Implement Multi-Bus CAN Interfaces
This commit is contained in:
BIN
.gitmodules
(Stored with Git LFS)
vendored
BIN
.gitmodules
(Stored with Git LFS)
vendored
Binary file not shown.
BIN
can-interface/.gitignore
(Stored with Git LFS)
vendored
BIN
can-interface/.gitignore
(Stored with Git LFS)
vendored
Binary file not shown.
5
can-interface/.vscode/settings.json
vendored
5
can-interface/.vscode/settings.json
vendored
@@ -10,10 +10,11 @@
|
||||
"idf.openOcdConfigs": [
|
||||
"board/esp32-wrover-kit-3.3v.cfg"
|
||||
],
|
||||
"idf.port": "/dev/ttyUSB0",
|
||||
"idf.port": "/dev/ttyUSB1",
|
||||
"idf.pythonBinPath": "/home/alexander/.espressif/python_env/idf5.3_py3.12_env/bin/python",
|
||||
"idf.toolsPath": "/home/alexander/.espressif",
|
||||
"idf.flashType": "UART",
|
||||
"idf.flashType": "JTAG",
|
||||
"idf.openOcdLaunchArgs": ["-c", "adapter_khz 10000"],
|
||||
"files.associations": {
|
||||
"*.tcc": "cpp",
|
||||
"cstdint": "cpp",
|
||||
|
||||
@@ -1 +0,0 @@
|
||||
/home/alexander/Projects/gobot/can-interface/circuit/gobot-can-interface/_autosave-gobot-can-interface.kicad_sch
|
||||
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface-backups/gobot-can-interface-2024-11-12_010429.zip
(Stored with Git LFS)
Normal file
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface-backups/gobot-can-interface-2024-11-12_010429.zip
(Stored with Git LFS)
Normal file
Binary file not shown.
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface-backups/gobot-can-interface-2024-11-12_011347.zip
(Stored with Git LFS)
Normal file
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface-backups/gobot-can-interface-2024-11-12_011347.zip
(Stored with Git LFS)
Normal file
Binary file not shown.
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface-backups/gobot-can-interface-2024-11-14_202426.zip
(Stored with Git LFS)
Normal file
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface-backups/gobot-can-interface-2024-11-14_202426.zip
(Stored with Git LFS)
Normal file
Binary file not shown.
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface-backups/gobot-can-interface-2024-11-15_170909.zip
(Stored with Git LFS)
Normal file
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface-backups/gobot-can-interface-2024-11-15_170909.zip
(Stored with Git LFS)
Normal file
Binary file not shown.
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface-backups/gobot-can-interface-2024-11-15_204011.zip
(Stored with Git LFS)
Normal file
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface-backups/gobot-can-interface-2024-11-15_204011.zip
(Stored with Git LFS)
Normal file
Binary file not shown.
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface-backups/gobot-can-interface-2024-11-21_223757.zip
(Stored with Git LFS)
Normal file
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface-backups/gobot-can-interface-2024-11-21_223757.zip
(Stored with Git LFS)
Normal file
Binary file not shown.
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface.kicad_sch
(Stored with Git LFS)
BIN
can-interface/circuit/gobot-can-interface/gobot-can-interface.kicad_sch
(Stored with Git LFS)
Binary file not shown.
@@ -0,0 +1,8 @@
|
||||
idf_component_register(SRCS
|
||||
"canTP.cpp"
|
||||
"gobotRPC.cpp"
|
||||
INCLUDE_DIRS "include"
|
||||
REQUIRES driver
|
||||
REQUIRES mcp2521
|
||||
REQUIRES mcp2521_hardware_interface
|
||||
)
|
||||
2866
can-interface/docs/Doxyfile
Normal file
2866
can-interface/docs/Doxyfile
Normal file
File diff suppressed because it is too large
Load Diff
1
can-interface/docs/doxygen-awesome-css
Submodule
1
can-interface/docs/doxygen-awesome-css
Submodule
Submodule can-interface/docs/doxygen-awesome-css added at 568f56cde6
@@ -2,5 +2,6 @@ idf_component_register(SRCS "hello_world_main.cpp"
|
||||
REQUIRES driver
|
||||
REQUIRES mcp2521
|
||||
REQUIRES mcp2521_hardware_interface
|
||||
REQUIRES CAN-Protocol-Stack
|
||||
REQUIRES spi_flash
|
||||
INCLUDE_DIRS "")
|
||||
|
||||
@@ -23,23 +23,40 @@
|
||||
|
||||
#include "mcp2521.hpp"
|
||||
|
||||
#define SPI_PIN_CS0 GPIO_NUM_5
|
||||
#define SPI_PIN_SCLK GPIO_NUM_18
|
||||
#define SPI_PIN_MISO GPIO_NUM_19
|
||||
#define SPI_PIN_MOSI GPIO_NUM_23
|
||||
#define CAN_INT_PIN GPIO_NUM_21
|
||||
|
||||
#define EXTERNAL_TRIGGER GPIO_NUM_26
|
||||
#define SPI_PIN_CS0 GPIO_NUM_25
|
||||
#define SPI_PIN_CS1 GPIO_NUM_27
|
||||
|
||||
void onRX(void *arg) {
|
||||
MCP2521 *mcp2521 = (MCP2521 *)arg;
|
||||
#define CAN_INT0_PIN GPIO_NUM_5
|
||||
#define CAN_INT1_PIN GPIO_NUM_26
|
||||
|
||||
rx_info info = mcp2521->get_rx_id(MCP2521_RX_BUFFER::RXB0);
|
||||
void onRX0(void *arg) {
|
||||
MCP2521 *mcp2521_0 = (MCP2521 *)arg;
|
||||
|
||||
rx_info info = mcp2521_0->get_rx_id(MCP2521_RX_BUFFER::RXB0);
|
||||
uint8_t data[8];
|
||||
|
||||
mcp2521->read_rx_buf(MCP2521_RX_BUFFER::RXB0, MCP2521_BUFFER_TYPE::DATA, data, info.length);
|
||||
mcp2521_0->read_rx_buf(MCP2521_RX_BUFFER::RXB0, MCP2521_BUFFER_TYPE::DATA, data, info.length);
|
||||
|
||||
printf("RX: (%x) ", info.id);
|
||||
printf("RX0: (%x) ", info.id);
|
||||
for (int i = 0; i < info.length; i++) {
|
||||
printf("%x ", data[i]);
|
||||
}
|
||||
printf("\n");
|
||||
}
|
||||
|
||||
void onRX1(void *arg) {
|
||||
MCP2521 *mcp2521_0 = (MCP2521 *)arg;
|
||||
|
||||
rx_info info = mcp2521_0->get_rx_id(MCP2521_RX_BUFFER::RXB0);
|
||||
uint8_t data[8];
|
||||
|
||||
mcp2521_0->read_rx_buf(MCP2521_RX_BUFFER::RXB0, MCP2521_BUFFER_TYPE::DATA, data, info.length);
|
||||
|
||||
printf("RX1: (%x) ", info.id);
|
||||
for (int i = 0; i < info.length; i++) {
|
||||
printf("%x ", data[i]);
|
||||
}
|
||||
@@ -52,46 +69,53 @@ extern "C" void app_main() {
|
||||
const gpio_num_t LED_PIN = GPIO_NUM_2;
|
||||
gpio_set_direction(LED_PIN, GPIO_MODE_OUTPUT);
|
||||
|
||||
gpio_set_direction(EXTERNAL_TRIGGER, GPIO_MODE_OUTPUT);
|
||||
gpio_set_level(EXTERNAL_TRIGGER, true);
|
||||
vTaskDelay(100 / portTICK_PERIOD_MS);
|
||||
|
||||
MCP2521_HardwareHandleFactory_ESPBus mcp2521_hardware_factory(
|
||||
VSPI_HOST,
|
||||
SPI_PIN_MOSI,
|
||||
SPI_PIN_MISO,
|
||||
SPI_PIN_SCLK
|
||||
);
|
||||
|
||||
MCP2521_HardwareHandle_ESPBus hardware_mcp2521_0 = mcp2521_hardware_factory.create(CAN_INT0_PIN, SPI_PIN_CS0);
|
||||
MCP2521_HardwareHandle_ESPBus hardware_mcp2521_1 = mcp2521_hardware_factory.create(CAN_INT1_PIN, SPI_PIN_CS1);
|
||||
|
||||
vTaskDelay(100 / portTICK_PERIOD_MS);
|
||||
|
||||
|
||||
spi_bus_config_t spi_bus;
|
||||
|
||||
MCP2521_Hardware_Handle_ESP hardware_mcp2521(
|
||||
VSPI_HOST,
|
||||
&spi_bus,
|
||||
SPI_PIN_MOSI,
|
||||
SPI_PIN_MISO,
|
||||
SPI_PIN_SCLK,
|
||||
SPI_PIN_CS0,
|
||||
CAN_INT_PIN
|
||||
);
|
||||
|
||||
MCP2521 mcp2521(&hardware_mcp2521);
|
||||
MCP2521 mcp2521_0(&hardware_mcp2521_0);
|
||||
MCP2521 mcp2521_1(&hardware_mcp2521_1);
|
||||
|
||||
uint8_t data[4] = {0xf0, 0x42, 0x13, 0x37};
|
||||
|
||||
gpio_set_level(EXTERNAL_TRIGGER, false);
|
||||
mcp2521.reset();
|
||||
mcp2521.enable_interrupts(true, true, true, true, true, true, true, true);
|
||||
mcp2521_0.reset();
|
||||
mcp2521_1.reset();
|
||||
mcp2521_0.enable_interrupts(true, true, true, true, true, true, true, true);
|
||||
mcp2521_1.enable_interrupts(true, true, true, true, true, true, true, true);
|
||||
|
||||
mcp2521.register_rx0_handler(onRX, &mcp2521);
|
||||
mcp2521.register_rx1_handler(onRX, &mcp2521);
|
||||
mcp2521.set_mode_of_operation(MCP2521_OPERATION_MODE::LOOPBACK, true);
|
||||
mcp2521_0.register_rx0_handler(onRX0, &mcp2521_0);
|
||||
mcp2521_1.register_rx0_handler(onRX1, &mcp2521_1);
|
||||
mcp2521_0.register_rx1_handler(onRX0, &mcp2521_0);
|
||||
mcp2521_1.register_rx1_handler(onRX1, &mcp2521_1);
|
||||
|
||||
vTaskDelay(3 / portTICK_PERIOD_MS);
|
||||
mcp2521_0.set_mode_of_operation(MCP2521_OPERATION_MODE::NORMAL, true);
|
||||
mcp2521_1.set_mode_of_operation(MCP2521_OPERATION_MODE::NORMAL, true);
|
||||
|
||||
mcp2521.prepare_tx(
|
||||
printf("CANSTAT0: %x\n", mcp2521_0.read_reg(MCP2521_CANSTAT));
|
||||
printf("CANSTAT1: %x\n", mcp2521_1.read_reg(MCP2521_CANSTAT));
|
||||
|
||||
vTaskDelay(20 / portTICK_PERIOD_MS);
|
||||
|
||||
mcp2521_0.prepare_tx(
|
||||
MCP2521_TX_BUFFER::TXB0, 0x042, data, 4, false, false);
|
||||
|
||||
mcp2521.request_to_send(MCP2521_TX_BUFFER::TXB0);
|
||||
|
||||
mcp2521.set_tx_id(MCP2521_TX_BUFFER::TXB0, 0x041, false);
|
||||
mcp2521.request_to_send(MCP2521_TX_BUFFER::TXB0);
|
||||
vTaskDelay(20 / portTICK_PERIOD_MS);
|
||||
mcp2521_0.request_to_send(MCP2521_TX_BUFFER::TXB0);
|
||||
//vTaskDelay(10 / portTICK_PERIOD_MS);
|
||||
//mcp2521_1.request_to_send(MCP2521_TX_BUFFER::TXB0);
|
||||
|
||||
//mcp2521_0.set_tx_id(MCP2521_TX_BUFFER::TXB0, 0x041, false);
|
||||
//mcp2521_0.request_to_send(MCP2521_TX_BUFFER::TXB0);
|
||||
|
||||
vTaskDelay(20 / portTICK_PERIOD_MS);
|
||||
|
||||
@@ -100,6 +124,6 @@ extern "C" void app_main() {
|
||||
gpio_set_level(LED_PIN, flag);
|
||||
flag = !flag;
|
||||
|
||||
vTaskDelay(100 / portTICK_PERIOD_MS);
|
||||
vTaskDelay(500 / portTICK_PERIOD_MS);
|
||||
}
|
||||
}
|
||||
|
||||
2008
can-interface/sdkconfig.old
Normal file
2008
can-interface/sdkconfig.old
Normal file
File diff suppressed because it is too large
Load Diff
152
can-interface/session-setup
Normal file
152
can-interface/session-setup
Normal file
@@ -0,0 +1,152 @@
|
||||
[General]
|
||||
decode_signals=2
|
||||
meta_objs=0
|
||||
views=1
|
||||
|
||||
[D0]
|
||||
color=4291714048
|
||||
conv_options=0
|
||||
conversion_type=0
|
||||
enabled=true
|
||||
name=INT0
|
||||
|
||||
[D1]
|
||||
color=4281623972
|
||||
conv_options=0
|
||||
conversion_type=0
|
||||
enabled=true
|
||||
name=CLK
|
||||
|
||||
[D2]
|
||||
color=4281623972
|
||||
conv_options=0
|
||||
conversion_type=0
|
||||
enabled=true
|
||||
name=MOSI
|
||||
|
||||
[D3]
|
||||
color=4281623972
|
||||
conv_options=0
|
||||
conversion_type=0
|
||||
enabled=true
|
||||
name=MISO
|
||||
|
||||
[D4]
|
||||
color=4294277376
|
||||
conv_options=0
|
||||
conversion_type=0
|
||||
enabled=true
|
||||
name=CE0
|
||||
|
||||
[D5]
|
||||
color=4279638298
|
||||
conv_options=0
|
||||
conversion_type=0
|
||||
enabled=true
|
||||
name=INT1
|
||||
|
||||
[D6]
|
||||
color=4279638298
|
||||
conv_options=0
|
||||
conversion_type=0
|
||||
enabled=true
|
||||
name=CE1
|
||||
|
||||
[D7]
|
||||
color=4285878395
|
||||
conv_options=0
|
||||
conversion_type=0
|
||||
enabled=true
|
||||
name=D7
|
||||
|
||||
[decode_signal0]
|
||||
channel0\assigned_signal_name=CLK
|
||||
channel0\initial_pin_state=2
|
||||
channel0\name=CLK
|
||||
channel1\assigned_signal_name=MISO
|
||||
channel1\initial_pin_state=2
|
||||
channel1\name=MISO
|
||||
channel2\assigned_signal_name=MOSI
|
||||
channel2\initial_pin_state=2
|
||||
channel2\name=MOSI
|
||||
channel3\assigned_signal_name=CE0
|
||||
channel3\initial_pin_state=2
|
||||
channel3\name=CS#
|
||||
channels=4
|
||||
color=4294277376
|
||||
conv_options=0
|
||||
conversion_type=0
|
||||
decoder0\ann_class0\visible=true
|
||||
decoder0\ann_class1\visible=true
|
||||
decoder0\ann_class2\visible=true
|
||||
decoder0\ann_class3\visible=true
|
||||
decoder0\ann_class4\visible=true
|
||||
decoder0\ann_class5\visible=true
|
||||
decoder0\ann_class6\visible=true
|
||||
decoder0\id=spi
|
||||
decoder0\options=0
|
||||
decoder0\row0\visible=true
|
||||
decoder0\row1\visible=true
|
||||
decoder0\row2\visible=true
|
||||
decoder0\row3\visible=true
|
||||
decoder0\row4\visible=true
|
||||
decoder0\row5\visible=true
|
||||
decoder0\row6\visible=true
|
||||
decoder0\visible=true
|
||||
decoders=1
|
||||
enabled=true
|
||||
name=SPI0
|
||||
|
||||
[decode_signal1]
|
||||
channel0\assigned_signal_name=CLK
|
||||
channel0\initial_pin_state=2
|
||||
channel0\name=CLK
|
||||
channel1\assigned_signal_name=MISO
|
||||
channel1\initial_pin_state=2
|
||||
channel1\name=MISO
|
||||
channel2\assigned_signal_name=MOSI
|
||||
channel2\initial_pin_state=2
|
||||
channel2\name=MOSI
|
||||
channel3\assigned_signal_name=CE1
|
||||
channel3\initial_pin_state=2
|
||||
channel3\name=CS#
|
||||
channels=4
|
||||
color=4279638298
|
||||
conv_options=0
|
||||
conversion_type=0
|
||||
decoder0\ann_class0\visible=true
|
||||
decoder0\ann_class1\visible=true
|
||||
decoder0\ann_class2\visible=true
|
||||
decoder0\ann_class3\visible=true
|
||||
decoder0\ann_class4\visible=true
|
||||
decoder0\ann_class5\visible=true
|
||||
decoder0\ann_class6\visible=true
|
||||
decoder0\id=spi
|
||||
decoder0\options=0
|
||||
decoder0\row0\visible=true
|
||||
decoder0\row1\visible=true
|
||||
decoder0\row2\visible=true
|
||||
decoder0\row3\visible=true
|
||||
decoder0\row4\visible=true
|
||||
decoder0\row5\visible=true
|
||||
decoder0\row6\visible=true
|
||||
decoder0\visible=true
|
||||
decoders=1
|
||||
enabled=true
|
||||
name=SPI1
|
||||
|
||||
[view0]
|
||||
D0\trace_height=38
|
||||
D1\trace_height=38
|
||||
D2\trace_height=38
|
||||
D3\trace_height=38
|
||||
D4\trace_height=38
|
||||
D5\trace_height=38
|
||||
D6\trace_height=38
|
||||
D7\trace_height=38
|
||||
offset=22 serialization::archive 19 0 0 0 0 52315583 48568089 25582163 47181659 91047901 0 -8 1 0 6
|
||||
scale=0.0021854614351496547
|
||||
segment_display_mode=1
|
||||
splitter_state=@ByteArray(\0\0\0\xff\0\0\0\x1\0\0\0\x2\0\0\0Z\0\0\x5\xa2\x1\0\0\0\x1\x1\0\0\0\x1\0)
|
||||
v_offset=-10
|
||||
zero_offset=22 serialization::archive 19 0 0 0 0 0 0 0 0 0 0 0 0 0 6
|
||||
@@ -0,0 +1,102 @@
|
||||
<mxfile host="Electron" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/24.7.17 Chrome/128.0.6613.36 Electron/32.0.1 Safari/537.36" version="24.7.17">
|
||||
<diagram name="Page-1" id="FmQN2vLuPXQQGOlHbBG4">
|
||||
<mxGraphModel dx="1195" dy="698" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="1169" pageHeight="827" math="0" shadow="0">
|
||||
<root>
|
||||
<mxCell id="0" />
|
||||
<mxCell id="1" parent="0" />
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-21" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0.75;exitY=1;exitDx=0;exitDy=0;entryX=0.75;entryY=0;entryDx=0;entryDy=0;endArrow=diamondThin;endFill=0;" edge="1" parent="1" source="xzzxaMGRirp7Gwq30BhV-1" target="xzzxaMGRirp7Gwq30BhV-18">
|
||||
<mxGeometry relative="1" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-1" value="«interface»<br><font face="Courier New"><b>I_MCP2521_</b><b>HardwareHandle</b></font>" style="html=1;whiteSpace=wrap;" vertex="1" parent="1">
|
||||
<mxGeometry x="520" y="120" width="200" height="60" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-9" value="<b><font face="Courier New">MCP2521_HardwareHandle_ESP</font></b>" style="html=1;whiteSpace=wrap;" vertex="1" parent="1">
|
||||
<mxGeometry x="230" y="260" width="250" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-11" value="<b><font face="Courier New">HardwareHandle_ESPBus</font></b>" style="html=1;whiteSpace=wrap;" vertex="1" parent="1">
|
||||
<mxGeometry x="230" y="200" width="250" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-12" value="" style="endArrow=none;dashed=1;html=1;rounded=0;exitX=1;exitY=1;exitDx=0;exitDy=0;strokeWidth=1;dashPattern=1 1;" edge="1" parent="1" source="xzzxaMGRirp7Gwq30BhV-14">
|
||||
<mxGeometry width="50" height="50" relative="1" as="geometry">
|
||||
<mxPoint x="1060" y="320" as="sourcePoint" />
|
||||
<mxPoint x="120" y="320" as="targetPoint" />
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-14" value="SPI - Hardware Level" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1">
|
||||
<mxGeometry x="760" y="280" width="160" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-15" value="" style="endArrow=block;html=1;rounded=0;dashed=1;endFill=0;exitX=1;exitY=0.5;exitDx=0;exitDy=0;entryX=0.25;entryY=1;entryDx=0;entryDy=0;" edge="1" parent="1" source="xzzxaMGRirp7Gwq30BhV-11" target="xzzxaMGRirp7Gwq30BhV-1">
|
||||
<mxGeometry width="50" height="50" relative="1" as="geometry">
|
||||
<mxPoint x="590" y="290" as="sourcePoint" />
|
||||
<mxPoint x="640" y="240" as="targetPoint" />
|
||||
<Array as="points">
|
||||
<mxPoint x="570" y="220" />
|
||||
</Array>
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-16" value="" style="endArrow=block;html=1;rounded=0;dashed=1;endFill=0;entryX=0.5;entryY=1;entryDx=0;entryDy=0;" edge="1" parent="1" source="xzzxaMGRirp7Gwq30BhV-9" target="xzzxaMGRirp7Gwq30BhV-1">
|
||||
<mxGeometry width="50" height="50" relative="1" as="geometry">
|
||||
<mxPoint x="520" y="280" as="sourcePoint" />
|
||||
<mxPoint x="580" y="250" as="targetPoint" />
|
||||
<Array as="points">
|
||||
<mxPoint x="620" y="280" />
|
||||
</Array>
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-17" value="MCP2521 - Device Level" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1">
|
||||
<mxGeometry x="760" y="388" width="160" height="32" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-18" value="<b><font face="Courier New">MCP2521_CommandInterface</font></b>" style="html=1;whiteSpace=wrap;" vertex="1" parent="1">
|
||||
<mxGeometry x="520" y="340" width="200" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-19" value="<b>MCP2521</b>" style="html=1;whiteSpace=wrap;" vertex="1" parent="1">
|
||||
<mxGeometry x="520" y="420" width="200" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-20" value="" style="endArrow=block;html=1;rounded=0;endFill=0;exitX=0.5;exitY=0;exitDx=0;exitDy=0;entryX=0.5;entryY=1;entryDx=0;entryDy=0;" edge="1" parent="1" source="xzzxaMGRirp7Gwq30BhV-19" target="xzzxaMGRirp7Gwq30BhV-18">
|
||||
<mxGeometry width="50" height="50" relative="1" as="geometry">
|
||||
<mxPoint x="670" y="544" as="sourcePoint" />
|
||||
<mxPoint x="720" y="494" as="targetPoint" />
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-23" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;entryX=0.746;entryY=0.064;entryDx=0;entryDy=0;entryPerimeter=0;" edge="1" parent="1" source="xzzxaMGRirp7Gwq30BhV-22" target="xzzxaMGRirp7Gwq30BhV-11">
|
||||
<mxGeometry relative="1" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-24" value="creates" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="xzzxaMGRirp7Gwq30BhV-23">
|
||||
<mxGeometry x="-0.3135" y="1" relative="1" as="geometry">
|
||||
<mxPoint x="16" y="1" as="offset" />
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-22" value="<b><font face="Courier New">MCP2421_HardwareHandleFactory_ESPBus</font></b>" style="html=1;whiteSpace=wrap;" vertex="1" parent="1">
|
||||
<mxGeometry x="180" y="120" width="300" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-25" value="" style="endArrow=none;dashed=1;html=1;rounded=0;exitX=1;exitY=1;exitDx=0;exitDy=0;strokeWidth=1;dashPattern=1 1;" edge="1" parent="1">
|
||||
<mxGeometry width="50" height="50" relative="1" as="geometry">
|
||||
<mxPoint x="920" y="480" as="sourcePoint" />
|
||||
<mxPoint x="120" y="480" as="targetPoint" />
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-26" value="Network Stack" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" vertex="1" parent="1">
|
||||
<mxGeometry x="760" y="480" width="160" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-27" value="<b>Socket_CANTP</b>" style="html=1;whiteSpace=wrap;" vertex="1" parent="1">
|
||||
<mxGeometry x="520" y="500" width="200" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-28" value="<b>Socket_GoBotRPC</b>" style="html=1;whiteSpace=wrap;" vertex="1" parent="1">
|
||||
<mxGeometry x="520" y="580" width="200" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-29" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0.75;exitY=1;exitDx=0;exitDy=0;endArrow=diamondThin;endFill=0;entryX=0.5;entryY=0;entryDx=0;entryDy=0;" edge="1" parent="1" target="xzzxaMGRirp7Gwq30BhV-27">
|
||||
<mxGeometry relative="1" as="geometry">
|
||||
<mxPoint x="619.76" y="460" as="sourcePoint" />
|
||||
<mxPoint x="640" y="520" as="targetPoint" />
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-30" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0.75;exitY=1;exitDx=0;exitDy=0;endArrow=diamondThin;endFill=0;" edge="1" parent="1">
|
||||
<mxGeometry relative="1" as="geometry">
|
||||
<mxPoint x="619.5799999999999" y="540" as="sourcePoint" />
|
||||
<mxPoint x="619.9699999999999" y="580" as="targetPoint" />
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
</root>
|
||||
</mxGraphModel>
|
||||
</diagram>
|
||||
</mxfile>
|
||||
102
common-libaries/mcp2521/docs/MCP2521_Libary_ClassDiagram.drawio
Normal file
102
common-libaries/mcp2521/docs/MCP2521_Libary_ClassDiagram.drawio
Normal file
@@ -0,0 +1,102 @@
|
||||
<mxfile host="Electron" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) draw.io/24.7.17 Chrome/128.0.6613.36 Electron/32.0.1 Safari/537.36" version="24.7.17">
|
||||
<diagram name="Page-1" id="FmQN2vLuPXQQGOlHbBG4">
|
||||
<mxGraphModel dx="1434" dy="838" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="1169" pageHeight="827" math="0" shadow="0">
|
||||
<root>
|
||||
<mxCell id="0" />
|
||||
<mxCell id="1" parent="0" />
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-21" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0.75;exitY=1;exitDx=0;exitDy=0;entryX=0.75;entryY=0;entryDx=0;entryDy=0;endArrow=diamondThin;endFill=0;" parent="1" source="xzzxaMGRirp7Gwq30BhV-1" target="xzzxaMGRirp7Gwq30BhV-18" edge="1">
|
||||
<mxGeometry relative="1" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-1" value="«interface»<br><font face="Courier New"><b>I_MCP2521_</b><b>HardwareHandle</b></font>" style="html=1;whiteSpace=wrap;" parent="1" vertex="1">
|
||||
<mxGeometry x="520" y="120" width="200" height="60" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-9" value="<b><font face="Courier New">MCP2521_HardwareHandle_ESP</font></b>" style="html=1;whiteSpace=wrap;" parent="1" vertex="1">
|
||||
<mxGeometry x="230" y="260" width="250" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-11" value="<b><font face="Courier New">MCP2521_</font></b><b><font face="Courier New">HardwareHandle_ESPBus</font></b>" style="html=1;whiteSpace=wrap;" parent="1" vertex="1">
|
||||
<mxGeometry x="230" y="200" width="250" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-12" value="" style="endArrow=none;dashed=1;html=1;rounded=0;exitX=1;exitY=1;exitDx=0;exitDy=0;strokeWidth=1;dashPattern=1 1;" parent="1" source="xzzxaMGRirp7Gwq30BhV-14" edge="1">
|
||||
<mxGeometry width="50" height="50" relative="1" as="geometry">
|
||||
<mxPoint x="1060" y="320" as="sourcePoint" />
|
||||
<mxPoint x="120" y="320" as="targetPoint" />
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-14" value="SPI - Hardware Level" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1">
|
||||
<mxGeometry x="760" y="280" width="160" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-15" value="" style="endArrow=block;html=1;rounded=0;dashed=1;endFill=0;exitX=1;exitY=0.5;exitDx=0;exitDy=0;entryX=0.25;entryY=1;entryDx=0;entryDy=0;" parent="1" source="xzzxaMGRirp7Gwq30BhV-11" target="xzzxaMGRirp7Gwq30BhV-1" edge="1">
|
||||
<mxGeometry width="50" height="50" relative="1" as="geometry">
|
||||
<mxPoint x="590" y="290" as="sourcePoint" />
|
||||
<mxPoint x="640" y="240" as="targetPoint" />
|
||||
<Array as="points">
|
||||
<mxPoint x="570" y="220" />
|
||||
</Array>
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-16" value="" style="endArrow=block;html=1;rounded=0;dashed=1;endFill=0;entryX=0.5;entryY=1;entryDx=0;entryDy=0;" parent="1" source="xzzxaMGRirp7Gwq30BhV-9" target="xzzxaMGRirp7Gwq30BhV-1" edge="1">
|
||||
<mxGeometry width="50" height="50" relative="1" as="geometry">
|
||||
<mxPoint x="520" y="280" as="sourcePoint" />
|
||||
<mxPoint x="580" y="250" as="targetPoint" />
|
||||
<Array as="points">
|
||||
<mxPoint x="620" y="280" />
|
||||
</Array>
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-17" value="MCP2521 - Device Level" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1">
|
||||
<mxGeometry x="760" y="388" width="160" height="32" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-18" value="<b><font face="Courier New">MCP2521_CommandInterface</font></b>" style="html=1;whiteSpace=wrap;" parent="1" vertex="1">
|
||||
<mxGeometry x="520" y="340" width="200" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-19" value="<b>MCP2521</b>" style="html=1;whiteSpace=wrap;" parent="1" vertex="1">
|
||||
<mxGeometry x="520" y="420" width="200" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-20" value="" style="endArrow=block;html=1;rounded=0;endFill=0;exitX=0.5;exitY=0;exitDx=0;exitDy=0;entryX=0.5;entryY=1;entryDx=0;entryDy=0;" parent="1" source="xzzxaMGRirp7Gwq30BhV-19" target="xzzxaMGRirp7Gwq30BhV-18" edge="1">
|
||||
<mxGeometry width="50" height="50" relative="1" as="geometry">
|
||||
<mxPoint x="670" y="544" as="sourcePoint" />
|
||||
<mxPoint x="720" y="494" as="targetPoint" />
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-23" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;entryX=0.746;entryY=0.064;entryDx=0;entryDy=0;entryPerimeter=0;" parent="1" source="xzzxaMGRirp7Gwq30BhV-22" target="xzzxaMGRirp7Gwq30BhV-11" edge="1">
|
||||
<mxGeometry relative="1" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-24" value="creates" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" parent="xzzxaMGRirp7Gwq30BhV-23" vertex="1" connectable="0">
|
||||
<mxGeometry x="-0.3135" y="1" relative="1" as="geometry">
|
||||
<mxPoint x="16" y="1" as="offset" />
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-22" value="<b><font face="Courier New">MCP2521_HardwareHandleFactory_ESPBus</font></b>" style="html=1;whiteSpace=wrap;" parent="1" vertex="1">
|
||||
<mxGeometry x="180" y="120" width="300" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-25" value="" style="endArrow=none;dashed=1;html=1;rounded=0;exitX=1;exitY=1;exitDx=0;exitDy=0;strokeWidth=1;dashPattern=1 1;" parent="1" edge="1">
|
||||
<mxGeometry width="50" height="50" relative="1" as="geometry">
|
||||
<mxPoint x="920" y="480" as="sourcePoint" />
|
||||
<mxPoint x="120" y="480" as="targetPoint" />
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-26" value="Network Stack" style="text;html=1;align=center;verticalAlign=middle;whiteSpace=wrap;rounded=0;" parent="1" vertex="1">
|
||||
<mxGeometry x="760" y="480" width="160" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-27" value="<b>Socket_CANTP</b>" style="html=1;whiteSpace=wrap;" parent="1" vertex="1">
|
||||
<mxGeometry x="520" y="500" width="200" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-28" value="<b>Socket_GoBotRPC</b>" style="html=1;whiteSpace=wrap;" parent="1" vertex="1">
|
||||
<mxGeometry x="520" y="580" width="200" height="40" as="geometry" />
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-29" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0.75;exitY=1;exitDx=0;exitDy=0;endArrow=diamondThin;endFill=0;entryX=0.5;entryY=0;entryDx=0;entryDy=0;" parent="1" target="xzzxaMGRirp7Gwq30BhV-27" edge="1">
|
||||
<mxGeometry relative="1" as="geometry">
|
||||
<mxPoint x="619.76" y="460" as="sourcePoint" />
|
||||
<mxPoint x="640" y="520" as="targetPoint" />
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
<mxCell id="xzzxaMGRirp7Gwq30BhV-30" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0.75;exitY=1;exitDx=0;exitDy=0;endArrow=diamondThin;endFill=0;" parent="1" edge="1">
|
||||
<mxGeometry relative="1" as="geometry">
|
||||
<mxPoint x="619.5799999999999" y="540" as="sourcePoint" />
|
||||
<mxPoint x="619.9699999999999" y="580" as="targetPoint" />
|
||||
</mxGeometry>
|
||||
</mxCell>
|
||||
</root>
|
||||
</mxGraphModel>
|
||||
</diagram>
|
||||
</mxfile>
|
||||
@@ -3,4 +3,5 @@
|
||||
#include "mcp2521_toplevel.hpp"
|
||||
#include "mcp2521_command.hpp"
|
||||
#include "mcp2521_hardware_esp.hpp"
|
||||
#include "mcp2521_hardware_esp_bus_factory.hpp"
|
||||
#include "mcp2521_addresses.hpp"
|
||||
@@ -40,9 +40,9 @@ struct rx_info {
|
||||
uint8_t length;
|
||||
};
|
||||
|
||||
class MCP2521_Command_Interface {
|
||||
class MCP2521_CommandInterface {
|
||||
private:
|
||||
MCP2521_Hardware_Handle * hardware_handle;
|
||||
I_MCP2521_HardwareHandle * hardware_handle;
|
||||
|
||||
intHandlerFunction_t rx0_handler;
|
||||
intHandlerFunction_t rx1_handler;
|
||||
@@ -63,8 +63,8 @@ private:
|
||||
void * message_error_handler_arg;
|
||||
public:
|
||||
|
||||
MCP2521_Command_Interface(
|
||||
MCP2521_Hardware_Handle * hardware_handle
|
||||
MCP2521_CommandInterface(
|
||||
I_MCP2521_HardwareHandle * hardware_handle
|
||||
);
|
||||
|
||||
void handleInterrupt();
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
#include "mcp2521_command.hpp"
|
||||
#include "mcp2521_addresses.hpp"
|
||||
|
||||
class MCP2521 : public MCP2521_Command_Interface {
|
||||
class MCP2521 : public MCP2521_CommandInterface {
|
||||
private:
|
||||
public:
|
||||
void set_tx_id(MCP2521_TX_BUFFER buffer, uint16_t id, bool extended);
|
||||
|
||||
@@ -4,12 +4,12 @@
|
||||
#include "mcp2521_addresses.hpp"
|
||||
|
||||
void runIntHandler(void *arg) {
|
||||
MCP2521_Command_Interface *command_interface = (MCP2521_Command_Interface *)arg;
|
||||
MCP2521_CommandInterface *command_interface = (MCP2521_CommandInterface *)arg;
|
||||
command_interface->handleInterrupt();
|
||||
}
|
||||
|
||||
MCP2521_Command_Interface::MCP2521_Command_Interface(
|
||||
MCP2521_Hardware_Handle * hardware_handle
|
||||
MCP2521_CommandInterface::MCP2521_CommandInterface(
|
||||
I_MCP2521_HardwareHandle * hardware_handle
|
||||
) {
|
||||
this->hardware_handle = hardware_handle;
|
||||
this->hardware_handle->registerIntHandler(runIntHandler, (void *)this);
|
||||
@@ -33,42 +33,42 @@ MCP2521_Command_Interface::MCP2521_Command_Interface(
|
||||
message_error_handler_arg = NULL;
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::reset() {
|
||||
void MCP2521_CommandInterface::reset() {
|
||||
hardware_handle->execute(MCP2521_OP_RESET);
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::read_reg(uint8_t address, uint8_t *data, size_t length) {
|
||||
void MCP2521_CommandInterface::read_reg(uint8_t address, uint8_t *data, size_t length) {
|
||||
hardware_handle->read(MCP2521_OP_READ, data, length, address);
|
||||
}
|
||||
|
||||
uint8_t MCP2521_Command_Interface::read_reg(uint8_t address) {
|
||||
uint8_t MCP2521_CommandInterface::read_reg(uint8_t address) {
|
||||
return hardware_handle->read(MCP2521_OP_READ, address);
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::read_rx_buf(MCP2521_RX_BUFFER buffer, MCP2521_BUFFER_TYPE type, uint8_t *data, size_t length) {
|
||||
void MCP2521_CommandInterface::read_rx_buf(MCP2521_RX_BUFFER buffer, MCP2521_BUFFER_TYPE type, uint8_t *data, size_t length) {
|
||||
uint8_t address = (buffer << 1) | (type << 2);
|
||||
hardware_handle->read(MCP2521_OP_READ_RX_BUFFER | address, data, length);
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::write_reg(uint8_t address, uint8_t *data, size_t length) {
|
||||
void MCP2521_CommandInterface::write_reg(uint8_t address, uint8_t *data, size_t length) {
|
||||
hardware_handle->write(MCP2521_OP_WRITE, data, length, address);
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::write_reg(uint8_t address, uint8_t data) {
|
||||
void MCP2521_CommandInterface::write_reg(uint8_t address, uint8_t data) {
|
||||
hardware_handle->write(MCP2521_OP_WRITE, data, address);
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::write_tx_buf(MCP2521_TX_BUFFER buffer, MCP2521_BUFFER_TYPE type, uint8_t *data, size_t length) {
|
||||
void MCP2521_CommandInterface::write_tx_buf(MCP2521_TX_BUFFER buffer, MCP2521_BUFFER_TYPE type, uint8_t *data, size_t length) {
|
||||
uint8_t address = (buffer << 1) | (type);
|
||||
hardware_handle->write(MCP2521_OP_LOAD_TX_BUFFER | address, data, length);
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::request_to_send(bool txb2, bool txb1, bool txb0) {
|
||||
void MCP2521_CommandInterface::request_to_send(bool txb2, bool txb1, bool txb0) {
|
||||
uint8_t data = (txb2 << 2) | (txb1 << 1) | txb0;
|
||||
hardware_handle->execute(MCP2521_OP_RTS | data);
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::request_to_send(MCP2521_TX_BUFFER buffer) {
|
||||
void MCP2521_CommandInterface::request_to_send(MCP2521_TX_BUFFER buffer) {
|
||||
uint8_t mask = 0;
|
||||
|
||||
switch (buffer) {
|
||||
@@ -86,15 +86,15 @@ void MCP2521_Command_Interface::request_to_send(MCP2521_TX_BUFFER buffer) {
|
||||
hardware_handle->execute(MCP2521_OP_RTS | mask);
|
||||
}
|
||||
|
||||
uint8_t MCP2521_Command_Interface::read_status() {
|
||||
uint8_t MCP2521_CommandInterface::read_status() {
|
||||
return hardware_handle->read(MCP2521_OP_READ_STATUS);
|
||||
}
|
||||
|
||||
uint8_t MCP2521_Command_Interface::read_rx_status() {
|
||||
uint8_t MCP2521_CommandInterface::read_rx_status() {
|
||||
return hardware_handle->read(MCP2521_OP_RX_STATUS);
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::bit_modify(uint8_t address, uint8_t mask, uint8_t data) {
|
||||
void MCP2521_CommandInterface::bit_modify(uint8_t address, uint8_t mask, uint8_t data) {
|
||||
uint8_t data_array[3] = {address, mask, data};
|
||||
hardware_handle->write(MCP2521_OP_BIT_MODIFY, data_array, 3);
|
||||
}
|
||||
@@ -1,47 +1,47 @@
|
||||
#include "mcp2521.hpp"
|
||||
#include "mcp2521_addresses.hpp"
|
||||
|
||||
void MCP2521_Command_Interface::register_rx0_handler(intHandlerFunction_t handler, void* args) {
|
||||
void MCP2521_CommandInterface::register_rx0_handler(intHandlerFunction_t handler, void* args) {
|
||||
rx0_handler = handler;
|
||||
rx0_handler_arg = args;
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::register_rx1_handler(intHandlerFunction_t handler, void* args) {
|
||||
void MCP2521_CommandInterface::register_rx1_handler(intHandlerFunction_t handler, void* args) {
|
||||
rx1_handler = handler;
|
||||
rx1_handler_arg = args;
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::register_tx0_handler(intHandlerFunction_t handler, void* args) {
|
||||
void MCP2521_CommandInterface::register_tx0_handler(intHandlerFunction_t handler, void* args) {
|
||||
tx0_handler = handler;
|
||||
tx0_handler_arg = args;
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::register_tx1_handler(intHandlerFunction_t handler, void* args) {
|
||||
void MCP2521_CommandInterface::register_tx1_handler(intHandlerFunction_t handler, void* args) {
|
||||
tx1_handler = handler;
|
||||
tx1_handler_arg = args;
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::register_tx2_handler(intHandlerFunction_t handler, void* args) {
|
||||
void MCP2521_CommandInterface::register_tx2_handler(intHandlerFunction_t handler, void* args) {
|
||||
tx2_handler = handler;
|
||||
tx2_handler_arg = args;
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::register_error_handler(intHandlerFunction_t handler, void* args) {
|
||||
void MCP2521_CommandInterface::register_error_handler(intHandlerFunction_t handler, void* args) {
|
||||
error_handler = handler;
|
||||
error_handler_arg = args;
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::register_wakeup_handler(intHandlerFunction_t handler, void* args) {
|
||||
void MCP2521_CommandInterface::register_wakeup_handler(intHandlerFunction_t handler, void* args) {
|
||||
wakeup_handler = handler;
|
||||
wakeup_handler_arg = args;
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::register_message_error_handler(intHandlerFunction_t handler, void* args) {
|
||||
void MCP2521_CommandInterface::register_message_error_handler(intHandlerFunction_t handler, void* args) {
|
||||
message_error_handler = handler;
|
||||
message_error_handler_arg = args;
|
||||
}
|
||||
|
||||
void MCP2521_Command_Interface::handleInterrupt() {
|
||||
void MCP2521_CommandInterface::handleInterrupt() {
|
||||
uint8_t flags = read_reg(MCP2521_CANINTF);
|
||||
uint8_t clearBits = 0;
|
||||
|
||||
|
||||
@@ -1,5 +1,7 @@
|
||||
idf_component_register(SRCS "esp_implementation_init.cpp"
|
||||
"esp_implementation_cmd.cpp"
|
||||
"esp_implementation_int.cpp"
|
||||
"esp_implementation_bus.cpp"
|
||||
"esp_implementation_bus_factory.cpp"
|
||||
INCLUDE_DIRS "include"
|
||||
REQUIRES driver)
|
||||
@@ -0,0 +1,58 @@
|
||||
#ifdef ESP_PLATFORM
|
||||
#include "freertos/FreeRTOS.h"
|
||||
|
||||
#include "mcp2521_hardware_esp_bus.hpp"
|
||||
#include "mcp2521_hardware_esp.hpp"
|
||||
|
||||
MCP2521_HardwareHandle_ESPBus::MCP2521_HardwareHandle_ESPBus(
|
||||
QueueHandle_t send_queue,
|
||||
spi_host_device_t spi_host,
|
||||
spi_bus_config_t * bus_config,
|
||||
gpio_num_t cs,
|
||||
gpio_num_t int_pin
|
||||
) : MCP2521_HardwareHandle_ESP(spi_host, bus_config, cs, int_pin) {
|
||||
this->send_queue = send_queue;
|
||||
this->receive_queue = xQueueCreate(3, sizeof(spi_message_t));
|
||||
}
|
||||
|
||||
void MCP2521_HardwareHandle_ESPBus::spi_transmit(spi_transaction_t *t) {
|
||||
spi_message_t message = {
|
||||
.transaction = t,
|
||||
.queue = send_queue,
|
||||
.spi_device_handle = spi_device_handle
|
||||
};
|
||||
|
||||
xQueueSend(send_queue, &message, portMAX_DELAY);
|
||||
xQueueReceive(receive_queue, &message, portMAX_DELAY);
|
||||
}
|
||||
|
||||
void MCP2521_HardwareHandle_ESPBus::initPins(
|
||||
gpio_num_t int_pin
|
||||
) {
|
||||
canInterruptSemaphore = xSemaphoreCreateBinary();
|
||||
|
||||
gpio_config_t io_conf;
|
||||
io_conf.intr_type = GPIO_INTR_NEGEDGE;
|
||||
io_conf.mode = GPIO_MODE_INPUT;
|
||||
io_conf.pin_bit_mask = 1 << int_pin;
|
||||
io_conf.pull_down_en = GPIO_PULLDOWN_DISABLE;
|
||||
io_conf.pull_up_en = GPIO_PULLUP_ENABLE;
|
||||
gpio_config(&io_conf);
|
||||
|
||||
gpio_isr_handler_add(int_pin, gpio_isr_can_handler, this);
|
||||
|
||||
char taskName[32];
|
||||
sprintf(taskName, "canInterruptTask_%d", int_pin);
|
||||
|
||||
xTaskCreatePinnedToCore(
|
||||
(TaskFunction_t)&handleInteruptTaskCallerFn,
|
||||
taskName,
|
||||
2048,
|
||||
this,
|
||||
5,
|
||||
&canInterruptTaskHandle,
|
||||
0
|
||||
);
|
||||
}
|
||||
|
||||
#endif
|
||||
@@ -0,0 +1,67 @@
|
||||
#pragma once
|
||||
|
||||
#ifdef ESP_PLATFORM
|
||||
#include "freertos/FreeRTOS.h"
|
||||
|
||||
#include "mcp2521_hardware_esp_bus_factory.hpp"
|
||||
#include "mcp2521_hardware_esp_bus.hpp"
|
||||
#include "mcp2521_hardware_esp.hpp"
|
||||
|
||||
void transactionTaskWrapperFn(void *pvParameters) {
|
||||
MCP2521_HardwareHandleFactory_ESPBus *factory = (MCP2521_HardwareHandleFactory_ESPBus *)pvParameters;
|
||||
factory->transactionTaskFn();
|
||||
|
||||
}
|
||||
|
||||
MCP2521_HardwareHandleFactory_ESPBus::MCP2521_HardwareHandleFactory_ESPBus(
|
||||
spi_host_device_t spi_host,
|
||||
gpio_num_t mosi,
|
||||
gpio_num_t miso,
|
||||
gpio_num_t sclk
|
||||
) {
|
||||
this->spi_host = spi_host;
|
||||
this->mosi = mosi;
|
||||
this->miso = miso;
|
||||
this->sclk = sclk;
|
||||
|
||||
|
||||
gpio_install_isr_service(0);
|
||||
|
||||
MCP2521_HardwareHandle_ESP::initSPIBus(spi_host, mosi, miso, sclk, &bus_config);
|
||||
|
||||
spi_queue = xQueueCreate(12, sizeof(spi_message_t));
|
||||
xTaskCreatePinnedToCore(
|
||||
(TaskFunction_t)&transactionTaskWrapperFn,
|
||||
"transactionTask",
|
||||
2048,
|
||||
this,
|
||||
3,
|
||||
&transactionTaskHandle,
|
||||
0
|
||||
);
|
||||
}
|
||||
|
||||
void MCP2521_HardwareHandleFactory_ESPBus::transactionTaskFn() {
|
||||
spi_message_t message;
|
||||
|
||||
while(true) {
|
||||
xQueueReceive(spi_queue, &message, portMAX_DELAY);
|
||||
spi_device_transmit(message.spi_device_handle, message.transaction);
|
||||
}
|
||||
}
|
||||
|
||||
MCP2521_HardwareHandle_ESPBus MCP2521_HardwareHandleFactory_ESPBus::create(
|
||||
gpio_num_t int_pin,
|
||||
gpio_num_t cs
|
||||
) {
|
||||
return MCP2521_HardwareHandle_ESPBus(
|
||||
spi_queue,
|
||||
spi_host,
|
||||
&bus_config,
|
||||
cs,
|
||||
int_pin
|
||||
);
|
||||
}
|
||||
|
||||
|
||||
#endif
|
||||
@@ -5,13 +5,13 @@
|
||||
|
||||
const uint8_t null_buffer[32] = {0};
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::spi_transmit(spi_transaction_t *t) {
|
||||
void MCP2521_HardwareHandle_ESP::spi_transmit(spi_transaction_t *t) {
|
||||
xSemaphoreTake(spiMutex, portMAX_DELAY);
|
||||
spi_device_transmit(this->spi_device_handle, t);
|
||||
xSemaphoreGive(spiMutex);
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::execute(uint8_t cmd) {
|
||||
void MCP2521_HardwareHandle_ESP::execute(uint8_t cmd) {
|
||||
spi_transaction_ext_t t = {
|
||||
.base = {
|
||||
.flags = SPI_TRANS_VARIABLE_CMD | SPI_TRANS_VARIABLE_ADDR,
|
||||
@@ -30,7 +30,7 @@ void MCP2521_Hardware_Handle_ESP::execute(uint8_t cmd) {
|
||||
spi_transmit((spi_transaction_t*)(&t));
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::execute(uint8_t cmd, uint8_t address) {
|
||||
void MCP2521_HardwareHandle_ESP::execute(uint8_t cmd, uint8_t address) {
|
||||
spi_transaction_ext_t t = {
|
||||
.base = {
|
||||
.flags = SPI_TRANS_VARIABLE_CMD | SPI_TRANS_VARIABLE_ADDR,
|
||||
@@ -49,7 +49,7 @@ void MCP2521_Hardware_Handle_ESP::execute(uint8_t cmd, uint8_t address) {
|
||||
spi_transmit((spi_transaction_t*)(&t));
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::read(uint8_t cmd, uint8_t *data, size_t length, uint8_t address) {
|
||||
void MCP2521_HardwareHandle_ESP::read(uint8_t cmd, uint8_t *data, size_t length, uint8_t address) {
|
||||
spi_transaction_ext_t t = {
|
||||
.base = {
|
||||
.flags = SPI_TRANS_VARIABLE_CMD | SPI_TRANS_VARIABLE_ADDR,
|
||||
@@ -68,7 +68,7 @@ void MCP2521_Hardware_Handle_ESP::read(uint8_t cmd, uint8_t *data, size_t length
|
||||
spi_transmit((spi_transaction_t*)(&t));
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::read(uint8_t cmd, uint8_t *data, size_t length) {
|
||||
void MCP2521_HardwareHandle_ESP::read(uint8_t cmd, uint8_t *data, size_t length) {
|
||||
spi_transaction_ext_t t = {
|
||||
.base = {
|
||||
.flags = SPI_TRANS_VARIABLE_CMD | SPI_TRANS_VARIABLE_ADDR,
|
||||
@@ -87,7 +87,7 @@ void MCP2521_Hardware_Handle_ESP::read(uint8_t cmd, uint8_t *data, size_t length
|
||||
spi_transmit((spi_transaction_t*)(&t));
|
||||
}
|
||||
|
||||
uint8_t MCP2521_Hardware_Handle_ESP::read(uint8_t cmd, uint8_t address) {
|
||||
uint8_t MCP2521_HardwareHandle_ESP::read(uint8_t cmd, uint8_t address) {
|
||||
uint8_t result = 0;
|
||||
spi_transaction_ext_t t = {
|
||||
.base = {
|
||||
@@ -108,7 +108,7 @@ uint8_t MCP2521_Hardware_Handle_ESP::read(uint8_t cmd, uint8_t address) {
|
||||
return result;
|
||||
}
|
||||
|
||||
uint8_t MCP2521_Hardware_Handle_ESP::read(uint8_t cmd) {
|
||||
uint8_t MCP2521_HardwareHandle_ESP::read(uint8_t cmd) {
|
||||
uint8_t result;
|
||||
spi_transaction_ext_t t = {
|
||||
.base = {
|
||||
@@ -129,7 +129,7 @@ uint8_t MCP2521_Hardware_Handle_ESP::read(uint8_t cmd) {
|
||||
return result;
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::write(uint8_t cmd, uint8_t *data, size_t length, uint8_t address) {
|
||||
void MCP2521_HardwareHandle_ESP::write(uint8_t cmd, uint8_t *data, size_t length, uint8_t address) {
|
||||
uint8_t result;
|
||||
spi_transaction_ext_t t = {
|
||||
.base = {
|
||||
@@ -149,7 +149,7 @@ void MCP2521_Hardware_Handle_ESP::write(uint8_t cmd, uint8_t *data, size_t lengt
|
||||
spi_transmit((spi_transaction_t*)(&t));
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::write(uint8_t cmd, uint8_t *data, size_t length) {
|
||||
void MCP2521_HardwareHandle_ESP::write(uint8_t cmd, uint8_t *data, size_t length) {
|
||||
spi_transaction_ext_t t = {
|
||||
.base = {
|
||||
.flags = SPI_TRANS_VARIABLE_CMD | SPI_TRANS_VARIABLE_ADDR,
|
||||
@@ -168,7 +168,7 @@ void MCP2521_Hardware_Handle_ESP::write(uint8_t cmd, uint8_t *data, size_t lengt
|
||||
spi_transmit((spi_transaction_t*)(&t));
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::write(uint8_t cmd, uint8_t data, uint8_t address) {
|
||||
void MCP2521_HardwareHandle_ESP::write(uint8_t cmd, uint8_t data, uint8_t address) {
|
||||
spi_transaction_ext_t t = {
|
||||
.base = {
|
||||
.flags = SPI_TRANS_VARIABLE_CMD | SPI_TRANS_VARIABLE_ADDR,
|
||||
@@ -187,7 +187,7 @@ void MCP2521_Hardware_Handle_ESP::write(uint8_t cmd, uint8_t data, uint8_t addre
|
||||
spi_transmit((spi_transaction_t*)(&t));
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::write(uint8_t cmd, uint8_t data) {
|
||||
void MCP2521_HardwareHandle_ESP::write(uint8_t cmd, uint8_t data) {
|
||||
spi_transaction_ext_t t = {
|
||||
.base = {
|
||||
.flags = SPI_TRANS_VARIABLE_CMD | SPI_TRANS_VARIABLE_ADDR,
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
|
||||
MCP2521_Hardware_Handle_ESP::MCP2521_Hardware_Handle_ESP(
|
||||
MCP2521_HardwareHandle_ESP::MCP2521_HardwareHandle_ESP(
|
||||
spi_host_device_t spi_host,
|
||||
spi_bus_config_t *bus_config,
|
||||
gpio_num_t mosi,
|
||||
@@ -23,7 +23,7 @@ MCP2521_Hardware_Handle_ESP::MCP2521_Hardware_Handle_ESP(
|
||||
initSPIDevice(spi_host, cs);
|
||||
}
|
||||
|
||||
MCP2521_Hardware_Handle_ESP::MCP2521_Hardware_Handle_ESP(
|
||||
MCP2521_HardwareHandle_ESP::MCP2521_HardwareHandle_ESP(
|
||||
spi_host_device_t spi_host,
|
||||
spi_bus_config_t *bus_config,
|
||||
gpio_num_t cs,
|
||||
@@ -34,11 +34,11 @@ MCP2521_Hardware_Handle_ESP::MCP2521_Hardware_Handle_ESP(
|
||||
initSPIDevice(spi_host, cs);
|
||||
}
|
||||
|
||||
MCP2521_Hardware_Handle_ESP::~MCP2521_Hardware_Handle_ESP() {
|
||||
MCP2521_HardwareHandle_ESP::~MCP2521_HardwareHandle_ESP() {
|
||||
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::initSPIBus(
|
||||
void MCP2521_HardwareHandle_ESP::initSPIBus(
|
||||
spi_host_device_t spi_host,
|
||||
gpio_num_t mosi,
|
||||
gpio_num_t miso,
|
||||
@@ -57,7 +57,7 @@ void MCP2521_Hardware_Handle_ESP::initSPIBus(
|
||||
spi_bus_initialize(spi_host, bus_config, SPI_DMA_CH_AUTO);
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::initSPIDevice(
|
||||
void MCP2521_HardwareHandle_ESP::initSPIDevice(
|
||||
spi_host_device_t spi_host,
|
||||
gpio_num_t cs
|
||||
) {
|
||||
@@ -85,7 +85,7 @@ void MCP2521_Hardware_Handle_ESP::initSPIDevice(
|
||||
spiMutex = xSemaphoreCreateMutex();
|
||||
}
|
||||
|
||||
spi_bus_config_t * MCP2521_Hardware_Handle_ESP::getSPI_bus_config() {
|
||||
spi_bus_config_t * MCP2521_HardwareHandle_ESP::getSPI_bus_config() {
|
||||
return this->spi_bus_config;
|
||||
}
|
||||
|
||||
|
||||
@@ -6,16 +6,16 @@
|
||||
#include "mcp2521_hardware_esp.hpp"
|
||||
|
||||
static void IRAM_ATTR gpio_isr_can_handler(void* arg) {
|
||||
MCP2521_Hardware_Handle_ESP * handle = (MCP2521_Hardware_Handle_ESP *)arg;
|
||||
MCP2521_HardwareHandle_ESP * handle = (MCP2521_HardwareHandle_ESP *)arg;
|
||||
handle->isr_can_interrupt();
|
||||
}
|
||||
|
||||
static void handleInteruptTaskCallerFn(void *arg) {
|
||||
MCP2521_Hardware_Handle_ESP * handle = (MCP2521_Hardware_Handle_ESP *)arg;
|
||||
MCP2521_HardwareHandle_ESP * handle = (MCP2521_HardwareHandle_ESP *)arg;
|
||||
handle->handleIntteruptTaskFn();
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::initPins(
|
||||
void MCP2521_HardwareHandle_ESP::initPins(
|
||||
gpio_num_t int_pin
|
||||
) {
|
||||
canInterruptSemaphore = xSemaphoreCreateBinary();
|
||||
@@ -31,24 +31,25 @@ void MCP2521_Hardware_Handle_ESP::initPins(
|
||||
gpio_install_isr_service(0);
|
||||
gpio_isr_handler_add(int_pin, gpio_isr_can_handler, this);
|
||||
|
||||
xTaskCreate(
|
||||
xTaskCreatePinnedToCore(
|
||||
(TaskFunction_t)&handleInteruptTaskCallerFn,
|
||||
"canInterruptTask",
|
||||
2048,
|
||||
this,
|
||||
5,
|
||||
&canInterruptTaskHandle
|
||||
&canInterruptTaskHandle,
|
||||
0
|
||||
);
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::handleIntteruptTaskFn() {
|
||||
void MCP2521_HardwareHandle_ESP::handleIntteruptTaskFn() {
|
||||
while(true) {
|
||||
xSemaphoreTake(canInterruptSemaphore, portMAX_DELAY);
|
||||
intHandler(intHandlerArg);
|
||||
}
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::isr_can_interrupt() {
|
||||
void MCP2521_HardwareHandle_ESP::isr_can_interrupt() {
|
||||
BaseType_t wokenTask = pdFALSE;
|
||||
xSemaphoreGiveFromISR(canInterruptSemaphore, &wokenTask);
|
||||
|
||||
@@ -57,7 +58,7 @@ void MCP2521_Hardware_Handle_ESP::isr_can_interrupt() {
|
||||
}
|
||||
}
|
||||
|
||||
void MCP2521_Hardware_Handle_ESP::registerIntHandler(intHandlerFunction_t handler, void * arg) {
|
||||
void MCP2521_HardwareHandle_ESP::registerIntHandler(intHandlerFunction_t handler, void * arg) {
|
||||
intHandlerArg = arg;
|
||||
intHandler = handler;
|
||||
}
|
||||
|
||||
@@ -1,3 +1,13 @@
|
||||
/**
|
||||
* @file mcp2521_hardware_esp.hpp
|
||||
* @author AlexanderHD27
|
||||
* @brief
|
||||
* @version 0.1
|
||||
* @date 2024-11-16
|
||||
*
|
||||
* @copyright Copyright (c) 2024
|
||||
*
|
||||
*/
|
||||
#pragma once
|
||||
#include "mcp2521_hardware_handle.hpp"
|
||||
|
||||
@@ -8,24 +18,48 @@
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
|
||||
class MCP2521_Hardware_Handle_ESP : public MCP2521_Hardware_Handle {
|
||||
char spi_tmp_buffer;
|
||||
static void handleInteruptTaskCallerFn(void *arg);
|
||||
static void IRAM_ATTR gpio_isr_can_handler(void* arg);
|
||||
|
||||
spi_bus_config_t * spi_bus_config;
|
||||
spi_device_interface_config_t spi_device_config;
|
||||
spi_device_handle_t spi_device_handle;
|
||||
/**
|
||||
* @brief Hardware handle for MCP2521 over SPI on ESP32
|
||||
* This is should not be used if multiple MCP2521 are on the same SPI bus
|
||||
*/
|
||||
class MCP2521_HardwareHandle_ESP : public I_MCP2521_HardwareHandle {
|
||||
protected:
|
||||
void spi_transmit(spi_transaction_t *t);
|
||||
|
||||
/**
|
||||
* @brief Sempahore, that is set every time the MCP2521 triggers an interrupt by the canInterruptTaskHandle
|
||||
*/
|
||||
SemaphoreHandle_t canInterruptSemaphore = NULL;
|
||||
SemaphoreHandle_t spiMutex = NULL;
|
||||
|
||||
|
||||
/**
|
||||
* @brief Handle to task that handles the MCP2521 interrupt
|
||||
* A Handle can be registered via the registerIntHandler method
|
||||
*/
|
||||
TaskHandle_t canInterruptTaskHandle = NULL;
|
||||
|
||||
void spi_transmit(spi_transaction_t *t);
|
||||
spi_device_handle_t spi_device_handle;
|
||||
|
||||
private:
|
||||
spi_bus_config_t * spi_bus_config;
|
||||
char spi_tmp_buffer;
|
||||
|
||||
spi_device_interface_config_t spi_device_config;
|
||||
|
||||
/**
|
||||
* @brief Sempahore, that protects the SPI bus from being accessed by multiple tasks at the same time
|
||||
*
|
||||
*/
|
||||
SemaphoreHandle_t spiMutex = NULL;
|
||||
|
||||
void * intHandlerArg = NULL;
|
||||
intHandlerFunction_t intHandler = NULL;
|
||||
|
||||
public:
|
||||
MCP2521_Hardware_Handle_ESP(
|
||||
MCP2521_HardwareHandle_ESP(
|
||||
spi_host_device_t spi_host,
|
||||
spi_bus_config_t *bus_config,
|
||||
gpio_num_t mosi,
|
||||
@@ -35,7 +69,7 @@ public:
|
||||
gpio_num_t int_pin
|
||||
);
|
||||
|
||||
MCP2521_Hardware_Handle_ESP(
|
||||
MCP2521_HardwareHandle_ESP(
|
||||
spi_host_device_t spi_host,
|
||||
spi_bus_config_t *bus_config,
|
||||
gpio_num_t cs,
|
||||
@@ -59,12 +93,22 @@ public:
|
||||
gpio_num_t int_pin
|
||||
);
|
||||
|
||||
~MCP2521_Hardware_Handle_ESP();
|
||||
~MCP2521_HardwareHandle_ESP();
|
||||
|
||||
spi_bus_config_t * getSPI_bus_config();
|
||||
|
||||
// ISR Stuff
|
||||
/**
|
||||
* @brief This function is called by the ISR, that is triggered by the MCP2521
|
||||
* This function just set the canInterruptSemaphore, that then unblocks the canInterruptTaskHandle.
|
||||
* So this function should be as short as possible, let the reset of the work be done in the canInterruptTaskHandle
|
||||
*/
|
||||
void isr_can_interrupt();
|
||||
|
||||
/**
|
||||
* This is the methode run as canInterruptTaskHandle.
|
||||
* It should continously aquire the canInterruptSemaphore and then call the intHandler
|
||||
*/
|
||||
void handleIntteruptTaskFn();
|
||||
|
||||
// Inherited from MCP2521_Hardware_Handle
|
||||
|
||||
@@ -0,0 +1,46 @@
|
||||
#pragma once
|
||||
|
||||
#include "mcp2521_hardware_esp.hpp"
|
||||
|
||||
#include "driver/gpio.h"
|
||||
#include "driver/spi_master.h"
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
|
||||
struct spi_message_t {
|
||||
spi_transaction_t *transaction;
|
||||
QueueHandle_t queue;
|
||||
spi_device_handle_t spi_device_handle;
|
||||
};
|
||||
|
||||
/**
|
||||
* @brief Hardware handle for MCP2521 over SPI in a multi-Bus-Setup on ESP32
|
||||
* This should not be created directly, use the MCP2521_HardwareHandleFactory_ESPBus instead
|
||||
*/
|
||||
class MCP2521_HardwareHandle_ESPBus : public MCP2521_HardwareHandle_ESP {
|
||||
using MCP2521_HardwareHandle_ESP::MCP2521_HardwareHandle_ESP;
|
||||
private:
|
||||
QueueHandle_t send_queue;
|
||||
QueueHandle_t receive_queue;
|
||||
|
||||
/**
|
||||
* @brief Wrapper around the spi_transmit function, that locks the spiMutex before calling spi_transmit.
|
||||
* The muxtex is shared with all other MCP2521_HardwareHandle_ESPBus instances created by the same MCP2521_HardwareHandleFactory_ESPBus
|
||||
* @overload
|
||||
*
|
||||
* @param t ESP32 SPI Transaction struct
|
||||
*/
|
||||
void spi_transmit(spi_transaction_t *t);
|
||||
public:
|
||||
MCP2521_HardwareHandle_ESPBus(
|
||||
QueueHandle_t send_queue,
|
||||
spi_host_device_t spi_host,
|
||||
spi_bus_config_t * bus_config,
|
||||
gpio_num_t cs,
|
||||
gpio_num_t int_pin
|
||||
);
|
||||
|
||||
void initPins(
|
||||
gpio_num_t int_pin
|
||||
);
|
||||
};
|
||||
@@ -0,0 +1,41 @@
|
||||
#pragma once
|
||||
|
||||
#ifdef ESP_PLATFORM
|
||||
#include "mcp2521_hardware_handle.hpp"
|
||||
#include "mcp2521_hardware_esp_bus.hpp"
|
||||
|
||||
#include "driver/gpio.h"
|
||||
#include "driver/spi_master.h"
|
||||
#include "freertos/FreeRTOS.h"
|
||||
#include "freertos/task.h"
|
||||
#include "freertos/queue.h"
|
||||
|
||||
class MCP2521_HardwareHandleFactory_ESPBus {
|
||||
private:
|
||||
spi_bus_config_t bus_config;
|
||||
spi_host_device_t spi_host;
|
||||
|
||||
gpio_num_t mosi;
|
||||
gpio_num_t miso;
|
||||
gpio_num_t sclk;
|
||||
|
||||
QueueHandle_t spi_queue;
|
||||
TaskHandle_t transactionTaskHandle;
|
||||
|
||||
public:
|
||||
MCP2521_HardwareHandleFactory_ESPBus(
|
||||
spi_host_device_t spi_host,
|
||||
gpio_num_t mosi,
|
||||
gpio_num_t miso,
|
||||
gpio_num_t sclk
|
||||
);
|
||||
|
||||
void transactionTaskFn();
|
||||
|
||||
MCP2521_HardwareHandle_ESPBus create(
|
||||
gpio_num_t int_pin,
|
||||
gpio_num_t cs
|
||||
);
|
||||
};
|
||||
|
||||
#endif
|
||||
@@ -2,23 +2,118 @@
|
||||
#include <cstdint>
|
||||
#include <strings.h>
|
||||
|
||||
/**
|
||||
* @brief Handler function pointer type
|
||||
*
|
||||
*/
|
||||
typedef void (*intHandlerFunction_t)(void *);
|
||||
|
||||
class MCP2521_Hardware_Handle {
|
||||
/**
|
||||
* @brief Hardware handle for MCP2521
|
||||
* @interface
|
||||
* This is an abstraction over the sepific hardware setup, eg. SPI@ESP32 or RP2040
|
||||
*
|
||||
*/
|
||||
class I_MCP2521_HardwareHandle {
|
||||
public:
|
||||
/**
|
||||
* @brief Registeres a function that is called when the MCP2521 triggers an interrupt
|
||||
*
|
||||
* @param handler This function is called when the MCP2521 triggers an interrupt
|
||||
* @param arg Arguments passed to the handler-function
|
||||
*/
|
||||
virtual void registerIntHandler(intHandlerFunction_t handler, void * arg) = 0;
|
||||
|
||||
/**
|
||||
* @overload
|
||||
* @brief justed sends a 8bit command to the MCP2521
|
||||
*
|
||||
* @param cmd command to send
|
||||
*/
|
||||
virtual void execute(uint8_t cmd) = 0;
|
||||
|
||||
/**
|
||||
* @overload
|
||||
* @brief executes a command (8 bit) with an address (8 bit)
|
||||
*
|
||||
* @param cmd 8 bit command
|
||||
* @param address 8 bit address
|
||||
*/
|
||||
virtual void execute(uint8_t cmd, uint8_t address) = 0;
|
||||
|
||||
/**
|
||||
*
|
||||
* @brief Executes a read from the MCP2521 with command, data buffer, length and address
|
||||
* @overload
|
||||
*
|
||||
* @param cmd Command to MCP2521
|
||||
* @param data Data buffer to store the read data
|
||||
* @param length How many bytes to read
|
||||
* @param address Address to read from
|
||||
*/
|
||||
virtual void read(uint8_t cmd, uint8_t *data, size_t length, uint8_t address) = 0;
|
||||
|
||||
/**
|
||||
* @brief Executes a read from the MCP2521 with command, data buffer and length
|
||||
* @overload
|
||||
*
|
||||
* @param cmd Command to MCP2521
|
||||
* @param data Data buffer to store the read data
|
||||
* @param length How many bytes to read
|
||||
*/
|
||||
virtual void read(uint8_t cmd, uint8_t *data, size_t length) = 0;
|
||||
|
||||
/**
|
||||
* @brief Executes a read from the MCP2521 with command and address, returns just one byte
|
||||
*
|
||||
* @param cmd Command to MCP2521
|
||||
* @param address Address to read from
|
||||
* @return uint8_t
|
||||
*/
|
||||
virtual uint8_t read(uint8_t cmd, uint8_t address) = 0;
|
||||
|
||||
/**
|
||||
* @brief Executes a read from the MCP2521 with command, returns just one byte
|
||||
*
|
||||
* @param cmd Command to MCP2521
|
||||
* @return uint8_t
|
||||
*/
|
||||
virtual uint8_t read(uint8_t cmd) = 0;
|
||||
|
||||
/**
|
||||
* @brief Writes data to the MCP2521 with command, data buffer, length and address
|
||||
*
|
||||
* @param cmd Command to MCP2521
|
||||
* @param data Data buffer to write
|
||||
* @param length Length of the data buffer
|
||||
* @param address Where to write the data
|
||||
*/
|
||||
virtual void write(uint8_t cmd, uint8_t *data, size_t length, uint8_t address) = 0;
|
||||
|
||||
/**
|
||||
* @brief Wirites data to the MCP2521 with command, data buffer and length
|
||||
*
|
||||
* @param cmd Command to MCP2521
|
||||
* @param data Data buffer to write
|
||||
* @param length Length of the data buffer
|
||||
*/
|
||||
virtual void write(uint8_t cmd, uint8_t *data, size_t length) = 0;
|
||||
|
||||
/**
|
||||
* @brief Writes data to the MCP2521 with command, data (on byte) and address
|
||||
*
|
||||
* @param cmd Command to MCP2521
|
||||
* @param data Data byte to write
|
||||
* @param address Where to write the data
|
||||
*/
|
||||
virtual void write(uint8_t cmd, uint8_t data, uint8_t address) = 0;
|
||||
|
||||
/**
|
||||
* @brief Writes to the MCP2521 with command and data (one byte)
|
||||
*
|
||||
* @param cmd Command to MCP2521
|
||||
* @param data Data byte to write
|
||||
*/
|
||||
virtual void write(uint8_t cmd, uint8_t data) = 0;
|
||||
};
|
||||
|
||||
|
||||
Reference in New Issue
Block a user