mirror of
https://github.com/dalathegreat/Battery-Emulator.git
synced 2025-10-03 01:39:30 +02:00
Initial version of Lilygo T_2CAN board
This commit is contained in:
parent
50f4227266
commit
62486d9bf1
14 changed files with 213 additions and 877 deletions
|
@ -31,7 +31,7 @@
|
||||||
#include "src/devboard/wifi/wifi.h"
|
#include "src/devboard/wifi/wifi.h"
|
||||||
#include "src/inverter/INVERTERS.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!
|
#error You must select a target hardware in the USER_SETTINGS.h file!
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -1,7 +1,8 @@
|
||||||
#include "comm_can.h"
|
#include "comm_can.h"
|
||||||
#include <algorithm>
|
#include <algorithm>
|
||||||
#include <map>
|
#include <map>
|
||||||
#include "../../lib/miwagner-ESP32-Arduino-CAN/ESP32CAN.h"
|
#include "esp_twai.h"
|
||||||
|
#include "esp_twai_onchip.h"
|
||||||
#include "../../lib/pierremolinaro-ACAN2517FD/ACAN2517FD.h"
|
#include "../../lib/pierremolinaro-ACAN2517FD/ACAN2517FD.h"
|
||||||
#include "../../lib/pierremolinaro-acan2515/ACAN2515.h"
|
#include "../../lib/pierremolinaro-acan2515/ACAN2515.h"
|
||||||
#include "CanReceiver.h"
|
#include "CanReceiver.h"
|
||||||
|
@ -20,7 +21,11 @@ struct CanReceiverRegistration {
|
||||||
static std::multimap<CAN_Interface, CanReceiverRegistration> can_receivers;
|
static std::multimap<CAN_Interface, CanReceiverRegistration> can_receivers;
|
||||||
|
|
||||||
// Parameters
|
// Parameters
|
||||||
CAN_device_t CAN_cfg; // CAN Config
|
twai_node_handle_t node_hdl = NULL;
|
||||||
|
twai_onchip_node_config_t node_config = {
|
||||||
|
.tx_queue_depth = 5
|
||||||
|
};
|
||||||
|
|
||||||
const uint8_t rx_queue_size = 10; // Receive Queue size
|
const uint8_t rx_queue_size = 10; // Receive Queue size
|
||||||
volatile bool send_ok_native = 0;
|
volatile bool send_ok_native = 0;
|
||||||
volatile bool send_ok_2515 = 0;
|
volatile bool send_ok_2515 = 0;
|
||||||
|
@ -57,6 +62,32 @@ ACAN2517FDSettings* settings2517;
|
||||||
|
|
||||||
bool native_can_initialized = false;
|
bool native_can_initialized = false;
|
||||||
|
|
||||||
|
static bool twai_rx_callback(twai_node_handle_t handle, const twai_rx_done_event_data_t *edata, void *user_ctx)
|
||||||
|
{
|
||||||
|
uint8_t recv_buff[8];
|
||||||
|
twai_frame_t rx_frame = {
|
||||||
|
.buffer = recv_buff,
|
||||||
|
.buffer_len = sizeof(recv_buff),
|
||||||
|
};
|
||||||
|
if (ESP_OK == twai_node_receive_from_isr(handle, &rx_frame)) {
|
||||||
|
CAN_frame frame;
|
||||||
|
frame.ID = rx_frame.header.id;
|
||||||
|
frame.DLC = rx_frame.header.dlc;
|
||||||
|
frame.ext_ID = rx_frame.header.ide;
|
||||||
|
for (uint8_t i = 0; i < frame.DLC && i < 8; i++) {
|
||||||
|
frame.data.u8[i] = rx_frame.buffer[i];
|
||||||
|
}
|
||||||
|
map_can_frame_to_variable(&frame, CAN_NATIVE);
|
||||||
|
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
twai_event_callbacks_t user_cbs = {
|
||||||
|
.on_rx_done = twai_rx_callback
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
bool init_CAN() {
|
bool init_CAN() {
|
||||||
|
|
||||||
auto nativeIt = can_receivers.find(CAN_NATIVE);
|
auto nativeIt = can_receivers.find(CAN_NATIVE);
|
||||||
|
@ -73,17 +104,17 @@ bool init_CAN() {
|
||||||
digitalWrite(se_pin, LOW);
|
digitalWrite(se_pin, LOW);
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_cfg.speed = (CAN_speed_t)nativeIt->second.speed;
|
|
||||||
|
|
||||||
if (!esp32hal->alloc_pins("CAN", tx_pin, rx_pin)) {
|
if (!esp32hal->alloc_pins("CAN", tx_pin, rx_pin)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_cfg.tx_pin_id = tx_pin;
|
node_config.io_cfg.tx = tx_pin;
|
||||||
CAN_cfg.rx_pin_id = rx_pin;
|
node_config.io_cfg.rx = rx_pin;
|
||||||
CAN_cfg.rx_queue = xQueueCreate(rx_queue_size, sizeof(CAN_frame_t));
|
node_config.bit_timing.bitrate = (int)nativeIt->second.speed * 1000UL;
|
||||||
// Init CAN Module
|
twai_new_node_onchip(&node_config, &node_hdl);
|
||||||
ESP32Can.CANInit();
|
twai_node_register_event_callbacks(node_hdl, &user_cbs, NULL);
|
||||||
|
twai_node_enable(node_hdl);
|
||||||
|
|
||||||
native_can_initialized = true;
|
native_can_initialized = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -104,6 +135,15 @@ bool init_CAN() {
|
||||||
#endif // DEBUG_LOG
|
#endif // DEBUG_LOG
|
||||||
gBuffer.initWithSize(25);
|
gBuffer.initWithSize(25);
|
||||||
|
|
||||||
|
//ToDo: Refactor this
|
||||||
|
pinMode(9, OUTPUT);
|
||||||
|
digitalWrite(9, HIGH);
|
||||||
|
delay(100);
|
||||||
|
digitalWrite(9, LOW);
|
||||||
|
delay(100);
|
||||||
|
digitalWrite(9, HIGH);
|
||||||
|
delay(100);
|
||||||
|
|
||||||
can2515 = new ACAN2515(cs_pin, SPI2515, int_pin);
|
can2515 = new ACAN2515(cs_pin, SPI2515, int_pin);
|
||||||
|
|
||||||
SPI2515.begin(sck_pin, miso_pin, mosi_pin);
|
SPI2515.begin(sck_pin, miso_pin, mosi_pin);
|
||||||
|
@ -206,15 +246,15 @@ void transmit_can_frame_to_interface(const CAN_frame* tx_frame, int interface) {
|
||||||
switch (interface) {
|
switch (interface) {
|
||||||
case CAN_NATIVE:
|
case CAN_NATIVE:
|
||||||
|
|
||||||
CAN_frame_t frame;
|
twai_frame_t frame;
|
||||||
frame.MsgID = tx_frame->ID;
|
frame.header.id = tx_frame->ID;
|
||||||
frame.FIR.B.FF = tx_frame->ext_ID ? CAN_frame_ext : CAN_frame_std;
|
frame.header.dlc = tx_frame->DLC;
|
||||||
frame.FIR.B.DLC = tx_frame->DLC;
|
frame.buffer = tx_frame->data.u8;
|
||||||
frame.FIR.B.RTR = CAN_no_RTR;
|
frame.buffer_len = tx_frame->DLC;
|
||||||
for (uint8_t i = 0; i < tx_frame->DLC; i++) {
|
frame.header.ide = tx_frame->ext_ID ? 1 : 0;
|
||||||
frame.data.u8[i] = tx_frame->data.u8[i];
|
|
||||||
}
|
send_ok_native = twai_node_transmit(node_hdl, &frame, 0);
|
||||||
send_ok_native = ESP32Can.CANWriteFrame(&frame);
|
|
||||||
if (!send_ok_native) {
|
if (!send_ok_native) {
|
||||||
datalayer.system.info.can_native_send_fail = true;
|
datalayer.system.info.can_native_send_fail = true;
|
||||||
}
|
}
|
||||||
|
@ -223,7 +263,7 @@ void transmit_can_frame_to_interface(const CAN_frame* tx_frame, int interface) {
|
||||||
//Struct with ACAN2515 library format, needed to use the MCP2515 library for CAN2
|
//Struct with ACAN2515 library format, needed to use the MCP2515 library for CAN2
|
||||||
CANMessage MCP2515Frame;
|
CANMessage MCP2515Frame;
|
||||||
MCP2515Frame.id = tx_frame->ID;
|
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.len = tx_frame->DLC;
|
||||||
MCP2515Frame.rtr = false;
|
MCP2515Frame.rtr = false;
|
||||||
for (uint8_t i = 0; i < MCP2515Frame.len; i++) {
|
for (uint8_t i = 0; i < MCP2515Frame.len; i++) {
|
||||||
|
@ -244,7 +284,7 @@ void transmit_can_frame_to_interface(const CAN_frame* tx_frame, int interface) {
|
||||||
MCP2518Frame.type = CANFDMessage::CAN_DATA;
|
MCP2518Frame.type = CANFDMessage::CAN_DATA;
|
||||||
}
|
}
|
||||||
MCP2518Frame.id = tx_frame->ID;
|
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;
|
MCP2518Frame.len = tx_frame->DLC;
|
||||||
for (uint8_t i = 0; i < MCP2518Frame.len; i++) {
|
for (uint8_t i = 0; i < MCP2518Frame.len; i++) {
|
||||||
MCP2518Frame.data[i] = tx_frame->data.u8[i];
|
MCP2518Frame.data[i] = tx_frame->data.u8[i];
|
||||||
|
@ -262,10 +302,6 @@ void transmit_can_frame_to_interface(const CAN_frame* tx_frame, int interface) {
|
||||||
|
|
||||||
// Receive functions
|
// Receive functions
|
||||||
void receive_can() {
|
void receive_can() {
|
||||||
if (native_can_initialized) {
|
|
||||||
receive_frame_can_native(); // Receive CAN messages from native CAN port
|
|
||||||
}
|
|
||||||
|
|
||||||
if (can2515) {
|
if (can2515) {
|
||||||
receive_frame_can_addon(); // Receive CAN messages on add-on MCP2515 chip
|
receive_frame_can_addon(); // Receive CAN messages on add-on MCP2515 chip
|
||||||
}
|
}
|
||||||
|
@ -275,24 +311,7 @@ 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;
|
|
||||||
}
|
|
||||||
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);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void receive_frame_can_addon() { // This section checks if we have a complete CAN message incoming on add-on CAN port
|
void receive_frame_can_addon() { // This section checks if we have a complete CAN message incoming on add-on CAN port
|
||||||
CAN_frame rx_frame; // Struct with our CAN format
|
CAN_frame rx_frame; // Struct with our CAN format
|
||||||
|
@ -302,7 +321,7 @@ void receive_frame_can_addon() { // This section checks if we have a complete C
|
||||||
can2515->receive(MCP2515frame);
|
can2515->receive(MCP2515frame);
|
||||||
|
|
||||||
rx_frame.ID = MCP2515frame.id;
|
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;
|
rx_frame.DLC = MCP2515frame.len;
|
||||||
for (uint8_t i = 0; i < MCP2515frame.len && i < 8; i++) {
|
for (uint8_t i = 0; i < MCP2515frame.len && i < 8; i++) {
|
||||||
rx_frame.data.u8[i] = MCP2515frame.data[i];
|
rx_frame.data.u8[i] = MCP2515frame.data[i];
|
||||||
|
@ -415,7 +434,8 @@ void dump_can_frame(CAN_frame& frame, frameDirection msgDir) {
|
||||||
|
|
||||||
void stop_can() {
|
void stop_can() {
|
||||||
if (can_receivers.find(CAN_NATIVE) != can_receivers.end()) {
|
if (can_receivers.find(CAN_NATIVE) != can_receivers.end()) {
|
||||||
ESP32Can.CANStop();
|
//ToDo: Implement
|
||||||
|
//ESP32Can.CANStop();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (can2515) {
|
if (can2515) {
|
||||||
|
@ -431,7 +451,8 @@ void stop_can() {
|
||||||
|
|
||||||
void restart_can() {
|
void restart_can() {
|
||||||
if (can_receivers.find(CAN_NATIVE) != can_receivers.end()) {
|
if (can_receivers.find(CAN_NATIVE) != can_receivers.end()) {
|
||||||
ESP32Can.CANInit();
|
//ToDo: Implement
|
||||||
|
//ESP32Can.CANInit();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (can2515) {
|
if (can2515) {
|
||||||
|
@ -446,11 +467,12 @@ void restart_can() {
|
||||||
}
|
}
|
||||||
|
|
||||||
CAN_Speed change_can_speed(CAN_Interface interface, CAN_Speed speed) {
|
CAN_Speed change_can_speed(CAN_Interface interface, CAN_Speed speed) {
|
||||||
auto oldSpeed = (CAN_Speed)CAN_cfg.speed;
|
//ToDo: Implement
|
||||||
if (interface == CAN_Interface::CAN_NATIVE) {
|
//auto oldSpeed = (CAN_Speed)CAN_cfg.speed;
|
||||||
CAN_cfg.speed = (CAN_speed_t)speed;
|
//if (interface == CAN_Interface::CAN_NATIVE) {
|
||||||
|
// CAN_cfg.speed = (CAN_speed_t)speed;
|
||||||
// ReInit native CAN module at new speed
|
// ReInit native CAN module at new speed
|
||||||
ESP32Can.CANInit();
|
// ESP32Can.CANInit();
|
||||||
}
|
//}
|
||||||
return oldSpeed;
|
return speed;
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,7 +1,6 @@
|
||||||
#ifndef _OBD_H_
|
#ifndef _OBD_H_
|
||||||
#define _OBD_H_
|
#define _OBD_H_
|
||||||
|
|
||||||
#include "../../lib/miwagner-ESP32-Arduino-CAN/ESP32CAN.h"
|
|
||||||
#include "comm_can.h"
|
#include "comm_can.h"
|
||||||
|
|
||||||
void handle_obd_frame(CAN_frame& rx_frame);
|
void handle_obd_frame(CAN_frame& rx_frame);
|
||||||
|
|
|
@ -3,21 +3,24 @@
|
||||||
#include "../../../USER_SETTINGS.h"
|
#include "../../../USER_SETTINGS.h"
|
||||||
|
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
#include "hw_3LB.h"
|
|
||||||
#include "hw_devkit.h"
|
|
||||||
#include "hw_lilygo.h"
|
|
||||||
#include "hw_stark.h"
|
|
||||||
|
|
||||||
Esp32Hal* esp32hal = nullptr;
|
Esp32Hal* esp32hal = nullptr;
|
||||||
|
|
||||||
void init_hal() {
|
void init_hal() {
|
||||||
#if defined(HW_LILYGO)
|
#if defined(HW_LILYGO)
|
||||||
|
#include "hw_lilygo.h"
|
||||||
esp32hal = new LilyGoHal();
|
esp32hal = new LilyGoHal();
|
||||||
|
#elif defined(HW_LILYGO2CAN)
|
||||||
|
#include "hw_lilygo2can.h"
|
||||||
|
esp32hal = new LilyGo2CANHal();
|
||||||
#elif defined(HW_STARK)
|
#elif defined(HW_STARK)
|
||||||
|
#include "hw_stark.h"
|
||||||
esp32hal = new StarkHal();
|
esp32hal = new StarkHal();
|
||||||
#elif defined(HW_3LB)
|
#elif defined(HW_3LB)
|
||||||
|
#include "hw_3LB.h"
|
||||||
esp32hal = new ThreeLBHal();
|
esp32hal = new ThreeLBHal();
|
||||||
#elif defined(HW_DEVKIT)
|
#elif defined(HW_DEVKIT)
|
||||||
|
#include "hw_devkit.h"
|
||||||
esp32hal = new DevKitHal();
|
esp32hal = new DevKitHal();
|
||||||
#else
|
#else
|
||||||
#error "No HW defined."
|
#error "No HW defined."
|
||||||
|
|
67
Software/src/devboard/hal/hw_lilygo2can.h
Normal file
67
Software/src/devboard/hal/hw_lilygo2can.h
Normal file
|
@ -0,0 +1,67 @@
|
||||||
|
#ifndef __HW_LILYGO2CAN_H__
|
||||||
|
#define __HW_LILYGO2CAN_H__
|
||||||
|
|
||||||
|
#include "hal.h"
|
||||||
|
|
||||||
|
class LilyGo2CANHal : public Esp32Hal {
|
||||||
|
public:
|
||||||
|
const char* name() { return "LilyGo T_2CAN"; }
|
||||||
|
|
||||||
|
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; }
|
||||||
|
|
||||||
|
// 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
|
|
@ -891,6 +891,9 @@ String processor(const String& var) {
|
||||||
#ifdef HW_LILYGO
|
#ifdef HW_LILYGO
|
||||||
content += " Hardware: LilyGo T-CAN485";
|
content += " Hardware: LilyGo T-CAN485";
|
||||||
#endif // HW_LILYGO
|
#endif // HW_LILYGO
|
||||||
|
#ifdef HW_LILYGO2CAN
|
||||||
|
content += " Hardware: LilyGo T_2CAN";
|
||||||
|
#endif // HW_LILYGO2CAN
|
||||||
#ifdef HW_STARK
|
#ifdef HW_STARK
|
||||||
content += " Hardware: Stark CMR Module";
|
content += " Hardware: Stark CMR Module";
|
||||||
#endif // HW_STARK
|
#endif // HW_STARK
|
||||||
|
|
|
@ -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;
|
|
||||||
}
|
|
|
@ -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
|
|
|
@ -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__ */
|
|
|
@ -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;
|
|
|
@ -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
|
|
|
@ -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_ */
|
|
43
boards/esp32s3_flash_16MB.json
Normal file
43
boards/esp32s3_flash_16MB.json
Normal 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"
|
||||||
|
}
|
|
@ -50,3 +50,22 @@ board_build.partitions = min_spiffs.csv
|
||||||
framework = arduino
|
framework = arduino
|
||||||
build_flags = -I include -DHW_STARK -DCOMMON_IMAGE -DDEBUG_VIA_USB
|
build_flags = -I include -DHW_STARK -DCOMMON_IMAGE -DDEBUG_VIA_USB
|
||||||
lib_deps =
|
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 =
|
Loading…
Add table
Add a link
Reference in a new issue