diff --git a/.gitignore b/.gitignore index 259148f..a368c67 100644 --- a/.gitignore +++ b/.gitignore @@ -1,32 +1,5 @@ -# Prerequisites -*.d - -# Compiled Object files -*.slo -*.lo -*.o -*.obj - -# Precompiled Headers -*.gch -*.pch - -# Compiled Dynamic libraries -*.so -*.dylib -*.dll - -# Fortran module files -*.mod -*.smod - -# Compiled Static libraries -*.lai -*.la -*.a -*.lib - -# Executables -*.exe -*.out -*.app +.pioenvs +.piolibdeps +.vscode/.browse.c_cpp.db* +.vscode/c_cpp_properties.json +.vscode/launch.json \ No newline at end of file diff --git a/LICENSE b/LICENSE index 44a1223..9927f42 100644 --- a/LICENSE +++ b/LICENSE @@ -1,21 +1,21 @@ -MIT License - -Copyright (c) 2018 Michael Wagner - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. +MIT License + +Copyright (c) 2018 Michael Wagner + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/README.md b/README.md index eaedbb5..dea1a5a 100644 --- a/README.md +++ b/README.md @@ -1,2 +1,24 @@ -# ESP32-Arduino-CAN -An Arduino CAN-Bus library for ESP32 +# Arduino Library for the ESP32 CAN Bus (ESP32-Arduino-CAN) + +## Features + +* Support the CAN Bus from the ESP32 (SJA1000) +* CAN Messages send and receive +* Various Bus speeds +* Standard and Extended Frames +* CAN Message Filter + + + +## Third Party Components + +- Arduino-ESP32-CAN-Demo + - Arduino CAN Demo from [iotsharing.com - nhatuan84](https://github.com/nhatuan84/arduino-esp32-can-demo) + +- ESPCan Driver + - Base CAN Driver from [Thomas Barth](https://github.com/ThomasBarth/ESP32-CAN-Driver) and [Nayar Systems](https://github.com/nayarsystems/ESP32-CAN-Driver) + - General [Component CAN Driver Pack](https://github.com/ESP32DE/ESP32-CAN-Driver/tree/Component_CAN_Driver_Pack) Work for ESP-IDF with menuconfig from [rudi ;-)](http://esp32.de) + +## Usage + +See the examples in the [/examples](examples) folder. \ No newline at end of file diff --git a/examples/esp32can_basic/esp32can_basic.ino b/examples/esp32can_basic/esp32can_basic.ino new file mode 100644 index 0000000..3102ee9 --- /dev/null +++ b/examples/esp32can_basic/esp32can_basic.ino @@ -0,0 +1,64 @@ +#include +#include + +CAN_device_t CAN_cfg; // CAN Config +unsigned long previousMillis = 0; // will store last time a CAN Message was send +const int interval = 1000; // interval at which send CAN Messages (milliseconds) +const int rx_queue_size = 10; // Receive Queue size + +void setup() { + Serial.begin(115200); + Serial.println("Basic Demo - ESP32-Arduino-CAN"); + CAN_cfg.speed = CAN_SPEED_125KBPS; + CAN_cfg.tx_pin_id = GPIO_NUM_5; + CAN_cfg.rx_pin_id = GPIO_NUM_4; + CAN_cfg.rx_queue = xQueueCreate(rx_queue_size, sizeof(CAN_frame_t)); + // Init CAN Module + ESP32Can.CANInit(); +} + +void loop() { + + CAN_frame_t rx_frame; + + unsigned long currentMillis = millis(); + + // Receive next CAN frame from queue + if (xQueueReceive(CAN_cfg.rx_queue, &rx_frame, 3 * portTICK_PERIOD_MS) == pdTRUE) { + + if (rx_frame.FIR.B.FF == CAN_frame_std) { + printf("New standard frame"); + } + else { + printf("New extended frame"); + } + + if (rx_frame.FIR.B.RTR == CAN_RTR) { + printf(" RTR from 0x%08X, DLC %d\r\n", rx_frame.MsgID, rx_frame.FIR.B.DLC); + } + else { + printf(" from 0x%08X, DLC %d, Data ", rx_frame.MsgID, rx_frame.FIR.B.DLC); + for (int i = 0; i < rx_frame.FIR.B.DLC; i++) { + printf("0x%02X ", rx_frame.data.u8[i]); + } + printf("\n"); + } + } + // Send CAN Message + if (currentMillis - previousMillis >= interval) { + previousMillis = currentMillis; + CAN_frame_t tx_frame; + tx_frame.FIR.B.FF = CAN_frame_std; + tx_frame.MsgID = 0x001; + tx_frame.FIR.B.DLC = 8; + tx_frame.data.u8[0] = 0x00; + tx_frame.data.u8[1] = 0x01; + tx_frame.data.u8[2] = 0x02; + tx_frame.data.u8[3] = 0x03; + tx_frame.data.u8[4] = 0x04; + tx_frame.data.u8[5] = 0x05; + tx_frame.data.u8[6] = 0x06; + tx_frame.data.u8[7] = 0x07; + ESP32Can.CANWriteFrame(&tx_frame); + } +} diff --git a/examples/esp32can_filter/esp32can_filter.ino b/examples/esp32can_filter/esp32can_filter.ino new file mode 100644 index 0000000..1743d7e --- /dev/null +++ b/examples/esp32can_filter/esp32can_filter.ino @@ -0,0 +1,65 @@ +#include +#include + +CAN_device_t CAN_cfg; // CAN Config +const int rx_queue_size = 10; // Receive Queue size + +void setup() { + Serial.begin(115200); + Serial.println("Filter Demo - ESP32-Arduino-CAN"); + CAN_cfg.speed = CAN_SPEED_125KBPS; + CAN_cfg.tx_pin_id = GPIO_NUM_5; + CAN_cfg.rx_pin_id = GPIO_NUM_4; + CAN_cfg.rx_queue = xQueueCreate(rx_queue_size, sizeof(CAN_frame_t)); + + // Set CAN Filter + // See in the SJA1000 Datasheet chapter "6.4.15 Acceptance filter" + // and the APPLICATION NOTE AN97076 chapter "4.1.2 Acceptance Filter" + // for PeliCAN Mode + CAN_filter_t p_filter; + p_filter.FM = Single_Mode; + + p_filter.ACR0 = 0x29; + p_filter.ACR1 = 0; + p_filter.ACR2 = 0; + p_filter.ACR3 = 0; + + p_filter.AMR0 = 0; + p_filter.AMR1 = 0xFF; + p_filter.AMR2 = 0xFF; + p_filter.AMR3 = 0xFF; + ESP32Can.CANConfigFilter(&p_filter); + + // Init CAN Module + ESP32Can.CANInit(); +} + +void loop() { + + CAN_frame_t rx_frame; + + unsigned long currentMillis = millis(); + + // Receive next CAN frame from queue + if (xQueueReceive(CAN_cfg.rx_queue, &rx_frame, 3 * portTICK_PERIOD_MS) == pdTRUE) { + + if (rx_frame.FIR.B.FF == CAN_frame_std) { + printf("New standard frame"); + } + else { + printf("New extended frame"); + } + + if (rx_frame.FIR.B.RTR == CAN_RTR) { + printf(" RTR from 0x%08X, DLC %d\r\n", rx_frame.MsgID, rx_frame.FIR.B.DLC); + } + else { + printf(" from 0x%08X, DLC %d, Data ", rx_frame.MsgID, rx_frame.FIR.B.DLC); + for (int i = 0; i < rx_frame.FIR.B.DLC; i++) { + printf("0x%02X ", rx_frame.data.u8[i]); + } + printf("\n"); + } + } +} + diff --git a/examples/esp32can_mirror/esp32can_mirror.ino b/examples/esp32can_mirror/esp32can_mirror.ino new file mode 100644 index 0000000..59d2466 --- /dev/null +++ b/examples/esp32can_mirror/esp32can_mirror.ino @@ -0,0 +1,45 @@ +#include +#include + +CAN_device_t CAN_cfg; // CAN Config +const int rx_queue_size = 10; // Receive Queue size + +void setup() { + Serial.begin(115200); + Serial.println("Mirror Demo - ESP32-Arduino-CAN"); + CAN_cfg.speed = CAN_SPEED_125KBPS; + CAN_cfg.tx_pin_id = GPIO_NUM_5; + CAN_cfg.rx_pin_id = GPIO_NUM_4; + CAN_cfg.rx_queue = xQueueCreate(rx_queue_size, sizeof(CAN_frame_t)); + // Init CAN Module + ESP32Can.CANInit(); +} + +void loop() { + CAN_frame_t rx_frame; + //receive next CAN frame from queue + if (xQueueReceive(CAN_cfg.rx_queue, &rx_frame, 3 * portTICK_PERIOD_MS) == pdTRUE) { + + if (rx_frame.FIR.B.FF == CAN_frame_std) { + printf("New standard frame"); + } + else { + printf("New extended frame"); + } + + if (rx_frame.FIR.B.RTR == CAN_RTR) { + printf(" RTR from 0x%08X, DLC %d\r\n", rx_frame.MsgID, rx_frame.FIR.B.DLC); + } + else { + printf(" from 0x%08X, DLC %d, Data ", rx_frame.MsgID, rx_frame.FIR.B.DLC); + for (int i = 0; i < rx_frame.FIR.B.DLC; i++) { + printf("0x%02X ", rx_frame.data.u8[i]); + } + printf("\n"); + } + + //respond to sender + ESP32Can.CANWriteFrame(&rx_frame); + } + +} diff --git a/keywords.txt b/keywords.txt new file mode 100644 index 0000000..8e0baea --- /dev/null +++ b/keywords.txt @@ -0,0 +1,20 @@ +####################################### +# Syntax Coloring Map ESP32CAN +####################################### + +####################################### +# Datatypes (KEYWORD1) +####################################### + +ESP32CAN KEYWORD1 ESP32CAN + +####################################### +# Methods and Functions (KEYWORD2) +####################################### +CANInit KEYWORD2 +CANWriteFrame KEYWORD2 +CANStop KEYWORD2 +CANConfigFilter KEYWORD2 +####################################### +# Constants (LITERAL1) +####################################### diff --git a/library.properties b/library.properties new file mode 100644 index 0000000..9e0b21b --- /dev/null +++ b/library.properties @@ -0,0 +1,9 @@ +name=ESP32CAN +version=0.0.1 +author=Michael Wagner +maintainer=https://github.com/miwagner +sentence=ESP32-Arduino-CAN +paragraph=ESP32-Arduino-CAN +category=Device Control +url=https://github.com/miwagner/ESP32-Arduino-CAN +architectures=esp32 diff --git a/src/CAN.c b/src/CAN.c new file mode 100644 index 0000000..259a32c --- /dev/null +++ b/src/CAN.c @@ -0,0 +1,299 @@ +/** + * @section License + * + * The MIT License (MIT) + * + * Copyright (c) 2017, Thomas Barth, barth-dev.de + * 2017, Jaime Breva, jbreva@nayarsystems.com + * 2018, Michael Wagner, mw@iot-make.de + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + * + */ + +#include "CAN.h" + +#include "freertos/FreeRTOS.h" +#include "freertos/queue.h" + +#include "esp_intr.h" +#include "soc/dport_reg.h" +#include + +#include "driver/gpio.h" + +#include "can_regdef.h" +#include "CAN_config.h" + +// CAN Filter - no acceptance filter +static CAN_filter_t __filter = { Dual_Mode, 0, 0, 0, 0, 0Xff, 0Xff, 0Xff, 0Xff }; + +static void CAN_read_frame_phy(); +static void CAN_isr(void *arg_p); +static int CAN_write_frame_phy(const CAN_frame_t *p_frame); +static SemaphoreHandle_t sem_tx_complete; + +static void CAN_isr(void *arg_p) { + + // Interrupt flag buffer + __CAN_IRQ_t interrupt; + BaseType_t higherPriorityTaskWoken = pdFALSE; + + // Read interrupt status and clear flags + interrupt = MODULE_CAN->IR.U; + + // Handle RX frame available interrupt + if ((interrupt & __CAN_IRQ_RX) != 0) + CAN_read_frame_phy(&higherPriorityTaskWoken); + + // Handle TX complete interrupt + // Handle error interrupts. + if ((interrupt & (__CAN_IRQ_TX | __CAN_IRQ_ERR //0x4 + | __CAN_IRQ_DATA_OVERRUN // 0x8 + | __CAN_IRQ_WAKEUP // 0x10 + | __CAN_IRQ_ERR_PASSIVE // 0x20 + | __CAN_IRQ_ARB_LOST // 0x40 + | __CAN_IRQ_BUS_ERR // 0x80 + )) != 0) { + xSemaphoreGive(sem_tx_complete); + } + + // check if any higher priority task has been woken by any handler + if (higherPriorityTaskWoken) + portYIELD_FROM_ISR(); +} + +static void CAN_read_frame_phy(BaseType_t *higherPriorityTaskWoken) { + + // byte iterator + uint8_t __byte_i; + + // frame read buffer + CAN_frame_t __frame; + + // check if we have a queue. If not, operation is aborted. + if (CAN_cfg.rx_queue == NULL) { + // Let the hardware know the frame has been read. + MODULE_CAN->CMR.B.RRB = 1; + return; + } + + // get FIR + __frame.FIR.U = MODULE_CAN->MBX_CTRL.FCTRL.FIR.U; + + // check if this is a standard or extended CAN frame + // standard frame + if (__frame.FIR.B.FF == CAN_frame_std) { + + // Get Message ID + __frame.MsgID = _CAN_GET_STD_ID; + + // deep copy data bytes + for (__byte_i = 0; __byte_i < __frame.FIR.B.DLC; __byte_i++) + __frame.data.u8[__byte_i] = MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.STD.data[__byte_i]; + } + // extended frame + else { + + // Get Message ID + __frame.MsgID = _CAN_GET_EXT_ID; + + // deep copy data bytes + for (__byte_i = 0; __byte_i < __frame.FIR.B.DLC; __byte_i++) + __frame.data.u8[__byte_i] = MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.EXT.data[__byte_i]; + } + + // send frame to input queue + xQueueSendToBackFromISR(CAN_cfg.rx_queue, &__frame, higherPriorityTaskWoken); + + // Let the hardware know the frame has been read. + MODULE_CAN->CMR.B.RRB = 1; +} + +static int CAN_write_frame_phy(const CAN_frame_t *p_frame) { + + // byte iterator + uint8_t __byte_i; + + // copy frame information record + MODULE_CAN->MBX_CTRL.FCTRL.FIR.U = p_frame->FIR.U; + + // standard frame + if (p_frame->FIR.B.FF == CAN_frame_std) { + + // Write message ID + _CAN_SET_STD_ID(p_frame->MsgID); + + // Copy the frame data to the hardware + for (__byte_i = 0; __byte_i < p_frame->FIR.B.DLC; __byte_i++) + MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.STD.data[__byte_i] = p_frame->data.u8[__byte_i]; + + } + // extended frame + else { + + // Write message ID + _CAN_SET_EXT_ID(p_frame->MsgID); + + // Copy the frame data to the hardware + for (__byte_i = 0; __byte_i < p_frame->FIR.B.DLC; __byte_i++) + MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.EXT.data[__byte_i] = p_frame->data.u8[__byte_i]; + } + + // Transmit frame + MODULE_CAN->CMR.B.TR = 1; + + return 0; +} + +int CAN_init() { + + // Time quantum + double __tq; + + // enable module + DPORT_SET_PERI_REG_MASK(DPORT_PERIP_CLK_EN_REG, DPORT_CAN_CLK_EN); + DPORT_CLEAR_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_CAN_RST); + + // configure TX pin + gpio_set_level(CAN_cfg.tx_pin_id, 1); + gpio_set_direction(CAN_cfg.tx_pin_id, GPIO_MODE_OUTPUT); + gpio_matrix_out(CAN_cfg.tx_pin_id, CAN_TX_IDX, 0, 0); + gpio_pad_select_gpio(CAN_cfg.tx_pin_id); + + // configure RX pin + gpio_set_direction(CAN_cfg.rx_pin_id, GPIO_MODE_INPUT); + gpio_matrix_in(CAN_cfg.rx_pin_id, CAN_RX_IDX, 0); + gpio_pad_select_gpio(CAN_cfg.rx_pin_id); + + // set to PELICAN mode + MODULE_CAN->CDR.B.CAN_M = 0x1; + + // synchronization jump width is the same for all baud rates + MODULE_CAN->BTR0.B.SJW = 0x1; + + // TSEG2 is the same for all baud rates + MODULE_CAN->BTR1.B.TSEG2 = 0x1; + + // select time quantum and set TSEG1 + switch (CAN_cfg.speed) { + case CAN_SPEED_1000KBPS: + MODULE_CAN->BTR1.B.TSEG1 = 0x4; + __tq = 0.125; + break; + + case CAN_SPEED_800KBPS: + MODULE_CAN->BTR1.B.TSEG1 = 0x6; + __tq = 0.125; + break; + + case CAN_SPEED_200KBPS: + MODULE_CAN->BTR1.B.TSEG1 = 0xc; + MODULE_CAN->BTR1.B.TSEG2 = 0x5; + __tq = 0.25; + break; + + default: + MODULE_CAN->BTR1.B.TSEG1 = 0xc; + __tq = ((float) 1000 / CAN_cfg.speed) / 16; + } + + // set baud rate prescaler + MODULE_CAN->BTR0.B.BRP = (uint8_t) round((((APB_CLK_FREQ * __tq) / 2) - 1) / 1000000) - 1; + + /* Set sampling + * 1 -> triple; the bus is sampled three times; recommended for low/medium speed buses (class A and B) where + * filtering spikes on the bus line is beneficial 0 -> single; the bus is sampled once; recommended for high speed + * buses (SAE class C)*/ + MODULE_CAN->BTR1.B.SAM = 0x1; + + // enable all interrupts + MODULE_CAN->IER.U = 0xff; + + // Set acceptance filter + MODULE_CAN->MOD.B.AFM = __filter.FM; + MODULE_CAN->MBX_CTRL.ACC.CODE[0] = __filter.ACR0; + MODULE_CAN->MBX_CTRL.ACC.CODE[1] = __filter.ACR1; + MODULE_CAN->MBX_CTRL.ACC.CODE[2] = __filter.ACR2; + MODULE_CAN->MBX_CTRL.ACC.CODE[3] = __filter.ACR3; + MODULE_CAN->MBX_CTRL.ACC.MASK[0] = __filter.AMR0; + MODULE_CAN->MBX_CTRL.ACC.MASK[1] = __filter.AMR1; + MODULE_CAN->MBX_CTRL.ACC.MASK[2] = __filter.AMR2; + MODULE_CAN->MBX_CTRL.ACC.MASK[3] = __filter.AMR3; + + // set to normal mode + MODULE_CAN->OCR.B.OCMODE = __CAN_OC_NOM; + + // clear error counters + MODULE_CAN->TXERR.U = 0; + MODULE_CAN->RXERR.U = 0; + (void) MODULE_CAN->ECC; + + // clear interrupt flags + (void) MODULE_CAN->IR.U; + + // install CAN ISR + esp_intr_alloc(ETS_CAN_INTR_SOURCE, 0, CAN_isr, NULL, NULL); + + // allocate the tx complete semaphore + sem_tx_complete = xSemaphoreCreateBinary(); + + // Showtime. Release Reset Mode. + MODULE_CAN->MOD.B.RM = 0; + + return 0; +} + +int CAN_write_frame(const CAN_frame_t *p_frame) { + if (sem_tx_complete == NULL) { + return -1; + } + + // Write the frame to the controller + CAN_write_frame_phy(p_frame); + + // wait for the frame tx to complete + xSemaphoreTake(sem_tx_complete, portMAX_DELAY); + + return 0; +} + +int CAN_stop() { + // enter reset mode + MODULE_CAN->MOD.B.RM = 1; + + return 0; +} + +int CAN_config_filter(const CAN_filter_t* p_filter) { + + __filter.FM = p_filter->FM; + __filter.ACR0 = p_filter->ACR0; + __filter.ACR1 = p_filter->ACR1; + __filter.ACR2 = p_filter->ACR2; + __filter.ACR3 = p_filter->ACR3; + __filter.AMR0 = p_filter->AMR0; + __filter.AMR1 = p_filter->AMR1; + __filter.AMR2 = p_filter->AMR2; + __filter.AMR3 = p_filter->AMR3; + + return 0; +} \ No newline at end of file diff --git a/src/CAN.h b/src/CAN.h new file mode 100644 index 0000000..b7f5fd8 --- /dev/null +++ b/src/CAN.h @@ -0,0 +1,130 @@ +/** + * @section License + * + * The MIT License (MIT) + * + * Copyright (c) 2017, Thomas Barth, barth-dev.de + * 2018, Michael Wagner, mw@iot-make.de + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +#ifndef __DRIVERS_CAN_H__ +#define __DRIVERS_CAN_H__ + +#include +#include "CAN_config.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * \brief CAN frame type (standard/extended) + */ +typedef enum { + CAN_frame_std = 0, /**< Standard frame, using 11 bit identifer. */ + CAN_frame_ext = 1 /**< Extended frame, using 29 bit identifer. */ +} CAN_frame_format_t; + +/** + * \brief CAN RTR + */ +typedef enum { + CAN_no_RTR = 0, /**< No RTR frame. */ + CAN_RTR = 1 /**< RTR frame. */ +} CAN_RTR_t; + +/** \brief Frame information record type */ +typedef union { + uint32_t U; /**< \brief Unsigned access */ + struct { + uint8_t DLC : 4; /**< \brief [3:0] DLC, Data length container */ + unsigned int unknown_2 : 2; /**< \brief \internal unknown */ + CAN_RTR_t RTR : 1; /**< \brief [6:6] RTR, Remote Transmission Request */ + CAN_frame_format_t FF : 1; /**< \brief [7:7] Frame Format, see# CAN_frame_format_t*/ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved */ + } B; +} CAN_FIR_t; + +/** \brief CAN Frame structure */ +typedef struct { + CAN_FIR_t FIR; /**< \brief Frame information record*/ + uint32_t MsgID; /**< \brief Message ID */ + union { + uint8_t u8[8]; /**< \brief Payload byte access*/ + uint32_t u32[2]; /**< \brief Payload u32 access*/ + } data; +} CAN_frame_t; + +typedef enum { + Dual_Mode=0, /**< \brief The dual acceptance filter option is enabled (two filters, each with the length of 16 bit are active) */ + Single_Mode=1 /**< \brief The single acceptance filter option is enabled (one filter with the length of 32 bit is active) */ +} CAN_filter_mode_t; + +/** \brief CAN Filter structure */ +typedef struct { + CAN_filter_mode_t FM:1; /**< \brief [0:0] Filter Mode */ + uint8_t ACR0; /**< \brief Acceptance Code Register ACR0 */ + uint8_t ACR1; /**< \brief Acceptance Code Register ACR1 */ + uint8_t ACR2; /**< \brief Acceptance Code Register ACR2 */ + uint8_t ACR3; /**< \brief Acceptance Code Register ACR3 */ + uint8_t AMR0; /**< \brief Acceptance Mask Register AMR0 */ + uint8_t AMR1; /**< \brief Acceptance Mask Register AMR1 */ + uint8_t AMR2; /**< \brief Acceptance Mask Register AMR2 */ + uint8_t AMR3; /**< \brief Acceptance Mask Register AMR3 */ +} CAN_filter_t; + +/** + * \brief Initialize the CAN Module + * + * \return 0 CAN Module had been initialized + */ +int CAN_init(void); + +/** + * \brief Send a can frame + * + * \param p_frame Pointer to the frame to be send, see #CAN_frame_t + * \return 0 Frame has been written to the module + */ +int CAN_write_frame(const CAN_frame_t *p_frame); + +/** + * \brief Stops the CAN Module + * + * \return 0 CAN Module was stopped + */ +int CAN_stop(void); + +/** + * \brief Config CAN Filter, must call before CANInit() + * + * \param p_filter Pointer to the filter, see #CAN_filter_t + * \return 0 CAN Filter had been initialized + */ +int CAN_config_filter(const CAN_filter_t* p_filter); + + +#ifdef __cplusplus +} +#endif + +#endif diff --git a/src/CAN_config.h b/src/CAN_config.h new file mode 100644 index 0000000..2840a3c --- /dev/null +++ b/src/CAN_config.h @@ -0,0 +1,71 @@ +/** + * @section License + * + * The MIT License (MIT) + * + * Copyright (c) 2017, Thomas Barth, barth-dev.de + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +#ifndef __DRIVERS_CAN_CFG_H__ +#define __DRIVERS_CAN_CFG_H__ + +#include "freertos/FreeRTOS.h" +#include "freertos/queue.h" +#include "freertos/task.h" +#include "driver/gpio.h" +#include "freertos/semphr.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** \brief CAN Node Bus speed */ +typedef enum { + CAN_SPEED_100KBPS = 100, /**< \brief CAN Node runs at 100kBit/s. */ + CAN_SPEED_125KBPS = 125, /**< \brief CAN Node runs at 125kBit/s. */ + CAN_SPEED_200KBPS = 200, /**< \brief CAN Node runs at 250kBit/s. */ + CAN_SPEED_250KBPS = 250, /**< \brief CAN Node runs at 250kBit/s. */ + CAN_SPEED_500KBPS = 500, /**< \brief CAN Node runs at 500kBit/s. */ + CAN_SPEED_800KBPS = 800, /**< \brief CAN Node runs at 800kBit/s. */ + CAN_SPEED_1000KBPS = 1000 /**< \brief CAN Node runs at 1000kBit/s. */ +} CAN_speed_t; + +/** \brief CAN configuration structure */ +typedef struct { + CAN_speed_t speed; /**< \brief CAN speed. */ + gpio_num_t tx_pin_id; /**< \brief TX pin. */ + gpio_num_t rx_pin_id; /**< \brief RX pin. */ + QueueHandle_t rx_queue; /**< \brief Handler to FreeRTOS RX queue. */ + QueueHandle_t tx_queue; /**< \brief Handler to FreeRTOS TX queue. */ + TaskHandle_t tx_handle; /**< \brief Handler to FreeRTOS TX task. */ + TaskHandle_t rx_handle; /**< \brief Handler to FreeRTOS RX task. */ +} CAN_device_t; + +/** \brief CAN configuration reference */ +extern CAN_device_t CAN_cfg; + +#ifdef __cplusplus +} +#endif + +#endif /* __DRIVERS_CAN_CFG_H__ */ diff --git a/src/ESP32CAN.cpp b/src/ESP32CAN.cpp new file mode 100644 index 0000000..1412b4a --- /dev/null +++ b/src/ESP32CAN.cpp @@ -0,0 +1,20 @@ +#include "ESP32CAN.h" + +int ESP32CAN::CANInit() +{ + return CAN_init(); +} +int ESP32CAN::CANWriteFrame(const CAN_frame_t* p_frame) +{ + return CAN_write_frame(p_frame); +} +int ESP32CAN::CANStop() +{ + return CAN_stop(); +} +int ESP32CAN::CANConfigFilter(const CAN_filter_t* p_filter) +{ + return CAN_config_filter(p_filter); +} + +ESP32CAN ESP32Can; diff --git a/src/ESP32CAN.h b/src/ESP32CAN.h new file mode 100644 index 0000000..0cbe156 --- /dev/null +++ b/src/ESP32CAN.h @@ -0,0 +1,17 @@ +#ifndef ESP32CAN_H +#define ESP32CAN_H + +#include "CAN_config.h" +#include "CAN.h" + +class ESP32CAN +{ + public: + int CANInit(); + int CANConfigFilter(const CAN_filter_t* p_filter); + int CANWriteFrame(const CAN_frame_t* p_frame); + int CANStop(); +}; + +extern ESP32CAN ESP32Can; +#endif diff --git a/src/can_regdef.h b/src/can_regdef.h new file mode 100644 index 0000000..967ac81 --- /dev/null +++ b/src/can_regdef.h @@ -0,0 +1,279 @@ +/** + * @section License + * + * The MIT License (MIT) + * + * Copyright (c) 2017, Thomas Barth, barth-dev.de + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, copy, + * modify, merge, publish, distribute, sublicense, and/or sell copies + * of the Software, and to permit persons to whom the Software is + * furnished to do so, subject to the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + +#ifndef __DRIVERS_CAN_REGDEF_H_ +#define __DRIVERS_CAN_REGDEF_H_ + +#include "CAN.h" //CAN_FIR_t + +#ifdef __cplusplus +extern "C" { +#endif + +/** \brief Start address of CAN registers */ +#define MODULE_CAN ((volatile CAN_Module_t *) 0x3ff6b000) + +/** \brief Get standard message ID */ +#define _CAN_GET_STD_ID \ + (((uint32_t) MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.STD.ID[0] << 3) | (MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.STD.ID[1] >> 5)) + +/** \brief Get extended message ID */ +#define _CAN_GET_EXT_ID \ + (((uint32_t) MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.EXT.ID[0] << 21) | \ + (MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.EXT.ID[1] << 13) | (MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.EXT.ID[2] << 5) | \ + (MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.EXT.ID[3] >> 3)) + +/** \brief Set standard message ID */ +#define _CAN_SET_STD_ID(x) \ + MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.STD.ID[0] = ((x) >> 3); \ + MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.STD.ID[1] = ((x) << 5); + +/** \brief Set extended message ID */ +#define _CAN_SET_EXT_ID(x) \ + MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.EXT.ID[0] = ((x) >> 21); \ + MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.EXT.ID[1] = ((x) >> 13); \ + MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.EXT.ID[2] = ((x) >> 5); \ + MODULE_CAN->MBX_CTRL.FCTRL.TX_RX.EXT.ID[3] = ((x) << 3); + +/** \brief Interrupt status register */ +typedef enum { + __CAN_IRQ_RX = BIT(0), /**< \brief RX Interrupt */ + __CAN_IRQ_TX = BIT(1), /**< \brief TX Interrupt */ + __CAN_IRQ_ERR = BIT(2), /**< \brief Error Interrupt */ + __CAN_IRQ_DATA_OVERRUN = BIT(3), /**< \brief Data Overrun Interrupt */ + __CAN_IRQ_WAKEUP = BIT(4), /**< \brief Wakeup Interrupt */ + __CAN_IRQ_ERR_PASSIVE = BIT(5), /**< \brief Passive Error Interrupt */ + __CAN_IRQ_ARB_LOST = BIT(6), /**< \brief Arbitration lost interrupt */ + __CAN_IRQ_BUS_ERR = BIT(7), /**< \brief Bus error Interrupt */ +} __CAN_IRQ_t; + +/** \brief OCMODE options. */ +typedef enum { + __CAN_OC_BOM = 0b00, /**< \brief bi-phase output mode */ + __CAN_OC_TOM = 0b01, /**< \brief test output mode */ + __CAN_OC_NOM = 0b10, /**< \brief normal output mode */ + __CAN_OC_COM = 0b11, /**< \brief clock output mode */ +} __CAN_OCMODE_t; + +/** + * CAN controller (SJA1000). + */ +typedef struct { + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int RM : 1; /**< \brief MOD.0 Reset Mode */ + unsigned int LOM : 1; /**< \brief MOD.1 Listen Only Mode */ + unsigned int STM : 1; /**< \brief MOD.2 Self Test Mode */ + unsigned int AFM : 1; /**< \brief MOD.3 Acceptance Filter Mode */ + unsigned int SM : 1; /**< \brief MOD.4 Sleep Mode */ + unsigned int reserved_27 : 27; /**< \brief \internal Reserved */ + } B; + } MOD; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int TR : 1; /**< \brief CMR.0 Transmission Request */ + unsigned int AT : 1; /**< \brief CMR.1 Abort Transmission */ + unsigned int RRB : 1; /**< \brief CMR.2 Release Receive Buffer */ + unsigned int CDO : 1; /**< \brief CMR.3 Clear Data Overrun */ + unsigned int GTS : 1; /**< \brief CMR.4 Go To Sleep */ + unsigned int reserved_27 : 27; /**< \brief \internal Reserved */ + } B; + } CMR; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int RBS : 1; /**< \brief SR.0 Receive Buffer Status */ + unsigned int DOS : 1; /**< \brief SR.1 Data Overrun Status */ + unsigned int TBS : 1; /**< \brief SR.2 Transmit Buffer Status */ + unsigned int TCS : 1; /**< \brief SR.3 Transmission Complete Status */ + unsigned int RS : 1; /**< \brief SR.4 Receive Status */ + unsigned int TS : 1; /**< \brief SR.5 Transmit Status */ + unsigned int ES : 1; /**< \brief SR.6 Error Status */ + unsigned int BS : 1; /**< \brief SR.7 Bus Status */ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved */ + } B; + } SR; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int RI : 1; /**< \brief IR.0 Receive Interrupt */ + unsigned int TI : 1; /**< \brief IR.1 Transmit Interrupt */ + unsigned int EI : 1; /**< \brief IR.2 Error Interrupt */ + unsigned int DOI : 1; /**< \brief IR.3 Data Overrun Interrupt */ + unsigned int WUI : 1; /**< \brief IR.4 Wake-Up Interrupt */ + unsigned int EPI : 1; /**< \brief IR.5 Error Passive Interrupt */ + unsigned int ALI : 1; /**< \brief IR.6 Arbitration Lost Interrupt */ + unsigned int BEI : 1; /**< \brief IR.7 Bus Error Interrupt */ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved */ + } B; + } IR; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int RIE : 1; /**< \brief IER.0 Receive Interrupt Enable */ + unsigned int TIE : 1; /**< \brief IER.1 Transmit Interrupt Enable */ + unsigned int EIE : 1; /**< \brief IER.2 Error Interrupt Enable */ + unsigned int DOIE : 1; /**< \brief IER.3 Data Overrun Interrupt Enable */ + unsigned int WUIE : 1; /**< \brief IER.4 Wake-Up Interrupt Enable */ + unsigned int EPIE : 1; /**< \brief IER.5 Error Passive Interrupt Enable */ + unsigned int ALIE : 1; /**< \brief IER.6 Arbitration Lost Interrupt Enable */ + unsigned int BEIE : 1; /**< \brief IER.7 Bus Error Interrupt Enable */ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved */ + } B; + } IER; + uint32_t RESERVED0; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int BRP : 6; /**< \brief BTR0[5:0] Baud Rate Prescaler */ + unsigned int SJW : 2; /**< \brief BTR0[7:6] Synchronization Jump Width*/ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved */ + } B; + } BTR0; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int TSEG1 : 4; /**< \brief BTR1[3:0] Timing Segment 1 */ + unsigned int TSEG2 : 3; /**< \brief BTR1[6:4] Timing Segment 2*/ + unsigned int SAM : 1; /**< \brief BTR1.7 Sampling*/ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved */ + } B; + } BTR1; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int OCMODE : 2; /**< \brief OCR[1:0] Output Control Mode, see # */ + unsigned int OCPOL0 : 1; /**< \brief OCR.2 Output Control Polarity 0 */ + unsigned int OCTN0 : 1; /**< \brief OCR.3 Output Control Transistor N0 */ + unsigned int OCTP0 : 1; /**< \brief OCR.4 Output Control Transistor P0 */ + unsigned int OCPOL1 : 1; /**< \brief OCR.5 Output Control Polarity 1 */ + unsigned int OCTN1 : 1; /**< \brief OCR.6 Output Control Transistor N1 */ + unsigned int OCTP1 : 1; /**< \brief OCR.7 Output Control Transistor P1 */ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved */ + } B; + } OCR; + uint32_t RESERVED1[2]; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int ALC : 8; /**< \brief ALC[7:0] Arbitration Lost Capture */ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved */ + } B; + } ALC; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int ECC : 8; /**< \brief ECC[7:0] Error Code Capture */ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved */ + } B; + } ECC; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int EWLR : 8; /**< \brief EWLR[7:0] Error Warning Limit */ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved */ + } B; + } EWLR; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int RXERR : 8; /**< \brief RXERR[7:0] Receive Error Counter */ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved */ + } B; + } RXERR; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int TXERR : 8; /**< \brief TXERR[7:0] Transmit Error Counter */ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved */ + } B; + } TXERR; + + union { + struct { + uint32_t CODE[4]; /**< \brief Acceptance Message ID */ + uint32_t MASK[4]; /**< \brief Acceptance Mask */ + uint32_t RESERVED2[5]; + } ACC; /**< \brief Acceptance filtering */ + struct { + CAN_FIR_t FIR; /**< \brief Frame information record */ + union { + struct { + uint32_t ID[2]; /**< \brief Standard frame message-ID*/ + uint32_t data[8]; /**< \brief Standard frame payload */ + uint32_t reserved[2]; + } STD; /**< \brief Standard frame format */ + struct { + uint32_t ID[4]; /**< \brief Extended frame message-ID*/ + uint32_t data[8]; /**< \brief Extended frame payload */ + } EXT; /**< \brief Extended frame format */ + } TX_RX; /**< \brief RX/TX interface */ + } FCTRL; /**< \brief Function control regs */ + } MBX_CTRL; /**< \brief Mailbox control */ + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int RMC : 8; /**< \brief RMC[7:0] RX Message Counter */ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved Enable */ + } B; + } RMC; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int RBSA : 8; /**< \brief RBSA[7:0] RX Buffer Start Address */ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved Enable */ + } B; + } RBSA; + union { + uint32_t U; /**< \brief Unsigned access */ + struct { + unsigned int COD : 3; /**< \brief CDR[2:0] CLKOUT frequency selector based of fOSC*/ + unsigned int COFF : 1; /**< \brief CDR.3 CLKOUT off*/ + unsigned int reserved_1 : 1; /**< \brief \internal Reserved */ + unsigned int + RXINTEN : 1; /**< \brief CDR.5 This bit allows the TX1 output to be used as a dedicated receive interrupt + output*/ + unsigned int + CBP : 1; /**< \brief CDR.6 allows to bypass the CAN input comparator and is only possible in reset mode.*/ + unsigned int + CAN_M : 1; /**< \brief CDR.7 If CDR.7 is at logic 0 the CAN controller operates in BasicCAN mode. If set to + logic 1 the CAN controller operates in PeliCAN mode. Write access is only possible in reset + mode*/ + unsigned int reserved_24 : 24; /**< \brief \internal Reserved */ + } B; + } CDR; + uint32_t IRAM[2]; +} CAN_Module_t; + +#ifdef __cplusplus +} +#endif + +#endif /* __DRIVERS_CAN_REGDEF_H_ */