Updating native can library to ACAN_ESP32

This commit is contained in:
Matt Holmes 2025-08-17 19:23:07 +01:00
parent 62486d9bf1
commit eb047badfd
11 changed files with 1761 additions and 73 deletions

View file

@ -1,8 +1,7 @@
#include "comm_can.h" #include "comm_can.h"
#include <algorithm> #include <algorithm>
#include <map> #include <map>
#include "esp_twai.h" #include "../../lib/pierremolinaro-acan-esp32/ACAN_ESP32.h"
#include "esp_twai_onchip.h"
#include "../../lib/pierremolinaro-ACAN2517FD/ACAN2517FD.h" #include "../../lib/pierremolinaro-ACAN2517FD/ACAN2517FD.h"
#include "../../lib/pierremolinaro-acan2515/ACAN2515.h" #include "../../lib/pierremolinaro-acan2515/ACAN2515.h"
#include "CanReceiver.h" #include "CanReceiver.h"
@ -20,12 +19,6 @@ struct CanReceiverRegistration {
static std::multimap<CAN_Interface, CanReceiverRegistration> can_receivers; static std::multimap<CAN_Interface, CanReceiverRegistration> can_receivers;
// Parameters
twai_node_handle_t node_hdl = NULL;
twai_onchip_node_config_t node_config = {
.tx_queue_depth = 5
};
const uint8_t rx_queue_size = 10; // Receive Queue size const uint8_t rx_queue_size = 10; // Receive Queue size
volatile bool send_ok_native = 0; volatile bool send_ok_native = 0;
volatile bool send_ok_2515 = 0; volatile bool send_ok_2515 = 0;
@ -46,6 +39,8 @@ void register_can_receiver(CanReceiver* receiver, CAN_Interface interface, CAN_S
DEBUG_PRINTF("CAN receiver registered, total: %d\n", can_receivers.size()); DEBUG_PRINTF("CAN receiver registered, total: %d\n", can_receivers.size());
} }
ACAN_ESP32_Settings* settingsespcan;
static const uint32_t QUARTZ_FREQUENCY = CRYSTAL_FREQUENCY_MHZ * 1000000UL; //MHZ configured in USER_SETTINGS.h static const uint32_t QUARTZ_FREQUENCY = CRYSTAL_FREQUENCY_MHZ * 1000000UL; //MHZ configured in USER_SETTINGS.h
SPIClass SPI2515; SPIClass SPI2515;
@ -62,32 +57,6 @@ ACAN2517FDSettings* settings2517;
bool native_can_initialized = false; bool native_can_initialized = false;
static bool twai_rx_callback(twai_node_handle_t handle, const twai_rx_done_event_data_t *edata, void *user_ctx)
{
uint8_t recv_buff[8];
twai_frame_t rx_frame = {
.buffer = recv_buff,
.buffer_len = sizeof(recv_buff),
};
if (ESP_OK == twai_node_receive_from_isr(handle, &rx_frame)) {
CAN_frame frame;
frame.ID = rx_frame.header.id;
frame.DLC = rx_frame.header.dlc;
frame.ext_ID = rx_frame.header.ide;
for (uint8_t i = 0; i < frame.DLC && i < 8; i++) {
frame.data.u8[i] = rx_frame.buffer[i];
}
map_can_frame_to_variable(&frame, CAN_NATIVE);
}
return false;
}
twai_event_callbacks_t user_cbs = {
.on_rx_done = twai_rx_callback
};
bool init_CAN() { bool init_CAN() {
auto nativeIt = can_receivers.find(CAN_NATIVE); auto nativeIt = can_receivers.find(CAN_NATIVE);
@ -108,14 +77,43 @@ bool init_CAN() {
return false; return false;
} }
node_config.io_cfg.tx = tx_pin; settingsespcan = new ACAN_ESP32_Settings((int)nativeIt->second.speed * 1000UL);
node_config.io_cfg.rx = rx_pin; settingsespcan->mRequestedCANMode = ACAN_ESP32_Settings::NormalMode;
node_config.bit_timing.bitrate = (int)nativeIt->second.speed * 1000UL; settingsespcan->mTxPin = tx_pin;
twai_new_node_onchip(&node_config, &node_hdl); settingsespcan->mRxPin = rx_pin;
twai_node_register_event_callbacks(node_hdl, &user_cbs, NULL);
twai_node_enable(node_hdl);
const uint32_t errorCode = ACAN_ESP32::can.begin(*settingsespcan);
if (errorCode == 0)
{
native_can_initialized = true; native_can_initialized = true;
#ifdef DEBUG_LOG
logging.println("Native Can ok");
logging.print("Bit Rate prescaler: ");
logging.println(settingsespcan->mBitRatePrescaler);
logging.print("Time Segment 1: ");
logging.println(settingsespcan->mTimeSegment1);
logging.print("Time Segment 2: ");
logging.println(settingsespcan->mTimeSegment2);
logging.print ("RJW: ") ;
logging.println (settingsespcan->mRJW) ;
logging.print("Triple Sampling: ");
logging.println(settingsespcan->mTripleSampling ? "yes" : "no");
logging.print("Actual bit rate: ");
logging.print(settingsespcan->actualBitRate());
logging.println(" bit/s");
logging.print("Exact bit rate ? ");
logging.println(settingsespcan->exactBitRate() ? "yes" : "no");
logging.print("Sample point: ");
logging.print(settingsespcan->samplePointFromBitStart());
logging.println("%");
#endif // DEBUG_LOG
} else {
#ifdef DEBUG_LOG
logging.print("Error Native Can: 0x");
logging.println(errorCode, HEX);
#endif // DEBUG_LOG
return false;
}
} }
auto addonIt = can_receivers.find(CAN_ADDON_MCP2515); auto addonIt = can_receivers.find(CAN_ADDON_MCP2515);
@ -125,6 +123,7 @@ bool init_CAN() {
auto sck_pin = esp32hal->MCP2515_SCK(); auto sck_pin = esp32hal->MCP2515_SCK();
auto miso_pin = esp32hal->MCP2515_MISO(); auto miso_pin = esp32hal->MCP2515_MISO();
auto mosi_pin = esp32hal->MCP2515_MOSI(); auto mosi_pin = esp32hal->MCP2515_MOSI();
auto rst_pin = esp32hal->MCP2515_RST();
if (!esp32hal->alloc_pins("CAN", cs_pin, int_pin, sck_pin, miso_pin, mosi_pin)) { if (!esp32hal->alloc_pins("CAN", cs_pin, int_pin, sck_pin, miso_pin, mosi_pin)) {
return false; return false;
@ -135,14 +134,15 @@ bool init_CAN() {
#endif // DEBUG_LOG #endif // DEBUG_LOG
gBuffer.initWithSize(25); gBuffer.initWithSize(25);
//ToDo: Refactor this if(rst_pin != GPIO_NUM_NC) {
pinMode(9, OUTPUT); pinMode(rst_pin, OUTPUT);
digitalWrite(9, HIGH); digitalWrite(rst_pin, HIGH);
delay(100); delay(100);
digitalWrite(9, LOW); digitalWrite(rst_pin, LOW);
delay(100); delay(100);
digitalWrite(9, HIGH); digitalWrite(rst_pin, HIGH);
delay(100); delay(100);
}
can2515 = new ACAN2515(cs_pin, SPI2515, int_pin); can2515 = new ACAN2515(cs_pin, SPI2515, int_pin);
@ -156,11 +156,11 @@ bool init_CAN() {
const uint16_t errorCode2515 = can2515->begin(*settings2515, [] { can2515->isr(); }); const uint16_t errorCode2515 = can2515->begin(*settings2515, [] { can2515->isr(); });
if (errorCode2515 == 0) { if (errorCode2515 == 0) {
#ifdef DEBUG_LOG #ifdef DEBUG_LOG
logging.println("Can ok"); logging.println("MCP2515 Can ok");
#endif // DEBUG_LOG #endif // DEBUG_LOG
} else { } else {
#ifdef DEBUG_LOG #ifdef DEBUG_LOG
logging.print("Error Can: 0x"); logging.print("Error MCP2515 Can: 0x");
logging.println(errorCode2515, HEX); logging.println(errorCode2515, HEX);
#endif // DEBUG_LOG #endif // DEBUG_LOG
set_event(EVENT_CANMCP2515_INIT_FAILURE, (uint8_t)errorCode2515); set_event(EVENT_CANMCP2515_INIT_FAILURE, (uint8_t)errorCode2515);
@ -244,21 +244,21 @@ void transmit_can_frame_to_interface(const CAN_frame* tx_frame, int interface) {
#endif #endif
switch (interface) { switch (interface) {
case CAN_NATIVE: case CAN_NATIVE: {
twai_frame_t frame; CANMessage frame;
frame.header.id = tx_frame->ID; frame.id = tx_frame->ID;
frame.header.dlc = tx_frame->DLC; frame.ext = tx_frame->ext_ID;
frame.buffer = tx_frame->data.u8; frame.len = tx_frame->DLC;
frame.buffer_len = tx_frame->DLC; for (uint8_t i = 0; i < frame.len; i++) {
frame.header.ide = tx_frame->ext_ID ? 1 : 0; frame.data[i] = tx_frame->data.u8[i];
}
send_ok_native = twai_node_transmit(node_hdl, &frame, 0); send_ok_native = ACAN_ESP32::can.tryToSend(frame);
if (!send_ok_native) { if (!send_ok_native) {
datalayer.system.info.can_native_send_fail = true; datalayer.system.info.can_native_send_fail = true;
} }
break; } break;
case CAN_ADDON_MCP2515: { case CAN_ADDON_MCP2515: {
//Struct with ACAN2515 library format, needed to use the MCP2515 library for CAN2 //Struct with ACAN2515 library format, needed to use the MCP2515 library for CAN2
CANMessage MCP2515Frame; CANMessage MCP2515Frame;
@ -302,6 +302,10 @@ void transmit_can_frame_to_interface(const CAN_frame* tx_frame, int interface) {
// Receive functions // Receive functions
void receive_can() { void receive_can() {
if (native_can_initialized) {
receive_frame_can_native(); // Receive CAN messages from native CAN port
}
if (can2515) { if (can2515) {
receive_frame_can_addon(); // Receive CAN messages on add-on MCP2515 chip receive_frame_can_addon(); // Receive CAN messages on add-on MCP2515 chip
} }
@ -311,7 +315,25 @@ void receive_can() {
} }
} }
void receive_frame_can_native() { // This section checks if we have a complete CAN message incoming on native CAN port
CANMessage frame;
if (ACAN_ESP32::can.available()) {
if(ACAN_ESP32::can.receive(frame)){
CAN_frame rx_frame;
rx_frame.ID = frame.id;
rx_frame.ext_ID = frame.ext;
rx_frame.DLC = frame.len;
for (uint8_t i = 0; i < frame.len && i < 8; i++) {
rx_frame.data.u8[i] = frame.data[i];
}
//message incoming, pass it on to the handler
map_can_frame_to_variable(&rx_frame, CAN_NATIVE);
}
}
}
void receive_frame_can_addon() { // This section checks if we have a complete CAN message incoming on add-on CAN port void receive_frame_can_addon() { // This section checks if we have a complete CAN message incoming on add-on CAN port
CAN_frame rx_frame; // Struct with our CAN format CAN_frame rx_frame; // Struct with our CAN format
@ -434,8 +456,7 @@ void dump_can_frame(CAN_frame& frame, frameDirection msgDir) {
void stop_can() { void stop_can() {
if (can_receivers.find(CAN_NATIVE) != can_receivers.end()) { if (can_receivers.find(CAN_NATIVE) != can_receivers.end()) {
//ToDo: Implement ACAN_ESP32::can.end();
//ESP32Can.CANStop();
} }
if (can2515) { if (can2515) {
@ -451,8 +472,7 @@ void stop_can() {
void restart_can() { void restart_can() {
if (can_receivers.find(CAN_NATIVE) != can_receivers.end()) { if (can_receivers.find(CAN_NATIVE) != can_receivers.end()) {
//ToDo: Implement ACAN_ESP32::can.begin(*settingsespcan);
//ESP32Can.CANInit();
} }
if (can2515) { if (can2515) {
@ -467,12 +487,10 @@ void restart_can() {
} }
CAN_Speed change_can_speed(CAN_Interface interface, CAN_Speed speed) { CAN_Speed change_can_speed(CAN_Interface interface, CAN_Speed speed) {
//ToDo: Implement auto oldSpeed = (CAN_Speed)settingsespcan->mDesiredBitRate;
//auto oldSpeed = (CAN_Speed)CAN_cfg.speed; if (interface == CAN_Interface::CAN_NATIVE) {
//if (interface == CAN_Interface::CAN_NATIVE) { settingsespcan->mDesiredBitRate = (int)speed;
// CAN_cfg.speed = (CAN_speed_t)speed; ACAN_ESP32::can.begin(*settingsespcan);
// ReInit native CAN module at new speed }
// ESP32Can.CANInit();
//}
return speed; return speed;
} }

View file

@ -109,6 +109,8 @@ class Esp32Hal {
virtual gpio_num_t MCP2515_CS() { return GPIO_NUM_NC; } virtual gpio_num_t MCP2515_CS() { return GPIO_NUM_NC; }
// INT output of MCP2515 // INT output of MCP2515
virtual gpio_num_t MCP2515_INT() { return GPIO_NUM_NC; } virtual gpio_num_t MCP2515_INT() { return GPIO_NUM_NC; }
// Reset pin for MCP2515
virtual gpio_num_t MCP2515_RST() { return GPIO_NUM_NC; }
// CANFD_ADDON defines for MCP2517 // CANFD_ADDON defines for MCP2517
virtual gpio_num_t MCP2517_SCK() { return GPIO_NUM_NC; } virtual gpio_num_t MCP2517_SCK() { return GPIO_NUM_NC; }

View file

@ -16,6 +16,7 @@ class LilyGo2CANHal : public Esp32Hal {
virtual gpio_num_t MCP2515_MISO() { return GPIO_NUM_13; } virtual gpio_num_t MCP2515_MISO() { return GPIO_NUM_13; }
virtual gpio_num_t MCP2515_CS() { return GPIO_NUM_10; } virtual gpio_num_t MCP2515_CS() { return GPIO_NUM_10; }
virtual gpio_num_t MCP2515_INT() { return GPIO_NUM_8; } virtual gpio_num_t MCP2515_INT() { return GPIO_NUM_8; }
virtual gpio_num_t MCP2515_RST() { return GPIO_NUM_9; }
// CANFD_ADDON defines for MCP2517 // CANFD_ADDON defines for MCP2517
virtual gpio_num_t MCP2517_SCK() { return GPIO_NUM_17; } virtual gpio_num_t MCP2517_SCK() { return GPIO_NUM_17; }

View file

@ -0,0 +1,526 @@
//------------------------------------------------------------------------------
// Include files
//------------------------------------------------------------------------------
#include "ACAN_ESP32.h"
//------------------------------------------------------------------------------
//--- Header for periph_module_enable
#if ESP_ARDUINO_VERSION >= ESP_ARDUINO_VERSION_VAL(3, 0, 0)
#include <esp_private/periph_ctrl.h>
#else
#include <driver/periph_ctrl.h>
#endif
#include <hal/clk_gate_ll.h> // For ESP32 board manager
//------------------------------------------------------------------------------
// ESP32 Critical Section
//------------------------------------------------------------------------------
// taskENTER_CRITICAL() of FREE-RTOS is deprecated as portENTER_CRITICAL() in ESP32
//--- https://esp32.com/viewtopic.php?t=1703
static portMUX_TYPE portMux = portMUX_INITIALIZER_UNLOCKED ;
//------------------------------------------------------------------------------
// CONSTRUCTOR for ESP32C6 (2 TWAI controllers)
//------------------------------------------------------------------------------
#ifdef CONFIG_IDF_TARGET_ESP32C6
ACAN_ESP32::ACAN_ESP32 (const uint32_t inBaseAddress,
const uint32_t inTxPinIndexSelector,
const uint32_t inRxPinIndexSelector,
const periph_module_t inPeriphModule,
const periph_interrupt_t inInterruptSource,
const uint32_t inClockEnableAddress) :
twaiBaseAddress (inBaseAddress),
twaiTxPinSelector (inTxPinIndexSelector),
twaiRxPinSelector (inRxPinIndexSelector),
twaiPeriphModule (inPeriphModule),
twaiInterruptSource (inInterruptSource),
twaiClockEnableAddress (inClockEnableAddress),
mAcceptedFrameFormat (ACAN_ESP32_Filter::standardAndExtended),
mDriverReceiveBuffer (),
mDriverTransmitBuffer (),
mDriverIsSending (false) {
}
#endif
//------------------------------------------------------------------------------
// CONSTRUCTOR for others (1 TWAI controller)
//------------------------------------------------------------------------------
#ifndef CONFIG_IDF_TARGET_ESP32C6
ACAN_ESP32::ACAN_ESP32 (void) :
mAcceptedFrameFormat (ACAN_ESP32_Filter::standardAndExtended),
mDriverReceiveBuffer (),
mDriverTransmitBuffer (),
mDriverIsSending (false) {
}
#endif
//------------------------------------------------------------------------------
// Set the GPIO pins
//------------------------------------------------------------------------------
void ACAN_ESP32::setGPIOPins (const gpio_num_t inTXPin,
const gpio_num_t inRXPin) {
//--- Set TX pin
pinMode (inTXPin, OUTPUT) ;
pinMatrixOutAttach (inTXPin, twaiTxPinSelector, false, false) ;
//--- Set RX pin
pinMode (inRXPin, INPUT) ;
pinMatrixInAttach (inRXPin, twaiRxPinSelector, false) ;
}
//------------------------------------------------------------------------------
// Set the Requested Mode
//------------------------------------------------------------------------------
void ACAN_ESP32::setRequestedCANMode (const ACAN_ESP32_Settings & inSettings,
const ACAN_ESP32_Filter & inFilter) {
// ESP32 CAN Operation Mode Configuration
//
// Supported Mode MODE Registers
// - Normal Mode - Reset -> bit(0)
// - No ACK - ListenOnly -> bit(1)
// - Acceptance Filter - SelfTest -> bit(2)
// - Acceptance Filter -> bit(3)
uint8_t requestedMode = 0 ;
switch (inSettings.mRequestedCANMode) {
case ACAN_ESP32_Settings::NormalMode :
break ;
case ACAN_ESP32_Settings::ListenOnlyMode :
requestedMode = TWAI_LISTEN_ONLY_MODE ;
break ;
case ACAN_ESP32_Settings::LoopBackMode :
requestedMode = TWAI_SELF_TEST_MODE ;
break ;
}
if (inFilter.mAMFSingle) {
requestedMode |= TWAI_RX_FILTER_MODE ;
}
TWAI_MODE_REG () = requestedMode | TWAI_RESET_MODE ;
uint32_t unusedResult __attribute__((unused)) = TWAI_MODE_REG () ;
do{
TWAI_MODE_REG () = requestedMode ;
}while ((TWAI_MODE_REG () & TWAI_RESET_MODE) != 0) ;
}
//------------------------------------------------------------------------------
// Set the Bus timing Registers
//------------------------------------------------------------------------------
inline void ACAN_ESP32::setBitTimingSettings (const ACAN_ESP32_Settings & inSettings) {
// BUS TIMING Configuration of ESP32 CAN
// ACAN_ESP32_Settings calculates the best values for the desired bit Rate.
//--- Caution! TWAI_BUS_TIMING_0_REG is specific
#ifdef CONFIG_IDF_TARGET_ESP32
// BTR0 : bit (0 - 5) -> Baud Rate Prescaller (BRP)
// bit (6 - 7) -> Resynchronization Jump Width (RJW)
TWAI_BUS_TIMING_0_REG () =
((inSettings.mRJW - 1) << 6) | // SJW
((inSettings.mBitRatePrescaler - 1) << 0) // BRP
;
#elif defined (CONFIG_IDF_TARGET_ESP32S3)
// BTR0 : bit (00 - 13) -> Baud Rate Prescaller (BRP)
// bit (14 - 15) -> Resynchronization Jump Width (RJW)
TWAI_BUS_TIMING_0_REG () =
((inSettings.mRJW - 1) << 14) | // SJW
((inSettings.mBitRatePrescaler - 1) << 0) // BRP
;
#elif defined (CONFIG_IDF_TARGET_ESP32S2)
// BTR0 : bit (00 - 13) -> Baud Rate Prescaller (BRP)
// bit (14 - 15) -> Resynchronization Jump Width (RJW)
TWAI_BUS_TIMING_0_REG () =
((inSettings.mRJW - 1) << 14) | // SJW
((inSettings.mBitRatePrescaler - 1) << 0) // BRP
;
#elif defined (CONFIG_IDF_TARGET_ESP32C3)
// BTR0 : bit (00 - 13) -> Baud Rate Prescaller (BRP)
// bit (14 - 15) -> Resynchronization Jump Width (RJW)
TWAI_BUS_TIMING_0_REG () =
((inSettings.mRJW - 1) << 14) | // SJW
((inSettings.mBitRatePrescaler - 1) << 0) // BRP
;
#elif defined (CONFIG_IDF_TARGET_ESP32C6)
// BTR0 : bit (00 - 13) -> Baud Rate Prescaller (BRP)
// bit (14 - 15) -> Resynchronization Jump Width (RJW)
TWAI_BUS_TIMING_0_REG () =
((inSettings.mRJW - 1) << 14) | // SJW
((inSettings.mBitRatePrescaler - 1) << 0) // BRP
;
#else
#error "Unknown board"
#endif
//--- BTR1: bit (0 - 3) -> TimeSegment 1 (Tseg1)
// bit (4 - 6) -> TimeSegment 2 (Tseg2)
// bit (7) -> TripleSampling? (SAM)
TWAI_BUS_TIMING_1_REG () =
((inSettings.mTripleSampling) << 7) | // Sampling
((inSettings.mTimeSegment2 - 1) << 4) | // Tseg2
((inSettings.mTimeSegment1 - 1) << 0) // Tseg1
;
}
//------------------------------------------------------------------------------
void ACAN_ESP32::setAcceptanceFilter (const ACAN_ESP32_Filter & inFilter) {
//--- Write the Code and Mask Registers with Acceptance Filter Settings
if (inFilter.mAMFSingle) {
TWAI_MODE_REG () |= TWAI_RX_FILTER_MODE ;
}
mAcceptedFrameFormat = inFilter.mFormat ;
TWAI_ACC_CODE_FILTER (0) = inFilter.mACR0 ;
TWAI_ACC_CODE_FILTER (1) = inFilter.mACR1 ;
TWAI_ACC_CODE_FILTER (2) = inFilter.mACR2 ;
TWAI_ACC_CODE_FILTER (3) = inFilter.mACR3 ;
TWAI_ACC_MASK_FILTER (0) = inFilter.mAMR0 ;
TWAI_ACC_MASK_FILTER (1) = inFilter.mAMR1 ;
TWAI_ACC_MASK_FILTER (2) = inFilter.mAMR2 ;
TWAI_ACC_MASK_FILTER (3) = inFilter.mAMR3 ;
}
//------------------------------------------------------------------------------
// BEGIN
//------------------------------------------------------------------------------
uint32_t ACAN_ESP32::begin (const ACAN_ESP32_Settings & inSettings,
const ACAN_ESP32_Filter & inFilterSettings) {
// Serial.println (twaiBaseAddress, HEX) ;
uint32_t errorCode = 0 ; // Ok by default
//--------------------------------- Enable CAN module clock (only for ESP32C6)
#ifdef CONFIG_IDF_TARGET_ESP32C6
#define ACAN_CLOCK_ENABLE_REG (*((volatile uint32_t *) twaiClockEnableAddress))
ACAN_CLOCK_ENABLE_REG = 1 << 22 ;
//--- Display enable settings (for twai0)
// #define ACAN_PCR_TWAI0_CONF_REG (*((volatile uint32_t *) (0x60096000 + 0x05C)))
// #define ACAN_PCR_TWAI0_FUNC_CLK_CONF_REG (*((volatile uint32_t *) (0x60096000 + 0x060)))
// Serial.print ("Reset reg (should be 1): 0x") ;
// Serial.println (ACAN_PCR_TWAI0_CONF_REG, HEX) ;
// Serial.print ("Clock select reg (should be 0x400000): 0x") ;
// Serial.println (ACAN_PCR_TWAI0_FUNC_CLK_CONF_REG, HEX) ;
#endif
//--------------------------------- Enable CAN module
periph_module_enable (twaiPeriphModule) ;
//--------------------------------- Set GPIO pins
setGPIOPins (inSettings.mTxPin, inSettings.mRxPin);
//--------------------------------- Required: It is must to enter RESET Mode to write the Configuration Registers
TWAI_CMD_REG () = TWAI_ABORT_TX ;
TWAI_MODE_REG () = TWAI_RESET_MODE ;
while ((TWAI_MODE_REG () & TWAI_RESET_MODE) == 0) {
TWAI_MODE_REG () = TWAI_RESET_MODE ;
}
if ((TWAI_MODE_REG () & TWAI_RESET_MODE) == 0) {
errorCode = kNotInResetModeInConfiguration ;
}
//--------------------------------- Disable Interupts
TWAI_INT_ENA_REG () = 0 ;
if (mInterruptHandler != nullptr) {
esp_intr_free (mInterruptHandler) ;
mInterruptHandler = nullptr ;
}
//--------------------------------- Use Pelican Mode
TWAI_CLOCK_DIVIDER_REG () = TWAI_EXT_MODE ;
//---- Check the Register access and bit timing settings before writing to the Bit Timing Registers
TWAI_BUS_TIMING_0_REG () = 0x55 ;
bool ok = TWAI_BUS_TIMING_0_REG () == 0x55 ;
if (ok) {
TWAI_BUS_TIMING_0_REG () = 0xAA ;
ok = TWAI_BUS_TIMING_0_REG () == 0xAA ;
}
if (!ok) {
errorCode |= kCANRegistersError ;
}
//----------------------------------- If ok, check the bit timing settings are correct
if (!inSettings.mBitRateClosedToDesiredRate) {
errorCode |= kTooFarFromDesiredBitRate;
}
errorCode |= inSettings.CANBitSettingConsistency ();
//----------------------------------- Allocate buffer
if (!mDriverReceiveBuffer.initWithSize (inSettings.mDriverReceiveBufferSize)) {
errorCode |= kCannotAllocateDriverReceiveBuffer ;
}
if (!mDriverTransmitBuffer.initWithSize (inSettings.mDriverTransmitBufferSize)) {
errorCode |= kCannotAllocateDriverTransmitBuffer ;
}
//--------------------------------- Set Bus timing Registers
if (errorCode == 0) {
setBitTimingSettings (inSettings) ;
}
//--------------------------------- Set the Acceptance Filter
setAcceptanceFilter (inFilterSettings) ;
//--------------------------------- Set and clear the error counters to default value
TWAI_ERR_WARNING_LIMIT_REG () = 96 ;
TWAI_RX_ERR_CNT_REG () = 0 ;
//--------------------------------- Clear the Interrupt Registers
const uint32_t unusedVariable __attribute__((unused)) = TWAI_INT_RAW_REG () ;
//--------------------------------- Set Interrupt Service Routine
esp_intr_alloc (twaiInterruptSource, 0, isr, this, & mInterruptHandler) ;
//--------------------------------- Enable Interupts
TWAI_INT_ENA_REG () = TWAI_TX_INT_ENA | TWAI_RX_INT_ENA ;
//--------------------------------- Set to Requested Mode
setRequestedCANMode (inSettings, inFilterSettings) ;
//---
return errorCode ;
}
//----------------------------------------------------------------------------------------
// Stop CAN controller and uninstall ISR
//----------------------------------------------------------------------------------------
void ACAN_ESP32::end (void) {
//--------------------------------- Abort any pending transfer, don't care about resetting
TWAI_CMD_REG () = TWAI_ABORT_TX ;
//--------------------------------- Disable Interupts
TWAI_INT_ENA_REG () = 0 ;
if (mInterruptHandler != nullptr) {
esp_intr_free (mInterruptHandler) ;
mInterruptHandler = nullptr ;
}
//--------------------------------- Disable CAN module
periph_module_disable (PERIPH_TWAI_MODULE) ;
}
//------------------------------------------------------------------------------
//--- Status Flags (returns 0 if no error)
// Bit 0 : hardware receive FIFO overflow
// Bit 1 : driver receive FIFO overflow
// Bit 2 : bus off
// Bit 3 : reset mode
uint32_t ACAN_ESP32::statusFlags (void) const {
uint32_t result = 0 ; // Ok
const uint32_t status = TWAI_STATUS_REG () ;
//--- Hardware receive FIFO overflow ?
if ((status & TWAI_OVERRUN_ST) != 0) {
result |= 1U << 0 ;
}
//--- Driver receive FIFO overflow ?
if (mDriverReceiveBuffer.didOverflow ()) {
result |= 1U << 1 ;
}
//--- Bus off ?
if ((status & TWAI_BUS_OFF_ST) != 0) {
result |= 1U << 2 ;
}
//--- Reset mode ?
if ((TWAI_MODE_REG () & TWAI_RESET_MODE) != 0) {
result |= 1U << 3 ;
}
//---
return result ;
}
//------------------------------------------------------------------------------
bool ACAN_ESP32::recoverFromBusOff (void) const {
const bool isBusOff = (TWAI_STATUS_REG () & TWAI_BUS_OFF_ST) != 0 ;
const bool inResetMode = (TWAI_MODE_REG () & TWAI_RESET_MODE) != 0 ;
const bool recover = isBusOff && inResetMode ;
if (recover) {
TWAI_MODE_REG () &= ~ TWAI_RESET_MODE ;
}
return recover ;
}
//------------------------------------------------------------------------------
// Interrupt Handler
//------------------------------------------------------------------------------
void IRAM_ATTR ACAN_ESP32::isr (void * inUserArgument) {
ACAN_ESP32 * myDriver = (ACAN_ESP32 *) inUserArgument ;
portENTER_CRITICAL (&portMux) ;
const uint32_t interrupt = myDriver->TWAI_INT_RAW_REG () ;
if ((interrupt & TWAI_RX_INT_ST) != 0) {
myDriver->handleRXInterrupt () ;
}
if ((interrupt & TWAI_TX_INT_ST) != 0) {
myDriver->handleTXInterrupt () ;
}
portEXIT_CRITICAL (&portMux) ;
portYIELD_FROM_ISR () ;
}
//------------------------------------------------------------------------------
void ACAN_ESP32::handleTXInterrupt (void) {
CANMessage message ;
const bool sendmsg = mDriverTransmitBuffer.remove (message) ;
if (sendmsg) {
internalSendMessage (message) ;
}else {
mDriverIsSending = false ;
}
}
//------------------------------------------------------------------------------
void ACAN_ESP32::handleRXInterrupt (void) {
CANMessage frame;
getReceivedMessage (frame) ;
switch (mAcceptedFrameFormat) {
case ACAN_ESP32_Filter::standard :
if (!frame.ext) {
mDriverReceiveBuffer.append (frame) ;
}
break ;
case ACAN_ESP32_Filter::extended :
if (frame.ext) {
mDriverReceiveBuffer.append (frame) ;
}
break ;
case ACAN_ESP32_Filter::standardAndExtended :
mDriverReceiveBuffer.append (frame) ;
break ;
}
}
//------------------------------------------------------------------------------
// RECEPTION
//------------------------------------------------------------------------------
bool ACAN_ESP32::available (void) const {
const bool hasReceivedMessage = mDriverReceiveBuffer.count () > 0 ;
return hasReceivedMessage ;
}
//------------------------------------------------------------------------------
bool ACAN_ESP32::receive (CANMessage & outMessage) {
portENTER_CRITICAL (&portMux) ;
const bool hasReceivedMessage = mDriverReceiveBuffer.remove (outMessage) ;
portEXIT_CRITICAL (&portMux) ;
return hasReceivedMessage ;
}
//------------------------------------------------------------------------------
void ACAN_ESP32::getReceivedMessage (CANMessage & outFrame) {
const uint32_t frameInfo = TWAI_FRAME_INFO () ;
outFrame.len = frameInfo & 0xF;
if (outFrame.len > 8) {
outFrame.len = 8 ;
}
outFrame.rtr = (frameInfo & TWAI_RTR) != 0 ;
outFrame.ext = (frameInfo & TWAI_FRAME_FORMAT_EFF) != 0 ;
if (!outFrame.ext) { //--- Standard Frame
outFrame.id = uint32_t (TWAI_ID_SFF(0)) << 3 ;
outFrame.id |= uint32_t (TWAI_ID_SFF(1)) >> 5 ;
for (uint8_t i=0 ; i<outFrame.len ; i++) {
outFrame.data[i] = uint8_t (TWAI_DATA_SFF (i)) ;
}
}else{ //--- Extended Frame
outFrame.id = uint32_t (TWAI_ID_EFF(0)) << 21 ;
outFrame.id |= uint32_t (TWAI_ID_EFF(1)) << 13 ;
outFrame.id |= uint32_t (TWAI_ID_EFF(2)) << 5 ;
outFrame.id |= uint32_t (TWAI_ID_EFF(3)) >> 3 ;
for (uint8_t i=0 ; i<outFrame.len ; i++) {
outFrame.data [i] = uint8_t (TWAI_DATA_EFF (i)) ;
}
}
TWAI_CMD_REG () = TWAI_RELEASE_BUF ;
}
//------------------------------------------------------------------------------
// TRANSMISSION
//------------------------------------------------------------------------------
bool ACAN_ESP32::tryToSend (const CANMessage & inMessage) {
bool sendMessage ;
//--- Bug fixed in 1.0.2 (thanks to DirkMeintjies)
portENTER_CRITICAL (&portMux) ;
if (mDriverIsSending) {
sendMessage = mDriverTransmitBuffer.append (inMessage);
}else{
internalSendMessage (inMessage) ;
mDriverIsSending = true ;
sendMessage = true ;
}
portEXIT_CRITICAL (&portMux) ;
return sendMessage ;
}
//------------------------------------------------------------------------------
void ACAN_ESP32::internalSendMessage (const CANMessage & inFrame) {
//--- DLC
const uint8_t dlc = (inFrame.len <= 8) ? inFrame.len : 8 ;
//--- RTR
const uint8_t rtr = inFrame.rtr ? TWAI_RTR : 0 ;
//--- Format
const uint8_t format = (inFrame.ext) ? TWAI_FRAME_FORMAT_EFF : TWAI_FRAME_FORMAT_SFF ;
//--- Set Frame Information
TWAI_FRAME_INFO () = format | rtr | dlc ;
//--- Identifier and data
if (!inFrame.ext) { //--- Standard Frame
//--- Set ID
TWAI_ID_SFF(0) = (inFrame.id >> 3) & 255 ;
TWAI_ID_SFF(1) = (inFrame.id << 5) & 255 ;
//--- Set data
for (uint8_t i=0 ; i<dlc ; i++) {
TWAI_DATA_SFF (i) = inFrame.data [i] ;
}
}else{ //--- Extended Frame
//--- Set ID
TWAI_ID_EFF(0) = (inFrame.id >> 21) & 255 ;
TWAI_ID_EFF(1) = (inFrame.id >> 13) & 255 ;
TWAI_ID_EFF(2) = (inFrame.id >> 5) & 255 ;
TWAI_ID_EFF(3) = (inFrame.id << 3) & 255 ;
//--- Set data
for (uint8_t i=0 ; i<dlc ; i++) {
TWAI_DATA_EFF (i) = inFrame.data [i] ;
}
}
//--- Send command
TWAI_CMD_REG () = ((TWAI_MODE_REG () & TWAI_SELF_TEST_MODE) != 0)
? TWAI_SELF_RX_REQ
: TWAI_TX_REQ
;
}
//------------------------------------------------------------------------------
// Driver instances for ESP32C6
//------------------------------------------------------------------------------
#ifdef CONFIG_IDF_TARGET_ESP32C6
ACAN_ESP32 ACAN_ESP32::can (DR_REG_TWAI0_BASE,
TWAI0_TX_IDX,
TWAI0_RX_IDX,
PERIPH_TWAI0_MODULE,
ETS_TWAI0_INTR_SOURCE,
PCR_TWAI0_FUNC_CLK_CONF_REG) ;
ACAN_ESP32 ACAN_ESP32::can1 (DR_REG_TWAI1_BASE,
TWAI1_TX_IDX,
TWAI1_RX_IDX,
PERIPH_TWAI1_MODULE,
ETS_TWAI1_INTR_SOURCE,
PCR_TWAI1_FUNC_CLK_CONF_REG) ;
#endif
//------------------------------------------------------------------------------
// Driver instance for others
//------------------------------------------------------------------------------
#ifndef CONFIG_IDF_TARGET_ESP32C6
ACAN_ESP32 ACAN_ESP32::can ;
#endif
//------------------------------------------------------------------------------

View file

@ -0,0 +1,375 @@
#pragma once
//------------------------------------------------------------------------------
// Include files
//------------------------------------------------------------------------------
#include "ACAN_ESP32_TWAI_base_address.h"
#include "ACAN_ESP32_Settings.h"
#include "ACAN_ESP32_CANMessage.h"
#include "ACAN_ESP32_Buffer16.h"
#include "ACAN_ESP32_AcceptanceFilters.h"
//------------------------------------------------------------------------------
// ESP32 CAN class
//------------------------------------------------------------------------------
class ACAN_ESP32 {
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// CONSTRUCTOR for ESP32C6 (2 TWAI controllers)
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
#ifdef CONFIG_IDF_TARGET_ESP32C6
private: const uint32_t twaiBaseAddress ;
private: const uint32_t twaiTxPinSelector ;
private: const uint32_t twaiRxPinSelector ;
private: const periph_module_t twaiPeriphModule ;
private: const periph_interrupt_t twaiInterruptSource ;
private: const uint32_t twaiClockEnableAddress ;
private: ACAN_ESP32 (const uint32_t inBaseAddress,
const uint32_t inTxPinIndexSelector,
const uint32_t inRxPinIndexSelector,
const periph_module_t inPeriphModule,
const periph_interrupt_t inInterruptSource,
const uint32_t inClockEnableAddress) ;
#endif
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// CONSTRUCTOR for others (1 TWAI controller)
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
#ifndef CONFIG_IDF_TARGET_ESP32C6
private: ACAN_ESP32 (void) ;
#endif
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Initialisation: returns 0 if ok, otherwise see error codes below
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: uint32_t begin (const ACAN_ESP32_Settings & inSettings,
const ACAN_ESP32_Filter & inFilterSettings = ACAN_ESP32_Filter::acceptAll ()) ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Deinit: Stop CAN controller and uninstall ISR
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: void end (void) ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// CAN Configuration Private Methods
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
private: void setGPIOPins (const gpio_num_t inTXPin, const gpio_num_t inRXPin);
private: void setBitTimingSettings(const ACAN_ESP32_Settings &inSettings) ;
private: void setRequestedCANMode (const ACAN_ESP32_Settings &inSettings,
const ACAN_ESP32_Filter & inFilter) ;
private: void setAcceptanceFilter (const ACAN_ESP32_Filter & inFilter) ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Receiving messages
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: bool available (void) const ;
public: bool receive (CANMessage & outMessage) ;
public: void getReceivedMessage (CANMessage & outFrame) ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Receive buffer
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
private: ACAN_ESP32_Filter::Format mAcceptedFrameFormat ;
private: ACAN_ESP32_Buffer16 mDriverReceiveBuffer ;
public: inline uint16_t driverReceiveBufferSize (void) const { return mDriverReceiveBuffer.size () ; }
public: inline uint16_t driverReceiveBufferCount (void) const { return mDriverReceiveBuffer.count() ; }
public: inline uint16_t driverReceiveBufferPeakCount (void) const { return mDriverReceiveBuffer.peakCount () ; }
public: inline void resetDriverReceiveBufferPeakCount (void) { mDriverReceiveBuffer.resetPeakCount () ; }
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Transmitting messages
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: bool tryToSend (const CANMessage & inMessage) ;
private: void internalSendMessage (const CANMessage & inFrame) ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Transmit buffer
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
private: ACAN_ESP32_Buffer16 mDriverTransmitBuffer ;
private: bool mDriverIsSending ;
public: inline uint16_t driverTransmitBufferSize (void) const { return mDriverTransmitBuffer.size () ; }
public: inline uint16_t driverTransmitBufferCount (void) const { return mDriverTransmitBuffer.count () ; }
public: inline uint16_t driverTransmitBufferPeakCount (void) const { return mDriverTransmitBuffer.peakCount () ; }
public: inline void resetDriverTransmitBufferPeakCount (void) { mDriverTransmitBuffer.resetPeakCount () ; }
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Error codes returned by begin
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: static const uint32_t kNotInResetModeInConfiguration = 1 << 16 ;
public: static const uint32_t kCANRegistersError = 1 << 17 ;
public: static const uint32_t kTooFarFromDesiredBitRate = 1 << 18 ;
public: static const uint32_t kInconsistentBitRateSettings = 1 << 19 ;
public: static const uint32_t kCannotAllocateDriverReceiveBuffer = 1 << 20 ;
public: static const uint32_t kCannotAllocateDriverTransmitBuffer = 1 << 21 ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Interrupt Handler
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: static void IRAM_ATTR isr (void * inUserArgument) ;
private: intr_handle_t mInterruptHandler ;
public: void handleTXInterrupt (void) ;
public: void handleRXInterrupt (void) ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// STATUS FLAGS
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
//--- Status Flags (returns 0 if no error)
// Bit 0 : hardware receive FIFO overflow
// Bit 1 : driver receive FIFO overflow
// Bit 2 : bus off
// Bit 3 : reset mode
public: uint32_t statusFlags (void) const ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Recover from Bus-Off
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: bool recoverFromBusOff (void) const ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// No Copy
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
private: ACAN_ESP32 (const ACAN_ESP32 &) = delete ;
private: ACAN_ESP32 & operator = (const ACAN_ESP32 &) = delete ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Driver instances
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: static ACAN_ESP32 can ;
#ifdef CONFIG_IDF_TARGET_ESP32C6
public: static ACAN_ESP32 can1 ;
#endif
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Register Access
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_MODE_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x000)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_CMD_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x004)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_STATUS_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x008)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_INT_RAW_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x00C)) ;
}
public: inline volatile uint32_t & TWAI_INT_ENA_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x010)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_BUS_TIMING_0_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x018)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_BUS_TIMING_1_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x01C)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_ARB_LOST_CAP_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x02C)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_ERR_CODE_CAP_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x030)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_ERR_WARNING_LIMIT_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x034)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_RX_ERR_CNT_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x038)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_TX_ERR_CNT_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x03C)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_FRAME_INFO (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x040)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
//----- SFF : Standard Frame Format - array size: 2
public: inline volatile uint32_t & TWAI_ID_SFF (const uint32_t inIndex) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x044 + 4 * inIndex)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
//----- EFF : Extended Frame Format - array size: 4
public: inline volatile uint32_t & TWAI_ID_EFF (const uint32_t inIndex) const {
return * ((volatile uint32_t *)(twaiBaseAddress + 0x044 + 4 * inIndex)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
//----- DATA array size: 8
public: inline volatile uint32_t & TWAI_DATA_SFF (const uint32_t inIndex) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x04C + 4 * inIndex)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
//----- DATA array size: 8
public: inline volatile uint32_t & TWAI_DATA_EFF (const uint32_t inIndex) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x054 + 4 * inIndex)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// CAN Acceptance Filter Registers
//----- CODE array size: 4
public: inline volatile uint32_t & TWAI_ACC_CODE_FILTER (const uint32_t inIndex) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x040 + 4 * inIndex)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
//----- MASK array size: 4
public: inline volatile uint32_t & TWAI_ACC_MASK_FILTER (const uint32_t inIndex) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x050 + 4 * inIndex)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_RX_MESSAGE_COUNTER_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x074)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline volatile uint32_t & TWAI_CLOCK_DIVIDER_REG (void) const {
return * ((volatile uint32_t *) (twaiBaseAddress + 0x07C)) ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
} ;
//------------------------------------------------------------------------------
// TWAI_MODE_REG bit definitions
//------------------------------------------------------------------------------
static const uint32_t TWAI_RESET_MODE = 0x01 ;
static const uint32_t TWAI_LISTEN_ONLY_MODE = 0x02 ;
static const uint32_t TWAI_SELF_TEST_MODE = 0x04 ;
static const uint32_t TWAI_RX_FILTER_MODE = 0x08 ;
//------------------------------------------------------------------------------
// TWAI_CMD bit definitions
//------------------------------------------------------------------------------
static const uint32_t TWAI_TX_REQ = 0x01 ;
static const uint32_t TWAI_ABORT_TX = 0x02 ;
static const uint32_t TWAI_RELEASE_BUF = 0x04 ;
static const uint32_t TWAI_CLR_OVERRUN = 0x08 ;
static const uint32_t TWAI_SELF_RX_REQ = 0x10 ;
//------------------------------------------------------------------------------
// TWAI_STATUS_REG bit definitions
//------------------------------------------------------------------------------
static const uint32_t TWAI_RX_BUF_ST = 0x01 ;
static const uint32_t TWAI_OVERRUN_ST = 0x02 ;
static const uint32_t TWAI_TX_BUF_ST = 0x04 ;
static const uint32_t TWAI_TX_COMPLETE = 0x08 ;
static const uint32_t TWAI_RX_ST = 0x10 ;
static const uint32_t TWAI_TX_ST = 0x20 ;
static const uint32_t TWAI_ERR_ST = 0x40 ;
static const uint32_t TWAI_BUS_OFF_ST = 0x80 ;
//------------------------------------------------------------------------------
// TWAI_INT_RAW_REG bit definitins
//------------------------------------------------------------------------------
static const uint32_t TWAI_RX_INT_ST = 0x01;
static const uint32_t TWAI_TX_INT_ST = 0x02;
static const uint32_t TWAI_ERR_WARN_INT_ST = 0x04;
static const uint32_t TWAI_OVERRUN_INT_ST = 0x08;
static const uint32_t TWAI_ERR_PASSIVE_INT_ST = 0x20;
static const uint32_t TWAI_ARB_LOST_INT_ST = 0x40;
static const uint32_t TWAI_BUS_ERR_INT_ST = 0x80;
//------------------------------------------------------------------------------
// TWAI_INT_ENA_REG bit definitions
//------------------------------------------------------------------------------
static const uint32_t TWAI_RX_INT_ENA = 0x01 ;
static const uint32_t TWAI_TX_INT_ENA = 0x02 ;
//------------------------------------------------------------------------------
// TWAI_FRAME_INFO bit definitions
//------------------------------------------------------------------------------
static const uint32_t TWAI_FRAME_FORMAT_SFF = 0x00 ;
static const uint32_t TWAI_FRAME_FORMAT_EFF = 0x80 ;
static const uint32_t TWAI_RTR = 0x40 ;
//------------------------------------------------------------------------------
// CAN FRAME REGISTERS definitions
//------------------------------------------------------------------------------
static const uint32_t TWAI_MSG_STD_ID = 0x7FF ;
static const uint32_t TWAI_MSG_EXT_ID = 0x1FFFFFFF ;
//------------------------------------------------------------------------------
// TWAI_CLOCK_DIVIDER_REG bit definition
//------------------------------------------------------------------------------
static const uint32_t TWAI_EXT_MODE = 0x80 ;
//------------------------------------------------------------------------------

View file

@ -0,0 +1,214 @@
#pragma once
//----------------------------------------------------------------------------------------
#include <Arduino.h>
//----------------------------------------------------------------------------------------
class ACAN_ESP32_Filter {
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: typedef enum : uint8_t { standard, extended, standardAndExtended } Format ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: typedef enum : uint8_t { data, remote, dataAndRemote } Type ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// public properties
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: uint8_t mACR0 ;
public: uint8_t mACR1 ;
public: uint8_t mACR2 ;
public: uint8_t mACR3 ;
public: uint8_t mAMR0 ;
public: uint8_t mAMR1 ;
public: uint8_t mAMR2 ;
public: uint8_t mAMR3 ;
public: bool mAMFSingle ;
public: Format mFormat ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Default private constructor
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
private: ACAN_ESP32_Filter (void) :
mACR0 (0),
mACR1 (0),
mACR2 (0),
mACR3 (0),
mAMR0 (0xFF),
mAMR1 (0xFF),
mAMR2 (0xFF),
mAMR3 (0xFF),
mAMFSingle (false),
mFormat (standardAndExtended) {
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Accept all filter
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: static inline ACAN_ESP32_Filter acceptAll (void) {
return ACAN_ESP32_Filter () ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Accept only standard frames
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: static inline ACAN_ESP32_Filter acceptStandardFrames (void) {
ACAN_ESP32_Filter result ;
result.mFormat = standard ;
return result ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Accept only extended frames
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: static inline ACAN_ESP32_Filter acceptExtendedFrames (void) {
ACAN_ESP32_Filter result ;
result.mFormat = extended ;
return result ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// singleStandardFilter: see SJA100 datasheet, figure 9 page 45 (and figure 10 page 46)
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: static inline ACAN_ESP32_Filter singleStandardFilter (const ACAN_ESP32_Filter::Type inType,
const uint16_t inIdentifier,
const uint16_t inDontCareMask) {
ACAN_ESP32_Filter result ;
result.mAMFSingle = true ; // Single Filter
result.mFormat = standard ;
result.mACR0 = uint8_t (inIdentifier >> 3) ;
result.mACR1 = uint8_t (inIdentifier << 5) ;
result.mAMR0 = uint8_t (inDontCareMask >> 3) ;
result.mAMR1 = uint8_t (inDontCareMask << 5) | 0x0F ;
switch (inType) {
case data :
break ;
case remote :
result.mACR1 |= 0x10 ;
break ;
case dataAndRemote :
result.mAMR1 |= 0x10 ;
break ;
}
return result ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// singleExtendedFilter: see SJA100 datasheet, figure 10 page 46 (and figure 9 page 45)
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: static inline ACAN_ESP32_Filter singleExtendedFilter (const ACAN_ESP32_Filter::Type inType,
const uint32_t inIdentifier,
const uint32_t inDontCareMask) {
ACAN_ESP32_Filter result ;
result.mAMFSingle = true ; // Single Filter
result.mFormat = extended ;
result.mACR0 = uint8_t (inIdentifier >> 21) ;
result.mACR1 = uint8_t (inIdentifier >> 13) ;
result.mACR2 = uint8_t (inIdentifier >> 5) ;
result.mACR3 = uint8_t (inIdentifier << 3) ;
result.mAMR0 = uint8_t (inDontCareMask >> 21) ;
result.mAMR1 = uint8_t (inDontCareMask >> 13) ;
result.mAMR2 = uint8_t (inDontCareMask >> 5) ;
result.mAMR3 = uint8_t (inDontCareMask << 3) ;
switch (inType) {
case data :
break ;
case remote :
result.mACR3 |= 0x04 ;
break ;
case dataAndRemote :
result.mAMR3 |= 0x04 ;
break ;
}
return result ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// dualStandardFilter: see SJA100 datasheet, figure 11 page 47 (and figure 12 page 48)
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: static inline ACAN_ESP32_Filter dualStandardFilter (const ACAN_ESP32_Filter::Type inType0,
const uint16_t inIdentifier0,
const uint16_t inDontCareMask0,
const ACAN_ESP32_Filter::Type inType1,
const uint16_t inIdentifier1,
const uint16_t inDontCareMask1) {
ACAN_ESP32_Filter result ;
result.mAMFSingle = false ; // Dual Filter
result.mFormat = standard ;
result.mACR0 = uint8_t (inIdentifier0 >> 3) ;
result.mACR1 = uint8_t (inIdentifier0 << 5) ;
result.mAMR0 = uint8_t (inDontCareMask0 >> 3) ;
result.mAMR1 = uint8_t (inDontCareMask0 << 5) | 0x0F ;
switch (inType0) {
case data :
break ;
case remote :
result.mACR1 |= 0x10 ;
break ;
case dataAndRemote :
result.mAMR1 |= 0x10 ;
break ;
}
result.mACR2 = uint8_t (inIdentifier1 >> 3) ;
result.mACR3 = uint8_t (inIdentifier1 << 5) ;
result.mAMR2 = uint8_t (inDontCareMask1 >> 3) ;
result.mAMR3 = uint8_t (inDontCareMask1 << 5) | 0x0F ;
switch (inType1) {
case data :
break ;
case remote :
result.mACR3 |= 0x10 ;
break ;
case dataAndRemote :
result.mAMR3 |= 0x10 ;
break ;
}
return result ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// dualExtendedFilter: see SJA100 datasheet, figure 12 page 48 (and figure 11 page 47)
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: static inline ACAN_ESP32_Filter dualExtendedFilter (const uint32_t inIdentifier0,
const uint32_t inDontCareMask0,
const uint32_t inIdentifier1,
const uint32_t inDontCareMask1) {
ACAN_ESP32_Filter result ;
result.mAMFSingle = false ; // Dual Filter
result.mFormat = extended ;
result.mACR0 = uint8_t (inIdentifier0 >> 21) ;
result.mACR1 = uint8_t (inIdentifier0 >> 13) ;
result.mAMR0 = uint8_t (inDontCareMask0 >> 21) ;
result.mAMR1 = uint8_t (inDontCareMask0 >> 13) ;
result.mACR2 = uint8_t (inIdentifier1 >> 21) ;
result.mACR3 = uint8_t (inIdentifier1 << 13) ;
result.mAMR2 = uint8_t (inDontCareMask1 >> 21) ;
result.mAMR3 = uint8_t (inDontCareMask1 << 13) ;
return result ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
} ;
//----------------------------------------------------------------------------------------

View file

@ -0,0 +1,135 @@
//----------------------------------------------------------------------------------------
#pragma once
//----------------------------------------------------------------------------------------
#include "ACAN_ESP32_CANMessage.h"
//----------------------------------------------------------------------------------------
class ACAN_ESP32_Buffer16 {
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Default constructor
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: ACAN_ESP32_Buffer16 (void) :
mBuffer (NULL),
mSize (0),
mReadIndex (0),
mCount (0),
mPeakCount (0) {
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Destructor
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: ~ ACAN_ESP32_Buffer16 (void) {
delete [] mBuffer ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Private properties
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
private: CANMessage * mBuffer ;
private: uint16_t mSize ;
private: uint16_t mReadIndex ;
private: uint16_t mCount ;
private: uint16_t mPeakCount ; // > mSize if overflow did occur
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Accessors
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline uint16_t size (void) const { return mSize ; }
public: inline uint16_t count (void) const { return mCount ; }
public: inline uint16_t peakCount (void) const { return mPeakCount ; }
public: inline uint16_t didOverflow (void) const { return mPeakCount > mSize ; }
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// initWithSize
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: bool initWithSize (const uint16_t inSize) {
delete [] mBuffer ;
mBuffer = new CANMessage [inSize] ;
const bool ok = mBuffer != NULL ;
mSize = ok ? inSize : 0 ;
mReadIndex = 0 ;
mCount = 0 ;
mPeakCount = 0 ;
return ok ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// append
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: bool append (const CANMessage & inMessage) {
const bool ok = mCount < mSize ;
if (ok) {
uint16_t writeIndex = mReadIndex + mCount ;
if (writeIndex >= mSize) {
writeIndex -= mSize ;
}
mBuffer [writeIndex] = inMessage ;
mCount += 1 ;
if (mPeakCount < mCount) {
mPeakCount = mCount ;
}
}else{
mPeakCount = mSize + 1 ; // Overflow
}
return ok ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Remove
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: bool remove (CANMessage & outMessage) {
const bool ok = mCount > 0 ;
if (ok) {
outMessage = mBuffer [mReadIndex] ;
mCount -= 1 ;
mReadIndex += 1 ;
if (mReadIndex == mSize) {
mReadIndex = 0 ;
}
}
return ok ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Free
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: void free (void) {
delete [] mBuffer ; mBuffer = nullptr ;
mSize = 0 ;
mReadIndex = 0 ;
mCount = 0 ;
mPeakCount = 0 ;
}
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Reset Peak Count
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: inline void resetPeakCount (void) { mPeakCount = mCount ; }
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// No copy
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
private: ACAN_ESP32_Buffer16 (const ACAN_ESP32_Buffer16 &) = delete ;
private: ACAN_ESP32_Buffer16 & operator = (const ACAN_ESP32_Buffer16 &) = delete ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
} ;
//----------------------------------------------------------------------------------------

View file

@ -0,0 +1,49 @@
//----------------------------------------------------------------------------------------
// Generic CAN Message
// by Pierre Molinaro
//
// This file is common to the following libraries
// https://github.com/pierremolinaro/acan
// https://github.com/pierremolinaro/acan2515
// https://github.com/pierremolinaro/acan2517
// https://github.com/pierremolinaro/acan2517FD
//
//----------------------------------------------------------------------------------------
#ifndef GENERIC_CAN_MESSAGE_DEFINED
#define GENERIC_CAN_MESSAGE_DEFINED
//----------------------------------------------------------------------------------------
#include <Arduino.h>
//----------------------------------------------------------------------------------------
class CANMessage {
public : uint32_t id = 0 ; // Frame identifier
public : bool ext = false ; // false -> standard frame, true -> extended frame
public : bool rtr = false ; // false -> data frame, true -> remote frame
public : uint8_t idx = 0 ; // This field is used by the driver
public : uint8_t len = 0 ; // Length of data (0 ... 8)
public : union {
uint64_t data64 ; // Caution: subject to endianness
int64_t data_s64 ; // Caution: subject to endianness
uint32_t data32 [2] ; // Caution: subject to endianness
int32_t data_s32 [2] ; // Caution: subject to endianness
float dataFloat [2] ; // Caution: subject to endianness
uint16_t data16 [4] ; // Caution: subject to endianness
int16_t data_s16 [4] ; // Caution: subject to endianness
int8_t data_s8 [8] ;
uint8_t data [8] = {0, 0, 0, 0, 0, 0, 0, 0} ;
} ;
} ;
//----------------------------------------------------------------------------------------
typedef enum {kStandard, kExtended} tFrameFormat ;
typedef enum {kData, kRemote} tFrameKind ;
typedef void (*ACANCallBackRoutine) (const CANMessage & inMessage) ;
//----------------------------------------------------------------------------------------
#endif

View file

@ -0,0 +1,128 @@
//----------------------------------------------------------------------------------------
// Include files
//----------------------------------------------------------------------------------------
#include "ACAN_ESP32_Settings.h"
//----------------------------------------------------------------------------------------
// CAN Settings
//----------------------------------------------------------------------------------------
ACAN_ESP32_Settings::ACAN_ESP32_Settings (const uint32_t inDesiredBitRate,
const uint32_t inTolerancePPM) :
mDesiredBitRate (inDesiredBitRate) {
uint32_t TQCount = MAX_TQ ; // TQ: min(3) max(25)
uint32_t bestBRP = MAX_BRP ; // Setting for slowest bit rate
uint32_t bestTQCount = MAX_TQ ; // Setting for slowest bit rate
uint32_t smallestError = UINT32_MAX ;
const uint32_t CANClock = CAN_CLOCK () ;
uint32_t BRP = CANClock / (inDesiredBitRate * TQCount) ; // BRP: min(2) max(128)
//--- Loop for finding best BRP and best TQCount
while ((TQCount >= MIN_TQ) && (BRP <= MAX_BRP)) {
//--- Compute error using BRP (caution: BRP should be > 0)
if (BRP >= MIN_BRP) {
const uint32_t error = CANClock - (inDesiredBitRate * TQCount * BRP) ; // error is always >= 0
if (error < smallestError) {
smallestError = error ;
bestBRP = BRP ;
bestTQCount = TQCount ;
}
}
//--- Compute error using BRP+1 (caution: BRP+1 should be <= 128)
if (BRP < MAX_BRP) {
const uint32_t error = (inDesiredBitRate * TQCount * (BRP + 1)) - CANClock ; // error is always >= 0
if (error < smallestError) {
smallestError = error ;
bestBRP = BRP + 1 ;
bestTQCount = TQCount ;
}
}
//--- Continue with next value of TQCount
TQCount -= 1 ;
BRP = CANClock / (inDesiredBitRate * TQCount) ;
}
//--- Set the BRP
mBitRatePrescaler = uint8_t (bestBRP) ;
//--- Compute PS2 (2 <= TSeg2 <= 8)
const uint32_t PS2 = 2 + 3 * (bestTQCount - 5) / 10 ;
mTimeSegment2 = uint8_t (PS2) ;
//--- Compute PS1 (1 <= PS1 <= 16)
const uint32_t PS1 = bestTQCount - PS2 - SYNC_SEGMENT ;
mTimeSegment1 = uint8_t (PS1) ;
//--- SJW (1...4) min of Tseg2
mRJW = (mTimeSegment2 > 4) ? 4 : mTimeSegment2 ;
//--- Triple sampling ?
mTripleSampling = (inDesiredBitRate <= 125000) && (mTimeSegment2 > 2) ;
//--- Final check of the configuration
const uint32_t W = bestTQCount * mDesiredBitRate * mBitRatePrescaler ;
const uint64_t diff = (CANClock > W) ? (CANClock - W) : (W - CANClock) ;
const uint64_t ppm = uint64_t (1000UL * 1000UL) ;
mBitRateClosedToDesiredRate = (diff * ppm) <= (uint64_t (W) * inTolerancePPM) ;
}
//----------------------------------------------------------------------------------------
uint32_t ACAN_ESP32_Settings::actualBitRate (void) const {
const uint32_t TQCount = SYNC_SEGMENT + mTimeSegment1 + mTimeSegment2 ;
return CAN_CLOCK () / mBitRatePrescaler / TQCount ;
}
//----------------------------------------------------------------------------------------
bool ACAN_ESP32_Settings::exactBitRate (void) const {
const uint32_t TQCount = SYNC_SEGMENT + mTimeSegment1 + mTimeSegment2 ;
return CAN_CLOCK () == (mDesiredBitRate * mBitRatePrescaler * TQCount) ;
}
//----------------------------------------------------------------------------------------
uint32_t ACAN_ESP32_Settings::ppmFromDesiredBitRate(void) const {
const uint32_t TQCount = SYNC_SEGMENT + mTimeSegment1 + mTimeSegment2 ;
const uint32_t W = TQCount * mDesiredBitRate * mBitRatePrescaler ;
const uint32_t CANClock = CAN_CLOCK () ;
const uint64_t diff = (CANClock > W) ? (CANClock - W) : (W - CANClock) ;
const uint64_t ppm = (uint64_t)(1000UL * 1000UL) ; // UL suffix is required for Arduino Uno
return uint32_t ((diff * ppm) / W) ;
}
//----------------------------------------------------------------------------------------
uint32_t ACAN_ESP32_Settings::samplePointFromBitStart (void) const {
const uint32_t TQCount = SYNC_SEGMENT + mTimeSegment1 + mTimeSegment2 ;
const uint32_t samplePoint = SYNC_SEGMENT + mTimeSegment1 - mTripleSampling ;
const uint32_t partPerCent = 100 ;
return (samplePoint * partPerCent) / TQCount ;
}
//----------------------------------------------------------------------------------------
uint16_t ACAN_ESP32_Settings::CANBitSettingConsistency (void) const {
uint16_t errorCode = 0 ; // No error
if (mBitRatePrescaler < MIN_BRP) {
errorCode |= kBitRatePrescalerIsZero ;
}else if (mBitRatePrescaler > MAX_BRP) {
errorCode |= kBitRatePrescalerIsGreaterThan64 ;
}
if (mTimeSegment1 == 0) {
errorCode |= kTimeSegment1IsZero ;
}else if ((mTimeSegment2 == 2) && mTripleSampling) {
errorCode |= kTimeSegment2Is2AndTripleSampling ;
}else if (mTimeSegment1 > MAX_TIME_SEGMENT_1) {
errorCode |= kTimeSegment1IsGreaterThan16 ;
}
if (mTimeSegment2 < 2) {
errorCode |= kTimeSegment2IsLowerThan2 ;
}else if (mTimeSegment2 > MAX_TIME_SEGMENT_2) {
errorCode |= kTimeSegment2IsGreaterThan8 ;
}
if (mRJW == 0) {
errorCode |= kRJWIsZero ;
}else if (mRJW > mTimeSegment2) {
errorCode |= kRJWIsGreaterThanTimeSegment2 ;
}else if (mRJW > MAX_SJW) {
errorCode |= kRJWIsGreaterThan4 ;
}
return errorCode ;
}
//----------------------------------------------------------------------------------------

View file

@ -0,0 +1,155 @@
//----------------------------------------------------------------------------------------
#pragma once
//----------------------------------------------------------------------------------------
// Include files
//----------------------------------------------------------------------------------------
#include <stdint.h>
//--- For getting getApbFrequency function declaration
#ifdef ARDUINO
#include <Arduino.h>
#endif
//----------------------------------------------------------------------------------------
// CAN CLOCK
//----------------------------------------------------------------------------------------
#ifdef ARDUINO
inline uint32_t CAN_CLOCK (void) { return getApbFrequency () / 2 ; }// APB_CLK_FREQ: 80 MHz APB CLOCK
#else
inline uint32_t CAN_CLOCK (void) { return 40 * 1000 * 1000 ; } // 40 MHz
#endif
//----------------------------------------------------------------------------------------
// ESP32 ACANSettings class
//----------------------------------------------------------------------------------------
class ACAN_ESP32_Settings {
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// ENUMERATED TYPE
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
//--- CAN driver operating modes
public: typedef enum
#ifdef ARDUINO
: uint8_t
#endif
{
NormalMode,
ListenOnlyMode,
LoopBackMode
} CANMode ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// CONSTRUCTOR
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: ACAN_ESP32_Settings (const uint32_t inDesiredBitRate,
const uint32_t inTolerancePPM = 1000) ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// CAN PINS
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
#ifdef ARDUINO
public: gpio_num_t mTxPin = GPIO_NUM_5 ;
public: gpio_num_t mRxPin = GPIO_NUM_4 ;
#endif
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// CAN BIT TIMING
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: uint32_t mDesiredBitRate ; // In kb/s
public: uint8_t mBitRatePrescaler = 0 ; // 1...64
public: uint8_t mTimeSegment1 = 0 ; // 1...16
public: uint8_t mTimeSegment2 = 0 ; // 2...8
public: uint8_t mRJW = 0 ; // 1...4
public: bool mTripleSampling = false ; // true --> triple sampling, false --> single sampling
public: bool mBitRateClosedToDesiredRate = false ; // The above configuration is correct
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Max values
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: static const uint8_t SYNC_SEGMENT = 1 ; // Fixed Sync Segment
public: static const uint32_t MAX_BRP = 64 ;
public: static const uint32_t MIN_BRP = 1 ;
public: static const uint32_t MAX_TQ = 25 ;
public: static const uint32_t MIN_TQ = 5 ;
public: static const uint8_t MAX_TIME_SEGMENT_1 = 16 ;
public: static const uint8_t MAX_TIME_SEGMENT_2 = 8 ;
public: static const uint8_t MAX_SJW = 4 ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Requested mode
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: CANMode mRequestedCANMode = NormalMode ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Receive buffer size
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: uint16_t mDriverReceiveBufferSize = 32 ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Transmit buffer sizes
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: uint16_t mDriverTransmitBufferSize = 16 ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Compute actual bit rate
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: uint32_t actualBitRate (void) const ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Exact bit rate ?
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: bool exactBitRate (void) const ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Distance between actual bit rate and requested bit rate (in ppm, part-per-million)
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: uint32_t ppmFromDesiredBitRate (void) const;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Distance of sample point from bit start (in ppc, part-per-cent, denoted by %)
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: uint32_t samplePointFromBitStart (void) const;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Bit settings are consistent ? (returns 0 if ok)
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: uint16_t CANBitSettingConsistency (void) const ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
// Constants returned by CANBitSettingConsistency
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
public: static const uint16_t kBitRatePrescalerIsZero = 1 << 0 ;
public: static const uint16_t kBitRatePrescalerIsGreaterThan64 = 1 << 1 ;
public: static const uint16_t kTimeSegment1IsZero = 1 << 2 ;
public: static const uint16_t kTimeSegment1IsGreaterThan16 = 1 << 3 ;
public: static const uint16_t kTimeSegment2IsLowerThan2 = 1 << 4 ;
public: static const uint16_t kTimeSegment2IsGreaterThan8 = 1 << 5 ;
public: static const uint16_t kTimeSegment2Is2AndTripleSampling = 1 << 6 ;
public: static const uint16_t kRJWIsZero = 1 << 7 ;
public: static const uint16_t kRJWIsGreaterThan4 = 1 << 8 ;
public: static const uint16_t kRJWIsGreaterThanTimeSegment2 = 1 << 9 ;
// - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
} ;
//----------------------------------------------------------------------------------------

View file

@ -0,0 +1,85 @@
//------------------------------------------------------------------------------
// ESP32 TWAI REGISTER BASE
// See sdkconfig.h files for defining CONFIG_IDF_TARGET_xxxx
// DR_REG_TWAI_BASE is defined in:
// - ~/Library/Arduino15/packages/esp32/hardware/esp32/2.0.11/tools/sdk/esp32c3/include/soc/esp32c3/include/soc/soc.h
// - ~//Library/Arduino15/packages/esp32/hardware/esp32/2.0.11/tools/sdk/esp32s3/include/soc/esp32s3/include/soc/soc.h
// DR_REG_CAN_BASE is defined in:
// - ~//Library/Arduino15/packages/esp32/hardware/esp32/2.0.11/tools/sdk/esp32/include/soc/esp32/include/soc/soc.h
// No definition for ESP32-S2 in ~/Library/Arduino15/packages/esp32/hardware/esp32/2.0.11/tools/sdk/esp32s2/include/soc/esp32s2/include/soc/soc.h
// However the ~/Library/Arduino15/packages/esp32/hardware/esp32/2.0.11/tools/ide-debug/svd/esp32s2.svd file defines
// the TWAI base address: 0x3F42B000
// But ESP32S2 reference manual (§3.3.5) gives two addresses:
// - 0x3F40_0000 + 0x0002_B000 = 0x3F42_B000 from PeriBus1 (faster)
// - 0x6000_0000 + 0x0002_B000 = 0x6002_B000 from PeriBus2
//
//------------------------------------------------------------------------------
#pragma once
//------------------------------------------------------------------------------
// Include files
//------------------------------------------------------------------------------
#include <stdint.h>
#include <freertos/FreeRTOS.h>
#include <freertos/queue.h>
#include <esp_intr_alloc.h>
#include <soc/gpio_sig_map.h>
#include <soc/periph_defs.h>
#include <soc/interrupts.h>
//------------------------------------------------------------------------------
// In ESP32 2.x board managers, ETS_TWAI_INTR_SOURCE is an int constant.
//
// In ESP32 3.0.0 board manager, ETS_TWAI_INTR_SOURCE is an periph_interrput_t constant.
//
// In ESP32 3.3.0-alpha1 board manager, periph_interrput_t has been deprecated
// in favor of periph_interrupt_t.
//------------------------------------------------------------------------------
// esp32/hardware/esp32/3.3.0-alpha1/cores/esp32/esp_arduino_version.h
#include <esp_arduino_version.h>
#if ESP_ARDUINO_VERSION < ESP_ARDUINO_VERSION_VAL(3, 0, 0)
typedef int periph_interrupt_t ;
#elif ESP_ARDUINO_VERSION < ESP_ARDUINO_VERSION_VAL(3, 3, 0)
typedef periph_interrput_t periph_interrupt_t ;
#endif
//------------------------------------------------------------------------------
#if defined (CONFIG_IDF_TARGET_ESP32S3)
static const uint32_t twaiBaseAddress = DR_REG_TWAI_BASE ; // 0x6002B000
static const uint32_t twaiTxPinSelector = TWAI_TX_IDX ;
static const uint32_t twaiRxPinSelector = TWAI_RX_IDX ;
static const periph_module_t twaiPeriphModule = PERIPH_TWAI_MODULE ;
static const periph_interrupt_t twaiInterruptSource = ETS_TWAI_INTR_SOURCE ;
#elif defined (CONFIG_IDF_TARGET_ESP32S2)
static const uint32_t twaiBaseAddress = 0x3F42B000 ;
static const uint32_t twaiTxPinSelector = TWAI_TX_IDX ;
static const uint32_t twaiRxPinSelector = TWAI_RX_IDX ;
static const periph_module_t twaiPeriphModule = PERIPH_TWAI_MODULE ;
static const periph_interrupt_t twaiInterruptSource = ETS_TWAI_INTR_SOURCE ;
#elif defined (CONFIG_IDF_TARGET_ESP32C3)
static const uint32_t twaiBaseAddress = DR_REG_TWAI_BASE ; // 0x6002B000
static const uint32_t twaiTxPinSelector = TWAI_TX_IDX ;
static const uint32_t twaiRxPinSelector = TWAI_RX_IDX ;
static const periph_module_t twaiPeriphModule = PERIPH_TWAI_MODULE ;
static const periph_interrupt_t twaiInterruptSource = ETS_TWAI_INTR_SOURCE ;
#elif defined (CONFIG_IDF_TARGET_ESP32C6)
// twaiBaseAddress, twaiTxPinSelector, twaiRxPinSelector, twaiPeriphModule
// and twaiInterruptSource are defined as instance properties
// of ACAN_ESP32 class
#elif defined (CONFIG_IDF_TARGET_ESP32)
static const uint32_t twaiBaseAddress = DR_REG_CAN_BASE ; // 0x3ff6B000
static const uint32_t twaiTxPinSelector = TWAI_TX_IDX ;
static const uint32_t twaiRxPinSelector = TWAI_RX_IDX ;
static const periph_module_t twaiPeriphModule = PERIPH_TWAI_MODULE ;
static const periph_interrupt_t twaiInterruptSource = ETS_TWAI_INTR_SOURCE ;
#else
#error "ESP32 TWAI (CAN) module not handled for this platform"
#endif
//------------------------------------------------------------------------------