Merge pull request #1384 from No-Signal/feature/lilygo_t_2can

Hardware: Add support for Lilygo T_2CAN board
This commit is contained in:
Daniel Öster 2025-08-31 14:56:55 +03:00 committed by GitHub
commit 0e904f9465
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
29 changed files with 1957 additions and 872 deletions

View file

@ -31,7 +31,7 @@
#include "src/devboard/wifi/wifi.h"
#include "src/inverter/INVERTERS.h"
#if !defined(HW_LILYGO) && !defined(HW_STARK) && !defined(HW_3LB) && !defined(HW_DEVKIT)
#if !defined(HW_LILYGO) && !defined(HW_LILYGO2CAN) && !defined(HW_STARK) && !defined(HW_3LB) && !defined(HW_DEVKIT)
#error You must select a target hardware in the USER_SETTINGS.h file!
#endif

View file

@ -1,8 +1,8 @@
#include "comm_can.h"
#include <algorithm>
#include <map>
#include "../../lib/miwagner-ESP32-Arduino-CAN/ESP32CAN.h"
#include "../../lib/pierremolinaro-ACAN2517FD/ACAN2517FD.h"
#include "../../lib/pierremolinaro-acan-esp32/ACAN_ESP32.h"
#include "../../lib/pierremolinaro-acan2515/ACAN2515.h"
#include "CanReceiver.h"
#include "USER_SETTINGS.h"
@ -19,8 +19,6 @@ struct CanReceiverRegistration {
static std::multimap<CAN_Interface, CanReceiverRegistration> can_receivers;
// Parameters
CAN_device_t CAN_cfg; // CAN Config
const uint8_t rx_queue_size = 10; // Receive Queue size
volatile bool send_ok_native = 0;
volatile bool send_ok_2515 = 0;
@ -41,7 +39,10 @@ void register_can_receiver(CanReceiver* receiver, CAN_Interface interface, CAN_S
DEBUG_PRINTF("CAN receiver registered, total: %d\n", can_receivers.size());
}
static const uint32_t QUARTZ_FREQUENCY = CRYSTAL_FREQUENCY_MHZ * 1000000UL; //MHZ configured in USER_SETTINGS.h
ACAN_ESP32_Settings* settingsespcan;
uint8_t user_selected_can_addon_crystal_frequency_mhz = 0;
static uint32_t QUARTZ_FREQUENCY;
SPIClass SPI2515;
ACAN2515* can2515;
@ -59,6 +60,12 @@ bool native_can_initialized = false;
bool init_CAN() {
if (user_selected_can_addon_crystal_frequency_mhz > 0) {
QUARTZ_FREQUENCY = user_selected_can_addon_crystal_frequency_mhz * 1000000UL;
} else {
QUARTZ_FREQUENCY = CRYSTAL_FREQUENCY_MHZ * 1000000UL;
}
auto nativeIt = can_receivers.find(CAN_NATIVE);
if (nativeIt != can_receivers.end()) {
auto se_pin = esp32hal->CAN_SE_PIN();
@ -73,18 +80,46 @@ bool init_CAN() {
digitalWrite(se_pin, LOW);
}
CAN_cfg.speed = (CAN_speed_t)nativeIt->second.speed;
if (!esp32hal->alloc_pins("CAN", tx_pin, rx_pin)) {
return false;
}
CAN_cfg.tx_pin_id = tx_pin;
CAN_cfg.rx_pin_id = rx_pin;
CAN_cfg.rx_queue = xQueueCreate(rx_queue_size, sizeof(CAN_frame_t));
// Init CAN Module
ESP32Can.CANInit();
native_can_initialized = true;
settingsespcan = new ACAN_ESP32_Settings((int)nativeIt->second.speed * 1000UL);
settingsespcan->mRequestedCANMode = ACAN_ESP32_Settings::NormalMode;
settingsespcan->mTxPin = tx_pin;
settingsespcan->mRxPin = rx_pin;
const uint32_t errorCode = ACAN_ESP32::can.begin(*settingsespcan);
if (errorCode == 0) {
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);
@ -94,6 +129,7 @@ bool init_CAN() {
auto sck_pin = esp32hal->MCP2515_SCK();
auto miso_pin = esp32hal->MCP2515_MISO();
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)) {
return false;
@ -102,6 +138,16 @@ bool init_CAN() {
logging.println("Dual CAN Bus (ESP32+MCP2515) selected");
gBuffer.initWithSize(25);
if (rst_pin != GPIO_NUM_NC) {
pinMode(rst_pin, OUTPUT);
digitalWrite(rst_pin, HIGH);
delay(100);
digitalWrite(rst_pin, LOW);
delay(100);
digitalWrite(rst_pin, HIGH);
delay(100);
}
can2515 = new ACAN2515(cs_pin, SPI2515, int_pin);
SPI2515.begin(sck_pin, miso_pin, mosi_pin);
@ -192,26 +238,26 @@ void transmit_can_frame_to_interface(const CAN_frame* tx_frame, int interface) {
#endif
switch (interface) {
case CAN_NATIVE:
case CAN_NATIVE: {
CAN_frame_t frame;
frame.MsgID = tx_frame->ID;
frame.FIR.B.FF = tx_frame->ext_ID ? CAN_frame_ext : CAN_frame_std;
frame.FIR.B.DLC = tx_frame->DLC;
frame.FIR.B.RTR = CAN_no_RTR;
for (uint8_t i = 0; i < tx_frame->DLC; i++) {
frame.data.u8[i] = tx_frame->data.u8[i];
CANMessage frame;
frame.id = tx_frame->ID;
frame.ext = tx_frame->ext_ID;
frame.len = tx_frame->DLC;
for (uint8_t i = 0; i < frame.len; i++) {
frame.data[i] = tx_frame->data.u8[i];
}
send_ok_native = ESP32Can.CANWriteFrame(&frame);
send_ok_native = ACAN_ESP32::can.tryToSend(frame);
if (!send_ok_native) {
datalayer.system.info.can_native_send_fail = true;
}
break;
} break;
case CAN_ADDON_MCP2515: {
//Struct with ACAN2515 library format, needed to use the MCP2515 library for CAN2
CANMessage MCP2515Frame;
MCP2515Frame.id = tx_frame->ID;
MCP2515Frame.ext = tx_frame->ext_ID ? CAN_frame_ext : CAN_frame_std;
MCP2515Frame.ext = tx_frame->ext_ID;
MCP2515Frame.len = tx_frame->DLC;
MCP2515Frame.rtr = false;
for (uint8_t i = 0; i < MCP2515Frame.len; i++) {
@ -232,7 +278,7 @@ void transmit_can_frame_to_interface(const CAN_frame* tx_frame, int interface) {
MCP2518Frame.type = CANFDMessage::CAN_DATA;
}
MCP2518Frame.id = tx_frame->ID;
MCP2518Frame.ext = tx_frame->ext_ID ? CAN_frame_ext : CAN_frame_std;
MCP2518Frame.ext = tx_frame->ext_ID;
MCP2518Frame.len = tx_frame->DLC;
for (uint8_t i = 0; i < MCP2518Frame.len; i++) {
MCP2518Frame.data[i] = tx_frame->data.u8[i];
@ -264,21 +310,22 @@ void receive_can() {
}
void receive_frame_can_native() { // This section checks if we have a complete CAN message incoming on native CAN port
CAN_frame_t rx_frame_native;
if (xQueueReceive(CAN_cfg.rx_queue, &rx_frame_native, 0) == pdTRUE) {
CAN_frame rx_frame;
rx_frame.ID = rx_frame_native.MsgID;
if (rx_frame_native.FIR.B.FF == CAN_frame_std) {
rx_frame.ext_ID = false;
} else { //CAN_frame_ext == 1
rx_frame.ext_ID = true;
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);
}
rx_frame.DLC = rx_frame_native.FIR.B.DLC;
for (uint8_t i = 0; i < rx_frame.DLC && i < 8; i++) {
rx_frame.data.u8[i] = rx_frame_native.data.u8[i];
}
//message incoming, pass it on to the handler
map_can_frame_to_variable(&rx_frame, CAN_NATIVE);
}
}
@ -290,7 +337,7 @@ void receive_frame_can_addon() { // This section checks if we have a complete C
can2515->receive(MCP2515frame);
rx_frame.ID = MCP2515frame.id;
rx_frame.ext_ID = MCP2515frame.ext ? CAN_frame_ext : CAN_frame_std;
rx_frame.ext_ID = MCP2515frame.ext;
rx_frame.DLC = MCP2515frame.len;
for (uint8_t i = 0; i < MCP2515frame.len && i < 8; i++) {
rx_frame.data.u8[i] = MCP2515frame.data[i];
@ -404,7 +451,7 @@ void dump_can_frame(CAN_frame& frame, frameDirection msgDir) {
void stop_can() {
if (can_receivers.find(CAN_NATIVE) != can_receivers.end()) {
ESP32Can.CANStop();
ACAN_ESP32::can.end();
}
if (can2515) {
@ -420,7 +467,7 @@ void stop_can() {
void restart_can() {
if (can_receivers.find(CAN_NATIVE) != can_receivers.end()) {
ESP32Can.CANInit();
ACAN_ESP32::can.begin(*settingsespcan);
}
if (can2515) {
@ -435,11 +482,10 @@ void restart_can() {
}
CAN_Speed change_can_speed(CAN_Interface interface, CAN_Speed speed) {
auto oldSpeed = (CAN_Speed)CAN_cfg.speed;
auto oldSpeed = (CAN_Speed)settingsespcan->mDesiredBitRate;
if (interface == CAN_Interface::CAN_NATIVE) {
CAN_cfg.speed = (CAN_speed_t)speed;
// ReInit native CAN module at new speed
ESP32Can.CANInit();
settingsespcan->mDesiredBitRate = (int)speed;
ACAN_ESP32::can.begin(*settingsespcan);
}
return oldSpeed;
return speed;
}

View file

@ -4,6 +4,7 @@
#include "../../devboard/utils/types.h"
extern bool use_canfd_as_can;
extern uint8_t user_selected_can_addon_crystal_frequency_mhz;
void dump_can_frame(CAN_frame& frame, frameDirection msgDir);
void transmit_can_frame_to_interface(const CAN_frame* tx_frame, int interface);

View file

@ -1,7 +1,6 @@
#ifndef _OBD_H_
#define _OBD_H_
#include "../../lib/miwagner-ESP32-Arduino-CAN/ESP32CAN.h"
#include "comm_can.h"
void handle_obd_frame(CAN_frame& rx_frame);

View file

@ -33,6 +33,8 @@ void init_stored_settings() {
settings.putBool("EQUIPMENT_STOP", datalayer.system.settings.equipment_stop_active);
#endif // LOAD_SAVED_SETTINGS_ON_BOOT
esp32hal->set_default_configuration_values();
char tempSSIDstring[63]; // Allocate buffer with sufficient size
size_t lengthSSID = settings.getString("SSID", tempSSIDstring, sizeof(tempSSIDstring));
if (lengthSSID > 0) { // Successfully read the string from memory. Set it to SSID!
@ -103,6 +105,7 @@ void init_stored_settings() {
user_selected_inverter_ah_capacity = settings.getUInt("INVAHCAPACITY", 0);
user_selected_inverter_battery_type = settings.getUInt("INVBTYPE", 0);
user_selected_inverter_ignore_contactors = settings.getBool("INVICNT", false);
user_selected_can_addon_crystal_frequency_mhz = settings.getUInt("CANFREQ", 8);
user_selected_tesla_digital_HVIL = settings.getBool("DIGITALHVIL", false);
user_selected_tesla_GTW_country = settings.getUInt("GTWCOUNTRY", 0);
user_selected_tesla_GTW_rightHandDrive = settings.getBool("GTWRHD", false);

View file

@ -2,6 +2,7 @@
#define _COMM_NVM_H_
#include <Preferences.h>
#include <WString.h>
#include <limits>
#include "../../datalayer/datalayer.h"
#include "../../devboard/utils/events.h"

View file

@ -3,21 +3,24 @@
#include "../../../USER_SETTINGS.h"
#include <Arduino.h>
#include "hw_3LB.h"
#include "hw_devkit.h"
#include "hw_lilygo.h"
#include "hw_stark.h"
Esp32Hal* esp32hal = nullptr;
void init_hal() {
#if defined(HW_LILYGO)
#include "hw_lilygo.h"
esp32hal = new LilyGoHal();
#elif defined(HW_LILYGO2CAN)
#include "hw_lilygo2can.h"
esp32hal = new LilyGo2CANHal();
#elif defined(HW_STARK)
#include "hw_stark.h"
esp32hal = new StarkHal();
#elif defined(HW_3LB)
#include "hw_3LB.h"
esp32hal = new ThreeLBHal();
#elif defined(HW_DEVKIT)
#include "hw_devkit.h"
esp32hal = new DevKitHal();
#else
#error "No HW defined."

View file

@ -4,6 +4,7 @@
#include <soc/gpio_num.h>
#include <chrono>
#include <unordered_map>
#include "../../../src/communication/nvm/comm_nvm.h"
#include "../../../src/devboard/utils/events.h"
#include "../../../src/devboard/utils/logging.h"
#include "../../../src/devboard/utils/types.h"
@ -24,6 +25,8 @@ class Esp32Hal {
virtual int MODBUS_CORE() { return 0; }
virtual int WIFICORE() { return 0; }
virtual void set_default_configuration_values() {}
template <typename... Pins>
bool alloc_pins(const char* name, Pins... pins) {
std::vector<gpio_num_t> requested_pins = {static_cast<gpio_num_t>(pins)...};
@ -109,6 +112,8 @@ class Esp32Hal {
virtual gpio_num_t MCP2515_CS() { return GPIO_NUM_NC; }
// INT output of MCP2515
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
virtual gpio_num_t MCP2517_SCK() { return GPIO_NUM_NC; }

View file

@ -0,0 +1,75 @@
#ifndef __HW_LILYGO2CAN_H__
#define __HW_LILYGO2CAN_H__
#include "hal.h"
class LilyGo2CANHal : public Esp32Hal {
public:
const char* name() { return "LilyGo T_2CAN"; }
virtual void set_default_configuration_values() {
BatteryEmulatorSettingsStore settings;
if (!settings.settingExists("CANFREQ")) {
settings.saveUInt("CANFREQ", 16);
}
}
virtual gpio_num_t CAN_TX_PIN() { return GPIO_NUM_7; }
virtual gpio_num_t CAN_RX_PIN() { return GPIO_NUM_6; }
// Built In MCP2515 CAN_ADDON
virtual gpio_num_t MCP2515_SCK() { return GPIO_NUM_12; }
virtual gpio_num_t MCP2515_MOSI() { return GPIO_NUM_11; }
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_INT() { return GPIO_NUM_8; }
virtual gpio_num_t MCP2515_RST() { return GPIO_NUM_9; }
// CANFD_ADDON defines for MCP2517
virtual gpio_num_t MCP2517_SCK() { return GPIO_NUM_17; }
virtual gpio_num_t MCP2517_SDI() { return GPIO_NUM_16; }
virtual gpio_num_t MCP2517_SDO() { return GPIO_NUM_18; }
virtual gpio_num_t MCP2517_CS() { return GPIO_NUM_15; }
virtual gpio_num_t MCP2517_INT() { return GPIO_NUM_14; }
// Contactor handling
virtual gpio_num_t POSITIVE_CONTACTOR_PIN() { return GPIO_NUM_38; }
virtual gpio_num_t NEGATIVE_CONTACTOR_PIN() { return GPIO_NUM_39; }
virtual gpio_num_t PRECHARGE_PIN() { return GPIO_NUM_40; }
virtual gpio_num_t SECOND_BATTERY_CONTACTORS_PIN() { return GPIO_NUM_41; }
// Automatic precharging
virtual gpio_num_t HIA4V1_PIN() { return GPIO_NUM_41; }
virtual gpio_num_t INVERTER_DISCONNECT_CONTACTOR_PIN() { return GPIO_NUM_40; }
// SMA CAN contactor pins
virtual gpio_num_t INVERTER_CONTACTOR_ENABLE_PIN() { return GPIO_NUM_14; }
virtual gpio_num_t INVERTER_CONTACTOR_ENABLE_LED_PIN() { return GPIO_NUM_5; }
// LED
virtual gpio_num_t LED_PIN() { return GPIO_NUM_4; }
virtual uint8_t LED_MAX_BRIGHTNESS() { return 40; }
// Equipment stop pin
virtual gpio_num_t EQUIPMENT_STOP_PIN() { return GPIO_NUM_5; }
// Battery wake up pins
virtual gpio_num_t WUP_PIN1() { return GPIO_NUM_40; }
virtual gpio_num_t WUP_PIN2() { return GPIO_NUM_38; }
std::vector<comm_interface> available_interfaces() {
return {comm_interface::CanNative, comm_interface::CanAddonMcp2515};
}
};
#define HalClass LilyGo2CANHal
/* ----- Error checks below, don't change (can't be moved to separate file) ----- */
#ifndef HW_CONFIGURED
#define HW_CONFIGURED
#else
#error Multiple HW defined! Please select a single HW
#endif
#endif

View file

@ -549,6 +549,10 @@ String settings_processor(const String& var, BatteryEmulatorSettingsStore& setti
return settings.getBool("INVICNT") ? "checked" : "";
}
if (var == "CANFREQ") {
return String(settings.getUInt("CANFREQ", 8));
}
if (var == "DIGITALHVIL") {
return settings.getBool("DIGITALHVIL") ? "checked" : "";
}
@ -924,6 +928,9 @@ const char* getCANInterfaceName(CAN_Interface interface) {
</select>
</div>
<label>Can Addon Frequency: </label>
<input name='CANFREQ' type='text' value="%CANFREQ%" pattern="^[0-9]+$" />
<label>Equipment stop button: </label><select name='EQSTOP'>
%EQSTOP%
</select>

View file

@ -512,6 +512,9 @@ void init_webserver() {
} else if (p->name() == "INVBTYPE") {
auto type = atoi(p->value().c_str());
settings.saveUInt("INVBTYPE", (int)type);
} else if (p->name() == "CANFREQ") {
auto type = atoi(p->value().c_str());
settings.saveUInt("CANFREQ", type);
} else if (p->name() == "GTWCOUNTRY") {
auto type = atoi(p->value().c_str());
settings.saveUInt("GTWCOUNTRY", type);
@ -903,6 +906,9 @@ String processor(const String& var) {
#ifdef HW_LILYGO
content += " Hardware: LilyGo T-CAN485";
#endif // HW_LILYGO
#ifdef HW_LILYGO2CAN
content += " Hardware: LilyGo T_2CAN";
#endif // HW_LILYGO2CAN
#ifdef HW_STARK
content += " Hardware: Stark CMR Module";
#endif // HW_STARK

View file

@ -1,298 +0,0 @@
/**
* @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_alloc.h" // Renamed when migrating ESP32 2.x -> 3.x
#include "soc/dport_reg.h"
#include "soc/gpio_sig_map.h"
#include <math.h>
#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) {
xSemaphoreGiveFromISR(sem_tx_complete, &higherPriorityTaskWoken);
}
// 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_SET_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_CAN_RST); //Added https://github.com/miwagner/ESP32-Arduino-CAN/pull/37/commits/feccb722866fbdcc7628b941efe9f79295b0cf81
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, TWAI_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, TWAI_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 = 0x0;
// enable all interrupts
MODULE_CAN->IER.U = 0xef; //ESP32 V3 0XEF ESP32 NOT V3 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;
}
bool CAN_write_frame(const CAN_frame_t *p_frame) {
if (sem_tx_complete == NULL) {
return false;
}
// Write the frame to the controller
CAN_write_frame_phy(p_frame);
return xSemaphoreTake(sem_tx_complete, 20) == pdTRUE ? true : false;
}
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;
}

View file

@ -1,135 +0,0 @@
/**
* @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 <stdint.h>
#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*/
uint64_t u64; /**< \brief Payload u64 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;
extern void gpio_matrix_in(uint32_t gpio, uint32_t signal_idx, bool inv);
extern void gpio_matrix_out(uint32_t gpio, uint32_t signal_idx, bool out_inv, bool oen_inv);
extern void gpio_pad_select_gpio(uint8_t gpio_num);
/**
* \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 1 Frame has been written to the module
*/
bool 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

View file

@ -1,71 +0,0 @@
/**
* @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__ */

View file

@ -1,19 +0,0 @@
#include "ESP32CAN.h"
#include <Arduino.h>
#include "../../devboard/utils/events.h"
int ESP32CAN::CANInit() {
return CAN_init();
}
bool 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;

View file

@ -1,18 +0,0 @@
#ifndef ESP32CAN_H
#define ESP32CAN_H
#include "../../lib/miwagner-ESP32-Arduino-CAN/CAN.h"
#include "../../lib/miwagner-ESP32-Arduino-CAN/CAN_config.h"
class ESP32CAN {
public:
bool tx_ok = true;
int CANInit();
int CANConfigFilter(const CAN_filter_t* p_filter);
bool CANWriteFrame(const CAN_frame_t* p_frame);
int CANStop();
void CANSetCfg(CAN_device_t* can_cfg);
};
extern ESP32CAN ESP32Can;
#endif

View file

@ -1,279 +0,0 @@
/**
* @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_ */

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
//------------------------------------------------------------------------------

View file

@ -0,0 +1,43 @@
{
"build": {
"arduino": {
"ldscript": "esp32s3_out.ld"
},
"core": "esp32",
"extra_flags": [
"-DARDUINO_ESP32S3_DEV",
"-DARDUINO_USB_MODE=1",
"-DARDUINO_RUNNING_CORE=1",
"-DARDUINO_EVENT_RUNNING_CORE=1"
],
"f_cpu": "240000000L",
"f_flash": "80000000L",
"flash_mode": "qio",
"mcu": "esp32s3",
"variant": "esp32s3"
},
"connectivity": [
"wifi"
],
"debug": {
"default_tool": "esp-builtin",
"onboard_tools": [
"esp-builtin"
],
"openocd_target": "esp32s3.cfg"
},
"frameworks": [
"arduino",
"espidf"
],
"name": "ESP32-S3-FLASH-16MB",
"upload": {
"flash_size": "16MB",
"maximum_ram_size": 327680,
"maximum_size": 16777216,
"require_upload_port": true,
"speed": 921600
},
"url": "null",
"vendor": "null"
}

View file

@ -50,3 +50,22 @@ board_build.partitions = min_spiffs.csv
framework = arduino
build_flags = -I include -DHW_STARK -DCOMMON_IMAGE -DDEBUG_VIA_USB
lib_deps =
[env:lilygo_2can_330]
platform = https://github.com/pioarduino/platform-espressif32/releases/download/55.03.30/platform-espressif32.zip
board = esp32s3_flash_16MB
monitor_speed = 115200
monitor_filters = default, time, log2file
board_build.arduino.partitions = default_16MB.csv
board_build.arduino.memory_type = qio_opi
framework = arduino
build_flags =
-I include
-D HW_LILYGO2CAN
-D COMMON_IMAGE
-D BOARD_HAS_PSRAM
-D ARDUINO_USB_MODE=1
-D ARDUINO_USB_CDC_ON_BOOT=1 ;1 is to use the USB port as a serial port
-D ARDUINO_RUNNING_CORE=1 ; Arduino Runs On Core (setup, loop)
-D ARDUINO_EVENT_RUNNING_CORE=1 ; Events Run On Core
lib_deps =

27
test/emul/Preferences.h Normal file
View file

@ -0,0 +1,27 @@
#ifndef PREFERENCES
#define PREFERENCES
#include <stdint.h>
class Preferences {
public:
Preferences() {}
bool begin(const char* name, bool readOnly = false, const char* partition_label = NULL);
void end();
bool clear();
size_t putUInt(const char* key, uint32_t value) { return 0; }
size_t putBool(const char* key, bool value) { return 0; }
size_t putString(const char* key, const char* value) { return 0; }
size_t putString(const char* key, String value) { return 0; }
bool isKey(const char* key) { return false; }
uint32_t getUInt(const char* key, uint32_t defaultValue = 0) { return 0; }
bool getBool(const char* key, bool defaultValue = false) { return false; }
size_t getString(const char* key, char* value, size_t maxLen) { return 0; }
String getString(const char* key, String defaultValue = String()) { return String(); }
};
#endif

View file

@ -43,6 +43,9 @@ class String {
// Accessor
const std::string& str() const { return data; }
// Comparison operators
bool operator==(const String& rhs) const { return data == rhs.data; }
// Concatenation
String operator+(const String& rhs) const { return String(data + rhs.data); }