Merge branch 'feat/twai_driver_legacy_target_support' into 'master'

feat(driver_twai): twai driver legacy target support (part_2)

Closes IDF-12480 and IDF-12808

See merge request espressif/esp-idf!36487
This commit is contained in:
Wan Lei
2025-05-01 11:05:11 +08:00
79 changed files with 2617 additions and 1562 deletions

View File

@@ -109,6 +109,7 @@ else()
esp_driver_ana_cmpr esp_driver_i2s esp_driver_sdmmc esp_driver_sdspi esp_driver_sdio
esp_driver_dac esp_driver_rmt esp_driver_tsens esp_driver_sdm esp_driver_i2c
esp_driver_uart esp_driver_ledc esp_driver_parlio esp_driver_usb_serial_jtag
esp_driver_twai
LDFRAGMENTS ${ldfragments}
)
if(CONFIG_SOC_ADC_SUPPORTED AND

View File

@@ -72,15 +72,7 @@ components/driver/test_apps/legacy_timer_driver:
depends_filepatterns:
- components/driver/deprecated/**/*timer*
components/driver/test_apps/touch_sensor_v1:
disable:
- if: SOC_TOUCH_SENSOR_VERSION != 1
components/driver/test_apps/touch_sensor_v2:
disable:
- if: SOC_TOUCH_SENSOR_VERSION != 2
components/driver/test_apps/twai:
components/driver/test_apps/legacy_twai:
disable:
- if: SOC_TWAI_SUPPORTED != 1 or SOC_TWAI_SUPPORT_FD == 1
reason: legacy driver doesn't support FD
@@ -88,3 +80,11 @@ components/driver/test_apps/twai:
- components/driver/twai/**/*
depends_components:
- esp_driver_gpio
components/driver/test_apps/touch_sensor_v1:
disable:
- if: SOC_TOUCH_SENSOR_VERSION != 1
components/driver/test_apps/touch_sensor_v2:
disable:
- if: SOC_TOUCH_SENSOR_VERSION != 2

View File

@@ -1,4 +1,4 @@
CONFIG_FREERTOS_HZ=1000
CONFIG_ESP_TASK_WDT=n
CONFIG_ESP_TASK_WDT_INIT=n
# primitives for checking sleep internal state
CONFIG_ESP_SLEEP_DEBUG=y

View File

@@ -1,19 +1,11 @@
menu "TWAI Configuration"
menu "Legacy TWAI Driver Configurations"
depends on SOC_TWAI_SUPPORTED
config TWAI_ISR_IN_IRAM
bool "Place TWAI ISR function into IRAM"
config TWAI_SKIP_LEGACY_CONFLICT_CHECK
bool "Skip legacy driver conflict check"
default n
help
Place the TWAI ISR in to IRAM. This will allow the ISR to avoid
cache misses, and also be able to run whilst the cache is disabled
(such as when writing to SPI Flash).
Note that if this option is enabled:
- Users should also set the ESP_INTR_FLAG_IRAM in the driver
configuration structure when installing the driver (see docs for
specifics).
- Alert logging (i.e., setting of the TWAI_ALERT_AND_LOG flag)
will have no effect.
This configuration option used to bypass the conflict check mechanism with legacy code.
config TWAI_ERRATA_FIX_BUS_OFF_REC
bool "Add SW workaround for REC change during bus-off"

View File

@@ -1,9 +1,3 @@
[mapping:twai_hal]
archive: libhal.a
entries:
if TWAI_ISR_IN_IRAM = y:
twai_hal_iram (noflash)
[mapping:twai_driver]
archive: libdriver.a
entries:
@@ -12,3 +6,23 @@ entries:
twai: twai_handle_rx_buffer_frames (noflash)
twai: twai_handle_tx_buffer_frame (noflash)
twai: twai_intr_handler_main (noflash)
[mapping:twai_hal_legacy]
archive: libhal.a
entries:
if TWAI_ISR_IN_IRAM = y:
twai_hal_sja1000: twai_hal_decode_interrupt (noflash)
twai_hal_sja1000: twai_hal_get_events (noflash)
twai_hal_sja1000: twai_hal_format_frame (noflash)
twai_hal_sja1000: twai_hal_parse_frame (noflash)
twai_hal_sja1000: twai_hal_set_tx_buffer_and_transmit (noflash)
twai_hal_sja1000: twai_hal_get_rx_msg_count (noflash)
twai_hal_sja1000: twai_hal_read_rx_fifo (noflash)
twai_hal_sja1000: twai_hal_check_state_flags (noflash)
if TWAI_ERRATA_FIX_RX_FRAME_INVALID = y || TWAI_ERRATA_FIX_RX_FIFO_CORRUPT = y:
twai_hal_sja1000: twai_hal_prepare_for_reset (noflash)
twai_hal_sja1000: twai_hal_recover_from_reset (noflash)
twai_hal_sja1000: twai_hal_backup_config (noflash)
twai_hal_sja1000: twai_hal_restore_config (noflash)
twai_hal_sja1000: twai_hal_get_reset_lost_rx_cnt (noflash)

View File

@@ -15,6 +15,7 @@
#include "esp_intr_alloc.h"
#include "esp_pm.h"
#include "esp_attr.h"
#include "esp_check.h"
#include "esp_heap_caps.h"
#include "esp_clk_tree.h"
#include "clk_ctrl_os.h"
@@ -28,6 +29,7 @@
#include "soc/io_mux_reg.h"
#include "soc/twai_periph.h"
#include "hal/twai_hal.h"
#include "hal/twai_ll.h"
#include "esp_rom_gpio.h"
#if SOC_TWAI_SUPPORT_SLEEP_RETENTION
#include "esp_private/sleep_retention.h"
@@ -79,7 +81,7 @@ typedef struct twai_obj_t {
gpio_num_t rx_io;
gpio_num_t clkout_io;
gpio_num_t bus_off_io;
twai_hal_context_t hal; // hal context
twai_hal_context_t *hal; // hal context
//Control and status members
twai_state_t state;
twai_mode_t mode;
@@ -136,11 +138,11 @@ static void twai_alert_handler(twai_obj_t *p_twai_obj, uint32_t alert_code, int
static inline void twai_handle_rx_buffer_frames(twai_obj_t *p_twai_obj, BaseType_t *task_woken, int *alert_req)
{
#ifdef SOC_TWAI_SUPPORTS_RX_STATUS
uint32_t msg_count = twai_hal_get_rx_msg_count(&p_twai_obj->hal);
uint32_t msg_count = twai_hal_get_rx_msg_count(p_twai_obj->hal);
for (uint32_t i = 0; i < msg_count; i++) {
twai_hal_frame_t frame;
if (twai_hal_read_rx_buffer_and_clear(&p_twai_obj->hal, &frame)) {
if (twai_hal_read_rx_fifo(p_twai_obj->hal, &frame)) {
//Valid frame copied from RX buffer
if (xQueueSendFromISR(p_twai_obj->rx_queue, &frame, task_woken) == pdTRUE) {
p_twai_obj->rx_msg_count++;
@@ -155,12 +157,12 @@ static inline void twai_handle_rx_buffer_frames(twai_obj_t *p_twai_obj, BaseType
}
}
#else //SOC_TWAI_SUPPORTS_RX_STATUS
uint32_t msg_count = twai_hal_get_rx_msg_count(&p_twai_obj->hal);
uint32_t msg_count = twai_hal_get_rx_msg_count(p_twai_obj->hal);
bool overrun = false;
//Clear all valid RX frames
for (int i = 0; i < msg_count; i++) {
twai_hal_frame_t frame;
if (twai_hal_read_rx_buffer_and_clear(&p_twai_obj->hal, &frame)) {
if (twai_hal_read_rx_fifo(p_twai_obj->hal, &frame)) {
//Valid frame copied from RX buffer
if (xQueueSendFromISR(p_twai_obj->rx_queue, &frame, task_woken) == pdTRUE) {
p_twai_obj->rx_msg_count++;
@@ -176,16 +178,16 @@ static inline void twai_handle_rx_buffer_frames(twai_obj_t *p_twai_obj, BaseType
}
//All remaining frames are treated as overrun. Clear them all
if (overrun) {
p_twai_obj->rx_overrun_count += twai_hal_clear_rx_fifo_overrun(&p_twai_obj->hal);
p_twai_obj->rx_overrun_count += twai_hal_clear_rx_fifo_overrun(p_twai_obj->hal);
twai_alert_handler(p_twai_obj, TWAI_ALERT_RX_FIFO_OVERRUN, alert_req);
}
#endif //SOC_TWAI_SUPPORTS_RX_STATUS
}
static inline void twai_handle_tx_buffer_frame(twai_obj_t *p_twai_obj, BaseType_t *task_woken, int *alert_req)
static inline void twai_handle_tx_buffer_frame(twai_obj_t *p_twai_obj, bool tx_success, BaseType_t *task_woken, int *alert_req)
{
//Handle previously transmitted frame
if (twai_hal_check_last_tx_successful(&p_twai_obj->hal)) {
if (tx_success) {
twai_alert_handler(p_twai_obj, TWAI_ALERT_TX_SUCCESS, alert_req);
} else {
p_twai_obj->tx_failed_count++;
@@ -197,13 +199,13 @@ static inline void twai_handle_tx_buffer_frame(twai_obj_t *p_twai_obj, BaseType_
assert(p_twai_obj->tx_msg_count >= 0); //Sanity check
//If not bus-off, check if there are more frames to transmit
if (!twai_hal_check_state_flags(&p_twai_obj->hal, TWAI_HAL_STATE_FLAG_BUS_OFF)
if (!twai_hal_check_state_flags(p_twai_obj->hal, TWAI_HAL_STATE_FLAG_BUS_OFF)
&& p_twai_obj->tx_msg_count > 0
&& p_twai_obj->tx_queue != NULL) {
twai_hal_frame_t frame;
int res = xQueueReceiveFromISR(p_twai_obj->tx_queue, &frame, task_woken);
if (res == pdTRUE) {
twai_hal_set_tx_buffer_and_transmit(&p_twai_obj->hal, &frame);
twai_hal_set_tx_buffer_and_transmit(p_twai_obj->hal, &frame, 0);
} else {
assert(false && "failed to get a frame from TX queue");
}
@@ -220,16 +222,16 @@ static void twai_intr_handler_main(void *arg)
int alert_req = 0;
uint32_t events;
portENTER_CRITICAL_ISR(&p_twai_obj->spinlock);
events = twai_hal_get_events(&p_twai_obj->hal); //Get the events that triggered the interrupt
events = twai_hal_get_events(p_twai_obj->hal); //Get the events that triggered the interrupt
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
if (events & TWAI_HAL_EVENT_NEED_PERIPH_RESET) {
twai_hal_prepare_for_reset(&p_twai_obj->hal);
twai_hal_prepare_for_reset(p_twai_obj->hal);
TWAI_RCC_ATOMIC() {
twai_ll_reset_register(p_twai_obj->controller_id);
}
twai_hal_recover_from_reset(&p_twai_obj->hal);
p_twai_obj->rx_missed_count += twai_hal_get_reset_lost_rx_cnt(&p_twai_obj->hal);
twai_hal_recover_from_reset(p_twai_obj->hal);
p_twai_obj->rx_missed_count += twai_hal_get_reset_lost_rx_cnt(p_twai_obj->hal);
twai_alert_handler(p_twai_obj, TWAI_ALERT_PERIPH_RESET, &alert_req);
}
#endif
@@ -238,7 +240,7 @@ static void twai_intr_handler_main(void *arg)
twai_handle_rx_buffer_frames(p_twai_obj, &task_woken, &alert_req);
}
if (events & TWAI_HAL_EVENT_TX_BUFF_FREE) {
twai_handle_tx_buffer_frame(p_twai_obj, &task_woken, &alert_req);
twai_handle_tx_buffer_frame(p_twai_obj, (events & TWAI_HAL_EVENT_TX_SUCCESS), &task_woken, &alert_req);
}
//Handle events that only require alerting (i.e. no handler)
@@ -270,7 +272,7 @@ static void twai_intr_handler_main(void *arg)
//Returned to error active
twai_alert_handler(p_twai_obj, TWAI_ALERT_ERR_ACTIVE, &alert_req);
}
if (events & TWAI_HAL_EVENT_ABOVE_EWL) {
if (events & TWAI_HAL_EVENT_ERROR_WARNING) {
//TEC or REC surpassed error warning limit
twai_alert_handler(p_twai_obj, TWAI_ALERT_ABOVE_ERR_WARN, &alert_req);
}
@@ -392,7 +394,7 @@ static esp_err_t twai_alloc_driver_obj(const twai_general_config_t *g_config, tw
esp_err_t ret;
//Create a TWAI driver object
twai_obj_t *p_obj = heap_caps_calloc(1, sizeof(twai_obj_t), TWAI_MALLOC_CAPS);
twai_obj_t *p_obj = heap_caps_calloc(1, sizeof(twai_obj_t) + twai_hal_get_mem_requirment(), TWAI_MALLOC_CAPS);
if (p_obj == NULL) {
return ESP_ERR_NO_MEM;
}
@@ -416,6 +418,7 @@ static esp_err_t twai_alloc_driver_obj(const twai_general_config_t *g_config, tw
}
p_obj->controller_id = controller_id;
p_obj->hal = (twai_hal_context_t *)(p_obj + 1); //hal context is place at end of driver context
#if CONFIG_PM_ENABLE
#if SOC_TWAI_CLK_SUPPORT_APB
@@ -550,12 +553,12 @@ esp_err_t twai_driver_install_v2(const twai_general_config_t *g_config, const tw
twai_hal_config_t hal_config = {
.clock_source_hz = clock_source_hz,
.controller_id = controller_id,
.intr_mask = DRIVER_DEFAULT_INTERRUPTS,
.enable_self_test = (p_twai_obj->mode == TWAI_MODE_NO_ACK),
.enable_listen_only = (p_twai_obj->mode == TWAI_MODE_LISTEN_ONLY),
};
if (twai_hal_init(&p_twai_obj->hal, &hal_config) == false) {
ret = ESP_ERR_INVALID_STATE;
goto err;
}
twai_hal_configure(&p_twai_obj->hal, t_config, f_config, DRIVER_DEFAULT_INTERRUPTS, g_config->clkout_divider);
ESP_GOTO_ON_FALSE(twai_hal_init(p_twai_obj->hal, &hal_config), ESP_ERR_INVALID_STATE, err, TWAI_TAG, "hardware not in reset state");
twai_hal_configure(p_twai_obj->hal, t_config, f_config, g_config->clkout_divider);
//Assign GPIO and Interrupts
twai_configure_gpio(p_twai_obj);
@@ -610,7 +613,7 @@ esp_err_t twai_driver_uninstall_v2(twai_handle_t handle)
ESP_ERROR_CHECK(esp_intr_disable(p_twai_obj->isr_handle));
//Clear registers by reading
twai_hal_deinit(&p_twai_obj->hal);
twai_hal_deinit(p_twai_obj->hal);
TWAI_PERI_ATOMIC() {
twai_ll_enable_clock(controller_id, false);
}
@@ -655,7 +658,7 @@ esp_err_t twai_start_v2(twai_handle_t handle)
}
p_twai_obj->rx_msg_count = 0;
p_twai_obj->tx_msg_count = 0;
twai_hal_start(&p_twai_obj->hal, p_twai_obj->mode);
twai_hal_start(p_twai_obj->hal);
p_twai_obj->state = TWAI_STATE_RUNNING;
portEXIT_CRITICAL(&handle->spinlock);
@@ -680,7 +683,7 @@ esp_err_t twai_stop_v2(twai_handle_t handle)
return ESP_ERR_INVALID_STATE;
}
twai_hal_stop(&p_twai_obj->hal);
twai_hal_stop(p_twai_obj->hal);
//Reset TX Queue and message count
if (p_twai_obj->tx_queue != NULL) {
@@ -720,12 +723,27 @@ esp_err_t twai_transmit_v2(twai_handle_t handle, const twai_message_t *message,
//Format frame
esp_err_t ret = ESP_FAIL;
twai_hal_frame_t tx_frame;
twai_hal_format_frame(message, &tx_frame);
twai_frame_header_t header = {
.id = message->identifier,
.dlc = message->data_length_code,
.ide = message->extd,
.rtr = message->rtr,
};
twai_hal_trans_desc_t hal_trans = {
.frame = {
.header = &header,
.buffer = (uint8_t *)message->data,
.buffer_len = TWAI_FRAME_MAX_LEN,
},
.config.retry_cnt = message->ss ? 0 : -1,
.config.loopback = message->self,
};
twai_hal_format_frame(&hal_trans, &tx_frame);
//Check if frame can be sent immediately
if (p_twai_obj->tx_msg_count == 0) {
//No other frames waiting to transmit. Bypass queue and transmit immediately
twai_hal_set_tx_buffer_and_transmit(&p_twai_obj->hal, &tx_frame);
twai_hal_set_tx_buffer_and_transmit(p_twai_obj->hal, &tx_frame, 0);
p_twai_obj->tx_msg_count++;
ret = ESP_OK;
}
@@ -738,9 +756,9 @@ esp_err_t twai_transmit_v2(twai_handle_t handle, const twai_message_t *message,
} else if (xQueueSend(p_twai_obj->tx_queue, &tx_frame, ticks_to_wait) == pdTRUE) {
//Copied to TX Queue
portENTER_CRITICAL(&handle->spinlock);
if ((!twai_hal_check_state_flags(&p_twai_obj->hal, TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED)) && uxQueueMessagesWaiting(p_twai_obj->tx_queue) > 0) {
if ((!twai_hal_check_state_flags(p_twai_obj->hal, TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED)) && uxQueueMessagesWaiting(p_twai_obj->tx_queue) > 0) {
//If the TX buffer is free but the TX queue is not empty. Check if we need to manually start a transmission
if (twai_hal_check_state_flags(&p_twai_obj->hal, TWAI_HAL_STATE_FLAG_BUS_OFF) || !twai_hal_check_state_flags(&p_twai_obj->hal, TWAI_HAL_STATE_FLAG_RUNNING)) {
if (twai_hal_check_state_flags(p_twai_obj->hal, TWAI_HAL_STATE_FLAG_BUS_OFF) || !twai_hal_check_state_flags(p_twai_obj->hal, TWAI_HAL_STATE_FLAG_RUNNING)) {
//TX buffer became free due to bus-off or is no longer running. No need to start a transmission
ret = ESP_ERR_INVALID_STATE;
} else {
@@ -748,7 +766,7 @@ esp_err_t twai_transmit_v2(twai_handle_t handle, const twai_message_t *message,
int res = xQueueReceive(p_twai_obj->tx_queue, &tx_frame, 0);
assert(res == pdTRUE);
(void)res;
twai_hal_set_tx_buffer_and_transmit(&p_twai_obj->hal, &tx_frame);
twai_hal_set_tx_buffer_and_transmit(p_twai_obj->hal, &tx_frame, 0);
p_twai_obj->tx_msg_count++;
ret = ESP_OK;
}
@@ -790,7 +808,14 @@ esp_err_t twai_receive_v2(twai_handle_t handle, twai_message_t *message, TickTyp
portEXIT_CRITICAL(&handle->spinlock);
//Decode frame
twai_hal_parse_frame(&rx_frame, message);
twai_frame_header_t header = {0};
twai_hal_parse_frame(&rx_frame, &header, message->data, TWAI_FRAME_MAX_LEN);
message->identifier = header.id;
message->data_length_code = header.dlc;
message->extd = header.ide;
message->rtr = header.rtr;
//Set remaining bytes of data to 0
memset(message->data + message->data_length_code, 0, TWAI_FRAME_MAX_LEN - message->data_length_code);
return ESP_OK;
}
@@ -870,7 +895,7 @@ esp_err_t twai_initiate_recovery_v2(twai_handle_t handle)
p_twai_obj->tx_msg_count = 0;
//Trigger start of recovery process
twai_hal_start_bus_recovery(&p_twai_obj->hal);
twai_hal_start_bus_recovery(p_twai_obj->hal);
p_twai_obj->state = TWAI_STATE_RECOVERING;
portEXIT_CRITICAL(&handle->spinlock);
@@ -896,8 +921,8 @@ esp_err_t twai_get_status_info_v2(twai_handle_t handle, twai_status_info_t *stat
status_info->tx_error_counter = 0;
status_info->rx_error_counter = 0;
} else {
status_info->tx_error_counter = twai_hal_get_tec(&p_twai_obj->hal);
status_info->rx_error_counter = twai_hal_get_rec(&p_twai_obj->hal);
status_info->tx_error_counter = twai_hal_get_tec(p_twai_obj->hal);
status_info->rx_error_counter = twai_hal_get_rec(p_twai_obj->hal);
}
status_info->msgs_to_tx = p_twai_obj->tx_msg_count;
status_info->msgs_to_rx = p_twai_obj->rx_msg_count;
@@ -927,7 +952,7 @@ esp_err_t twai_clear_transmit_queue_v2(twai_handle_t handle)
portENTER_CRITICAL(&handle->spinlock);
//If a message is currently undergoing transmission, the tx interrupt handler will decrement tx_msg_count
p_twai_obj->tx_msg_count = twai_hal_check_state_flags(&p_twai_obj->hal, TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED) ? 1 : 0;
p_twai_obj->tx_msg_count = twai_hal_check_state_flags(p_twai_obj->hal, TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED) ? 1 : 0;
xQueueReset(p_twai_obj->tx_queue);
portEXIT_CRITICAL(&handle->spinlock);
@@ -970,3 +995,21 @@ static esp_err_t s_twai_create_sleep_retention_link_cb(void *obj)
twai_reg_retention_info[host->controller_id].module_id);
}
#endif
#if CONFIG_TWAI_SKIP_LEGACY_CONFLICT_CHECK
/**
* @brief This function will be called during start up, to check that this legacy TWAI driver is not running along with the new TWAI driver
*/
__attribute__((constructor))
static void check_twai_driver_conflict(void)
{
// This function was declared as weak here. The new TWAI driver has the implementation.
// So if the new TWAI driver is not linked in, then `twai_new_node_onchip()` should be NULL at runtime.
extern __attribute__((weak)) esp_err_t twai_new_node_onchip(const void *node_config, void *node_ret);
if ((void *)twai_new_node_onchip != NULL) {
ESP_EARLY_LOGE(TWAI_TAG, "CONFLICT! driver_ng is not allowed to be used with this old driver");
abort();
}
ESP_EARLY_LOGW(TWAI_TAG, "This driver is an old driver, please migrate your application code to adapt `esp_twai_onchip.h`");
}
#endif

View File

@@ -8,8 +8,7 @@ set(srcs "esp_twai.c")
set(public_include "include")
set(priv_req esp_driver_gpio esp_pm)
# Currently support only FD targets
if(CONFIG_SOC_TWAI_SUPPORT_FD)
if(CONFIG_SOC_TWAI_SUPPORTED)
list(APPEND srcs "esp_twai_onchip.c")
endif()

View File

@@ -1,20 +1,21 @@
menu "ESP-Driver:TWAI Configurations"
depends on SOC_TWAI_SUPPORTED
config TWAI_ISR_INTO_IRAM
bool "Place TWAI ISR in IRAM to reduce latency"
config TWAI_ISR_IN_IRAM
bool "Place TWAI ISR function in IRAM"
select TWAI_OBJ_CACHE_SAFE
default n
help
Place ISR functions to IRAM to increase performance
Place the TWAI ISR in to IRAM to reduce latency and increase performance
config TWAI_ISR_CACHE_SAFE
bool "Allow TWAI ISR to execute when cache is disabled"
select TWAI_ISR_INTO_IRAM
bool "Allow TWAI ISR execute when cache disabled" if !SPI_FLASH_AUTO_SUSPEND
select TWAI_ISR_IN_IRAM
select ESP_PERIPH_CTRL_FUNC_IN_IRAM if TWAI_ERRATA_FIX_RX_FRAME_INVALID || TWAI_ERRATA_FIX_RX_FIFO_CORRUPT
default n
help
Allow TWAI works under Cache disabled, to enabled this config,
all callbacks and user_ctx should also place in IRAM
Allow TWAI works under Cache disabled (such as when writing to SPI Flash),
to enabled this config, all callbacks and user_ctx should also place in IRAM
config TWAI_OBJ_CACHE_SAFE
bool

View File

@@ -4,6 +4,7 @@
* SPDX-License-Identifier: Apache-2.0
*/
#include <sys/param.h>
#include "esp_twai.h"
#include "esp_private/twai_interface.h"
#include "esp_private/twai_utils.h"
@@ -32,7 +33,7 @@ uint32_t twai_node_timing_calc_param(const uint32_t source_freq, const twai_timi
if (total_div != tseg * pre_div) {
continue; // no integer tseg
}
if ((tseg < (hw_limit->tseg1_max + hw_limit->tseg2_max)) && (tseg >= (hw_limit->tseg1_min + hw_limit->tseg2_min))) {
if ((tseg <= (hw_limit->tseg1_max + hw_limit->tseg2_max + 1)) && (tseg >= (hw_limit->tseg1_min + hw_limit->tseg2_min))) {
break;
}
}
@@ -141,12 +142,12 @@ esp_err_t twai_node_transmit(twai_node_handle_t node, const twai_frame_t *frame,
return node->transmit(node, frame, timeout_ms);
}
esp_err_t twai_node_receive_from_isr(twai_node_handle_t node, twai_frame_header_t *header, uint8_t *rx_buffer, size_t buf_sz, size_t *received_len)
esp_err_t twai_node_receive_from_isr(twai_node_handle_t node, twai_frame_t *rx_frame)
{
ESP_RETURN_ON_FALSE_ISR(node && header, ESP_ERR_INVALID_ARG, TAG, "invalid argument: null");
ESP_RETURN_ON_FALSE_ISR(node && rx_frame, ESP_ERR_INVALID_ARG, TAG, "invalid argument: null");
ESP_RETURN_ON_FALSE_ISR(node->receive_isr, ESP_ERR_NOT_SUPPORTED, TAG, "receive func null");
return node->receive_isr(node, header, rx_buffer, buf_sz, received_len);
return node->receive_isr(node, rx_frame);
}
#if CONFIG_TWAI_ENABLE_DEBUG_LOG

View File

@@ -22,16 +22,8 @@
#define TWAI_PERI_ATOMIC()
#endif
#define DRIVER_DEFAULT_INTERRUPTS (TWAIFD_LL_INTR_TX_DONE |\
TWAIFD_LL_INTR_TX_SUCCESS |\
TWAIFD_LL_INTR_RX_NOT_EMPTY |\
TWAIFD_LL_INTR_RX_FULL |\
TWAIFD_LL_INTR_ERR_WARN |\
TWAIFD_LL_INTR_BUS_ERR |\
TWAIFD_LL_INTR_FSM_CHANGE |\
TWAIFD_LL_INTR_ARBI_LOST |\
TWAIFD_LL_INTR_DATA_OVERRUN)
#if SOC_TWAI_SUPPORT_FD
#include "hal/twaifd_ll.h"
static void _twai_rcc_clock_ctrl(uint8_t ctrlr_id, bool enable)
{
TWAI_RCC_ATOMIC() {
@@ -42,12 +34,37 @@ static void _twai_rcc_clock_ctrl(uint8_t ctrlr_id, bool enable)
twaifd_ll_enable_clock(ctrlr_id, enable);
}
}
static void _twai_rcc_clock_sel(uint8_t ctrlr_id, twai_clock_source_t clock)
{
TWAI_PERI_ATOMIC() {
twaifd_ll_set_clock_source(ctrlr_id, clock);
}
}
#else
#include "hal/twai_ll.h"
static void _twai_rcc_clock_ctrl(uint8_t ctrlr_id, bool enable)
{
TWAI_RCC_ATOMIC() {
twai_ll_enable_bus_clock(ctrlr_id, enable);
twai_ll_reset_register(ctrlr_id);
}
TWAI_PERI_ATOMIC() {
twai_ll_enable_clock(ctrlr_id, enable);
}
}
static void _twai_rcc_clock_sel(uint8_t ctrlr_id, twai_clock_source_t clock)
{
TWAI_PERI_ATOMIC() {
twai_ll_set_clock_source(ctrlr_id, clock);
}
}
#endif //SOC_TWAI_SUPPORT_FD
typedef struct {
struct twai_node_base api_base;
int ctrlr_id;
uint64_t gpio_reserved;
twai_hal_context_t hal;
twai_hal_context_t *hal;
intr_handle_t intr_hdl;
QueueHandle_t tx_mount_queue;
twai_clock_source_t curr_clk_src;
@@ -155,37 +172,47 @@ static void _node_release_io(twai_onchip_ctx_t *node)
static void _node_start_trans(twai_onchip_ctx_t *node)
{
const twai_frame_header_t *format = &node->p_curr_tx->header;
twai_hal_context_t *hal = &node->hal;
twai_hal_frame_t tx_frame = {};
const twai_frame_t *frame = node->p_curr_tx;
twai_hal_context_t *hal = node->hal;
int final_dlc = (format->dlc) ? format->dlc : twaifd_len2dlc(node->p_curr_tx->buffer_len);
int data_len = (format->dlc) ? twaifd_dlc2len(format->dlc) : node->p_curr_tx->buffer_len;
twaifd_ll_format_frame_header(format, final_dlc, &tx_frame);
twaifd_ll_format_frame_data(node->p_curr_tx->buffer, data_len, &tx_frame);
twai_hal_frame_t hal_buf = {};
twai_hal_trans_desc_t hal_trans = {
.frame = {
.header = (twai_frame_header_t *) &frame->header,
.buffer = frame->buffer,
.buffer_len = frame->buffer_len,
},
.config = {
.retry_cnt = hal->retry_cnt,
.loopback = hal->enable_loopback,
},
};
twai_hal_format_frame(&hal_trans, &hal_buf);
//TODO: utilize all txt buffers
twaifd_ll_mount_tx_buffer(hal->dev, &tx_frame, 0);
twaifd_ll_set_tx_cmd(hal->dev, 0, TWAIFD_LL_TX_CMD_READY);
twai_hal_set_tx_buffer_and_transmit(hal, &hal_buf, 0);
}
static void _node_isr_main(void *arg)
{
BaseType_t do_yield = pdFALSE;
twai_onchip_ctx_t *twai_ctx = arg;
uint32_t int_stat = twaifd_ll_get_intr_status(twai_ctx->hal.dev);
twai_ctx->tx_error_count = twaifd_ll_get_tec(twai_ctx->hal.dev);
twai_ctx->rx_error_count = twaifd_ll_get_rec(twai_ctx->hal.dev);
twaifd_ll_clr_intr_status(twai_ctx->hal.dev, int_stat);
uint32_t events = twai_hal_get_events(twai_ctx->hal); //Get the events that triggered the interrupt
// deal ERR event
if (int_stat & (TWAIFD_LL_INTR_BUS_ERR | TWAIFD_LL_INTR_ARBI_LOST)) {
uint32_t err_reason = twaifd_ll_get_err_reason_code(twai_ctx->hal.dev);
twai_error_event_data_t e_data = {0};
e_data.err_code.arb_lost = !!(int_stat & TWAIFD_LL_INTR_ARBI_LOST);
e_data.err_code.bit_err = (err_reason == TWAIFD_LL_ERR_BIT_ERR);
e_data.err_code.form_err = (err_reason == TWAIFD_LL_ERR_FRM_ERR);
e_data.err_code.stuff_err = (err_reason == TWAIFD_LL_ERR_STUF_ERR);
#if CONFIG_IDF_TARGET_ESP32 // only esp32 have this errata, TODO: IDF-13002 check errata runtime
if (events & TWAI_HAL_EVENT_NEED_PERIPH_RESET) {
twai_hal_prepare_for_reset(twai_ctx->hal);
TWAI_RCC_ATOMIC() {
twai_ll_reset_register(twai_ctx->ctrlr_id);
}
twai_hal_recover_from_reset(twai_ctx->hal);
}
#endif
// deal BUS ERR event
if (events & (TWAI_HAL_EVENT_BUS_ERR | TWAI_HAL_EVENT_ARB_LOST)) {
twai_error_event_data_t e_data = {
.err_flags = twai_hal_get_err_flags(twai_ctx->hal),
};
twai_ctx->history.bus_err_num ++;
if (twai_ctx->cbs.on_error) {
do_yield |= twai_ctx->cbs.on_error(&twai_ctx->api_base, &e_data, twai_ctx->user_data);
@@ -193,23 +220,49 @@ static void _node_isr_main(void *arg)
}
// deal FSM event
if (int_stat & (TWAIFD_LL_INTR_FSM_CHANGE | TWAIFD_LL_INTR_ERR_WARN)) {
twai_state_change_event_data_t e_data = {.old_sta = twai_ctx->state};
e_data.new_sta = twaifd_ll_get_fault_state(twai_ctx->hal.dev);
uint32_t limit = twaifd_ll_get_err_warn_limit(twai_ctx->hal.dev);
if ((e_data.new_sta == TWAI_ERROR_ACTIVE) && ((twai_ctx->tx_error_count >= limit) || (twai_ctx->rx_error_count >= limit))) {
e_data.new_sta = TWAI_ERROR_WARNING;
}
if (events & (TWAI_HAL_EVENT_ERROR_ACTIVE | TWAI_HAL_EVENT_ERROR_WARNING | TWAI_HAL_EVENT_ERROR_PASSIVE | TWAI_HAL_EVENT_BUS_OFF)) {
twai_error_state_t curr_sta = (events & TWAI_HAL_EVENT_BUS_OFF) ? TWAI_ERROR_BUS_OFF : \
(events & TWAI_HAL_EVENT_ERROR_PASSIVE) ? TWAI_ERROR_PASSIVE : \
(events & TWAI_HAL_EVENT_ERROR_WARNING) ? TWAI_ERROR_WARNING : TWAI_ERROR_ACTIVE;
twai_state_change_event_data_t e_data = {
.old_sta = twai_ctx->state,
.new_sta = curr_sta,
};
atomic_store(&twai_ctx->state, e_data.new_sta);
if (twai_ctx->cbs.on_state_change) {
do_yield |= twai_ctx->cbs.on_state_change(&twai_ctx->api_base, &e_data, twai_ctx->user_data);
}
}
// deal RX event, then TX later, TODO: DIG-620
if (events & TWAI_HAL_EVENT_RX_BUFF_FRAME) {
while (twai_hal_get_rx_msg_count(twai_ctx->hal)) {
if (twai_hal_read_rx_fifo(twai_ctx->hal, &twai_ctx->rcv_buff)) {
#if !SOC_TWAI_SUPPORT_FD
// the legacy hardware filter don't support split frame format std/ext in filter, check in software
if (!twai_hal_soft_filter_check_msg(twai_ctx->hal, &twai_ctx->rcv_buff)) {
continue; // soft filter to check if id type match the filter config
}
#endif
if (twai_ctx->cbs.on_rx_done) {
atomic_store(&twai_ctx->rx_isr, true); //todo: using compare_exchange to avoid intr from 2nd core
twai_rx_done_event_data_t rx_ev = {};
do_yield |= twai_ctx->cbs.on_rx_done(&twai_ctx->api_base, &rx_ev, twai_ctx->user_data);
atomic_store(&twai_ctx->rx_isr, false);
}
} else { // failed to read from RX fifo because message is overrun
#if !SOC_TWAI_SUPPORTS_RX_STATUS
twai_hal_clear_rx_fifo_overrun(twai_ctx->hal);
break;
#endif
}
}
}
// deal TX event
if (int_stat & (TWAIFD_LL_INTR_TX_DONE | TWAIFD_LL_INTR_TX_SUCCESS)) {
if (events & TWAI_HAL_EVENT_TX_BUFF_FREE) {
// only call tx_done_cb when tx without error, otherwise on_error_cb should triggered if it is registered
if (twai_ctx->cbs.on_tx_done && (int_stat & TWAIFD_LL_INTR_TX_DONE)) {
if (twai_ctx->cbs.on_tx_done && (events & TWAI_HAL_EVENT_TX_SUCCESS)) {
twai_tx_done_event_data_t tx_ev = {
.done_tx_frame = twai_ctx->p_curr_tx,
};
@@ -225,22 +278,6 @@ static void _node_isr_main(void *arg)
}
}
// deal RX event
if (int_stat & TWAIFD_LL_INTR_RX_NOT_EMPTY) {
while (twaifd_ll_get_rx_frame_count(twai_ctx->hal.dev)) {
twaifd_ll_get_rx_frame(twai_ctx->hal.dev, &twai_ctx->rcv_buff);
if (twai_ctx->cbs.on_rx_done) {
atomic_store(&twai_ctx->rx_isr, true);
const twai_rx_done_event_data_t rx_ev = {
};
do_yield |= twai_ctx->cbs.on_rx_done(&twai_ctx->api_base, &rx_ev, twai_ctx->user_data);
atomic_store(&twai_ctx->rx_isr, false);
}
}
// rx flag can only cleared after read to empty
twaifd_ll_clr_intr_status(twai_ctx->hal.dev, TWAIFD_LL_INTR_RX_NOT_EMPTY);
}
if (do_yield) {
portYIELD_FROM_ISR();
}
@@ -269,6 +306,7 @@ static esp_err_t _node_delete(twai_node_handle_t node)
ESP_RETURN_ON_FALSE(atomic_load(&twai_ctx->state) == TWAI_ERROR_BUS_OFF, ESP_ERR_INVALID_STATE, TAG, "delete node must when node stopped");
_node_release_io(twai_ctx);
twai_hal_deinit(twai_ctx->hal);
_twai_rcc_clock_ctrl(twai_ctx->ctrlr_id, false);
_node_destroy(twai_ctx);
return ESP_OK;
@@ -295,7 +333,7 @@ static esp_err_t _node_check_timing_valid(twai_onchip_ctx_t *twai_ctx, const twa
return ESP_OK;
}
ESP_RETURN_ON_FALSE(!timing->quanta_resolution_hz, ESP_ERR_INVALID_ARG, TAG, "quanta_resolution_hz is not supported"); //TODO: IDF-12725
ESP_RETURN_ON_FALSE((timing->brp >= SOC_TWAI_BRP_MIN) && (timing->brp <= SOC_TWAI_BRP_MAX), ESP_ERR_INVALID_ARG, TAG, "invalid brp");
ESP_RETURN_ON_FALSE(twai_hal_check_brp_validation(twai_ctx->hal, timing->brp), ESP_ERR_INVALID_ARG, TAG, "invalid brp");
ESP_RETURN_ON_FALSE((timing->tseg_1 >= TWAI_LL_TSEG1_MIN) && (timing->tseg_1 <= TWAI_LL_TSEG1_MAX), ESP_ERR_INVALID_ARG, TAG, "invalid tseg1");
ESP_RETURN_ON_FALSE((timing->tseg_2 >= TWAI_LL_TSEG2_MIN) && (timing->tseg_2 <= TWAI_LL_TSEG2_MAX), ESP_ERR_INVALID_ARG, TAG, "invalid tseg_2");
ESP_RETURN_ON_FALSE((timing->sjw >= 1) && (timing->sjw <= TWAI_LL_SJW_MAX), ESP_ERR_INVALID_ARG, TAG, "invalid swj");
@@ -312,6 +350,7 @@ static esp_err_t _node_set_bit_timing(twai_node_handle_t node, const twai_timing
new_clock_src = timing->clk_src ? timing->clk_src : TWAI_CLK_SRC_DEFAULT;
} else {
if (timing) {
ESP_RETURN_ON_FALSE(!twai_ctx->valid_fd_timing || !timing->clk_src || (timing->clk_src == TWAI_CLK_SRC_DEFAULT), ESP_ERR_INVALID_ARG, TAG, "don't change clk_src in single config");
new_clock_src = timing->clk_src ? timing->clk_src : TWAI_CLK_SRC_DEFAULT;
} else {
ESP_RETURN_ON_FALSE(!timing_fd->clk_src || (timing_fd->clk_src == TWAI_CLK_SRC_DEFAULT), ESP_ERR_INVALID_ARG, TAG, "don't change clk_src in single config");
@@ -322,33 +361,19 @@ static esp_err_t _node_set_bit_timing(twai_node_handle_t node, const twai_timing
ESP_RETURN_ON_ERROR(_node_check_timing_valid(twai_ctx, timing, source_freq), TAG, "invalid param");
ESP_RETURN_ON_ERROR(_node_check_timing_valid(twai_ctx, timing_fd, source_freq), TAG, "invalid fd param");
int ssp_offset = 0;
if (timing) {
twaifd_ll_set_nominal_bitrate(twai_ctx->hal.dev, timing);
if (timing->ssp_offset) {
// the underlying hardware calculates the ssp in system clock cycles, not in quanta time
ssp_offset = timing->ssp_offset * timing->brp;
}
twai_hal_configure_timing(twai_ctx->hal, timing);
}
#if SOC_TWAI_SUPPORT_FD
if (timing_fd) {
twai_ctx->valid_fd_timing = true;
twaifd_ll_set_fd_bitrate(twai_ctx->hal.dev, timing_fd);
// Note, the ssp_offset set for the data phase can override the nominal phase, because ssp is more necessary for a high bitrate communication
if (timing_fd->ssp_offset) {
// the underlying hardware calculates the ssp in system clock cycles, not in quanta time
ssp_offset = timing_fd->ssp_offset * timing_fd->brp;
}
twai_hal_configure_timing_fd(twai_ctx->hal, timing_fd);
}
#endif
// config ssp, the hardware offset_val TWAIFD_LL_SSP_SRC_MEAS_OFFSET measured by clock_src freq
twaifd_ll_config_secondary_sample_point(twai_ctx->hal.dev, (ssp_offset ? TWAIFD_LL_SSP_SRC_MEAS_OFFSET : TWAIFD_LL_SSP_SRC_NO_SSP), ssp_offset);
if (new_clock_src != twai_ctx->curr_clk_src) {
twai_ctx->curr_clk_src = new_clock_src;
TWAI_PERI_ATOMIC() {
twaifd_ll_set_clock_source(twai_ctx->ctrlr_id, new_clock_src);
}
_twai_rcc_clock_sel(twai_ctx->ctrlr_id, new_clock_src);
}
return ESP_OK;
}
@@ -364,10 +389,10 @@ static esp_err_t _node_calc_set_bit_timing(twai_node_handle_t node, twai_clock_s
ESP_RETURN_ON_ERROR(esp_clk_tree_src_get_freq_hz(root_clock_src, ESP_CLK_TREE_SRC_FREQ_PRECISION_APPROX, &source_freq), TAG, "can't get clock source freq");
twai_timing_advanced_config_t timing_adv = { .clk_src = root_clock_src, };
twai_timing_advanced_config_t *fd_cfg_ptr = NULL, timing_adv_fd = { .clk_src = root_clock_src, };
twai_timing_advanced_config_t *fd_cfg_ptr = NULL;
twai_timing_constraint_t hw_const = {
.brp_min = SOC_TWAI_BRP_MIN,
.brp_max = SOC_TWAI_BRP_MAX,
.brp_min = TWAI_LL_BRP_MIN,
.brp_max = TWAI_LL_BRP_MAX,
.tseg1_min = TWAI_LL_TSEG1_MIN,
.tseg1_max = TWAI_LL_TSEG1_MAX,
.tseg2_min = TWAI_LL_TSEG2_MIN,
@@ -381,6 +406,7 @@ static esp_err_t _node_calc_set_bit_timing(twai_node_handle_t node, twai_clock_s
ESP_LOGW(TAG, "bitrate precision loss, adjust from %ld to %ld", timing->bitrate, real_baud);
}
#if SOC_TWAI_SUPPORT_FD
twai_timing_advanced_config_t timing_adv_fd = { .clk_src = root_clock_src, };
if (timing_fd->bitrate) {
real_baud = twai_node_timing_calc_param(source_freq, timing_fd, &hw_const, &timing_adv_fd);
ESP_LOGD(TAG, "fd src %ld, param %ld %d %d %d %d %d", source_freq, timing_adv_fd.brp, timing_adv_fd.prop_seg, timing_adv_fd.tseg_1, timing_adv_fd.tseg_2, timing_adv_fd.sjw, timing_adv_fd.ssp_offset);
@@ -391,7 +417,7 @@ static esp_err_t _node_calc_set_bit_timing(twai_node_handle_t node, twai_clock_s
fd_cfg_ptr = &timing_adv_fd;
}
#endif
ESP_RETURN_ON_ERROR(_node_set_bit_timing(node, &timing_adv, fd_cfg_ptr), TAG, "invalid timing param");
ESP_RETURN_ON_ERROR(_node_set_bit_timing(node, &timing_adv, fd_cfg_ptr), TAG, "invalid timing param, bitrate can't achieve!");
return ESP_OK;
}
@@ -408,14 +434,14 @@ static esp_err_t _node_enable(twai_node_handle_t node)
ESP_RETURN_ON_ERROR(esp_pm_lock_acquire(twai_ctx->pm_lock), TAG, "acquire power manager failed");
}
#endif //CONFIG_PM_ENABLE
twaifd_ll_enable_hw(twai_ctx->hal.dev, true);
twaifd_ll_waiting_state_change(twai_ctx->hal.dev); // waiting hardware ready before resume transaction
twai_hal_start(twai_ctx->hal);
twai_error_state_t hw_state = twai_hal_get_err_state(twai_ctx->hal);
atomic_store(&twai_ctx->state, hw_state);
// continuing the transaction if there be
if (atomic_load(&twai_ctx->hw_busy) && twaifd_ll_get_fault_state(twai_ctx->hal.dev) != TWAI_ERROR_BUS_OFF) {
if (atomic_load(&twai_ctx->hw_busy) && hw_state != TWAI_ERROR_BUS_OFF) {
_node_start_trans(twai_ctx);
}
// once interrupt enabled, state_change_intr will fire at the moment and update the `twai_ctx->state`
ESP_RETURN_ON_ERROR(esp_intr_enable(twai_ctx->intr_hdl), TAG, "enable interrupt failed");
return ESP_OK;
}
@@ -425,9 +451,19 @@ static esp_err_t _node_disable(twai_node_handle_t node)
twai_onchip_ctx_t *twai_ctx = __containerof(node, twai_onchip_ctx_t, api_base);
ESP_RETURN_ON_FALSE(atomic_load(&twai_ctx->state) != TWAI_ERROR_BUS_OFF, ESP_ERR_INVALID_STATE, TAG, "node already disabled");
esp_intr_disable(twai_ctx->intr_hdl);
ESP_RETURN_ON_ERROR(esp_intr_disable(twai_ctx->intr_hdl), TAG, "disable interrupt failed");
atomic_store(&twai_ctx->state, TWAI_ERROR_BUS_OFF);
twaifd_ll_enable_hw(twai_ctx->hal.dev, false);
twai_hal_stop(twai_ctx->hal);
#if CONFIG_IDF_TARGET_ESP32 // only esp32 have this errata, TODO: IDF-13002 check errata runtime
// when `disable` happens during hardware busy, the next RX frame is corrupted, a HW reset can fix it
if (twai_hal_is_hw_busy(twai_ctx->hal)) {
twai_hal_backup_config(twai_ctx->hal);
TWAI_RCC_ATOMIC() {
twai_ll_reset_register(twai_ctx->ctrlr_id);
}
twai_hal_restore_config(twai_ctx->hal);
}
#endif
#if CONFIG_PM_ENABLE
if (twai_ctx->pm_lock) {
@@ -441,19 +477,14 @@ static esp_err_t _node_config_mask_filter(twai_node_handle_t node, uint8_t filte
{
twai_onchip_ctx_t *twai_ctx = __containerof(node, twai_onchip_ctx_t, api_base);
ESP_RETURN_ON_FALSE(filter_id < SOC_TWAI_MASK_FILTER_NUM, ESP_ERR_INVALID_ARG, TAG, "Invalid mask filter id %d", filter_id);
ESP_RETURN_ON_FALSE(mask_cfg->num_of_ids <= 1, ESP_ERR_INVALID_ARG, TAG, "Invalid num_of_ids");
#if SOC_TWAI_SUPPORT_FD
// FD targets don't support Dual filter
ESP_RETURN_ON_FALSE(!mask_cfg->dual_filter, ESP_ERR_NOT_SUPPORTED, TAG, "The target don't support Dual Filter");
#endif
ESP_RETURN_ON_FALSE(atomic_load(&twai_ctx->state) == TWAI_ERROR_BUS_OFF, ESP_ERR_INVALID_STATE, TAG, "config filter must when node stopped");
bool full_open = (mask_cfg->mask == 0) && (mask_cfg->id == 0);
bool full_close = (mask_cfg->mask == UINT32_MAX) && (mask_cfg->id == UINT32_MAX);
bool cc_ext = full_open || (!full_close && mask_cfg->is_ext && !mask_cfg->no_classic);
bool fd_ext = full_open || (!full_close && mask_cfg->is_ext && !mask_cfg->no_fd);
bool cc_std = full_open || (!full_close && !mask_cfg->is_ext && !mask_cfg->no_classic);
bool fd_std = full_open || (!full_close && !mask_cfg->is_ext && !mask_cfg->no_fd);
twaifd_ll_filter_enable_basic_ext(twai_ctx->hal.dev, filter_id, false, cc_ext);
twaifd_ll_filter_enable_fd_ext(twai_ctx->hal.dev, filter_id, false, fd_ext);
twaifd_ll_filter_enable_basic_std(twai_ctx->hal.dev, filter_id, false, cc_std);
twaifd_ll_filter_enable_fd_std(twai_ctx->hal.dev, filter_id, false, fd_std);
twaifd_ll_filter_set_id_mask(twai_ctx->hal.dev, filter_id, mask_cfg->is_ext, mask_cfg->id, mask_cfg->mask);
twai_hal_configure_filter(twai_ctx->hal, filter_id, mask_cfg);
return ESP_OK;
}
@@ -464,15 +495,7 @@ static esp_err_t _node_config_range_filter(twai_node_handle_t node, uint8_t filt
ESP_RETURN_ON_FALSE(filter_id < SOC_TWAI_RANGE_FILTER_NUM, ESP_ERR_INVALID_ARG, TAG, "Invalid range filter id %d", filter_id);
ESP_RETURN_ON_FALSE(atomic_load(&twai_ctx->state) == TWAI_ERROR_BUS_OFF, ESP_ERR_INVALID_STATE, TAG, "config filter must when node stopped");
bool cc_ext = range_cfg->is_ext && !range_cfg->no_classic;
bool fd_ext = range_cfg->is_ext && !range_cfg->no_fd;
bool cc_std = !range_cfg->is_ext && !range_cfg->no_classic;
bool fd_std = !range_cfg->is_ext && !range_cfg->no_fd;
twaifd_ll_filter_enable_basic_ext(twai_ctx->hal.dev, filter_id, true, cc_ext);
twaifd_ll_filter_enable_fd_ext(twai_ctx->hal.dev, filter_id, true, fd_ext);
twaifd_ll_filter_enable_basic_std(twai_ctx->hal.dev, filter_id, true, cc_std);
twaifd_ll_filter_enable_fd_std(twai_ctx->hal.dev, filter_id, true, fd_std);
twaifd_ll_filter_set_range(twai_ctx->hal.dev, 0, range_cfg->is_ext, range_cfg->range_high, range_cfg->range_low);
twai_hal_configure_range_filter(twai_ctx->hal, filter_id, range_cfg);
return ESP_OK;
}
#endif
@@ -484,7 +507,7 @@ static esp_err_t _node_recover(twai_node_handle_t node)
// After recover command, the hardware require 128 consecutive occurrences of 11 recessive bits received, so that it can be active again!
// Checking `twai_node_status_t::state` Or waiting `on_state_change` callback can know if recover is finish
twaifd_ll_set_operate_cmd(twai_ctx->hal.dev, TWAIFD_LL_HW_CMD_RST_ERR_CNT);
twai_hal_start_bus_recovery(twai_ctx->hal);
twai_ctx->history.bus_err_num = 0;
return ESP_OK;
}
@@ -512,9 +535,12 @@ static esp_err_t _node_queue_tx(twai_node_handle_t node, const twai_frame_t *fra
if (frame->header.dlc && frame->buffer_len) {
ESP_RETURN_ON_FALSE(frame->header.dlc == twaifd_len2dlc(frame->buffer_len), ESP_ERR_INVALID_ARG, TAG, "unmatched dlc and buffer_len");
}
#if !SOC_TWAI_SUPPORT_FD
ESP_RETURN_ON_FALSE(!frame->header.fdf || frame->buffer_len <= TWAI_FRAME_MAX_LEN, ESP_ERR_INVALID_ARG, TAG, "fdf flag or buffer_len not supported");
#endif
ESP_RETURN_ON_FALSE(frame->buffer_len <= (frame->header.fdf ? TWAIFD_FRAME_MAX_LEN : TWAI_FRAME_MAX_LEN), ESP_ERR_INVALID_ARG, TAG, "illegal transfer length (buffer_len %ld)", frame->buffer_len);
ESP_RETURN_ON_FALSE((!frame->header.brs) || (twai_ctx->valid_fd_timing), ESP_ERR_INVALID_ARG, TAG, "brs can't be used without config data_timing");
ESP_RETURN_ON_FALSE(!twai_ctx->hal.enable_listen_only, ESP_ERR_NOT_SUPPORTED, TAG, "node is config as listen only");
ESP_RETURN_ON_FALSE(!twai_ctx->hal->enable_listen_only, ESP_ERR_NOT_SUPPORTED, TAG, "node is config as listen only");
ESP_RETURN_ON_FALSE(atomic_load(&twai_ctx->state) != TWAI_ERROR_BUS_OFF, ESP_ERR_INVALID_STATE, TAG, "node is bus off");
TickType_t ticks_to_wait = (timeout == -1) ? portMAX_DELAY : pdMS_TO_TICKS(timeout);
@@ -537,18 +563,12 @@ static esp_err_t _node_queue_tx(twai_node_handle_t node, const twai_frame_t *fra
return ESP_OK;
}
static esp_err_t _node_parse_rx(twai_node_handle_t node, twai_frame_header_t *header, uint8_t *rx_buffer, size_t buf_len, size_t *ret_len)
static esp_err_t _node_parse_rx(twai_node_handle_t node, twai_frame_t *rx_frame)
{
twai_onchip_ctx_t *twai_ctx = __containerof(node, twai_onchip_ctx_t, api_base);
ESP_RETURN_ON_FALSE_ISR(atomic_load(&twai_ctx->rx_isr), ESP_ERR_INVALID_STATE, TAG, "rx can only called in `rx_done` callback");
twaifd_ll_parse_frame_header(&twai_ctx->rcv_buff, header);
uint32_t frame_data_len = twaifd_dlc2len(header->dlc);
uint8_t final_len = (frame_data_len < buf_len) ? frame_data_len : buf_len;
twaifd_ll_parse_frame_data(&twai_ctx->rcv_buff, rx_buffer, final_len);
if (ret_len) {
*ret_len = frame_data_len;
}
twai_hal_parse_frame(&twai_ctx->rcv_buff, &rx_frame->header, rx_frame->buffer, rx_frame->buffer_len);
return ESP_OK;
}
@@ -560,24 +580,21 @@ esp_err_t twai_new_node_onchip(const twai_onchip_node_config_t *node_config, twa
ESP_RETURN_ON_FALSE(!node_config->intr_priority || (BIT(node_config->intr_priority) & ESP_INTR_FLAG_LOWMED), ESP_ERR_INVALID_ARG, TAG, "Invalid intr_priority level");
// Allocate TWAI node object memory
twai_onchip_ctx_t *node = heap_caps_calloc(1, sizeof(twai_onchip_ctx_t), TWAI_MALLOC_CAPS);
twai_onchip_ctx_t *node = heap_caps_calloc(1, sizeof(twai_onchip_ctx_t) + twai_hal_get_mem_requirment(), TWAI_MALLOC_CAPS);
ESP_RETURN_ON_FALSE(node, ESP_ERR_NO_MEM, TAG, "No mem");
node->ctrlr_id = -1;
// Acquire controller
int ctrlr_id = _ctrlr_acquire(node);
ESP_GOTO_ON_FALSE(ctrlr_id != -1, ESP_ERR_NOT_FOUND, err, TAG, "Controller not available");
node->ctrlr_id = ctrlr_id;
node->hal = (twai_hal_context_t *)(node + 1); //hal context is place at end of driver context
// state is in bus_off before enabled
atomic_store(&node->state, TWAI_ERROR_BUS_OFF);
node->tx_mount_queue = xQueueCreateWithCaps(node_config->tx_queue_depth, sizeof(twai_frame_t *), TWAI_MALLOC_CAPS);
ESP_GOTO_ON_FALSE(node->tx_mount_queue, ESP_ERR_NO_MEM, err, TAG, "no_mem");
uint32_t intr_flags = TWAI_INTR_ALLOC_FLAGS;
if (node_config->intr_priority > 0) {
intr_flags |= BIT(node_config->intr_priority);
} else {
intr_flags |= ESP_INTR_FLAG_LOWMED;
}
intr_flags |= (node_config->intr_priority > 0) ? BIT(node_config->intr_priority) : ESP_INTR_FLAG_LOWMED;
ESP_GOTO_ON_ERROR(esp_intr_alloc(twai_controller_periph_signals.controllers[ctrlr_id].irq_id, intr_flags, _node_isr_main, (void *)node, &node->intr_hdl),
err, TAG, "Alloc interrupt failed");
@@ -586,19 +603,16 @@ esp_err_t twai_new_node_onchip(const twai_onchip_node_config_t *node_config, twa
// Initialize HAL and configure register defaults.
twai_hal_config_t hal_config = {
.controller_id = node->ctrlr_id,
.intr_mask = DRIVER_DEFAULT_INTERRUPTS,
.intr_mask = TWAI_LL_DRIVER_INTERRUPTS,
.retry_cnt = node_config->fail_retry_cnt,
.no_receive_rtr = node_config->flags.no_receive_rtr,
.enable_listen_only = node_config->flags.enable_listen_only,
.enable_self_test = node_config->flags.enable_self_test,
.enable_loopback = node_config->flags.enable_loopback,
};
ESP_GOTO_ON_FALSE(twai_hal_init(&node->hal, &hal_config), ESP_ERR_INVALID_STATE, err, TAG, "hardware not in reset state");
twaifd_ll_set_mode(node->hal.dev, node_config->flags.enable_listen_only, node_config->flags.enable_self_test, node_config->flags.enable_loopback);
twaifd_ll_set_tx_retrans_limit(node->hal.dev, node_config->fail_retry_cnt);
twaifd_ll_filter_block_rtr(node->hal.dev, node_config->flags.no_receive_rtr);
twaifd_ll_enable_filter_mode(node->hal.dev, true); // each filter still has independent enable control
twaifd_ll_enable_fd_mode(node->hal.dev, true); // fd frame still controlled by `header.fdf`
ESP_GOTO_ON_FALSE(twai_hal_init(node->hal, &hal_config), ESP_ERR_INVALID_STATE, err, TAG, "hardware not in reset state");
// Configure bus timing
ESP_GOTO_ON_ERROR(_node_calc_set_bit_timing(&node->api_base, node_config->clk_src, &node_config->bit_timing, &node_config->data_timing), err, TAG, "bitrate error");
// Configure GPIO
ESP_GOTO_ON_ERROR(_node_config_io(node, node_config), err, TAG, "gpio config failed");
#if CONFIG_PM_ENABLE
@@ -610,7 +624,9 @@ esp_err_t twai_new_node_onchip(const twai_onchip_node_config_t *node_config, twa
node->api_base.del = _node_delete;
node->api_base.recover = _node_recover;
node->api_base.config_mask_filter = _node_config_mask_filter;
#if SOC_TWAI_RANGE_FILTER_NUM
node->api_base.config_range_filter = _node_config_range_filter;
#endif
node->api_base.reconfig_timing = _node_set_bit_timing;
node->api_base.register_cbs = _node_register_callbacks;
node->api_base.transmit = _node_queue_tx;

View File

@@ -95,15 +95,12 @@ struct twai_node_base {
* @brief Receive a TWAI frame through the ISR callback
*
* @param[in] node Pointer to the TWAI node base
* @param[out] header Where to store frame header
* @param[out] rx_buffer Where to store frame data
* @param[in] buf_sz Bytes length of rx_buffer
* @param[out] received_len Optional, the real data length of rx frame comes from 'header->dlc'
* @param[out] rx_frame Pointer to the frame store rx content
* @return esp_err_t
* - ESP_OK: Success
* - ESP_ERR_TIMEOUT: Reception timeout
*/
esp_err_t (*receive_isr)(struct twai_node_base *node, twai_frame_header_t *header, uint8_t *rx_buffer, size_t buf_sz, size_t *received_len);
esp_err_t (*receive_isr)(struct twai_node_base *node, twai_frame_t *rx_frame);
/**
* @brief Recover the TWAI node from a bus-off state

View File

@@ -115,15 +115,14 @@ esp_err_t twai_node_transmit(twai_node_handle_t node, const twai_frame_t *frame,
* @brief Receive a TWAI frame from 'rx_done_cb'
*
* @note This function can only be called from the `rx_done_cb` callback, you can't call it from a task.
* @note Please also provide `buffer` and `buffer_len` inside the rx_frame
* @note Can get original data length from `twaifd_dlc2len(rx_frame.header.dlc)`
*
* @param[in] node Handle to the TWAI node
* @param[out] header Where to store frame header
* @param[out] rx_buffer Where to store frame data
* @param[in] buf_sz Bytes length of rx_buffer
* @param[out] received_len Optional, the real data length of rx frame comes from 'header->dlc', null if don't care
* @param[out] rx_frame Pointer to the frame store rx content
* @return ESP_OK on success, error code otherwise
*/
esp_err_t twai_node_receive_from_isr(twai_node_handle_t node, twai_frame_header_t *header, uint8_t *rx_buffer, size_t buf_sz, size_t *received_len);
esp_err_t twai_node_receive_from_isr(twai_node_handle_t node, twai_frame_t *rx_frame);
#ifdef __cplusplus
}

View File

@@ -13,6 +13,44 @@
extern "C" {
#endif
/**
* @brief Helper function to configure a dual 16-bit acceptance filter.
* @note For 29bits Extended IDs, ONLY high 16bits id/mask is used for eache filter.
*
* @param id1 First ID to filter.
* @param mask1 Mask for first ID.
* @param id2 Second ID to filter.
* @param mask2 Mask for second ID.
* @param is_ext True if using Extended (29-bit) IDs, false for Standard (11-bit) IDs.
* @return twai_mask_filter_config_t A filled filter configuration structure for dual filtering.
*/
static inline twai_mask_filter_config_t twai_make_dual_filter(uint16_t id1, uint16_t mask1, uint16_t id2, uint16_t mask2, bool is_ext)
{
/**
* Dual filter is a special mode in hardware,
* which allow split general 32bits filter register to 2 unit of 16 bits id/mask pairs then using as 2 filter
* below code do bit shifting to reach hardware requirement in this mode, for detail please refer to `Dual Filter Mode` of TRM
*
* 31 16 15 0
* ▼ ▼ ▼ ▼
* xxxxxxxxxxxxxxxx xxxxxxxxxxxxxxxx
* ◄─11 bits─► ◄─11 bits─►
* std filter 2 std filter 1
* ─────────────────────────────────
* ◄───16─bits────► ◄───16─bits────►
* ext filter 2 etx filter 1
*/
twai_mask_filter_config_t dual_cfg = {
.id = is_ext ? (((id1 & TWAI_EXT_ID_MASK) >> 13) << 16) | ((id2 & TWAI_EXT_ID_MASK) >> 13) : \
((id1 & TWAI_STD_ID_MASK) << 21) | ((id2 & TWAI_STD_ID_MASK) << 5),
.mask = is_ext ? (((mask1 & TWAI_EXT_ID_MASK) >> 13) << 16) | ((mask2 & TWAI_EXT_ID_MASK) >> 13) : \
((mask1 & TWAI_STD_ID_MASK) << 21) | ((mask2 & TWAI_STD_ID_MASK) << 5),
.is_ext = is_ext,
.dual_filter = true,
};
return dual_cfg;
}
/**
* @brief TWAI on-chip node initialization configuration structure
*/
@@ -25,7 +63,7 @@ typedef struct {
} io_cfg; /**< I/O configuration */
twai_clock_source_t clk_src; /**< Optional, clock source, remain 0 to using TWAI_CLK_SRC_DEFAULT by default */
twai_timing_basic_config_t bit_timing; /**< Timing configuration for classic twai and FD arbitration stage */
twai_timing_basic_config_t data_timing;/**< Optional, timing configuration for FD data stage */
twai_timing_basic_config_t data_timing; /**< Optional, timing configuration for FD data stage */
int8_t fail_retry_cnt; /**< Hardware retry limit if failed, range [-1:15], -1 for re-trans forever */
uint32_t tx_queue_depth; /**< Depth of the transmit queue */
int intr_priority; /**< Interrupt priority, [0:3] */

View File

@@ -35,34 +35,6 @@ typedef struct twai_frame_t {
size_t buffer_len; /**< buffer length of provided data buffer pointer, in bytes.*/
} twai_frame_t;
/**
* @brief Configuration for TWAI mask filter
*
* @note Set both id and mask to `0` to receive ALL frames, both `0xFFFFFFFF` to receive NONE frames
*/
typedef struct {
uint32_t id; /**< Base ID for filtering */
uint32_t mask; /**< Mask to determine the matching bits (1 = match bit, 0 = any bit) */
struct {
uint32_t is_ext: 1; /**< True for extended ID filtering, false for standard ID */
uint32_t no_classic: 1; /**< If true, Classic CAN frames are excluded (only CAN FD allowed) */
uint32_t no_fd: 1; /**< If true, CAN FD frames are excluded (only Classic CAN allowed) */
};
} twai_mask_filter_config_t;
/**
* @brief Range-based filter configuration structure
*/
typedef struct {
uint32_t range_low; /**< Lower bound of the filtering range */
uint32_t range_high; /**< Upper bound of the filtering range */
struct {
uint32_t is_ext: 1; /**< True for extended ID filtering, false for standard ID */
uint32_t no_classic: 1; /**< If true, Classic CAN frames are excluded (only CAN FD allowed) */
uint32_t no_fd: 1; /**< If true, CAN FD frames are excluded (only Classic CAN allowed) */
};
} twai_range_filter_config_t;
/**
* @brief TWAI node's status
*/
@@ -98,29 +70,15 @@ typedef struct {
* @brief TWAI "state change" event data
*/
typedef struct {
twai_error_state_t old_sta; // Previous error state
twai_error_state_t new_sta; // New error state after the change
twai_error_state_t old_sta; /**< Previous error state */
twai_error_state_t new_sta; /**< New error state after the change */
} twai_state_change_event_data_t;
/**
* @brief TWAI Error Type Structure
*/
typedef union {
struct {
uint32_t arb_lost: 1; /**< Arbitration lost error (lost arbitration during transmission) */
uint32_t bit_err: 1; /**< Bit error detected (dominant/recessive mismatch during arbitration or transmission) */
uint32_t form_err: 1; /**< Form error detected (frame fixed-form bit violation) */
uint32_t stuff_err: 1; /**< Stuff error detected (e.g. dominant error frame received) */
uint32_t reserved: 28; /**< Reserved bits for future use, must be set to zero */
};
uint32_t val; /**< Integrated error code */
} twai_error_code_t;
/**
* @brief TWAI "error" event data
*/
typedef struct {
twai_error_code_t err_code; /**< Error code indicating the type of the error */
twai_error_flags_t err_flags; /**< Error flags indicating the type of the error */
} twai_error_event_data_t;
/**

View File

@@ -1,8 +1,36 @@
[mapping:esp_twai]
archive: libesp_driver_twai.a
entries:
if TWAI_ISR_INTO_IRAM = y:
esp_twai: twai_node_receive_from_isr (no_flash)
esp_twai_onchip: _node_isr_main (no_flash)
esp_twai_onchip: _node_start_trans (no_flash)
esp_twai_onchip: _node_parse_rx (no_flash)
if TWAI_ISR_IN_IRAM = y:
esp_twai: twai_node_receive_from_isr (noflash)
esp_twai_onchip: _node_isr_main (noflash)
esp_twai_onchip: _node_start_trans (noflash)
esp_twai_onchip: _node_parse_rx (noflash)
[mapping:twai_hal]
archive: libhal.a
entries:
if TWAI_ISR_IN_IRAM = y:
if SOC_TWAI_SUPPORT_FD = y:
twai_hal_ctufd: twai_hal_format_frame (noflash)
twai_hal_ctufd: twai_hal_parse_frame (noflash)
twai_hal_ctufd: twai_hal_set_tx_buffer_and_transmit (noflash)
twai_hal_ctufd: twai_hal_get_rx_msg_count (noflash)
twai_hal_ctufd: twai_hal_read_rx_fifo (noflash)
twai_hal_ctufd: twai_hal_get_events (noflash)
else:
twai_hal_sja1000: twai_hal_format_frame (noflash)
twai_hal_sja1000: twai_hal_parse_frame (noflash)
twai_hal_sja1000: twai_hal_set_tx_buffer_and_transmit (noflash)
twai_hal_sja1000: twai_hal_get_rx_msg_count (noflash)
twai_hal_sja1000: twai_hal_read_rx_fifo (noflash)
twai_hal_sja1000: twai_hal_get_events (noflash)
twai_hal_sja1000: twai_hal_decode_interrupt (noflash)
twai_hal_sja1000: twai_hal_soft_filter_check_msg (noflash)
if IDF_TARGET_ESP32 = y:
twai_hal_sja1000: twai_hal_prepare_for_reset (noflash)
twai_hal_sja1000: twai_hal_recover_from_reset (noflash)
twai_hal_sja1000: twai_hal_backup_config (noflash)
twai_hal_sja1000: twai_hal_restore_config (noflash)
twai_hal_sja1000: twai_hal_clear_rx_fifo_overrun (noflash)

View File

@@ -1,6 +1,5 @@
components/esp_driver_twai/test_apps/twaifd_test:
components/esp_driver_twai/test_apps/test_twai:
disable:
- if: SOC_TWAI_SUPPORTED != 1 or SOC_TWAI_SUPPORT_FD != 1
reason: Only support FD targets now
- if: SOC_TWAI_SUPPORTED != 1
depends_components:
- esp_driver_twai

View File

@@ -5,9 +5,23 @@ cmake_minimum_required(VERSION 3.16)
set(COMPONENTS main)
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
project(twaifd_test)
project(test_twai)
message(STATUS "Checking TWAI registers are not read-write by half-word")
include($ENV{IDF_PATH}/tools/ci/check_register_rw_half_word.cmake)
check_register_rw_half_word(SOC_MODULES "twai*" "pcr" "hp_sys_clkrst"
HAL_MODULES "twai*")
if(CONFIG_COMPILER_DUMP_RTL_FILES)
add_custom_target(
check_test_app_sections ALL
COMMAND ${PYTHON} $ENV{IDF_PATH}/tools/ci/check_callgraph.py
--rtl-dirs ${CMAKE_BINARY_DIR}/esp-idf/esp_driver_twai/,${CMAKE_BINARY_DIR}/esp-idf/hal/
--elf-file ${CMAKE_BINARY_DIR}/test_twai.elf
find-refs
--from-sections=.iram0.text
--to-sections=.flash.text,.flash.rodata
--exit-code
DEPENDS ${elf}
)
endif()

View File

@@ -0,0 +1,2 @@
| Supported Targets | ESP32 | ESP32-C3 | ESP32-C5 | ESP32-C6 | ESP32-H2 | ESP32-P4 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- | -------- | -------- | -------- | -------- |

View File

@@ -0,0 +1,15 @@
set(srcs "test_app_main.c")
if(CONFIG_SOC_TWAI_SUPPORTED)
list(APPEND srcs "test_twai_common.c")
endif()
if(CONFIG_SOC_TWAI_SUPPORT_FD)
list(APPEND srcs "test_twai_fd.c")
endif()
idf_component_register(
SRCS ${srcs}
PRIV_REQUIRES esp_driver_twai esp_timer
WHOLE_ARCHIVE
)

View File

@@ -19,6 +19,7 @@ void setUp(void)
void tearDown(void)
{
esp_reent_cleanup();
unity_utils_evaluate_leaks_direct(LEAKS);
}

View File

@@ -0,0 +1,427 @@
/*
* SPDX-FileCopyrightText: 2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <string.h>
#include <sys/param.h>
#include "unity.h"
#include "unity_test_utils_cache.h"
#include "test_utils.h"
#include "esp_attr.h"
#include "esp_log.h"
#include "esp_heap_caps.h"
#include "freertos/FreeRTOS.h"
#include "esp_twai.h"
#include "esp_twai_onchip.h"
#define TEST_TX_GPIO 4
#define TEST_RX_GPIO 5
#define TEST_TWAI_QUEUE_DEPTH 5
#define TEST_TRANS_LEN 100
#define TEST_FRAME_LEN 7
#define TEST_FRAME_NUM howmany(TEST_TRANS_LEN, TEST_FRAME_LEN)
static IRAM_ATTR bool test_driver_install_rx_cb(twai_node_handle_t handle, const twai_rx_done_event_data_t *edata, void *user_ctx)
{
twai_frame_t rx_frame;
if (ESP_OK == twai_node_receive_from_isr(handle, &rx_frame)) {
ESP_EARLY_LOGI("Recv ", "id 0x%lx rtr %d", rx_frame.header.id, rx_frame.header.rtr);
}
if (rx_frame.header.id != 0x100) {
TEST_FAIL(); //callback is unregistered, should not run here
}
return false;
}
TEST_CASE("twai install uninstall (loopback)", "[TWAI]")
{
esp_err_t ret;
twai_node_handle_t node_hdl[SOC_TWAI_CONTROLLER_NUM + 1];
twai_onchip_node_config_t node_config = {
.io_cfg.tx = TEST_TX_GPIO,
.io_cfg.rx = TEST_TX_GPIO, // Using same pin for test without transceiver
.bit_timing.bitrate = 1000000,
.data_timing.bitrate = 1000000,
.tx_queue_depth = TEST_TWAI_QUEUE_DEPTH,
.flags.enable_loopback = true,
.flags.enable_self_test = true,
};
// loop 10 times to check memory leak
for (uint8_t loop = 0; loop < 10; loop ++) {
for (uint8_t i = 0; i < SOC_TWAI_CONTROLLER_NUM + 1; i++) {
ret = twai_new_node_onchip(&node_config, &node_hdl[i]);
printf("Install TWAI%d return %s\n", i, esp_err_to_name(ret));
TEST_ASSERT(ret == ((i < SOC_TWAI_CONTROLLER_NUM) ? ESP_OK : ESP_ERR_NOT_FOUND));
}
// can't disable before enable
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, twai_node_disable(node_hdl[0]));
twai_event_callbacks_t user_cbs = {
.on_rx_done = test_driver_install_rx_cb,
};
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl[0], &user_cbs, NULL));
printf("Test unregister callback\n");
user_cbs.on_rx_done = NULL;
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl[0], &user_cbs, NULL));
twai_frame_t tx_frame = {
.header.id = 0x82,
.header.rtr = true,
};
printf("Test transmit before enable\n");
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, twai_node_transmit(node_hdl[0], &tx_frame, 0));
TEST_ESP_OK(twai_node_enable(node_hdl[0]));
TEST_ESP_OK(twai_node_disable(node_hdl[0]));
TEST_ESP_OK(twai_node_enable(node_hdl[0]));
TEST_ESP_OK(twai_node_transmit(node_hdl[0], &tx_frame, 0));
TEST_ESP_OK(twai_node_disable(node_hdl[0]));
TEST_ESP_OK(twai_node_delete(node_hdl[0]));
printf("Test install after delete\n");
TEST_ESP_OK(twai_new_node_onchip(&node_config, &node_hdl[SOC_TWAI_CONTROLLER_NUM]));
user_cbs.on_rx_done = test_driver_install_rx_cb,
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl[SOC_TWAI_CONTROLLER_NUM], &user_cbs, NULL));
TEST_ESP_OK(twai_node_enable(node_hdl[SOC_TWAI_CONTROLLER_NUM]));
tx_frame.header.id = 0x100;
TEST_ESP_OK(twai_node_transmit(node_hdl[SOC_TWAI_CONTROLLER_NUM], &tx_frame, 0));
twai_frame_t rx_frame;
printf("Test receive from task\n");
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, twai_node_receive_from_isr(node_hdl[SOC_TWAI_CONTROLLER_NUM], &rx_frame));
TEST_ESP_OK(twai_node_disable(node_hdl[SOC_TWAI_CONTROLLER_NUM]));
for (uint8_t i = 1; i <= SOC_TWAI_CONTROLLER_NUM; i++) {
printf("Uninstall TWAI%d\n", i - 1);
TEST_ESP_OK(twai_node_delete(node_hdl[i]));
}
}
}
static IRAM_ATTR bool test_enable_disable_rx_cb(twai_node_handle_t handle, const twai_rx_done_event_data_t *edata, void *user_ctx)
{
twai_frame_t *rx_frame = user_ctx;
if (ESP_OK == twai_node_receive_from_isr(handle, rx_frame)) {
ESP_EARLY_LOGI("Recv", "RX id 0x%x len %d ext %d brs %d esi %d", rx_frame->header.id, twaifd_dlc2len(rx_frame->header.dlc), rx_frame->header.ide, rx_frame->header.brs, rx_frame->header.esi);
rx_frame->buffer += rx_frame->buffer_len;
}
return false;
}
TEST_CASE("twai transmit stop resume (loopback)", "[TWAI]")
{
// prepare test memory
uint8_t *send_pkg_ptr = heap_caps_malloc(TEST_TRANS_LEN, MALLOC_CAP_8BIT);
uint8_t *recv_pkg_ptr = heap_caps_malloc(TEST_TRANS_LEN, MALLOC_CAP_8BIT);
TEST_ASSERT(send_pkg_ptr && recv_pkg_ptr);
printf("Transmit %d bytes package in %d frames\n", TEST_TRANS_LEN, TEST_FRAME_NUM);
twai_node_handle_t node_hdl;
twai_onchip_node_config_t node_config = {
.io_cfg.tx = TEST_TX_GPIO,
.io_cfg.rx = TEST_TX_GPIO, // Using same pin for test without transceiver
.bit_timing.bitrate = 200000,
.tx_queue_depth = TEST_TWAI_QUEUE_DEPTH,
.flags.enable_loopback = true,
.flags.enable_self_test = true,
};
TEST_ESP_OK(twai_new_node_onchip(&node_config, &node_hdl));
twai_frame_t rx_frame = {
.buffer = recv_pkg_ptr,
.buffer_len = TEST_FRAME_LEN,
};
twai_event_callbacks_t user_cbs = {
.on_rx_done = test_enable_disable_rx_cb,
};
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl, &user_cbs, &rx_frame));
TEST_ESP_OK(twai_node_enable(node_hdl));
//create and enqueue all transfers
twai_frame_t *tx_msgs = heap_caps_calloc(TEST_FRAME_NUM, sizeof(twai_frame_t), MALLOC_CAP_8BIT);
TEST_ASSERT(tx_msgs);
for (uint32_t tx_cnt = 0; tx_cnt < TEST_FRAME_NUM; tx_cnt++) {
tx_msgs[tx_cnt].header.id = tx_cnt | 0x400;
tx_msgs[tx_cnt].header.ide = !!(tx_cnt % 3);
tx_msgs[tx_cnt].buffer = send_pkg_ptr + tx_cnt * TEST_FRAME_LEN;
tx_msgs[tx_cnt].buffer_len = ((tx_cnt + 1) == TEST_FRAME_NUM) ? (TEST_TRANS_LEN - tx_cnt * TEST_FRAME_LEN) : TEST_FRAME_LEN;
TEST_ESP_OK(twai_node_transmit(node_hdl, &tx_msgs[tx_cnt], 500));
}
TEST_ESP_OK(twai_node_disable(node_hdl));
for (uint8_t i = 3; i > 0; i--) {
printf("interrupted, %d sec\n", i);
vTaskDelay(1000);
}
printf("continuing ...\n");
TEST_ESP_OK(twai_node_enable(node_hdl));
//waiting pkg receive finish
while (rx_frame.buffer < recv_pkg_ptr + TEST_TRANS_LEN) {
vTaskDelay(1);
}
free(tx_msgs);
// check if pkg receive correct
printf("pkg check %s!!\n", memcmp(recv_pkg_ptr, send_pkg_ptr, TEST_TRANS_LEN) ? "failed" : "ok");
TEST_ASSERT_EQUAL_HEX8_ARRAY(send_pkg_ptr, recv_pkg_ptr, TEST_TRANS_LEN);
free(send_pkg_ptr);
free(recv_pkg_ptr);
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_delete(node_hdl));
}
static void test_random_trans_generator(twai_node_handle_t node_hdl, uint32_t trans_num)
{
uint8_t send_pkg_ptr[TWAI_FRAME_MAX_LEN];
twai_frame_t tx_msg = {
.buffer = send_pkg_ptr,
};
printf("Sending %ld random trans ...\n", trans_num);
for (uint32_t tx_cnt = 0; tx_cnt < trans_num; tx_cnt++) {
tx_msg.header.id = tx_cnt | 0xf000;
tx_msg.header.ide = !!(tx_cnt % 2);
tx_msg.header.rtr = !!(tx_cnt % 3);
tx_msg.buffer_len = tx_cnt % TWAI_FRAME_MAX_LEN;
TEST_ESP_OK(twai_node_transmit(node_hdl, &tx_msg, 0));
vTaskDelay(8); //as async transaction, waiting trans done
}
}
static IRAM_ATTR bool test_filter_rx_done_cb(twai_node_handle_t handle, const twai_rx_done_event_data_t *edata, void *user_ctx)
{
uint8_t *test_ctrl = user_ctx;
uint8_t recv_pkg_ptr[TWAI_FRAME_MAX_LEN];
twai_frame_t rx_frame = {
.buffer = recv_pkg_ptr,
.buffer_len = TWAI_FRAME_MAX_LEN,
};
if (ESP_OK == twai_node_receive_from_isr(handle, &rx_frame)) {
ESP_EARLY_LOGI("Recv", "RX id 0x%4x len %2d ext %d rmt %d", rx_frame.header.id, twaifd_dlc2len(rx_frame.header.dlc), rx_frame.header.ide, rx_frame.header.rtr);
switch (test_ctrl[0]) {
case 0: // receive something
TEST_ASSERT(rx_frame.header.id >= 0x10);
TEST_ASSERT(!rx_frame.header.ide);
break;
case 1: // receive all
case 2: break; // receive none
default: TEST_ASSERT(false);
}
test_ctrl[1] ++;
}
return false;
}
TEST_CASE("twai mask filter (loopback)", "[TWAI]")
{
uint8_t test_ctrl[2];
twai_node_handle_t node_hdl;
twai_onchip_node_config_t node_config = {
.io_cfg.tx = TEST_TX_GPIO,
.io_cfg.rx = TEST_TX_GPIO, // Using same pin for test without transceiver
.bit_timing.bitrate = 1000000,
.tx_queue_depth = TEST_TWAI_QUEUE_DEPTH,
.flags.enable_loopback = true,
.flags.enable_self_test = true,
};
TEST_ESP_OK(twai_new_node_onchip(&node_config, &node_hdl));
twai_event_callbacks_t user_cbs = {
.on_rx_done = test_filter_rx_done_cb,
};
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl, &user_cbs, test_ctrl));
twai_mask_filter_config_t mfilter_cfg = {0};
for (uint8_t i = 0; i < SOC_TWAI_MASK_FILTER_NUM; i++) {
printf("\n--------------------------------------\n");
test_ctrl[0] = 0;
test_ctrl[1] = 0;
mfilter_cfg.id = 0x10,
mfilter_cfg.mask = 0xf0,
mfilter_cfg.is_ext = false,
printf("Testing mask filter %d: id 0x%lx mask 0x%lx is_ext %d\n", i, mfilter_cfg.id, mfilter_cfg.mask, mfilter_cfg.is_ext);
TEST_ESP_OK(twai_node_config_mask_filter(node_hdl, i, &mfilter_cfg));
TEST_ESP_OK(twai_node_enable(node_hdl));
test_random_trans_generator(node_hdl, 30);
TEST_ASSERT_EQUAL(7, test_ctrl[1]); // must receive 7 of 30 frames under filter config
test_ctrl[0] = 1;
test_ctrl[1] = 0;
mfilter_cfg.id = 0;
mfilter_cfg.mask = 0;
printf("Change filter %d to receive ALL: id 0x%lx mask 0x%lx\n", i, mfilter_cfg.id, mfilter_cfg.mask);
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_config_mask_filter(node_hdl, i, &mfilter_cfg));
TEST_ESP_OK(twai_node_enable(node_hdl));
test_random_trans_generator(node_hdl, 20);
TEST_ASSERT_EQUAL(20, test_ctrl[1]);
test_ctrl[0] = 2;
test_ctrl[1] = 0;
mfilter_cfg.id = 0xFFFFFFFF;
mfilter_cfg.mask = 0xFFFFFFFF;
printf("Disable filter %d: id 0x%lx mask 0x%lx\n", i, mfilter_cfg.id, mfilter_cfg.mask);
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_config_mask_filter(node_hdl, i, &mfilter_cfg));
TEST_ESP_OK(twai_node_enable(node_hdl));
test_random_trans_generator(node_hdl, 40);
TEST_ASSERT_EQUAL(0, test_ctrl[1]);
TEST_ESP_OK(twai_node_disable(node_hdl));
}
TEST_ESP_OK(twai_node_delete(node_hdl));
}
//------------------ Dual Filter Test -------------------//
#if !SOC_TWAI_SUPPORT_FD
static IRAM_ATTR bool test_dual_filter_rx_done_cb(twai_node_handle_t handle, const twai_rx_done_event_data_t *edata, void *user_ctx)
{
uint8_t *test_ctrl = user_ctx;
uint8_t recv_pkg_ptr[TWAI_FRAME_MAX_LEN];
twai_frame_t rx_frame = {
.buffer = recv_pkg_ptr,
.buffer_len = TWAI_FRAME_MAX_LEN,
};
if (ESP_OK == twai_node_receive_from_isr(handle, &rx_frame)) {
ESP_EARLY_LOGI("Recv", "RX id 0x%4x len %2d ext %d rmt %d", rx_frame.header.id, twaifd_dlc2len(rx_frame.header.dlc), rx_frame.header.ide, rx_frame.header.rtr);
switch (test_ctrl[0]) {
case 0: // receive something
TEST_ASSERT(!rx_frame.header.ide);
TEST_ASSERT((rx_frame.header.id >= 0x10) && (rx_frame.header.id <= 0x2f));
break;
case 1: break; // receive none
default: TEST_ASSERT(false);
}
test_ctrl[1] ++;
}
return false;
}
TEST_CASE("twai dual 16bit mask filter (loopback)", "[TWAI]")
{
uint8_t test_ctrl[2];
twai_node_handle_t node_hdl;
twai_onchip_node_config_t node_config = {
.io_cfg.tx = TEST_TX_GPIO,
.io_cfg.rx = TEST_TX_GPIO, // Using same pin for test without transceiver
.bit_timing.bitrate = 1000000,
.tx_queue_depth = TEST_TWAI_QUEUE_DEPTH,
.flags.enable_loopback = true,
.flags.enable_self_test = true,
};
TEST_ESP_OK(twai_new_node_onchip(&node_config, &node_hdl));
twai_event_callbacks_t user_cbs = {
.on_rx_done = test_dual_filter_rx_done_cb,
};
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl, &user_cbs, test_ctrl));
printf("Testing dual filter: id1 0x%x mask1 0x%x, id2 0x%x mask2 0x%x\n", 0x020, 0x7f0, 0x013, 0x7f8);
test_ctrl[0] = 0;
test_ctrl[1] = 0;
// filter 1 receive only std id 0x02x
// filter 2 receive only std id 0x010~0x017
twai_mask_filter_config_t dual_config = twai_make_dual_filter(0x020, 0x7f0, 0x013, 0x7f8, false);
TEST_ESP_OK(twai_node_config_mask_filter(node_hdl, 0, &dual_config));
TEST_ESP_OK(twai_node_enable(node_hdl));
test_random_trans_generator(node_hdl, 50);
TEST_ASSERT_EQUAL(12, test_ctrl[1]); // must receive 12 of 50 frames under filter config
printf("Disable filter\n");
test_ctrl[0] = 1;
test_ctrl[1] = 0;
dual_config.id = 0xFFFFFFFF;
dual_config.mask = 0xFFFFFFFF;
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_config_mask_filter(node_hdl, 0, &dual_config));
TEST_ESP_OK(twai_node_enable(node_hdl));
test_random_trans_generator(node_hdl, 40);
TEST_ASSERT_EQUAL(0, test_ctrl[1]);
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_delete(node_hdl));
}
#endif
#if CONFIG_TWAI_ISR_CACHE_SAFE
static IRAM_ATTR bool test_iram_safe_rx_cb(twai_node_handle_t handle, const twai_rx_done_event_data_t *edata, void *user_ctx)
{
twai_frame_t *rx_frame = user_ctx;
if (ESP_OK == twai_node_receive_from_isr(handle, rx_frame)) {
esp_rom_printf(DRAM_STR("RX id 0x%x len %d ext %d brs %d esi %d\n"), rx_frame->header.id, twaifd_dlc2len(rx_frame->header.dlc), rx_frame->header.ide, rx_frame->header.brs, rx_frame->header.esi);
rx_frame->buffer += rx_frame->buffer_len;
}
return false;
}
static void IRAM_ATTR test_wait_trans_done_cache_disable(void *args)
{
twai_frame_t *rx_frame = ((twai_frame_t **)args)[0];
uint8_t *orig_buff = ((uint8_t **)args)[1];
esp_rom_printf(DRAM_STR("Cache disabled now !!!\n"));
//waiting pkg receive finish
while (rx_frame->buffer < orig_buff + TEST_TRANS_LEN) {
esp_rom_delay_us(1000);
}
}
TEST_CASE("twai driver cache safe (loopback)", "[TWAI]")
{
// prepare test memory
uint8_t *send_pkg_ptr = heap_caps_malloc(TEST_TRANS_LEN, MALLOC_CAP_8BIT);
uint8_t *recv_pkg_ptr = heap_caps_malloc(TEST_TRANS_LEN, MALLOC_CAP_8BIT);
TEST_ASSERT(send_pkg_ptr && recv_pkg_ptr);
printf("Transmit %d bytes package in %d frames\n", TEST_TRANS_LEN, TEST_FRAME_NUM);
twai_node_handle_t node_hdl;
twai_onchip_node_config_t node_config = {
.io_cfg.tx = TEST_TX_GPIO,
.io_cfg.rx = TEST_TX_GPIO, // Using same pin for test without transceiver
.bit_timing.bitrate = 50000, //slow bitrate to ensure cache disabled before tx_queue finish
.tx_queue_depth = TEST_FRAME_NUM,
.flags.enable_loopback = true,
.flags.enable_self_test = true,
};
TEST_ESP_OK(twai_new_node_onchip(&node_config, &node_hdl));
twai_frame_t rx_frame = {
.buffer = recv_pkg_ptr,
.buffer_len = TEST_FRAME_LEN,
};
twai_event_callbacks_t user_cbs = {
.on_rx_done = test_iram_safe_rx_cb,
};
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl, &user_cbs, &rx_frame));
TEST_ESP_OK(twai_node_enable(node_hdl));
//create and enqueue all transfers
twai_frame_t *tx_msgs = heap_caps_calloc(TEST_FRAME_NUM, sizeof(twai_frame_t), MALLOC_CAP_8BIT);
TEST_ASSERT(tx_msgs);
for (uint32_t tx_cnt = 0; tx_cnt < TEST_FRAME_NUM; tx_cnt++) {
tx_msgs[tx_cnt].header.id = tx_cnt | 0x400;
tx_msgs[tx_cnt].header.ide = !!(tx_cnt % 3);
tx_msgs[tx_cnt].buffer = send_pkg_ptr + tx_cnt * TEST_FRAME_LEN;
tx_msgs[tx_cnt].buffer_len = ((tx_cnt + 1) == TEST_FRAME_NUM) ? (TEST_TRANS_LEN - tx_cnt * TEST_FRAME_LEN) : TEST_FRAME_LEN;
TEST_ESP_OK(twai_node_transmit(node_hdl, &tx_msgs[tx_cnt], 0));
}
//disable cache immediately before tx_queue finish
void *user_data[2] = {&rx_frame, recv_pkg_ptr};
unity_utils_run_cache_disable_stub(test_wait_trans_done_cache_disable, user_data);
//if it is able to waiting finish, means pass the test
free(tx_msgs);
// check if pkg receive correct
printf("Transaction finish, pkg check %s!!\n", memcmp(recv_pkg_ptr, send_pkg_ptr, TEST_TRANS_LEN) ? "failed" : "ok");
TEST_ASSERT_EQUAL_HEX8_ARRAY(send_pkg_ptr, recv_pkg_ptr, TEST_TRANS_LEN);
free(send_pkg_ptr);
free(recv_pkg_ptr);
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_delete(node_hdl));
}
#endif //CONFIG_TWAI_ISR_CACHE_SAFE

View File

@@ -0,0 +1,206 @@
/*
* SPDX-FileCopyrightText: 2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <string.h>
#include <sys/param.h>
#include "unity.h"
#include "esp_log.h"
#include "esp_timer.h"
#include "esp_heap_caps.h"
#include "freertos/FreeRTOS.h"
#include "test_utils.h"
#include "esp_twai.h"
#include "esp_twai_onchip.h"
#define TEST_TX_GPIO 4
#define TEST_RX_GPIO 5
#define TEST_TWAI_QUEUE_DEPTH 5
static void test_random_trans_generator(twai_node_handle_t node_hdl, uint32_t trans_num)
{
uint8_t send_pkg_ptr[TWAIFD_FRAME_MAX_LEN];
twai_frame_t tx_msg = {
.buffer = send_pkg_ptr,
};
printf("Sending %ld random trans ...\n", trans_num);
for (uint32_t tx_cnt = 0; tx_cnt < trans_num; tx_cnt++) {
tx_msg.header.id = tx_cnt | 0xf000;
tx_msg.header.ide = !!(tx_cnt % 2);
tx_msg.header.rtr = !!(tx_cnt % 3);
tx_msg.header.fdf = !!(tx_cnt % 5);
tx_msg.buffer_len = tx_msg.header.fdf ? (tx_cnt % TWAIFD_FRAME_MAX_LEN) : (tx_cnt % TWAI_FRAME_MAX_LEN);
TEST_ESP_OK(twai_node_transmit(node_hdl, &tx_msg, 0));
vTaskDelay(8); //as async transaction, waiting trans done
}
}
static IRAM_ATTR bool test_range_filter_rx_done_cb(twai_node_handle_t handle, const twai_rx_done_event_data_t *edata, void *user_ctx)
{
uint8_t *test_ctrl = user_ctx;
uint8_t recv_pkg_ptr[TWAIFD_FRAME_MAX_LEN];
twai_frame_t rx_frame = {
.buffer = recv_pkg_ptr,
.buffer_len = TWAIFD_FRAME_MAX_LEN,
};
if (ESP_OK == twai_node_receive_from_isr(handle, &rx_frame)) {
ESP_EARLY_LOGI("Recv", "RX id 0x%4x len %2d ext %d rmt %d fd %d", rx_frame.header.id, twaifd_dlc2len(rx_frame.header.dlc), rx_frame.header.ide, rx_frame.header.rtr, rx_frame.header.fdf);
switch (test_ctrl[0]) {
case 0: // enable range filter
TEST_ASSERT(!rx_frame.header.ide);
TEST_ASSERT((rx_frame.header.id >= 0x0a) && (rx_frame.header.id <= 0x15));
break;
case 1: break; // disable range filter
default: TEST_ASSERT(false);
}
test_ctrl[1] ++;
}
return false;
}
TEST_CASE("twai range filter (loopback)", "[TWAI]")
{
uint8_t test_ctrl[2];
twai_node_handle_t node_hdl;
twai_onchip_node_config_t node_config = {
.io_cfg.tx = TEST_TX_GPIO,
.io_cfg.rx = TEST_TX_GPIO, // Using same pin for test without transceiver
.bit_timing.bitrate = 1000000,
.tx_queue_depth = TEST_TWAI_QUEUE_DEPTH,
.flags.enable_loopback = true,
.flags.enable_self_test = true,
};
TEST_ESP_OK(twai_new_node_onchip(&node_config, &node_hdl));
twai_event_callbacks_t user_cbs = {
.on_rx_done = test_range_filter_rx_done_cb,
};
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl, &user_cbs, test_ctrl));
// disable mask filter 0 which enabled by default
twai_mask_filter_config_t mfilter_cfg = {
.id = 0xFFFFFFFF,
.mask = 0xFFFFFFFF,
};
TEST_ESP_OK(twai_node_config_mask_filter(node_hdl, 0, &mfilter_cfg));
test_ctrl[0] = 0;
test_ctrl[1] = 0;
twai_range_filter_config_t rfilter_cfg = {
.range_low = 0x0a,
.range_high = 0x15,
.is_ext = false,
};
printf("Config range filter 0: 0x%lx - 0x%lx\n", rfilter_cfg.range_low, rfilter_cfg.range_high);
TEST_ESP_OK(twai_node_config_range_filter(node_hdl, 0, &rfilter_cfg));
TEST_ESP_OK(twai_node_enable(node_hdl));
test_random_trans_generator(node_hdl, 30);
TEST_ASSERT_EQUAL(6, test_ctrl[1]); // must receive 6 of 30 frames under filter config
test_ctrl[0] = 1;
test_ctrl[1] = 0;
rfilter_cfg.range_low = 1;
rfilter_cfg.range_high = 0; // config invalid range to disable range filter
printf("Disable range filter 0: 0x%lx - 0x%lx\n", rfilter_cfg.range_low, rfilter_cfg.range_high);
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_config_range_filter(node_hdl, 0, &rfilter_cfg));
TEST_ESP_OK(twai_node_enable(node_hdl));
test_random_trans_generator(node_hdl, 30);
TEST_ASSERT_EQUAL(0, test_ctrl[1]);
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_delete(node_hdl));
}
#define TEST_TRANS_TIME_BUF_LEN 20000
static IRAM_ATTR bool test_fd_trans_time_rx_cb(twai_node_handle_t handle, const twai_rx_done_event_data_t *edata, void *user_ctx)
{
twai_frame_t *rx_frame = user_ctx;
uint32_t data_len;
if (ESP_OK == twai_node_receive_from_isr(handle, rx_frame)) {
data_len = MIN(twaifd_dlc2len(rx_frame->header.dlc), rx_frame->buffer_len);
ESP_EARLY_LOGD("Recv", "RX id 0x%x len %d brs %d", rx_frame->header.id, data_len, rx_frame->header.brs);
rx_frame->buffer += data_len;
// calc the `rx_frame->buffer_len` for last frame receive
if ((rx_frame->header.id - 0x400 + 1) * rx_frame->buffer_len > (TEST_TRANS_TIME_BUF_LEN - rx_frame->buffer_len)) {
rx_frame->buffer_len = TEST_TRANS_TIME_BUF_LEN % rx_frame->buffer_len;
}
}
return false;
}
TEST_CASE("twai fd transmit time (loopback)", "[TWAI]")
{
// prepare test memory
uint8_t *send_pkg_ptr = heap_caps_malloc(TEST_TRANS_TIME_BUF_LEN, MALLOC_CAP_8BIT);
uint8_t *recv_pkg_ptr = heap_caps_malloc(TEST_TRANS_TIME_BUF_LEN, MALLOC_CAP_8BIT);
TEST_ASSERT(send_pkg_ptr && recv_pkg_ptr);
twai_node_handle_t node_hdl;
twai_onchip_node_config_t node_config = {
.io_cfg.tx = TEST_TX_GPIO,
.io_cfg.rx = TEST_TX_GPIO, // Using same pin for test without transceiver
.bit_timing.bitrate = 1000000,
.data_timing.bitrate = 4000000,
.data_timing.ssp_permill = 700, // ssp 70.0%
.tx_queue_depth = TEST_TWAI_QUEUE_DEPTH,
.flags.enable_loopback = true,
.flags.enable_self_test = true,
};
TEST_ESP_OK(twai_new_node_onchip(&node_config, &node_hdl));
twai_frame_t rx_frame = {.buffer_len = 64};
twai_event_callbacks_t user_cbs = {
.on_rx_done = test_fd_trans_time_rx_cb,
};
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl, &user_cbs, &rx_frame));
TEST_ESP_OK(twai_node_enable(node_hdl));
printf("%-12s %-14s %-14s %-7s %-15s %s\n", "pkg_len", "frame_len", "frame_num", "brs", "trans_time/ms", "result");
printf("-------------------------------------------------------------------------\n");
uint64_t time1, time2;
for (uint8_t test_mode = 0; test_mode < 3; test_mode ++) {
//create and enqueue all transfers
uint8_t frame_len = test_mode >= 1 ? 64 : 8;
uint16_t trans_num = howmany(TEST_TRANS_TIME_BUF_LEN, frame_len);
rx_frame.buffer = recv_pkg_ptr;
rx_frame.buffer_len = frame_len;
memset(recv_pkg_ptr, 0xff, TEST_TRANS_TIME_BUF_LEN);
twai_frame_t *tx_msgs = heap_caps_calloc(trans_num, sizeof(twai_frame_t), MALLOC_CAP_8BIT);
TEST_ASSERT(tx_msgs);
time1 = esp_timer_get_time();
for (uint32_t tx_cnt = 0; tx_cnt < trans_num; tx_cnt++) {
tx_msgs[tx_cnt].header.id = tx_cnt | 0x400;
tx_msgs[tx_cnt].header.fdf = frame_len == 64;
tx_msgs[tx_cnt].header.brs = test_mode == 2;
tx_msgs[tx_cnt].buffer = send_pkg_ptr + tx_cnt * frame_len;
tx_msgs[tx_cnt].buffer_len = ((tx_cnt + 1) == trans_num) ? (TEST_TRANS_TIME_BUF_LEN - tx_cnt * frame_len) : frame_len;
TEST_ESP_OK(twai_node_transmit(node_hdl, &tx_msgs[tx_cnt], 1000));
}
//waiting pkg receive finish
while (rx_frame.buffer < recv_pkg_ptr + TEST_TRANS_TIME_BUF_LEN) {
vTaskDelay(1);
}
time2 = esp_timer_get_time();
free(tx_msgs);
// check if pkg receive correct
printf("%-12d %-14d %-14d %-7d %-15.2f %-s\n",
TEST_TRANS_TIME_BUF_LEN,
frame_len,
trans_num,
(test_mode == 2),
(time2 - time1) / 1000.f,
memcmp(recv_pkg_ptr, send_pkg_ptr, TEST_TRANS_TIME_BUF_LEN) ? "failed" : "ok");
TEST_ASSERT_EQUAL_HEX8_ARRAY(send_pkg_ptr, recv_pkg_ptr, TEST_TRANS_TIME_BUF_LEN);
}
printf("-------------------------------------------------------------------------\n");
free(send_pkg_ptr);
free(recv_pkg_ptr);
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_delete(node_hdl));
}

View File

@@ -8,7 +8,7 @@ from pytest_embedded_idf.utils import soc_filtered_targets
@pytest.mark.generic
@pytest.mark.parametrize('config', ['release'], indirect=True)
@idf_parametrize('target', soc_filtered_targets('SOC_TWAI_SUPPORT_FD == 1'), indirect=['target'])
@pytest.mark.parametrize('config', ['release', 'cache_safe'], indirect=True)
@idf_parametrize('target', soc_filtered_targets('SOC_TWAI_SUPPORTED == 1'), indirect=['target'])
def test_driver_twai_loopbk(dut: Dut) -> None:
dut.run_all_single_board_cases(reset=True)

View File

@@ -0,0 +1,6 @@
CONFIG_COMPILER_DUMP_RTL_FILES=y
CONFIG_TWAI_ISR_CACHE_SAFE=y
CONFIG_FREERTOS_PLACE_FUNCTIONS_INTO_FLASH=y
CONFIG_COMPILER_OPTIMIZATION_NONE=y
CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT=y
CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_DISABLE=y

View File

@@ -1,2 +0,0 @@
| Supported Targets | ESP32-C5 |
| ----------------- | -------- |

View File

@@ -1,11 +0,0 @@
set(srcs "test_app_main.c")
if(CONFIG_SOC_TWAI_SUPPORT_FD)
list(APPEND srcs "test_twaifd.c")
endif()
idf_component_register(
SRCS ${srcs}
PRIV_REQUIRES esp_driver_twai
WHOLE_ARCHIVE
)

View File

@@ -1,336 +0,0 @@
/*
* SPDX-FileCopyrightText: 2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <string.h>
#include <sys/param.h>
#include "unity.h"
#include "esp_log.h"
#include "esp_heap_caps.h"
#include "freertos/FreeRTOS.h"
#include "test_utils.h"
#include "esp_twai.h"
#include "esp_twai_onchip.h"
#define TEST_TX_GPIO 4
#define TEST_RX_GPIO 5
#define TEST_TWAI_QUEUE_DEPTH 5
#define TEST_TRANS_LEN 100
#define TEST_FRAME_LEN 7
#define TEST_FRAME_NUM howmany(TEST_TRANS_LEN, TEST_FRAME_LEN)
static bool test_driver_install_rx_cb(twai_node_handle_t handle, const twai_rx_done_event_data_t *edata, void *user_ctx)
{
twai_frame_header_t rx_header;
if (ESP_OK == twai_node_receive_from_isr(handle, &rx_header, NULL, 0, NULL)) {
ESP_EARLY_LOGI("Recv ", "id 0x%lx rtr %d", rx_header.id, rx_header.rtr);
}
if (rx_header.id != 0x100) {
TEST_FAIL(); //callback is unregistered, should not run here
}
return false;
}
TEST_CASE("twai install uninstall (loopback)", "[TWAI]")
{
esp_err_t ret;
twai_node_handle_t node_hdl[SOC_TWAI_CONTROLLER_NUM + 1];
twai_onchip_node_config_t node_config = {
.io_cfg.tx = TEST_TX_GPIO,
.io_cfg.rx = TEST_TX_GPIO, // Using same pin for test without transceiver
.bit_timing.bitrate = 1000000,
.data_timing.bitrate = 1000000,
.tx_queue_depth = TEST_TWAI_QUEUE_DEPTH,
.flags.enable_loopback = true,
.flags.enable_self_test = true,
};
// loop 10 times to check memory leak
for (uint8_t loop = 0; loop < 10; loop ++) {
for (uint8_t i = 0; i < SOC_TWAI_CONTROLLER_NUM + 1; i++) {
ret = twai_new_node_onchip(&node_config, &node_hdl[i]);
printf("Install TWAI%d return %s\n", i, esp_err_to_name(ret));
TEST_ASSERT(ret == ((i < SOC_TWAI_CONTROLLER_NUM) ? ESP_OK : ESP_ERR_NOT_FOUND));
}
// can't disable before enable
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, twai_node_disable(node_hdl[0]));
twai_event_callbacks_t user_cbs = {
.on_rx_done = test_driver_install_rx_cb,
};
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl[0], &user_cbs, NULL));
printf("Test unregister callback\n");
user_cbs.on_rx_done = NULL;
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl[0], &user_cbs, NULL));
twai_frame_t tx_frame = {
.header.id = 0x82,
.header.rtr = true,
};
printf("Test transmit before enable\n");
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, twai_node_transmit(node_hdl[0], &tx_frame, 0));
TEST_ESP_OK(twai_node_enable(node_hdl[0]));
TEST_ESP_OK(twai_node_disable(node_hdl[0]));
TEST_ESP_OK(twai_node_enable(node_hdl[0]));
TEST_ESP_OK(twai_node_transmit(node_hdl[0], &tx_frame, 0));
TEST_ESP_OK(twai_node_disable(node_hdl[0]));
TEST_ESP_OK(twai_node_delete(node_hdl[0]));
printf("Test install after delete\n");
TEST_ESP_OK(twai_new_node_onchip(&node_config, &node_hdl[SOC_TWAI_CONTROLLER_NUM]));
user_cbs.on_rx_done = test_driver_install_rx_cb,
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl[SOC_TWAI_CONTROLLER_NUM], &user_cbs, NULL));
TEST_ESP_OK(twai_node_enable(node_hdl[SOC_TWAI_CONTROLLER_NUM]));
tx_frame.header.id = 0x100;
TEST_ESP_OK(twai_node_transmit(node_hdl[SOC_TWAI_CONTROLLER_NUM], &tx_frame, 0));
twai_frame_t rx_frame;
printf("Test receive from task\n");
TEST_ESP_ERR(ESP_ERR_INVALID_STATE, twai_node_receive_from_isr(node_hdl[SOC_TWAI_CONTROLLER_NUM], &rx_frame.header, rx_frame.buffer, rx_frame.buffer_len, NULL));
TEST_ESP_OK(twai_node_disable(node_hdl[SOC_TWAI_CONTROLLER_NUM]));
for (uint8_t i = 1; i <= SOC_TWAI_CONTROLLER_NUM; i++) {
printf("Uninstall TWAI%d\n", i - 1);
TEST_ESP_OK(twai_node_delete(node_hdl[i]));
}
}
}
static bool test_enable_disable_rx_cb(twai_node_handle_t handle, const twai_rx_done_event_data_t *edata, void *user_ctx)
{
twai_frame_t *rx_frame = user_ctx;
size_t ret_len;
if (ESP_OK == twai_node_receive_from_isr(handle, &rx_frame->header, rx_frame->buffer, rx_frame->buffer_len, &ret_len)) {
ESP_EARLY_LOGI("twai", "RX id 0x%x len %d ext %d fd %d brs %d esi %d", rx_frame->header.id, ret_len, rx_frame->header.ide, rx_frame->header.fdf, rx_frame->header.brs, rx_frame->header.esi);
rx_frame->buffer += rx_frame->buffer_len;
}
return false;
}
TEST_CASE("twai transmit stop resume (loopback)", "[TWAI]")
{
// prepare test memory
uint8_t *send_pkg_ptr = heap_caps_malloc(TEST_TRANS_LEN, MALLOC_CAP_8BIT);
uint8_t *recv_pkg_ptr = heap_caps_malloc(TEST_TRANS_LEN, MALLOC_CAP_8BIT);
TEST_ASSERT(send_pkg_ptr && recv_pkg_ptr);
printf("Transmit %d bytes package in %d frames\n", TEST_TRANS_LEN, TEST_FRAME_NUM);
twai_node_handle_t node_hdl;
twai_onchip_node_config_t node_config = {
.io_cfg.tx = TEST_TX_GPIO,
.io_cfg.rx = TEST_TX_GPIO, // Using same pin for test without transceiver
.bit_timing.bitrate = 20000,
.data_timing.bitrate = 4000000,
.data_timing.ssp_permill = 700, // ssp 70.0%
.tx_queue_depth = TEST_TWAI_QUEUE_DEPTH,
.flags.enable_loopback = true,
.flags.enable_self_test = true,
};
TEST_ESP_OK(twai_new_node_onchip(&node_config, &node_hdl));
// reconfig fd timing to 80M/(4+3+2+1)=8MHz, ssp=8/(4+3+2+1)=80%
twai_timing_advanced_config_t timing_fd = {
.brp = 1,
.prop_seg = 4,
.tseg_1 = 3,
.tseg_2 = 2,
.sjw = 2,
.ssp_offset = 8,
};
TEST_ESP_OK(twai_node_reconfig_timing(node_hdl, NULL, &timing_fd));
twai_frame_t rx_frame = {
.buffer = recv_pkg_ptr,
.buffer_len = TEST_FRAME_LEN,
};
twai_event_callbacks_t user_cbs = {
.on_rx_done = test_enable_disable_rx_cb,
};
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl, &user_cbs, &rx_frame));
TEST_ESP_OK(twai_node_enable(node_hdl));
//create and enqueue all transfers
twai_frame_t *tx_msgs = heap_caps_calloc(TEST_FRAME_NUM, sizeof(twai_frame_t), MALLOC_CAP_8BIT);
TEST_ASSERT(tx_msgs);
for (uint32_t tx_cnt = 0; tx_cnt < TEST_FRAME_NUM; tx_cnt++) {
tx_msgs[tx_cnt].header.id = tx_cnt | 0x400;
tx_msgs[tx_cnt].header.ide = !!(tx_cnt % 3);
tx_msgs[tx_cnt].header.fdf = !!(tx_cnt % 4);
tx_msgs[tx_cnt].header.brs = !!(tx_cnt % 2);
tx_msgs[tx_cnt].buffer = send_pkg_ptr + tx_cnt * TEST_FRAME_LEN;
tx_msgs[tx_cnt].buffer_len = ((tx_cnt + 1) == TEST_FRAME_NUM) ? (TEST_TRANS_LEN - tx_cnt * TEST_FRAME_LEN) : TEST_FRAME_LEN;
TEST_ESP_OK(twai_node_transmit(node_hdl, &tx_msgs[tx_cnt], 500));
}
TEST_ESP_OK(twai_node_disable(node_hdl));
for (uint8_t i = 3; i > 0; i--) {
printf("interrupted, %d sec\n", i);
vTaskDelay(1000);
}
printf("continuing ...\n");
TEST_ESP_OK(twai_node_enable(node_hdl));
//waiting pkg receive finish
while (rx_frame.buffer < recv_pkg_ptr + TEST_TRANS_LEN) {
vTaskDelay(1);
}
free(tx_msgs);
// check if pkg receive correct
printf("pkg check %s!!\n", memcmp(recv_pkg_ptr, send_pkg_ptr, TEST_TRANS_LEN) ? "failed" : "ok");
TEST_ASSERT_EQUAL_HEX8_ARRAY(send_pkg_ptr, recv_pkg_ptr, TEST_TRANS_LEN);
free(send_pkg_ptr);
free(recv_pkg_ptr);
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_delete(node_hdl));
}
static void test_random_trans_generator(twai_node_handle_t node_hdl, uint32_t trans_num)
{
uint8_t send_pkg_ptr[TWAIFD_FRAME_MAX_LEN];
twai_frame_t tx_msg = {
.buffer = send_pkg_ptr,
};
printf("Sending %ld random trans ...\n", trans_num);
for (uint32_t tx_cnt = 0; tx_cnt < trans_num; tx_cnt++) {
tx_msg.header.id = tx_cnt | 0xf000;
tx_msg.header.ide = !!(tx_cnt % 2);
tx_msg.header.rtr = !!(tx_cnt % 3);
tx_msg.header.fdf = !!(tx_cnt % 5);
tx_msg.buffer_len = tx_msg.header.fdf ? (tx_cnt % TWAIFD_FRAME_MAX_LEN) : (tx_cnt % TWAI_FRAME_MAX_LEN);
TEST_ESP_OK(twai_node_transmit(node_hdl, &tx_msg, 0));
vTaskDelay(8); //as async transaction, waiting trans done
}
}
static bool test_filter_rx_done_cb(twai_node_handle_t handle, const twai_rx_done_event_data_t *edata, void *user_ctx)
{
uint8_t *test_ctrl = user_ctx;
size_t ret_len;
uint8_t recv_pkg_ptr[TWAIFD_FRAME_MAX_LEN];
twai_frame_t rx_frame = {
.buffer = recv_pkg_ptr,
.buffer_len = TWAIFD_FRAME_MAX_LEN,
};
if (ESP_OK == twai_node_receive_from_isr(handle, &rx_frame.header, rx_frame.buffer, rx_frame.buffer_len, &ret_len)) {
ESP_EARLY_LOGI("twai", "RX id 0x%4x len %2d ext %d rmt %d fd %d", rx_frame.header.id, ret_len, rx_frame.header.ide, rx_frame.header.rtr, rx_frame.header.fdf);
switch (test_ctrl[0]) {
case 0: //filter 0
TEST_ASSERT(rx_frame.header.id >= 0x10);
TEST_ASSERT(!rx_frame.header.ide);
break;
case 1:
case 2: break;
case 3: //filter 1
TEST_ASSERT((rx_frame.header.id & 0xfff0) == 0xf000);
TEST_ASSERT(rx_frame.header.ide && !rx_frame.header.fdf);
break;
case 4: //range filter 0
TEST_ASSERT(!rx_frame.header.ide && rx_frame.header.fdf);
break;
default: TEST_ASSERT(false);
}
test_ctrl[1] ++;
}
return false;
}
TEST_CASE("twai filter (loopback)", "[TWAI]")
{
uint8_t test_ctrl[2];
twai_node_handle_t node_hdl;
twai_onchip_node_config_t node_config = {
.io_cfg.tx = TEST_TX_GPIO,
.io_cfg.rx = TEST_TX_GPIO, // Using same pin for test without transceiver
.bit_timing.bitrate = 1000000,
.tx_queue_depth = TEST_TWAI_QUEUE_DEPTH,
.flags.enable_loopback = true,
.flags.enable_self_test = true,
};
TEST_ESP_OK(twai_new_node_onchip(&node_config, &node_hdl));
twai_event_callbacks_t user_cbs = {
.on_rx_done = test_filter_rx_done_cb,
};
TEST_ESP_OK(twai_node_register_event_callbacks(node_hdl, &user_cbs, test_ctrl));
//------------------ Filter 0 -------------------//
test_ctrl[0] = 0;
test_ctrl[1] = 0;
printf("Testing mask filter 0\n");
twai_mask_filter_config_t mfilter_cfg0 = {
.id = 0x10,
.mask = 0xf0,
.is_ext = false,
};
TEST_ESP_OK(twai_node_config_mask_filter(node_hdl, 0, &mfilter_cfg0));
TEST_ESP_OK(twai_node_enable(node_hdl));
test_random_trans_generator(node_hdl, 30);
TEST_ASSERT_UINT8_WITHIN(30 / 2 - 1, 30 / 2, test_ctrl[1]); //after filter, rx frame should less than tx num
printf("Change to receive ALL\n");
test_ctrl[0] = 1;
test_ctrl[1] = 0;
// set to receive ALL
mfilter_cfg0.id = 0;
mfilter_cfg0.mask = 0;
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_config_mask_filter(node_hdl, 0, &mfilter_cfg0));
TEST_ESP_OK(twai_node_enable(node_hdl));
test_random_trans_generator(node_hdl, 30);
TEST_ASSERT_EQUAL(30, test_ctrl[1]);
printf("Change to receive NONE\n");
test_ctrl[0] = 2;
test_ctrl[1] = 0;
// set to receive NONE
mfilter_cfg0.id = 0xFFFFFFFF;
mfilter_cfg0.mask = 0xFFFFFFFF;
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_config_mask_filter(node_hdl, 0, &mfilter_cfg0));
TEST_ESP_OK(twai_node_enable(node_hdl));
test_random_trans_generator(node_hdl, 30);
TEST_ASSERT_EQUAL(0, test_ctrl[1]);
//------------------ Filter 1 -------------------//
test_ctrl[0] = 3;
test_ctrl[1] = 0;
printf("Testing mask filter 1\n");
twai_mask_filter_config_t mfilter_cfg1 = {
.id = 0xf000,
.mask = 0xfff0,
.is_ext = true,
.no_fd = true,
};
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_config_mask_filter(node_hdl, 1, &mfilter_cfg1));
TEST_ESP_OK(twai_node_enable(node_hdl));
test_random_trans_generator(node_hdl, 30);
TEST_ASSERT_UINT8_WITHIN(30 / 2 - 1, 30 / 2, test_ctrl[1]);
// set to receive NONE
mfilter_cfg1.id = 0xFFFFFFFF;
mfilter_cfg1.mask = 0xFFFFFFFF;
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_config_mask_filter(node_hdl, 1, &mfilter_cfg1));
//------------------ Range Filter 0 -------------------//
test_ctrl[0] = 4;
test_ctrl[1] = 0;
printf("Testing range filter 0\n");
twai_range_filter_config_t rfilter_cfg0 = {
.range_low = 0,
.range_high = 0xFFFFFFFF,
.is_ext = false,
.no_classic = true,
};
TEST_ESP_OK(twai_node_config_range_filter(node_hdl, 0, &rfilter_cfg0));
TEST_ESP_OK(twai_node_enable(node_hdl));
test_random_trans_generator(node_hdl, 30);
TEST_ASSERT_UINT8_WITHIN(30 / 2 - 1, 30 / 2, test_ctrl[1]);
TEST_ESP_OK(twai_node_disable(node_hdl));
TEST_ESP_OK(twai_node_delete(node_hdl));
}

View File

@@ -9,7 +9,6 @@
#include <stdlib.h>
#include <string.h>
#include <sys/cdefs.h>
#include <sys/param.h>
#include <sys/lock.h>
#include <stdatomic.h>
#include "sdkconfig.h"
@@ -32,6 +31,7 @@
#include "esp_intr_alloc.h"
#include "esp_heap_caps.h"
#include "esp_clk_tree.h"
#include "esp_memory_utils.h"
#include "esp_pm.h"
#include "esp_attr.h"
#include "esp_private/esp_gpio_reserve.h"

View File

@@ -135,7 +135,11 @@ elseif(NOT BOOTLOADER_BUILD)
endif()
if(CONFIG_SOC_TWAI_SUPPORTED)
list(APPEND srcs "twai_hal.c" "twai_hal_iram.c")
if(CONFIG_SOC_TWAI_SUPPORT_FD)
list(APPEND srcs "twai_hal_ctufd.c")
else()
list(APPEND srcs "twai_hal_sja1000.c")
endif()
endif()
if(CONFIG_SOC_GDMA_SUPPORTED)

View File

@@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@@ -18,23 +18,31 @@
#include <stdbool.h>
#include <stdlib.h>
#include "esp_assert.h"
#include "sdkconfig.h"
#include "hal/misc.h"
#include "hal/assert.h"
#include "hal/twai_types.h"
#include "hal/efuse_hal.h"
#include "soc/chip_revision.h"
#include "soc/twai_periph.h"
#include "soc/twai_struct.h"
#include "soc/dport_reg.h"
#define TWAI_LL_GET_HW(controller_id) ((controller_id == 0) ? (&TWAI) : NULL)
#define TWAI_LL_BRP_DIV_THRESH 128
#ifdef __cplusplus
extern "C" {
#endif
static uint32_t twai_ll_get_brp_max(void);
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_BRP_MIN 2
#define TWAI_LL_BRP_MAX twai_ll_get_brp_max() // max brp of esp32 is depends on chip version
#define TWAI_LL_TSEG1_MIN 1
#define TWAI_LL_TSEG2_MIN 1
#define TWAI_LL_TSEG1_MAX 16 //the max register value
#define TWAI_LL_TSEG2_MAX 8
#define TWAI_LL_SJW_MAX 4
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
#define TWAI_LL_STATUS_DOS (0x1 << 1) //Data Overrun Status
@@ -53,6 +61,9 @@ extern "C" {
#define TWAI_LL_INTR_ALI (0x1 << 6) //Arbitration Lost Interrupt
#define TWAI_LL_INTR_BEI (0x1 << 7) //Bus Error Interrupt
#define TWAI_LL_DRIVER_INTERRUPTS (TWAI_LL_INTR_RI | TWAI_LL_INTR_TI | TWAI_LL_INTR_EI | \
TWAI_LL_INTR_EPI | TWAI_LL_INTR_ALI | TWAI_LL_INTR_BEI)
/*
* The following frame structure has an NEARLY identical bit field layout to
* each byte of the TX buffer. This allows for formatting and parsing frames to
@@ -61,7 +72,7 @@ extern "C" {
* TX buffer are used in the frame structure to store the self_reception and
* single_shot flags which in turn indicate the type of transmission to execute.
*/
typedef union {
typedef union twai_ll_frame_buffer_t {
struct {
struct {
uint8_t dlc: 4; //Data length code (0 to 8) of the frame
@@ -87,7 +98,6 @@ typedef union {
ESP_STATIC_ASSERT(sizeof(twai_ll_frame_buffer_t) == 13, "TX/RX buffer type should be 13 bytes");
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
/**
* Some errata workarounds will require a hardware reset of the peripheral. Thus
* certain registers must be saved before the reset, and then restored after the
@@ -105,9 +115,7 @@ typedef struct {
uint8_t tx_error_counter_reg;
uint8_t clock_divider_reg;
} __attribute__((packed)) twai_ll_reg_save_t;
#endif //defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
#ifdef CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID
typedef enum {
TWAI_LL_ERR_BIT = 0,
TWAI_LL_ERR_FORM,
@@ -123,7 +131,7 @@ typedef enum {
} twai_ll_err_dir_t;
typedef enum {
TWAI_LL_ERR_SEG_SOF = 0,
TWAI_LL_ERR_SEG_SOF = 3,
TWAI_LL_ERR_SEG_ID_28_21 = 2,
TWAI_LL_ERR_SEG_SRTR = 4,
TWAI_LL_ERR_SEG_IDE = 5,
@@ -149,7 +157,6 @@ typedef enum {
TWAI_LL_ERR_SEG_OVRLD_FLAG = 28,
TWAI_LL_ERR_SEG_MAX = 29,
} twai_ll_err_seg_t;
#endif
/* ---------------------------- Reset and Clock Control ------------------------------ */
@@ -272,18 +279,10 @@ static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
static inline void twai_ll_set_mode(twai_dev_t *hw, bool listen_only, bool no_ack, bool loopback)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
hw->mode_reg.lom = 0;
hw->mode_reg.stm = 0;
} else if (mode == TWAI_MODE_NO_ACK) { //Self Test Mode (No Ack)
hw->mode_reg.lom = 0;
hw->mode_reg.stm = 1;
} else if (mode == TWAI_MODE_LISTEN_ONLY) { //Listen Only Mode
hw->mode_reg.lom = 1;
hw->mode_reg.stm = 0;
}
hw->mode_reg.lom = listen_only;
hw->mode_reg.stm = no_ack;
}
/* --------------------------- Command Register ----------------------------- */
@@ -424,30 +423,6 @@ static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
return hw->status_reg.val;
}
/**
* @brief Check if RX FIFO overrun status bit is set
*
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
__attribute__((always_inline))
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status_reg.dos;
}
/**
* @brief Check if previously TX was successful
*
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
__attribute__((always_inline))
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status_reg.tcs;
}
/* -------------------------- Interrupt Register ---------------------------- */
/**
@@ -478,16 +453,27 @@ static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
__attribute__((always_inline))
static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
{
#if SOC_TWAI_BRP_DIV_SUPPORTED
if (ESP_CHIP_REV_ABOVE(efuse_hal_chip_revision(), 200)) {
//ESP32 Rev 2 or later has brp div field. Need to mask it out
hw->interrupt_enable_reg.val = (hw->interrupt_enable_reg.val & 0x10) | intr_mask;
#else
} else {
hw->interrupt_enable_reg.val = intr_mask;
#endif
}
}
/* ------------------------ Bus Timing Registers --------------------------- */
/**
* @brief Get the hardware bitrate prediv max value
*
* @return Max brp value
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_brp_max(void)
{
return ESP_CHIP_REV_ABOVE(efuse_hal_chip_revision(), 200) ? 256 : 128;
}
/**
* @brief Check if the brp value valid
*
@@ -497,7 +483,7 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
__attribute__((always_inline))
static inline bool twai_ll_check_brp_validation(uint32_t brp)
{
bool valid = (brp >= SOC_TWAI_BRP_MIN) && (brp <= SOC_TWAI_BRP_MAX);
bool valid = (brp >= TWAI_LL_BRP_MIN) && (brp <= TWAI_LL_BRP_MAX);
// should be an even number
valid = valid && !(brp & 0x01);
if (brp > TWAI_LL_BRP_DIV_THRESH) {
@@ -524,7 +510,7 @@ static inline bool twai_ll_check_brp_validation(uint32_t brp)
__attribute__((always_inline))
static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t sjw, uint32_t tseg1, uint32_t tseg2, bool triple_sampling)
{
#if SOC_TWAI_BRP_DIV_SUPPORTED
if (ESP_CHIP_REV_ABOVE(efuse_hal_chip_revision(), 200)) {
if (brp > TWAI_LL_BRP_DIV_THRESH) {
//Need to set brp_div bit
hw->interrupt_enable_reg.brp_div = 1;
@@ -532,7 +518,7 @@ static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t
} else {
hw->interrupt_enable_reg.brp_div = 0;
}
#endif
}
hw->bus_timing_0_reg.brp = (brp / 2) - 1;
hw->bus_timing_0_reg.sjw = sjw - 1;
hw->bus_timing_1_reg.tseg1 = tseg1 - 1;
@@ -558,30 +544,20 @@ static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
/* ----------------------------- ECC Register ------------------------------- */
/**
* @brief Clear Error Code Capture register
* @brief Parse Error Code Capture register
*
* Reading the ECC register rearms the Bus Error Interrupt
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
{
(void)hw->error_code_capture_reg.val;
}
#ifdef CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID
static inline void twai_ll_parse_err_code_cap(twai_dev_t *hw,
twai_ll_err_type_t *type,
twai_ll_err_dir_t *dir,
twai_ll_err_seg_t *seg)
static inline void twai_ll_parse_err_code_cap(twai_dev_t *hw, twai_ll_err_type_t *type, twai_ll_err_dir_t *dir, twai_ll_err_seg_t *seg)
{
uint32_t ecc = hw->error_code_capture_reg.val;
*type = (twai_ll_err_type_t) ((ecc >> 6) & 0x3);
*dir = (twai_ll_err_dir_t) ((ecc >> 5) & 0x1);
*seg = (twai_ll_err_seg_t) (ecc & 0x1F);
}
#endif
/* ----------------------------- EWL Register ------------------------------- */
@@ -781,6 +757,18 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
}
}
/**
* @brief Check if the message in twai_ll_frame_buffer is extend id format or not
*
* @param rx_frame The rx_frame in twai_ll_frame_buffer_t type
* @return true if the message is extend id format, false if not
*/
__attribute__((always_inline))
static inline bool twai_ll_frame_is_ext_format(twai_ll_frame_buffer_t *rx_frame)
{
return rx_frame->frame_format;
}
/**
* @brief Parse formatted TWAI frame (RX Buffer Layout) into its constituent contents
*
@@ -792,7 +780,7 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
*/
__attribute__((always_inline))
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
uint8_t *data, uint32_t buf_sz, uint32_t *flags)
{
//Copy frame information
*dlc = rx_frame->dlc;
@@ -822,13 +810,10 @@ static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame,
uint8_t *data_buffer = (rx_frame->frame_format) ? rx_frame->extended.data : rx_frame->standard.data;
//Only copy data if the frame is a data frame (i.e. not a remote frame)
int data_length = (rx_frame->rtr) ? 0 : ((rx_frame->dlc > TWAI_FRAME_MAX_DLC) ? TWAI_FRAME_MAX_DLC : rx_frame->dlc);
data_length = (data_length < buf_sz) ? data_length : buf_sz;
for (int i = 0; i < data_length; i++) {
data[i] = data_buffer[i];
}
//Set remaining bytes of data to 0
for (int i = data_length; i < TWAI_FRAME_MAX_DLC; i++) {
data[i] = 0;
}
}
/* ----------------------- RX Message Count Register ------------------------ */
@@ -891,7 +876,6 @@ static inline void twai_ll_enable_extended_reg_layout(twai_dev_t *hw)
/* ------------------------- Register Save/Restore -------------------------- */
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
/**
* @brief Saves the current values of the TWAI controller's registers
*
@@ -948,7 +932,6 @@ static inline void twai_ll_restore_reg(twai_dev_t *hw, twai_ll_reg_save_t *reg_s
hw->tx_error_counter_reg.val = reg_save->tx_error_counter_reg;
hw->clock_divider_reg.val = reg_save->clock_divider_reg;
}
#endif //defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
#ifdef __cplusplus
}

View File

@@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2021-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2021-2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@@ -32,6 +32,13 @@ extern "C" {
#endif
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_BRP_MIN 2
#define TWAI_LL_BRP_MAX 16384
#define TWAI_LL_TSEG1_MIN 1
#define TWAI_LL_TSEG2_MIN 1
#define TWAI_LL_TSEG1_MAX 16 //the max register value
#define TWAI_LL_TSEG2_MAX 8
#define TWAI_LL_SJW_MAX 4
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
#define TWAI_LL_STATUS_DOS (0x1 << 1) //Data Overrun Status
@@ -51,6 +58,51 @@ extern "C" {
#define TWAI_LL_INTR_ALI (0x1 << 6) //Arbitration Lost Interrupt
#define TWAI_LL_INTR_BEI (0x1 << 7) //Bus Error Interrupt
#define TWAI_LL_DRIVER_INTERRUPTS (TWAI_LL_INTR_RI | TWAI_LL_INTR_TI | TWAI_LL_INTR_EI | \
TWAI_LL_INTR_EPI | TWAI_LL_INTR_ALI | TWAI_LL_INTR_BEI)
typedef enum {
TWAI_LL_ERR_BIT = 0,
TWAI_LL_ERR_FORM,
TWAI_LL_ERR_STUFF,
TWAI_LL_ERR_OTHER,
TWAI_LL_ERR_MAX,
} twai_ll_err_type_t;
typedef enum {
TWAI_LL_ERR_DIR_TX = 0,
TWAI_LL_ERR_DIR_RX,
TWAI_LL_ERR_DIR_MAX,
} twai_ll_err_dir_t;
typedef enum {
TWAI_LL_ERR_SEG_SOF = 3,
TWAI_LL_ERR_SEG_ID_28_21 = 2,
TWAI_LL_ERR_SEG_SRTR = 4,
TWAI_LL_ERR_SEG_IDE = 5,
TWAI_LL_ERR_SEG_ID_20_18 = 6,
TWAI_LL_ERR_SEG_ID_17_13 = 7,
TWAI_LL_ERR_SEG_CRC_SEQ = 8,
TWAI_LL_ERR_SEG_R0 = 9,
TWAI_LL_ERR_SEG_DATA = 10,
TWAI_LL_ERR_SEG_DLC = 11,
TWAI_LL_ERR_SEG_RTR = 12,
TWAI_LL_ERR_SEG_R1 = 13,
TWAI_LL_ERR_SEG_ID_4_0 = 14,
TWAI_LL_ERR_SEG_ID_12_5 = 15,
TWAI_LL_ERR_SEG_ACT_FLAG = 17,
TWAI_LL_ERR_SEG_INTER = 18,
TWAI_LL_ERR_SEG_SUPERPOS = 19,
TWAI_LL_ERR_SEG_PASS_FLAG = 22,
TWAI_LL_ERR_SEG_ERR_DELIM = 23,
TWAI_LL_ERR_SEG_CRC_DELIM = 24,
TWAI_LL_ERR_SEG_ACK_SLOT = 25,
TWAI_LL_ERR_SEG_EOF = 26,
TWAI_LL_ERR_SEG_ACK_DELIM = 27,
TWAI_LL_ERR_SEG_OVRLD_FLAG = 28,
TWAI_LL_ERR_SEG_MAX = 29,
} twai_ll_err_seg_t;
/*
* The following frame structure has an NEARLY identical bit field layout to
* each byte of the TX buffer. This allows for formatting and parsing frames to
@@ -59,7 +111,7 @@ extern "C" {
* TX buffer are used in the frame structure to store the self_reception and
* single_shot flags which in turn indicate the type of transmission to execute.
*/
typedef union {
typedef union twai_ll_frame_buffer_t {
struct {
struct {
uint8_t dlc: 4; //Data length code (0 to 8) of the frame
@@ -202,18 +254,10 @@ static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
static inline void twai_ll_set_mode(twai_dev_t *hw, bool listen_only, bool no_ack, bool loopback)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
hw->mode_reg.lom = 0;
hw->mode_reg.stm = 0;
} else if (mode == TWAI_MODE_NO_ACK) { //Self Test Mode (No Ack)
hw->mode_reg.lom = 0;
hw->mode_reg.stm = 1;
} else if (mode == TWAI_MODE_LISTEN_ONLY) { //Listen Only Mode
hw->mode_reg.lom = 1;
hw->mode_reg.stm = 0;
}
hw->mode_reg.lom = listen_only;
hw->mode_reg.stm = no_ack;
}
/* --------------------------- Command Register ----------------------------- */
@@ -354,30 +398,6 @@ static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
return hw->status_reg.val;
}
/**
* @brief Check if RX FIFO overrun status bit is set
*
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
__attribute__((always_inline))
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status_reg.dos;
}
/**
* @brief Check if previously TX was successful
*
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
__attribute__((always_inline))
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status_reg.tcs;
}
/* -------------------------- Interrupt Register ---------------------------- */
/**
@@ -422,7 +442,7 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
__attribute__((always_inline))
static inline bool twai_ll_check_brp_validation(uint32_t brp)
{
bool valid = (brp >= SOC_TWAI_BRP_MIN) && (brp <= SOC_TWAI_BRP_MAX);
bool valid = (brp >= TWAI_LL_BRP_MIN) && (brp <= TWAI_LL_BRP_MAX);
// should be an even number
valid = valid && !(brp & 0x01);
return valid;
@@ -469,16 +489,19 @@ static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
/* ----------------------------- ECC Register ------------------------------- */
/**
* @brief Clear Error Code Capture register
* @brief Parse Error Code Capture register
*
* Reading the ECC register rearms the Bus Error Interrupt
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
static inline void twai_ll_parse_err_code_cap(twai_dev_t *hw, twai_ll_err_type_t *type, twai_ll_err_dir_t *dir, twai_ll_err_seg_t *seg)
{
(void)hw->error_code_capture_reg.val;
uint32_t ecc = hw->error_code_capture_reg.val;
*type = (twai_ll_err_type_t) ((ecc >> 6) & 0x3);
*dir = (twai_ll_err_dir_t) ((ecc >> 5) & 0x1);
*seg = (twai_ll_err_seg_t) (ecc & 0x1F);
}
/* ----------------------------- EWL Register ------------------------------- */
@@ -679,6 +702,18 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
}
}
/**
* @brief Check if the message in twai_ll_frame_buffer is extend id format or not
*
* @param rx_frame The rx_frame in twai_ll_frame_buffer_t type
* @return true if the message is extend id format, false if not
*/
__attribute__((always_inline))
static inline bool twai_ll_frame_is_ext_format(twai_ll_frame_buffer_t *rx_frame)
{
return rx_frame->frame_format;
}
/**
* @brief Parse formatted TWAI frame (RX Buffer Layout) into its constituent contents
*
@@ -690,7 +725,7 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
*/
__attribute__((always_inline))
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
uint8_t *data, uint32_t buf_sz, uint32_t *flags)
{
//Copy frame information
*dlc = rx_frame->dlc;
@@ -720,13 +755,10 @@ static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame,
uint8_t *data_buffer = (rx_frame->frame_format) ? rx_frame->extended.data : rx_frame->standard.data;
//Only copy data if the frame is a data frame (i.e. not a remote frame)
int data_length = (rx_frame->rtr) ? 0 : ((rx_frame->dlc > TWAI_FRAME_MAX_DLC) ? TWAI_FRAME_MAX_DLC : rx_frame->dlc);
data_length = (data_length < buf_sz) ? data_length : buf_sz;
for (int i = 0; i < data_length; i++) {
data[i] = data_buffer[i];
}
//Set remaining bytes of data to 0
for (int i = data_length; i < TWAI_FRAME_MAX_DLC; i++) {
data[i] = 0;
}
}
/* ----------------------- RX Message Count Register ------------------------ */

View File

@@ -26,6 +26,8 @@ extern "C" {
#define TWAIFD_LL_GET_HW(num) (((num) == 0) ? (&TWAI0) : (&TWAI1))
#define TWAI_LL_BRP_MIN 1
#define TWAI_LL_BRP_MAX 255
#define TWAI_LL_TSEG1_MIN 0
#define TWAI_LL_TSEG2_MIN 1
#define TWAI_LL_TSEG1_MAX TWAIFD_PH1
@@ -62,6 +64,10 @@ extern "C" {
#define TWAIFD_LL_INTR_ARBI_LOST TWAIFD_ALI_INT_ST // Arbitration Lost Interrupt
#define TWAIFD_LL_INTR_DATA_OVERRUN TWAIFD_DOI_INT_ST // Data Overrun Interrupt
#define TWAI_LL_DRIVER_INTERRUPTS (TWAIFD_LL_INTR_TX_DONE | TWAIFD_LL_INTR_RX_NOT_EMPTY | TWAIFD_LL_INTR_RX_FULL | \
TWAIFD_LL_INTR_ERR_WARN | TWAIFD_LL_INTR_BUS_ERR | TWAIFD_LL_INTR_FSM_CHANGE | \
TWAIFD_LL_INTR_ARBI_LOST | TWAIFD_LL_INTR_DATA_OVERRUN)
/**
* @brief Enable the bus clock and module clock for twai module
*
@@ -284,6 +290,17 @@ static inline void twaifd_ll_clr_intr_status(twaifd_dev_t *hw, uint32_t intr_mas
}
/* ------------------------ Bus Timing Registers --------------------------- */
/**
* @brief Check if the brp value valid
*
* @param brp Bit rate prescaler value
* @return true or False
*/
static inline bool twaifd_ll_check_brp_validation(uint32_t brp)
{
return (brp >= TWAI_LL_BRP_MIN) && (brp <= TWAI_LL_BRP_MAX);
}
/**
* @brief Set bus timing nominal bit rate
*
@@ -333,39 +350,25 @@ static inline void twaifd_ll_config_secondary_sample_point(twaifd_dev_t *hw, uin
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->trv_delay_ssp_cfg, ssp_offset, offset_val);
}
/* ----------------------------- ALC Register ------------------------------- */
/* ----------------------------- ERR Capt Register ------------------------------- */
/**
* @brief Get the arbitration lost field from the TWAI-FD peripheral.
* @brief Get the error reason flags from the TWAI-FD peripheral.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @return The arbitration lost ID field.
* @return The error reasons, see `twai_error_flags_t`
*/
static inline uint32_t twaifd_ll_get_arb_lost_field(twaifd_dev_t *hw)
__attribute__((always_inline))
static inline twai_error_flags_t twaifd_ll_get_err_reason(twaifd_dev_t *hw)
{
return hw->err_capt_retr_ctr_alc_ts_info.alc_id_field;
}
/**
* @brief Get the bit where arbitration was lost from the TWAI-FD peripheral.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @return The bit position where arbitration was lost.
*/
static inline uint32_t twaifd_ll_get_arb_lost_bit(twaifd_dev_t *hw)
{
return hw->err_capt_retr_ctr_alc_ts_info.alc_bit;
}
/**
* @brief Get the error code reason from the TWAI-FD peripheral.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @return The error code, see `TWAIFD_LL_ERR_`
*/
static inline uint32_t twaifd_ll_get_err_reason_code(twaifd_dev_t *hw)
{
return hw->err_capt_retr_ctr_alc_ts_info.err_type;
uint8_t error_code = hw->err_capt_retr_ctr_alc_ts_info.err_type;
twai_error_flags_t errors = {
.bit_err = error_code == TWAIFD_LL_ERR_BIT_ERR,
.form_err = error_code == TWAIFD_LL_ERR_FRM_ERR,
.stuff_err = error_code == TWAIFD_LL_ERR_STUF_ERR,
.ack_err = error_code == TWAIFD_LL_ERR_ACK_ERR
};
return errors;
}
/* ----------------------------- EWL Register ------------------------------- */
@@ -383,6 +386,7 @@ static inline void twaifd_ll_set_err_warn_limit(twaifd_dev_t *hw, uint32_t ewl)
* @param hw Start address of the TWAI registers
* @return Error Warning Limit
*/
__attribute__((always_inline))
static inline uint32_t twaifd_ll_get_err_warn_limit(twaifd_dev_t *hw)
{
return HAL_FORCE_READ_U32_REG_FIELD(hw->ewl_erp_fault_state, ew_limit);
@@ -394,6 +398,7 @@ static inline uint32_t twaifd_ll_get_err_warn_limit(twaifd_dev_t *hw)
* @param hw Pointer to the TWAI-FD device hardware.
* @return Fault state (bus-off, error passive, or active state).
*/
__attribute__((always_inline))
static inline twai_error_state_t twaifd_ll_get_fault_state(twaifd_dev_t *hw)
{
if (hw->ewl_erp_fault_state.bof) {
@@ -434,6 +439,7 @@ static inline uint32_t twaifd_ll_get_err_count_fd(twaifd_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return REC value
*/
__attribute__((always_inline))
static inline uint32_t twaifd_ll_get_rec(twaifd_dev_t *hw)
{
return hw->rec_tec.rec_val;
@@ -446,6 +452,7 @@ static inline uint32_t twaifd_ll_get_rec(twaifd_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return TEC value
*/
__attribute__((always_inline))
static inline uint32_t twaifd_ll_get_tec(twaifd_dev_t *hw)
{
return hw->rec_tec.tec_val;

View File

@@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2022-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2022-2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@@ -21,6 +21,8 @@
#include "hal/misc.h"
#include "hal/assert.h"
#include "hal/twai_types.h"
#include "soc/twai_periph.h"
#include "soc/twai_reg.h"
#include "soc/twai_struct.h"
#include "soc/pcr_struct.h"
@@ -31,6 +33,13 @@ extern "C" {
#endif
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_BRP_MIN 2
#define TWAI_LL_BRP_MAX 32768
#define TWAI_LL_TSEG1_MIN 1
#define TWAI_LL_TSEG2_MIN 1
#define TWAI_LL_TSEG1_MAX (TWAI_TIME_SEGMENT1 + 1)
#define TWAI_LL_TSEG2_MAX (TWAI_TIME_SEGMENT2 + 1)
#define TWAI_LL_SJW_MAX (TWAI_SYNC_JUMP_WIDTH + 1)
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
#define TWAI_LL_STATUS_DOS (0x1 << 1) //Data Overrun Status
@@ -51,6 +60,51 @@ extern "C" {
#define TWAI_LL_INTR_BEI (0x1 << 7) //Bus Error Interrupt
#define TWAI_LL_INTR_BISI (0x1 << 8) //Bus Idle Status Interrupt
#define TWAI_LL_DRIVER_INTERRUPTS (TWAI_LL_INTR_RI | TWAI_LL_INTR_TI | TWAI_LL_INTR_EI | \
TWAI_LL_INTR_EPI | TWAI_LL_INTR_ALI | TWAI_LL_INTR_BEI)
typedef enum {
TWAI_LL_ERR_BIT = 0,
TWAI_LL_ERR_FORM,
TWAI_LL_ERR_STUFF,
TWAI_LL_ERR_OTHER,
TWAI_LL_ERR_MAX,
} twai_ll_err_type_t;
typedef enum {
TWAI_LL_ERR_DIR_TX = 0,
TWAI_LL_ERR_DIR_RX,
TWAI_LL_ERR_DIR_MAX,
} twai_ll_err_dir_t;
typedef enum {
TWAI_LL_ERR_SEG_SOF = 3,
TWAI_LL_ERR_SEG_ID_28_21 = 2,
TWAI_LL_ERR_SEG_SRTR = 4,
TWAI_LL_ERR_SEG_IDE = 5,
TWAI_LL_ERR_SEG_ID_20_18 = 6,
TWAI_LL_ERR_SEG_ID_17_13 = 7,
TWAI_LL_ERR_SEG_CRC_SEQ = 8,
TWAI_LL_ERR_SEG_R0 = 9,
TWAI_LL_ERR_SEG_DATA = 10,
TWAI_LL_ERR_SEG_DLC = 11,
TWAI_LL_ERR_SEG_RTR = 12,
TWAI_LL_ERR_SEG_R1 = 13,
TWAI_LL_ERR_SEG_ID_4_0 = 14,
TWAI_LL_ERR_SEG_ID_12_5 = 15,
TWAI_LL_ERR_SEG_ACT_FLAG = 17,
TWAI_LL_ERR_SEG_INTER = 18,
TWAI_LL_ERR_SEG_SUPERPOS = 19,
TWAI_LL_ERR_SEG_PASS_FLAG = 22,
TWAI_LL_ERR_SEG_ERR_DELIM = 23,
TWAI_LL_ERR_SEG_CRC_DELIM = 24,
TWAI_LL_ERR_SEG_ACK_SLOT = 25,
TWAI_LL_ERR_SEG_EOF = 26,
TWAI_LL_ERR_SEG_ACK_DELIM = 27,
TWAI_LL_ERR_SEG_OVRLD_FLAG = 28,
TWAI_LL_ERR_SEG_MAX = 29,
} twai_ll_err_seg_t;
/*
* The following frame structure has an NEARLY identical bit field layout to
* each byte of the TX buffer. This allows for formatting and parsing frames to
@@ -59,7 +113,7 @@ extern "C" {
* TX buffer are used in the frame structure to store the self_reception and
* single_shot flags which in turn indicate the type of transmission to execute.
*/
typedef union {
typedef union twai_ll_frame_buffer_t {
struct {
struct {
uint8_t dlc: 4; //Data length code (0 to 8) of the frame
@@ -222,18 +276,10 @@ static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
static inline void twai_ll_set_mode(twai_dev_t *hw, bool listen_only, bool no_ack, bool loopback)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
hw->mode.listen_only_mode = 0;
hw->mode.self_test_mode = 0;
} else if (mode == TWAI_MODE_NO_ACK) { //Self Test Mode (No Ack)
hw->mode.listen_only_mode = 0;
hw->mode.self_test_mode = 1;
} else if (mode == TWAI_MODE_LISTEN_ONLY) { //Listen Only Mode
hw->mode.listen_only_mode = 1;
hw->mode.self_test_mode = 0;
}
hw->mode.listen_only_mode = listen_only;
hw->mode.self_test_mode = no_ack;
}
/* --------------------------- Command Register ----------------------------- */
@@ -374,30 +420,6 @@ static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
return hw->status.val;
}
/**
* @brief Check if RX FIFO overrun status bit is set
*
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
__attribute__((always_inline))
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status.status_overrun;
}
/**
* @brief Check if previously TX was successful
*
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
__attribute__((always_inline))
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status.status_transmission_complete;
}
/* -------------------------- Interrupt Register ---------------------------- */
/**
@@ -442,7 +464,7 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
__attribute__((always_inline))
static inline bool twai_ll_check_brp_validation(uint32_t brp)
{
bool valid = (brp >= SOC_TWAI_BRP_MIN) && (brp <= SOC_TWAI_BRP_MAX);
bool valid = (brp >= TWAI_LL_BRP_MIN) && (brp <= TWAI_LL_BRP_MAX);
// should be an even number
valid = valid && !(brp & 0x01);
return valid;
@@ -489,16 +511,19 @@ static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
/* ----------------------------- ECC Register ------------------------------- */
/**
* @brief Clear Error Code Capture register
* @brief Parse Error Code Capture register
*
* Reading the ECC register rearms the Bus Error Interrupt
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
static inline void twai_ll_parse_err_code_cap(twai_dev_t *hw, twai_ll_err_type_t *type, twai_ll_err_dir_t *dir, twai_ll_err_seg_t *seg)
{
(void)hw->err_code_cap.val;
uint32_t ecc = hw->err_code_cap.val;
*type = (twai_ll_err_type_t) ((ecc >> 6) & 0x3);
*dir = (twai_ll_err_dir_t) ((ecc >> 5) & 0x1);
*seg = (twai_ll_err_seg_t) (ecc & 0x1F);
}
/* ----------------------------- EWL Register ------------------------------- */
@@ -699,6 +724,18 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
}
}
/**
* @brief Check if the message in twai_ll_frame_buffer is extend id format or not
*
* @param rx_frame The rx_frame in twai_ll_frame_buffer_t type
* @return true if the message is extend id format, false if not
*/
__attribute__((always_inline))
static inline bool twai_ll_frame_is_ext_format(twai_ll_frame_buffer_t *rx_frame)
{
return rx_frame->frame_format;
}
/**
* @brief Parse formatted TWAI frame (RX Buffer Layout) into its constituent contents
*
@@ -710,7 +747,7 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
*/
__attribute__((always_inline))
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
uint8_t *data, uint32_t buf_sz, uint32_t *flags)
{
//Copy frame information
*dlc = rx_frame->dlc;
@@ -740,13 +777,10 @@ static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame,
uint8_t *data_buffer = (rx_frame->frame_format) ? rx_frame->extended.data : rx_frame->standard.data;
//Only copy data if the frame is a data frame (i.e. not a remote frame)
int data_length = (rx_frame->rtr) ? 0 : ((rx_frame->dlc > TWAI_FRAME_MAX_DLC) ? TWAI_FRAME_MAX_DLC : rx_frame->dlc);
data_length = (data_length < buf_sz) ? data_length : buf_sz;
for (int i = 0; i < data_length; i++) {
data[i] = data_buffer[i];
}
//Set remaining bytes of data to 0
for (int i = data_length; i < TWAI_FRAME_MAX_DLC; i++) {
data[i] = 0;
}
}
/* ----------------------- RX Message Count Register ------------------------ */

View File

@@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2021-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2021-2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@@ -22,6 +22,7 @@
#include "hal/assert.h"
#include "hal/twai_types.h"
#include "soc/twai_periph.h"
#include "soc/twai_reg.h"
#include "soc/twai_struct.h"
#include "soc/pcr_struct.h"
@@ -32,6 +33,13 @@ extern "C" {
#endif
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_BRP_MIN 2
#define TWAI_LL_BRP_MAX 32768
#define TWAI_LL_TSEG1_MIN 1
#define TWAI_LL_TSEG2_MIN 1
#define TWAI_LL_TSEG1_MAX (TWAI_TIME_SEGMENT1 + 1)
#define TWAI_LL_TSEG2_MAX (TWAI_TIME_SEGMENT2 + 1)
#define TWAI_LL_SJW_MAX (TWAI_SYNC_JUMP_WIDTH + 1)
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
#define TWAI_LL_STATUS_DOS (0x1 << 1) //Data Overrun Status
@@ -51,6 +59,51 @@ extern "C" {
#define TWAI_LL_INTR_ALI (0x1 << 6) //Arbitration Lost Interrupt
#define TWAI_LL_INTR_BEI (0x1 << 7) //Bus Error Interrupt
#define TWAI_LL_DRIVER_INTERRUPTS (TWAI_LL_INTR_RI | TWAI_LL_INTR_TI | TWAI_LL_INTR_EI | \
TWAI_LL_INTR_EPI | TWAI_LL_INTR_ALI | TWAI_LL_INTR_BEI)
typedef enum {
TWAI_LL_ERR_BIT = 0,
TWAI_LL_ERR_FORM,
TWAI_LL_ERR_STUFF,
TWAI_LL_ERR_OTHER,
TWAI_LL_ERR_MAX,
} twai_ll_err_type_t;
typedef enum {
TWAI_LL_ERR_DIR_TX = 0,
TWAI_LL_ERR_DIR_RX,
TWAI_LL_ERR_DIR_MAX,
} twai_ll_err_dir_t;
typedef enum {
TWAI_LL_ERR_SEG_SOF = 3,
TWAI_LL_ERR_SEG_ID_28_21 = 2,
TWAI_LL_ERR_SEG_SRTR = 4,
TWAI_LL_ERR_SEG_IDE = 5,
TWAI_LL_ERR_SEG_ID_20_18 = 6,
TWAI_LL_ERR_SEG_ID_17_13 = 7,
TWAI_LL_ERR_SEG_CRC_SEQ = 8,
TWAI_LL_ERR_SEG_R0 = 9,
TWAI_LL_ERR_SEG_DATA = 10,
TWAI_LL_ERR_SEG_DLC = 11,
TWAI_LL_ERR_SEG_RTR = 12,
TWAI_LL_ERR_SEG_R1 = 13,
TWAI_LL_ERR_SEG_ID_4_0 = 14,
TWAI_LL_ERR_SEG_ID_12_5 = 15,
TWAI_LL_ERR_SEG_ACT_FLAG = 17,
TWAI_LL_ERR_SEG_INTER = 18,
TWAI_LL_ERR_SEG_SUPERPOS = 19,
TWAI_LL_ERR_SEG_PASS_FLAG = 22,
TWAI_LL_ERR_SEG_ERR_DELIM = 23,
TWAI_LL_ERR_SEG_CRC_DELIM = 24,
TWAI_LL_ERR_SEG_ACK_SLOT = 25,
TWAI_LL_ERR_SEG_EOF = 26,
TWAI_LL_ERR_SEG_ACK_DELIM = 27,
TWAI_LL_ERR_SEG_OVRLD_FLAG = 28,
TWAI_LL_ERR_SEG_MAX = 29,
} twai_ll_err_seg_t;
/*
* The following frame structure has an NEARLY identical bit field layout to
* each byte of the TX buffer. This allows for formatting and parsing frames to
@@ -59,7 +112,7 @@ extern "C" {
* TX buffer are used in the frame structure to store the self_reception and
* single_shot flags which in turn indicate the type of transmission to execute.
*/
typedef union {
typedef union twai_ll_frame_buffer_t {
struct {
struct {
uint8_t dlc: 4; //Data length code (0 to 8) of the frame
@@ -201,18 +254,10 @@ static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
static inline void twai_ll_set_mode(twai_dev_t *hw, bool listen_only, bool no_ack, bool loopback)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
hw->mode.listen_only_mode = 0;
hw->mode.self_test_mode = 0;
} else if (mode == TWAI_MODE_NO_ACK) { //Self Test Mode (No Ack)
hw->mode.listen_only_mode = 0;
hw->mode.self_test_mode = 1;
} else if (mode == TWAI_MODE_LISTEN_ONLY) { //Listen Only Mode
hw->mode.listen_only_mode = 1;
hw->mode.self_test_mode = 0;
}
hw->mode.listen_only_mode = listen_only;
hw->mode.self_test_mode = no_ack;
}
/* --------------------------- Command Register ----------------------------- */
@@ -353,30 +398,6 @@ static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
return hw->status.val;
}
/**
* @brief Check if RX FIFO overrun status bit is set
*
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
__attribute__((always_inline))
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status.status_overrun;
}
/**
* @brief Check if previously TX was successful
*
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
__attribute__((always_inline))
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status.status_transmission_complete;
}
/* -------------------------- Interrupt Register ---------------------------- */
/**
@@ -421,7 +442,7 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
__attribute__((always_inline))
static inline bool twai_ll_check_brp_validation(uint32_t brp)
{
bool valid = (brp >= SOC_TWAI_BRP_MIN) && (brp <= SOC_TWAI_BRP_MAX);
bool valid = (brp >= TWAI_LL_BRP_MIN) && (brp <= TWAI_LL_BRP_MAX);
// should be an even number
valid = valid && !(brp & 0x01);
return valid;
@@ -468,16 +489,19 @@ static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
/* ----------------------------- ECC Register ------------------------------- */
/**
* @brief Clear Error Code Capture register
* @brief Parse Error Code Capture register
*
* Reading the ECC register rearms the Bus Error Interrupt
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
static inline void twai_ll_parse_err_code_cap(twai_dev_t *hw, twai_ll_err_type_t *type, twai_ll_err_dir_t *dir, twai_ll_err_seg_t *seg)
{
(void)hw->err_code_cap.val;
uint32_t ecc = hw->err_code_cap.val;
*type = (twai_ll_err_type_t) ((ecc >> 6) & 0x3);
*dir = (twai_ll_err_dir_t) ((ecc >> 5) & 0x1);
*seg = (twai_ll_err_seg_t) (ecc & 0x1F);
}
/* ----------------------------- EWL Register ------------------------------- */
@@ -678,6 +702,18 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
}
}
/**
* @brief Check if the message in twai_ll_frame_buffer is extend id format or not
*
* @param rx_frame The rx_frame in twai_ll_frame_buffer_t type
* @return true if the message is extend id format, false if not
*/
__attribute__((always_inline))
static inline bool twai_ll_frame_is_ext_format(twai_ll_frame_buffer_t *rx_frame)
{
return rx_frame->frame_format;
}
/**
* @brief Parse formatted TWAI frame (RX Buffer Layout) into its constituent contents
*
@@ -689,7 +725,7 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
*/
__attribute__((always_inline))
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
uint8_t *data, uint32_t buf_sz, uint32_t *flags)
{
//Copy frame information
*dlc = rx_frame->dlc;
@@ -719,13 +755,10 @@ static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame,
uint8_t *data_buffer = (rx_frame->frame_format) ? rx_frame->extended.data : rx_frame->standard.data;
//Only copy data if the frame is a data frame (i.e. not a remote frame)
int data_length = (rx_frame->rtr) ? 0 : ((rx_frame->dlc > TWAI_FRAME_MAX_DLC) ? TWAI_FRAME_MAX_DLC : rx_frame->dlc);
data_length = (data_length < buf_sz) ? data_length : buf_sz;
for (int i = 0; i < data_length; i++) {
data[i] = data_buffer[i];
}
//Set remaining bytes of data to 0
for (int i = data_length; i < TWAI_FRAME_MAX_DLC; i++) {
data[i] = 0;
}
}
/* ----------------------- RX Message Count Register ------------------------ */

View File

@@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2023-2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@@ -21,18 +21,25 @@
#include "hal/misc.h"
#include "hal/assert.h"
#include "hal/twai_types.h"
#include "soc/twai_periph.h"
#include "soc/twai_reg.h"
#include "soc/twai_struct.h"
#include "soc/hp_sys_clkrst_struct.h"
#define TWAI_LL_GET_HW(controller_id) ((controller_id == 0) ? (&TWAI0) : \
(controller_id == 1) ? (&TWAI1) : \
(&TWAI2))
#define TWAI_LL_GET_HW(controller_id) ((controller_id == 0) ? (&TWAI0) : (controller_id == 1) ? (&TWAI1) : (&TWAI2))
#ifdef __cplusplus
extern "C" {
#endif
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_BRP_MIN 2
#define TWAI_LL_BRP_MAX 32768
#define TWAI_LL_TSEG1_MIN 1
#define TWAI_LL_TSEG2_MIN 1
#define TWAI_LL_TSEG1_MAX (TWAI_TIME_SEGMENT1 + 1)
#define TWAI_LL_TSEG2_MAX (TWAI_TIME_SEGMENT2 + 1)
#define TWAI_LL_SJW_MAX (TWAI_SYNC_JUMP_WIDTH + 1)
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
#define TWAI_LL_STATUS_DOS (0x1 << 1) //Data Overrun Status
@@ -53,6 +60,51 @@ extern "C" {
#define TWAI_LL_INTR_BEI (0x1 << 7) //Bus Error Interrupt
#define TWAI_LL_INTR_BISI (0x1 << 8) //Bus Idle Status Interrupt
#define TWAI_LL_DRIVER_INTERRUPTS (TWAI_LL_INTR_RI | TWAI_LL_INTR_TI | TWAI_LL_INTR_EI | \
TWAI_LL_INTR_EPI | TWAI_LL_INTR_ALI | TWAI_LL_INTR_BEI)
typedef enum {
TWAI_LL_ERR_BIT = 0,
TWAI_LL_ERR_FORM,
TWAI_LL_ERR_STUFF,
TWAI_LL_ERR_OTHER,
TWAI_LL_ERR_MAX,
} twai_ll_err_type_t;
typedef enum {
TWAI_LL_ERR_DIR_TX = 0,
TWAI_LL_ERR_DIR_RX,
TWAI_LL_ERR_DIR_MAX,
} twai_ll_err_dir_t;
typedef enum {
TWAI_LL_ERR_SEG_SOF = 3,
TWAI_LL_ERR_SEG_ID_28_21 = 2,
TWAI_LL_ERR_SEG_SRTR = 4,
TWAI_LL_ERR_SEG_IDE = 5,
TWAI_LL_ERR_SEG_ID_20_18 = 6,
TWAI_LL_ERR_SEG_ID_17_13 = 7,
TWAI_LL_ERR_SEG_CRC_SEQ = 8,
TWAI_LL_ERR_SEG_R0 = 9,
TWAI_LL_ERR_SEG_DATA = 10,
TWAI_LL_ERR_SEG_DLC = 11,
TWAI_LL_ERR_SEG_RTR = 12,
TWAI_LL_ERR_SEG_R1 = 13,
TWAI_LL_ERR_SEG_ID_4_0 = 14,
TWAI_LL_ERR_SEG_ID_12_5 = 15,
TWAI_LL_ERR_SEG_ACT_FLAG = 17,
TWAI_LL_ERR_SEG_INTER = 18,
TWAI_LL_ERR_SEG_SUPERPOS = 19,
TWAI_LL_ERR_SEG_PASS_FLAG = 22,
TWAI_LL_ERR_SEG_ERR_DELIM = 23,
TWAI_LL_ERR_SEG_CRC_DELIM = 24,
TWAI_LL_ERR_SEG_ACK_SLOT = 25,
TWAI_LL_ERR_SEG_EOF = 26,
TWAI_LL_ERR_SEG_ACK_DELIM = 27,
TWAI_LL_ERR_SEG_OVRLD_FLAG = 28,
TWAI_LL_ERR_SEG_MAX = 29,
} twai_ll_err_seg_t;
/*
* The following frame structure has an NEARLY identical bit field layout to
* each byte of the TX buffer. This allows for formatting and parsing frames to
@@ -61,7 +113,7 @@ extern "C" {
* TX buffer are used in the frame structure to store the self_reception and
* single_shot flags which in turn indicate the type of transmission to execute.
*/
typedef union {
typedef union twai_ll_frame_buffer_t {
struct {
struct {
uint8_t dlc: 4; //Data length code (0 to 8) of the frame
@@ -245,18 +297,10 @@ static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
static inline void twai_ll_set_mode(twai_dev_t *hw, bool listen_only, bool no_ack, bool loopback)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
hw->mode.listen_only_mode = 0;
hw->mode.self_test_mode = 0;
} else if (mode == TWAI_MODE_NO_ACK) { //Self Test Mode (No Ack)
hw->mode.listen_only_mode = 0;
hw->mode.self_test_mode = 1;
} else if (mode == TWAI_MODE_LISTEN_ONLY) { //Listen Only Mode
hw->mode.listen_only_mode = 1;
hw->mode.self_test_mode = 0;
}
hw->mode.listen_only_mode = listen_only;
hw->mode.self_test_mode = no_ack;
}
/* --------------------------- Command Register ----------------------------- */
@@ -397,30 +441,6 @@ static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
return hw->status.val;
}
/**
* @brief Check if RX FIFO overrun status bit is set
*
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
__attribute__((always_inline))
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status.status_overrun;
}
/**
* @brief Check if previously TX was successful
*
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
__attribute__((always_inline))
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status.status_transmission_complete;
}
/* -------------------------- Interrupt Register ---------------------------- */
/**
@@ -465,7 +485,7 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
__attribute__((always_inline))
static inline bool twai_ll_check_brp_validation(uint32_t brp)
{
bool valid = (brp >= SOC_TWAI_BRP_MIN) && (brp <= SOC_TWAI_BRP_MAX);
bool valid = (brp >= TWAI_LL_BRP_MIN) && (brp <= TWAI_LL_BRP_MAX);
// should be an even number
valid = valid && !(brp & 0x01);
return valid;
@@ -512,16 +532,19 @@ static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
/* ----------------------------- ECC Register ------------------------------- */
/**
* @brief Clear Error Code Capture register
* @brief Parse Error Code Capture register
*
* Reading the ECC register rearms the Bus Error Interrupt
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
static inline void twai_ll_parse_err_code_cap(twai_dev_t *hw, twai_ll_err_type_t *type, twai_ll_err_dir_t *dir, twai_ll_err_seg_t *seg)
{
(void)hw->err_code_cap.val;
uint32_t ecc = hw->err_code_cap.val;
*type = (twai_ll_err_type_t) ((ecc >> 6) & 0x3);
*dir = (twai_ll_err_dir_t) ((ecc >> 5) & 0x1);
*seg = (twai_ll_err_seg_t) (ecc & 0x1F);
}
/* ----------------------------- EWL Register ------------------------------- */
@@ -721,6 +744,18 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
}
}
/**
* @brief Check if the message in twai_ll_frame_buffer is extend id format or not
*
* @param rx_frame The rx_frame in twai_ll_frame_buffer_t type
* @return true if the message is extend id format, false if not
*/
__attribute__((always_inline))
static inline bool twai_ll_frame_is_ext_format(twai_ll_frame_buffer_t *rx_frame)
{
return rx_frame->frame_format;
}
/**
* @brief Parse formatted TWAI frame (RX Buffer Layout) into its constituent contents
*
@@ -731,7 +766,8 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
* @param[out] format Type of TWAI frame
*/
__attribute__((always_inline))
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc, uint8_t *data, uint32_t *flags)
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t buf_sz, uint32_t *flags)
{
//Copy frame information
*dlc = rx_frame->dlc;
@@ -761,13 +797,10 @@ static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame,
uint8_t *data_buffer = (rx_frame->frame_format) ? rx_frame->extended.data : rx_frame->standard.data;
//Only copy data if the frame is a data frame (i.e. not a remote frame)
int data_length = (rx_frame->rtr) ? 0 : ((rx_frame->dlc > TWAI_FRAME_MAX_DLC) ? TWAI_FRAME_MAX_DLC : rx_frame->dlc);
data_length = (data_length < buf_sz) ? data_length : buf_sz;
for (int i = 0; i < data_length; i++) {
data[i] = data_buffer[i];
}
//Set remaining bytes of data to 0
for (int i = data_length; i < TWAI_FRAME_MAX_DLC; i++) {
data[i] = 0;
}
}
/* ----------------------- RX Message Count Register ------------------------ */

View File

@@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@@ -32,6 +32,13 @@ extern "C" {
#endif
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_BRP_MIN 2
#define TWAI_LL_BRP_MAX 32768
#define TWAI_LL_TSEG1_MIN 1
#define TWAI_LL_TSEG2_MIN 1
#define TWAI_LL_TSEG1_MAX 16 //the max register value
#define TWAI_LL_TSEG2_MAX 8
#define TWAI_LL_SJW_MAX 4
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
#define TWAI_LL_STATUS_DOS (0x1 << 1) //Data Overrun Status
@@ -51,6 +58,51 @@ extern "C" {
#define TWAI_LL_INTR_ALI (0x1 << 6) //Arbitration Lost Interrupt
#define TWAI_LL_INTR_BEI (0x1 << 7) //Bus Error Interrupt
#define TWAI_LL_DRIVER_INTERRUPTS (TWAI_LL_INTR_RI | TWAI_LL_INTR_TI | TWAI_LL_INTR_EI | \
TWAI_LL_INTR_EPI | TWAI_LL_INTR_ALI | TWAI_LL_INTR_BEI)
typedef enum {
TWAI_LL_ERR_BIT = 0,
TWAI_LL_ERR_FORM,
TWAI_LL_ERR_STUFF,
TWAI_LL_ERR_OTHER,
TWAI_LL_ERR_MAX,
} twai_ll_err_type_t;
typedef enum {
TWAI_LL_ERR_DIR_TX = 0,
TWAI_LL_ERR_DIR_RX,
TWAI_LL_ERR_DIR_MAX,
} twai_ll_err_dir_t;
typedef enum {
TWAI_LL_ERR_SEG_SOF = 3,
TWAI_LL_ERR_SEG_ID_28_21 = 2,
TWAI_LL_ERR_SEG_SRTR = 4,
TWAI_LL_ERR_SEG_IDE = 5,
TWAI_LL_ERR_SEG_ID_20_18 = 6,
TWAI_LL_ERR_SEG_ID_17_13 = 7,
TWAI_LL_ERR_SEG_CRC_SEQ = 8,
TWAI_LL_ERR_SEG_R0 = 9,
TWAI_LL_ERR_SEG_DATA = 10,
TWAI_LL_ERR_SEG_DLC = 11,
TWAI_LL_ERR_SEG_RTR = 12,
TWAI_LL_ERR_SEG_R1 = 13,
TWAI_LL_ERR_SEG_ID_4_0 = 14,
TWAI_LL_ERR_SEG_ID_12_5 = 15,
TWAI_LL_ERR_SEG_ACT_FLAG = 17,
TWAI_LL_ERR_SEG_INTER = 18,
TWAI_LL_ERR_SEG_SUPERPOS = 19,
TWAI_LL_ERR_SEG_PASS_FLAG = 22,
TWAI_LL_ERR_SEG_ERR_DELIM = 23,
TWAI_LL_ERR_SEG_CRC_DELIM = 24,
TWAI_LL_ERR_SEG_ACK_SLOT = 25,
TWAI_LL_ERR_SEG_EOF = 26,
TWAI_LL_ERR_SEG_ACK_DELIM = 27,
TWAI_LL_ERR_SEG_OVRLD_FLAG = 28,
TWAI_LL_ERR_SEG_MAX = 29,
} twai_ll_err_seg_t;
/*
* The following frame structure has an NEARLY identical bit field layout to
* each byte of the TX buffer. This allows for formatting and parsing frames to
@@ -59,7 +111,7 @@ extern "C" {
* TX buffer are used in the frame structure to store the self_reception and
* single_shot flags which in turn indicate the type of transmission to execute.
*/
typedef union {
typedef union twai_ll_frame_buffer_t {
struct {
struct {
uint8_t dlc: 4; //Data length code (0 to 8) of the frame
@@ -205,18 +257,10 @@ static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
static inline void twai_ll_set_mode(twai_dev_t *hw, bool listen_only, bool no_ack, bool loopback)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
hw->mode_reg.lom = 0;
hw->mode_reg.stm = 0;
} else if (mode == TWAI_MODE_NO_ACK) { //Self Test Mode (No Ack)
hw->mode_reg.lom = 0;
hw->mode_reg.stm = 1;
} else if (mode == TWAI_MODE_LISTEN_ONLY) { //Listen Only Mode
hw->mode_reg.lom = 1;
hw->mode_reg.stm = 0;
}
hw->mode_reg.lom = listen_only;
hw->mode_reg.stm = no_ack;
}
/* --------------------------- Command Register ----------------------------- */
@@ -357,30 +401,6 @@ static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
return hw->status_reg.val;
}
/**
* @brief Check if RX FIFO overrun status bit is set
*
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
__attribute__((always_inline))
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status_reg.dos;
}
/**
* @brief Check if previously TX was successful
*
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
__attribute__((always_inline))
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status_reg.tcs;
}
/* -------------------------- Interrupt Register ---------------------------- */
/**
@@ -425,7 +445,7 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
__attribute__((always_inline))
static inline bool twai_ll_check_brp_validation(uint32_t brp)
{
bool valid = (brp >= SOC_TWAI_BRP_MIN) && (brp <= SOC_TWAI_BRP_MAX);
bool valid = (brp >= TWAI_LL_BRP_MIN) && (brp <= TWAI_LL_BRP_MAX);
// should be an even number
valid = valid && !(brp & 0x01);
return valid;
@@ -472,16 +492,19 @@ static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
/* ----------------------------- ECC Register ------------------------------- */
/**
* @brief Clear Error Code Capture register
* @brief Parse Error Code Capture register
*
* Reading the ECC register rearms the Bus Error Interrupt
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
static inline void twai_ll_parse_err_code_cap(twai_dev_t *hw, twai_ll_err_type_t *type, twai_ll_err_dir_t *dir, twai_ll_err_seg_t *seg)
{
(void)hw->error_code_capture_reg.val;
uint32_t ecc = hw->error_code_capture_reg.val;
*type = (twai_ll_err_type_t) ((ecc >> 6) & 0x3);
*dir = (twai_ll_err_dir_t) ((ecc >> 5) & 0x1);
*seg = (twai_ll_err_seg_t) (ecc & 0x1F);
}
/* ----------------------------- EWL Register ------------------------------- */
@@ -682,6 +705,18 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
}
}
/**
* @brief Check if the message in twai_ll_frame_buffer is extend id format or not
*
* @param rx_frame The rx_frame in twai_ll_frame_buffer_t type
* @return true if the message is extend id format, false if not
*/
__attribute__((always_inline))
static inline bool twai_ll_frame_is_ext_format(twai_ll_frame_buffer_t *rx_frame)
{
return rx_frame->frame_format;
}
/**
* @brief Parse formatted TWAI frame (RX Buffer Layout) into its constituent contents
*
@@ -693,7 +728,7 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
*/
__attribute__((always_inline))
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
uint8_t *data, uint32_t buf_sz, uint32_t *flags)
{
//Copy frame information
*dlc = rx_frame->dlc;
@@ -723,13 +758,10 @@ static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame,
uint8_t *data_buffer = (rx_frame->frame_format) ? rx_frame->extended.data : rx_frame->standard.data;
//Only copy data if the frame is a data frame (i.e. not a remote frame)
int data_length = (rx_frame->rtr) ? 0 : ((rx_frame->dlc > TWAI_FRAME_MAX_DLC) ? TWAI_FRAME_MAX_DLC : rx_frame->dlc);
data_length = (data_length < buf_sz) ? data_length : buf_sz;
for (int i = 0; i < data_length; i++) {
data[i] = data_buffer[i];
}
//Set remaining bytes of data to 0
for (int i = data_length; i < TWAI_FRAME_MAX_DLC; i++) {
data[i] = 0;
}
}
/* ----------------------- RX Message Count Register ------------------------ */

View File

@@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@@ -32,6 +32,13 @@ extern "C" {
#endif
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_BRP_MIN 2
#define TWAI_LL_BRP_MAX 16384
#define TWAI_LL_TSEG1_MIN 1
#define TWAI_LL_TSEG2_MIN 1
#define TWAI_LL_TSEG1_MAX 16 //the max register value
#define TWAI_LL_TSEG2_MAX 8
#define TWAI_LL_SJW_MAX 4
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
#define TWAI_LL_STATUS_DOS (0x1 << 1) //Data Overrun Status
@@ -51,6 +58,51 @@ extern "C" {
#define TWAI_LL_INTR_ALI (0x1 << 6) //Arbitration Lost Interrupt
#define TWAI_LL_INTR_BEI (0x1 << 7) //Bus Error Interrupt
#define TWAI_LL_DRIVER_INTERRUPTS (TWAI_LL_INTR_RI | TWAI_LL_INTR_TI | TWAI_LL_INTR_EI | \
TWAI_LL_INTR_EPI | TWAI_LL_INTR_ALI | TWAI_LL_INTR_BEI)
typedef enum {
TWAI_LL_ERR_BIT = 0,
TWAI_LL_ERR_FORM,
TWAI_LL_ERR_STUFF,
TWAI_LL_ERR_OTHER,
TWAI_LL_ERR_MAX,
} twai_ll_err_type_t;
typedef enum {
TWAI_LL_ERR_DIR_TX = 0,
TWAI_LL_ERR_DIR_RX,
TWAI_LL_ERR_DIR_MAX,
} twai_ll_err_dir_t;
typedef enum {
TWAI_LL_ERR_SEG_SOF = 3,
TWAI_LL_ERR_SEG_ID_28_21 = 2,
TWAI_LL_ERR_SEG_SRTR = 4,
TWAI_LL_ERR_SEG_IDE = 5,
TWAI_LL_ERR_SEG_ID_20_18 = 6,
TWAI_LL_ERR_SEG_ID_17_13 = 7,
TWAI_LL_ERR_SEG_CRC_SEQ = 8,
TWAI_LL_ERR_SEG_R0 = 9,
TWAI_LL_ERR_SEG_DATA = 10,
TWAI_LL_ERR_SEG_DLC = 11,
TWAI_LL_ERR_SEG_RTR = 12,
TWAI_LL_ERR_SEG_R1 = 13,
TWAI_LL_ERR_SEG_ID_4_0 = 14,
TWAI_LL_ERR_SEG_ID_12_5 = 15,
TWAI_LL_ERR_SEG_ACT_FLAG = 17,
TWAI_LL_ERR_SEG_INTER = 18,
TWAI_LL_ERR_SEG_SUPERPOS = 19,
TWAI_LL_ERR_SEG_PASS_FLAG = 22,
TWAI_LL_ERR_SEG_ERR_DELIM = 23,
TWAI_LL_ERR_SEG_CRC_DELIM = 24,
TWAI_LL_ERR_SEG_ACK_SLOT = 25,
TWAI_LL_ERR_SEG_EOF = 26,
TWAI_LL_ERR_SEG_ACK_DELIM = 27,
TWAI_LL_ERR_SEG_OVRLD_FLAG = 28,
TWAI_LL_ERR_SEG_MAX = 29,
} twai_ll_err_seg_t;
/*
* The following frame structure has an NEARLY identical bit field layout to
* each byte of the TX buffer. This allows for formatting and parsing frames to
@@ -59,7 +111,7 @@ extern "C" {
* TX buffer are used in the frame structure to store the self_reception and
* single_shot flags which in turn indicate the type of transmission to execute.
*/
typedef union {
typedef union twai_ll_frame_buffer_t {
struct {
struct {
uint8_t dlc: 4; //Data length code (0 to 8) of the frame
@@ -202,18 +254,10 @@ static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
static inline void twai_ll_set_mode(twai_dev_t *hw, bool listen_only, bool no_ack, bool loopback)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
hw->mode_reg.lom = 0;
hw->mode_reg.stm = 0;
} else if (mode == TWAI_MODE_NO_ACK) { //Self Test Mode (No Ack)
hw->mode_reg.lom = 0;
hw->mode_reg.stm = 1;
} else if (mode == TWAI_MODE_LISTEN_ONLY) { //Listen Only Mode
hw->mode_reg.lom = 1;
hw->mode_reg.stm = 0;
}
hw->mode_reg.lom = listen_only;
hw->mode_reg.stm = no_ack;
}
/* --------------------------- Command Register ----------------------------- */
@@ -354,30 +398,6 @@ static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
return hw->status_reg.val;
}
/**
* @brief Check if RX FIFO overrun status bit is set
*
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
__attribute__((always_inline))
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status_reg.dos;
}
/**
* @brief Check if previously TX was successful
*
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
__attribute__((always_inline))
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status_reg.tcs;
}
/* -------------------------- Interrupt Register ---------------------------- */
/**
@@ -422,7 +442,7 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
__attribute__((always_inline))
static inline bool twai_ll_check_brp_validation(uint32_t brp)
{
bool valid = (brp >= SOC_TWAI_BRP_MIN) && (brp <= SOC_TWAI_BRP_MAX);
bool valid = (brp >= TWAI_LL_BRP_MIN) && (brp <= TWAI_LL_BRP_MAX);
// should be an even number
valid = valid && !(brp & 0x01);
return valid;
@@ -469,16 +489,19 @@ static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
/* ----------------------------- ECC Register ------------------------------- */
/**
* @brief Clear Error Code Capture register
* @brief Parse Error Code Capture register
*
* Reading the ECC register rearms the Bus Error Interrupt
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
static inline void twai_ll_parse_err_code_cap(twai_dev_t *hw, twai_ll_err_type_t *type, twai_ll_err_dir_t *dir, twai_ll_err_seg_t *seg)
{
(void)hw->error_code_capture_reg.val;
uint32_t ecc = hw->error_code_capture_reg.val;
*type = (twai_ll_err_type_t) ((ecc >> 6) & 0x3);
*dir = (twai_ll_err_dir_t) ((ecc >> 5) & 0x1);
*seg = (twai_ll_err_seg_t) (ecc & 0x1F);
}
/* ----------------------------- EWL Register ------------------------------- */
@@ -679,6 +702,18 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
}
}
/**
* @brief Check if the message in twai_ll_frame_buffer is extend id format or not
*
* @param rx_frame The rx_frame in twai_ll_frame_buffer_t type
* @return true if the message is extend id format, false if not
*/
__attribute__((always_inline))
static inline bool twai_ll_frame_is_ext_format(twai_ll_frame_buffer_t *rx_frame)
{
return rx_frame->frame_format;
}
/**
* @brief Parse formatted TWAI frame (RX Buffer Layout) into its constituent contents
*
@@ -690,7 +725,7 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
*/
__attribute__((always_inline))
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
uint8_t *data, uint32_t buf_sz, uint32_t *flags)
{
//Copy frame information
*dlc = rx_frame->dlc;
@@ -720,13 +755,10 @@ static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame,
uint8_t *data_buffer = (rx_frame->frame_format) ? rx_frame->extended.data : rx_frame->standard.data;
//Only copy data if the frame is a data frame (i.e. not a remote frame)
int data_length = (rx_frame->rtr) ? 0 : ((rx_frame->dlc > TWAI_FRAME_MAX_DLC) ? TWAI_FRAME_MAX_DLC : rx_frame->dlc);
data_length = (data_length < buf_sz) ? data_length : buf_sz;
for (int i = 0; i < data_length; i++) {
data[i] = data_buffer[i];
}
//Set remaining bytes of data to 0
for (int i = data_length; i < TWAI_FRAME_MAX_DLC; i++) {
data[i] = 0;
}
}
/* ----------------------- RX Message Count Register ------------------------ */

View File

@@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@@ -7,7 +7,6 @@
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use in application code.
* See readme.md in hal/include/hal/readme.md
******************************************************************************/
#pragma once
@@ -19,15 +18,15 @@
#include "hal/twai_types.h"
#if SOC_TWAI_SUPPORTED
#if SOC_TWAI_SUPPORT_FD
#include "hal/twaifd_ll.h"
typedef twaifd_dev_t* twai_soc_handle_t;
typedef twaifd_frame_buffer_t twai_hal_frame_t;
typedef struct twaifd_dev_t *twai_soc_handle_t;
typedef union twaifd_frame_buffer_t twai_hal_frame_t;
#else
#include "hal/twai_ll.h"
typedef twai_dev_t* twai_soc_handle_t;
typedef twai_ll_frame_buffer_t twai_hal_frame_t;
typedef struct twai_dev_t *twai_soc_handle_t;
typedef union twai_ll_frame_buffer_t twai_hal_frame_t;
#endif
typedef struct twai_hal_errata_ctx_t twai_hal_errata_ctx_t;
#ifdef __cplusplus
extern "C" {
@@ -45,15 +44,13 @@ extern "C" {
#define TWAI_HAL_STATE_FLAG_ERR_PASSIVE (1 << 3) //TEC or REC is >= 128
#define TWAI_HAL_STATE_FLAG_BUS_OFF (1 << 4) //Bus-off due to TEC >= 256
#define TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED (1 << 5) //Transmit buffer is occupied
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
#define TWAI_HAL_STATE_FLAG_TX_NEED_RETRY (1 << 7) //TX needs to be restarted due to errata workarounds
#endif
//Interrupt Events
#define TWAI_HAL_EVENT_BUS_OFF (1 << 0)
#define TWAI_HAL_EVENT_BUS_RECOV_CPLT (1 << 1)
#define TWAI_HAL_EVENT_BUS_RECOV_PROGRESS (1 << 2)
#define TWAI_HAL_EVENT_ABOVE_EWL (1 << 3)
#define TWAI_HAL_EVENT_ERROR_WARNING (1 << 3)
#define TWAI_HAL_EVENT_BELOW_EWL (1 << 4)
#define TWAI_HAL_EVENT_ERROR_PASSIVE (1 << 5)
#define TWAI_HAL_EVENT_ERROR_ACTIVE (1 << 6)
@@ -61,20 +58,20 @@ extern "C" {
#define TWAI_HAL_EVENT_ARB_LOST (1 << 8)
#define TWAI_HAL_EVENT_RX_BUFF_FRAME (1 << 9)
#define TWAI_HAL_EVENT_TX_BUFF_FREE (1 << 10)
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
#define TWAI_HAL_EVENT_NEED_PERIPH_RESET (1 << 11)
#endif
#define TWAI_HAL_EVENT_TX_SUCCESS (1 << 12)
typedef struct {
twai_soc_handle_t dev; // TWAI SOC layer handle (i.e. register base address)
uint32_t state_flags;
uint32_t clock_source_hz;
twai_error_flags_t errors;
uint8_t sja1000_filter_id_type; // hardware don't check id type, check in software, 0:no_filter, 1: std_id_only, 2: ext_id_only
int8_t retry_cnt;
bool enable_self_test;
bool enable_loopback;
bool enable_listen_only;
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
twai_hal_frame_t tx_frame_save;
twai_ll_reg_save_t reg_save;
uint8_t rx_msg_cnt_save;
#endif
twai_hal_errata_ctx_t *errata_ctx;
} twai_hal_context_t;
/* ---------------------------- Init and Config ----------------------------- */
@@ -83,36 +80,19 @@ typedef struct {
int controller_id;
uint32_t clock_source_hz;
uint32_t intr_mask;
int8_t retry_cnt;
bool no_receive_rtr;
bool enable_self_test;
bool enable_loopback;
bool enable_listen_only;
} twai_hal_config_t;
/**
* @brief Translate TWAIFD format DLC code to bytes length
* @param[in] dlc The frame DLC code follow the FD spec
* @return The byte length of DLC stand for
* @brief Get the memory requirement of hal_ctx and errata workaround context
*
* @return size_t
*/
__attribute__((always_inline))
static inline int twaifd_dlc2len(uint8_t dlc) {
HAL_ASSERT(dlc <= TWAIFD_FRAME_MAX_DLC);
return (dlc <= 8) ? dlc :
(dlc <= 12) ? (dlc - 8) * 4 + 8 :
(dlc <= 13) ? (dlc - 12) * 8 + 24 :
(dlc - 13) * 16 + 32;
}
/**
* @brief Translate TWAIFD format bytes length to DLC code
* @param[in] byte_len The byte length of the message
* @return The FD adopted frame DLC code
*/
__attribute__((always_inline))
static inline uint8_t twaifd_len2dlc(int byte_len) {
HAL_ASSERT((byte_len <= TWAIFD_FRAME_MAX_LEN) && (byte_len >= 0));
return (byte_len <= 8) ? byte_len :
(byte_len <= 24) ? (byte_len - 8 + 3) / 4 + 8 :
(byte_len <= 32) ? (byte_len - 24 + 7) / 8 + 12 :
(byte_len - 32 + 15) / 16 + 13;
}
size_t twai_hal_get_mem_requirment(void);
/**
* @brief Initialize TWAI peripheral and HAL context
@@ -126,7 +106,6 @@ static inline uint8_t twaifd_len2dlc(int byte_len) {
*/
bool twai_hal_init(twai_hal_context_t *hal_ctx, const twai_hal_config_t *config);
#if !SOC_TWAI_SUPPORT_FD
/**
* @brief Deinitialize the TWAI peripheral and HAL context
*
@@ -137,16 +116,66 @@ bool twai_hal_init(twai_hal_context_t *hal_ctx, const twai_hal_config_t *config)
void twai_hal_deinit(twai_hal_context_t *hal_ctx);
/**
* @brief Configure the TWAI peripheral
* @brief Configure the TWAI peripheral for legacy driver (deprecated)
*
* @param hal_ctx Context of the HAL layer
* @param t_config Pointer to timing configuration structure
* @param f_config Pointer to filter configuration structure
* @param intr_mask Mask of interrupts to enable
* @param clkout_divider Clock divider value for CLKOUT. Set to -1 to disable CLKOUT
*/
void twai_hal_configure(twai_hal_context_t *hal_ctx, const twai_timing_config_t *t_config, const twai_filter_config_t *f_config, uint32_t intr_mask, uint32_t clkout_divider);
void twai_hal_configure(twai_hal_context_t *hal_ctx, const twai_timing_config_t *t_config, const twai_filter_config_t *f_config, uint32_t clkout_divider);
/**
* @brief Check if the brp value valid for hardware register
*
* @param hal_ctx Context of the HAL layer
* @param brp Bit rate prescaler value
* @return true or False
*/
bool twai_hal_check_brp_validation(twai_hal_context_t *hal_ctx, uint32_t brp);
/**
* @brief Configure the TWAI timing
*
* @param hal_ctx Context of the HAL layer
* @param t_config Pointer to timing configuration structure
*/
void twai_hal_configure_timing(twai_hal_context_t *hal_ctx, const twai_timing_advanced_config_t *t_config);
/**
* @brief Configure the TWAI timing of FD data
*
* @param hal_ctx Context of the HAL layer
* @param t_config_fd Pointer to fd timing configuration structure
*/
void twai_hal_configure_timing_fd(twai_hal_context_t *hal_ctx, const twai_timing_advanced_config_t *t_config_fd);
/**
* @brief Configure the TWAI mask filter
*
* @param hal_ctx Context of the HAL layer
* @param filter_id Which filter to be configured
* @param f_config Pointer to filter configuration structure
*/
void twai_hal_configure_filter(twai_hal_context_t *hal_ctx, uint8_t filter_id, const twai_mask_filter_config_t *f_config);
/**
* @brief Configure the TWAI range filter
*
* @param hal_ctx Context of the HAL layer
* @param filter_id Which filter to be configured
* @param f_config Pointer to filter configuration structure
*/
void twai_hal_configure_range_filter(twai_hal_context_t *hal_ctx, uint8_t filter_id, const twai_range_filter_config_t *f_config);
/**
* @brief Check if the message in rx_frame match the filter config which save in hal_ctx
*
* @param hal_ctx Context of the HAL layer
* @param rx_frame Where the message will be checked saved in
* @return true: Pass the configured filter, false: don't pass
*/
bool twai_hal_soft_filter_check_msg(twai_hal_context_t *hal_ctx, twai_hal_frame_t *rx_frame);
/* -------------------------------- Actions --------------------------------- */
/**
@@ -156,9 +185,8 @@ void twai_hal_configure(twai_hal_context_t *hal_ctx, const twai_timing_config_t
* reset mode so that the TWAI peripheral can participate in bus activities.
*
* @param hal_ctx Context of the HAL layer
* @param mode Operating mode
*/
void twai_hal_start(twai_hal_context_t *hal_ctx, twai_mode_t mode);
void twai_hal_start(twai_hal_context_t *hal_ctx);
/**
* @brief Stop the TWAI peripheral
@@ -175,12 +203,7 @@ void twai_hal_stop(twai_hal_context_t *hal_ctx);
*
* @param hal_ctx Context of the HAL layer
*/
static inline void twai_hal_start_bus_recovery(twai_hal_context_t *hal_ctx)
{
TWAI_HAL_CLEAR_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED);
TWAI_HAL_SET_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_RECOVERING);
twai_ll_exit_reset_mode(hal_ctx->dev);
}
void twai_hal_start_bus_recovery(twai_hal_context_t *hal_ctx);
/**
* @brief Get the value of the TX Error Counter
@@ -188,10 +211,7 @@ static inline void twai_hal_start_bus_recovery(twai_hal_context_t *hal_ctx)
* @param hal_ctx Context of the HAL layer
* @return TX Error Counter Value
*/
static inline uint32_t twai_hal_get_tec(twai_hal_context_t *hal_ctx)
{
return twai_ll_get_tec((hal_ctx)->dev);
}
uint32_t twai_hal_get_tec(twai_hal_context_t *hal_ctx);
/**
* @brief Get the value of the RX Error Counter
@@ -199,34 +219,7 @@ static inline uint32_t twai_hal_get_tec(twai_hal_context_t *hal_ctx)
* @param hal_ctx Context of the HAL layer
* @return RX Error Counter Value
*/
static inline uint32_t twai_hal_get_rec(twai_hal_context_t *hal_ctx)
{
return twai_ll_get_rec((hal_ctx)->dev);
}
/**
* @brief Get the RX message count register
*
* @param hal_ctx Context of the HAL layer
* @return RX message count
*/
__attribute__((always_inline))
static inline uint32_t twai_hal_get_rx_msg_count(twai_hal_context_t *hal_ctx)
{
return twai_ll_get_rx_msg_count((hal_ctx)->dev);
}
/**
* @brief Check if the last transmitted frame was successful
*
* @param hal_ctx Context of the HAL layer
* @return True if successful
*/
__attribute__((always_inline))
static inline bool twai_hal_check_last_tx_successful(twai_hal_context_t *hal_ctx)
{
return twai_ll_is_last_tx_successful((hal_ctx)->dev);
}
uint32_t twai_hal_get_rec(twai_hal_context_t *hal_ctx);
/**
* @brief Check if certain HAL state flags are set
@@ -239,11 +232,7 @@ static inline bool twai_hal_check_last_tx_successful(twai_hal_context_t *hal_ctx
* @param check_flags Bit mask of flags to check
* @return True if one or more of the flags in check_flags are set
*/
__attribute__((always_inline))
static inline bool twai_hal_check_state_flags(twai_hal_context_t *hal_ctx, uint32_t check_flags)
{
return hal_ctx->state_flags & check_flags;
}
bool twai_hal_check_state_flags(twai_hal_context_t *hal_ctx, uint32_t check_flags);
/* ----------------------------- Event Handling ----------------------------- */
@@ -266,23 +255,61 @@ static inline bool twai_hal_check_state_flags(twai_hal_context_t *hal_ctx, uint3
*/
uint32_t twai_hal_get_events(twai_hal_context_t *hal_ctx);
/**
* @brief Get the hardware error fsm state (active/passive/bus_off)
*
* @param hal_ctx Context of the HAL layer
* @return twai_error_state
*/
twai_error_state_t twai_hal_get_err_state(twai_hal_context_t *hal_ctx);
/**
* @brief Get hardware transmit error flags
*
* @param hal_ctx Context of the HAL layer
* @return twai_error_flags_t
*/
__attribute__((always_inline))
static inline twai_error_flags_t twai_hal_get_err_flags(twai_hal_context_t *hal_ctx)
{
return hal_ctx->errors;
}
/* ------------------------------- TX and RX -------------------------------- */
/**
* @brief Get the RX message count register
*
* @param hal_ctx Context of the HAL layer
* @return RX message count
*/
uint32_t twai_hal_get_rx_msg_count(twai_hal_context_t *hal_ctx);
/**
* @brief TWAI hal transaction description type
*/
typedef struct {
struct {
twai_frame_header_t *header; // message attribute/metadata, exclude data buffer
uint8_t *buffer; // buffer address for tx and rx message data
size_t buffer_len; // buffer length of provided data buffer pointer, in bytes.
} frame;
struct {
int8_t retry_cnt; // Number of retransmission attempts (-1 for unlimited)
bool loopback; // loopback this message
} config; // Hardware config for TX transaction
} twai_hal_trans_desc_t;
/**
* @brief Format a TWAI Frame
*
* This function takes a TWAI message structure (containing ID, DLC, data, and
* flags) and formats it to match the layout of the TX frame buffer.
*
* @param message Pointer to TWAI message
* @param trans_desc Pointer to TWAI hal trans config
* @param frame Pointer to empty frame structure
*/
static inline void twai_hal_format_frame(const twai_message_t *message, twai_hal_frame_t *frame)
{
//Direct call to ll function
twai_ll_format_frame_buffer(message->identifier, message->data_length_code, message->data,
message->flags, frame);
}
void twai_hal_format_frame(const twai_hal_trans_desc_t *trans_desc, twai_hal_frame_t *frame);
/**
* @brief Parse a TWAI Frame
@@ -293,12 +320,7 @@ static inline void twai_hal_format_frame(const twai_message_t *message, twai_hal
* @param frame Pointer to frame structure
* @param message Pointer to empty message structure
*/
static inline void twai_hal_parse_frame(twai_hal_frame_t *frame, twai_message_t *message)
{
//Direct call to ll function
twai_ll_parse_frame_buffer(frame, &message->identifier, &message->data_length_code,
message->data, &message->flags);
}
void twai_hal_parse_frame(const twai_hal_frame_t *frame, twai_frame_header_t *header, uint8_t *buffer, uint8_t buffer_len);
/**
* @brief Copy a frame into the TX buffer and transmit
@@ -309,8 +331,9 @@ static inline void twai_hal_parse_frame(twai_hal_frame_t *frame, twai_message_t
*
* @param hal_ctx Context of the HAL layer
* @param tx_frame Pointer to structure containing formatted TX frame
* @param buffer_idx Hardware message buffer id to use
*/
void twai_hal_set_tx_buffer_and_transmit(twai_hal_context_t *hal_ctx, twai_hal_frame_t *tx_frame);
void twai_hal_set_tx_buffer_and_transmit(twai_hal_context_t *hal_ctx, twai_hal_frame_t *tx_frame, uint8_t buffer_idx);
/**
* @brief Copy a frame from the RX buffer and release
@@ -326,25 +349,7 @@ void twai_hal_set_tx_buffer_and_transmit(twai_hal_context_t *hal_ctx, twai_hal_f
* @param rx_frame Pointer to structure to store RX frame
* @return True if a valid frame was copied and released. False if overrun.
*/
__attribute__((always_inline))
static inline bool twai_hal_read_rx_buffer_and_clear(twai_hal_context_t *hal_ctx, twai_hal_frame_t *rx_frame)
{
#ifdef SOC_TWAI_SUPPORTS_RX_STATUS
if (twai_ll_get_status(hal_ctx->dev) & TWAI_LL_STATUS_MS) {
//Release the buffer for this particular overrun frame
twai_ll_set_cmd_release_rx_buffer(hal_ctx->dev);
return false;
}
#else
if (twai_ll_get_status(hal_ctx->dev) & TWAI_LL_STATUS_DOS) {
//No need to release RX buffer as we'll be releasing all RX frames in continuously later
return false;
}
#endif
twai_ll_get_rx_buffer(hal_ctx->dev, rx_frame);
twai_ll_set_cmd_release_rx_buffer(hal_ctx->dev);
return true;
}
bool twai_hal_read_rx_fifo(twai_hal_context_t *hal_ctx, twai_hal_frame_t *rx_frame);
#ifndef SOC_TWAI_SUPPORTS_RX_STATUS
/**
@@ -356,25 +361,32 @@ static inline bool twai_hal_read_rx_buffer_and_clear(twai_hal_context_t *hal_ctx
* @param hal_ctx Context of the HAL layer
* @return Number of overrun messages cleared from RX FIFO
*/
__attribute__((always_inline))
static inline uint32_t twai_hal_clear_rx_fifo_overrun(twai_hal_context_t *hal_ctx)
{
uint32_t msg_cnt = 0;
//Note: Need to keep polling th rx message counter in case another message arrives whilst clearing
while (twai_ll_get_rx_msg_count(hal_ctx->dev) > 0) {
twai_ll_set_cmd_release_rx_buffer(hal_ctx->dev);
msg_cnt++;
}
//Set a clear data overrun command to clear the data overrun status bit
twai_ll_set_cmd_clear_data_overrun(hal_ctx->dev);
return msg_cnt;
}
uint32_t twai_hal_clear_rx_fifo_overrun(twai_hal_context_t *hal_ctx);
#endif //SOC_TWAI_SUPPORTS_RX_STATUS
/* --------------------------- Errata Workarounds --------------------------- */
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
/**
* @brief Check if hardware is busy (transmitting / receiving)
*
* @param hal_ctx Context of the HAL layer
*/
bool twai_hal_is_hw_busy(twai_hal_context_t *hal_ctx);
/**
* @brief Backup the hardware configs, to prepare for hardware reset
*
* @param hal_ctx Context of the HAL layer
*/
void twai_hal_backup_config(twai_hal_context_t *hal_ctx);
/**
* @brief Restore the hardware configs which backup before
*
* @param hal_ctx Context of the HAL layer
*/
void twai_hal_restore_config(twai_hal_context_t *hal_ctx);
/**
* @brief Prepare the peripheral for a HW reset
*
@@ -412,13 +424,7 @@ void twai_hal_recover_from_reset(twai_hal_context_t *hal_ctx);
* @param hal_ctx Context of the HAL layer
* @return uint32_t Number of RX messages lost due to HW reset
*/
__attribute__((always_inline))
static inline uint32_t twai_hal_get_reset_lost_rx_cnt(twai_hal_context_t *hal_ctx)
{
return hal_ctx->rx_msg_cnt_save;
}
#endif //defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
#endif // !SOC_TWAI_SUPPORT_FD
uint32_t twai_hal_get_reset_lost_rx_cnt(twai_hal_context_t *hal_ctx);
#ifdef __cplusplus
}

View File

@@ -9,6 +9,7 @@
#include <stdint.h>
#include "soc/soc_caps.h"
#include "soc/clk_tree_defs.h"
#include "hal/assert.h"
#include "hal/twai_types_deprecated.h" //for backward competiblity, remove on 6.0
#ifdef __cplusplus
@@ -28,7 +29,7 @@ extern "C" {
#define TWAIFD_FRAME_MAX_LEN 64
/**
* @brief TWAI error states
* @brief TWAI node error fsm states
*/
typedef enum {
TWAI_ERROR_ACTIVE, /**< Error active state: TEC/REC < 96 */
@@ -37,6 +38,20 @@ typedef enum {
TWAI_ERROR_BUS_OFF, /**< Bus-off state: TEC >= 256 (node offline) */
} twai_error_state_t;
/**
* @brief TWAI transmit error type structure
*/
typedef union {
struct {
uint32_t arb_lost: 1; /**< Arbitration lost error (lost arbitration during transmission) */
uint32_t bit_err: 1; /**< Bit error detected (dominant/recessive mismatch during transmission) */
uint32_t form_err: 1; /**< Form error detected (frame fixed-form bit violation) */
uint32_t stuff_err: 1; /**< Stuff error detected (e.g. dominant error frame received) */
uint32_t ack_err: 1; /**< ACK error (no ack), transmission without acknowledge received */
};
uint32_t val; /**< Integrated error flags */
} twai_error_flags_t;
/**
* @brief TWAI group clock source
* @note User should select the clock source based on the power and resolution requirement
@@ -69,6 +84,39 @@ typedef struct {
*/
typedef twai_timing_config_t twai_timing_advanced_config_t;
/**
* @brief Configuration for TWAI mask filter
*/
typedef struct {
union{
uint32_t id; /**< Single base ID for filtering */
struct {
uint32_t *id_list; /**< Base ID list array for filtering, which share the same `mask` */
uint32_t num_of_ids; /**< List length of `id_list`, remain empty to using single `id` instead of `id_list` */
};
};
uint32_t mask; /**< Mask to determine the matching bits (1 = match bit, 0 = any bit) */
struct {
uint32_t is_ext: 1; /**< True for extended ID filtering, false for standard ID */
uint32_t no_classic: 1; /**< If true, Classic TWAI frames are excluded (only TWAI FD allowed) */
uint32_t no_fd: 1; /**< If true, TWAI FD frames are excluded (only Classic TWAI allowed) */
uint32_t dual_filter: 1; /**< Set filter as dual-16bits filter mode, see `twai_make_dual_filter()` for easy config */
};
} twai_mask_filter_config_t;
/**
* @brief Range-based filter configuration structure
*/
typedef struct {
uint32_t range_low; /**< Lower bound of the filtering range */
uint32_t range_high; /**< Upper bound of the filtering range */
struct {
uint32_t is_ext: 1; /**< True for extended ID filtering, false for standard ID */
uint32_t no_classic: 1; /**< If true, Classic TWAI frames are excluded (only TWAI FD allowed) */
uint32_t no_fd: 1; /**< If true, TWAI FD frames are excluded (only Classic TWAI allowed) */
};
} twai_range_filter_config_t;
/**
* @brief TWAI frame header/format struct type
*/
@@ -88,6 +136,34 @@ typedef struct {
};
} twai_frame_header_t;
/**
* @brief Translate TWAIFD format DLC code to bytes length
* @param[in] dlc The frame DLC code follow the FD spec
* @return The byte length of DLC stand for
*/
__attribute__((always_inline))
static inline uint16_t twaifd_dlc2len(uint16_t dlc) {
HAL_ASSERT(dlc <= TWAIFD_FRAME_MAX_DLC);
return (dlc <= 8) ? dlc :
(dlc <= 12) ? (dlc - 8) * 4 + 8 :
(dlc <= 13) ? (dlc - 12) * 8 + 24 :
(dlc - 13) * 16 + 32;
}
/**
* @brief Translate TWAIFD format bytes length to DLC code
* @param[in] byte_len The byte length of the message
* @return The FD adopted frame DLC code
*/
__attribute__((always_inline))
static inline uint16_t twaifd_len2dlc(uint16_t byte_len) {
HAL_ASSERT(byte_len <= TWAIFD_FRAME_MAX_LEN);
return (byte_len <= 8) ? byte_len :
(byte_len <= 24) ? (byte_len - 8 + 3) / 4 + 8 :
(byte_len <= 32) ? (byte_len - 24 + 7) / 8 + 12 :
(byte_len - 32 + 15) / 16 + 13;
}
#ifdef __cplusplus
}
#endif

View File

@@ -1,116 +0,0 @@
/*
* SPDX-FileCopyrightText: 2015-2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <stddef.h>
#include "sdkconfig.h"
#include "hal/twai_hal.h"
#include "hal/efuse_hal.h"
#include "soc/soc_caps.h"
//Default values written to various registers on initialization
#define TWAI_HAL_INIT_TEC 0
#define TWAI_HAL_INIT_REC 0
#define TWAI_HAL_INIT_EWL 96
/* ---------------------------- Init and Config ----------------------------- */
#if SOC_TWAI_SUPPORT_FD
bool twai_hal_init(twai_hal_context_t *hal_ctx, const twai_hal_config_t *config)
{
hal_ctx->dev = TWAIFD_LL_GET_HW(config->controller_id);
hal_ctx->enable_listen_only = config->enable_listen_only;
twaifd_ll_reset(hal_ctx->dev);
//mode should be changed under disabled
twaifd_ll_enable_hw(hal_ctx->dev, false);
twaifd_ll_enable_rxfifo_auto_incrase(hal_ctx->dev, true);
twaifd_ll_enable_intr(hal_ctx->dev, config->intr_mask);
return true;
}
#else
bool twai_hal_init(twai_hal_context_t *hal_ctx, const twai_hal_config_t *config)
{
//Initialize HAL context
hal_ctx->dev = TWAI_LL_GET_HW(config->controller_id);
hal_ctx->state_flags = 0;
hal_ctx->clock_source_hz = config->clock_source_hz;
//Initialize TWAI controller, and set default values to registers
twai_ll_enter_reset_mode(hal_ctx->dev);
if (!twai_ll_is_in_reset_mode(hal_ctx->dev)) { //Must enter reset mode to write to config registers
return false;
}
#if SOC_TWAI_SUPPORT_MULTI_ADDRESS_LAYOUT
twai_ll_enable_extended_reg_layout(hal_ctx->dev); //Changes the address layout of the registers
#endif
twai_ll_set_mode(hal_ctx->dev, TWAI_MODE_LISTEN_ONLY); //Freeze REC by changing to LOM mode
//Both TEC and REC should start at 0
twai_ll_set_tec(hal_ctx->dev, TWAI_HAL_INIT_TEC);
twai_ll_set_rec(hal_ctx->dev, TWAI_HAL_INIT_REC);
twai_ll_set_err_warn_lim(hal_ctx->dev, TWAI_HAL_INIT_EWL); //Set default value of for EWL
return true;
}
void twai_hal_deinit(twai_hal_context_t *hal_ctx)
{
//Clear any pending registers
(void) twai_ll_get_and_clear_intrs(hal_ctx->dev);
twai_ll_set_enabled_intrs(hal_ctx->dev, 0);
twai_ll_clear_arb_lost_cap(hal_ctx->dev);
twai_ll_clear_err_code_cap(hal_ctx->dev);
hal_ctx->dev = NULL;
}
void twai_hal_configure(twai_hal_context_t *hal_ctx, const twai_timing_config_t *t_config, const twai_filter_config_t *f_config, uint32_t intr_mask, uint32_t clkout_divider)
{
uint32_t brp = t_config->brp;
// both quanta_resolution_hz and brp can affect the baud rate
// but a non-zero quanta_resolution_hz takes higher priority
if (t_config->quanta_resolution_hz) {
brp = hal_ctx->clock_source_hz / t_config->quanta_resolution_hz;
}
//Configure bus timing, acceptance filter, CLKOUT, and interrupts
twai_ll_set_bus_timing(hal_ctx->dev, brp, t_config->sjw, t_config->tseg_1, t_config->tseg_2, t_config->triple_sampling);
twai_ll_set_acc_filter(hal_ctx->dev, f_config->acceptance_code, f_config->acceptance_mask, f_config->single_filter);
twai_ll_set_clkout(hal_ctx->dev, clkout_divider);
twai_ll_set_enabled_intrs(hal_ctx->dev, intr_mask);
(void) twai_ll_get_and_clear_intrs(hal_ctx->dev); //Clear any latched interrupts
}
/* -------------------------------- Actions --------------------------------- */
void twai_hal_start(twai_hal_context_t *hal_ctx, twai_mode_t mode)
{
twai_ll_set_mode(hal_ctx->dev, mode); //Set operating mode
//Clear the TEC and REC
twai_ll_set_tec(hal_ctx->dev, 0);
#ifdef CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM
/*
Errata workaround: Prevent transmission of dominant error frame while in listen only mode by setting REC to 128
before exiting reset mode. This forces the controller to be error passive (thus only transmits recessive bits).
The TEC/REC remain frozen in listen only mode thus ensuring we remain error passive.
*/
if (mode == TWAI_MODE_LISTEN_ONLY) {
twai_ll_set_rec(hal_ctx->dev, 128);
} else
#endif
{
twai_ll_set_rec(hal_ctx->dev, 0);
}
(void) twai_ll_get_and_clear_intrs(hal_ctx->dev); //Clear any latched interrupts
TWAI_HAL_SET_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_RUNNING);
twai_ll_exit_reset_mode(hal_ctx->dev);
}
void twai_hal_stop(twai_hal_context_t *hal_ctx)
{
twai_ll_enter_reset_mode(hal_ctx->dev);
(void) twai_ll_get_and_clear_intrs(hal_ctx->dev);
twai_ll_set_mode(hal_ctx->dev, TWAI_MODE_LISTEN_ONLY); //Freeze REC by changing to LOM mode
//Any TX is immediately halted on entering reset mode
TWAI_HAL_CLEAR_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED | TWAI_HAL_STATE_FLAG_RUNNING);
}
#endif //SOC_TWAI_SUPPORT_FD

View File

@@ -0,0 +1,191 @@
/*
* SPDX-FileCopyrightText: 2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include "hal/twai_hal.h"
#include "hal/twaifd_ll.h"
size_t twai_hal_get_mem_requirment(void) {
return sizeof(twai_hal_context_t);
}
bool twai_hal_init(twai_hal_context_t *hal_ctx, const twai_hal_config_t *config)
{
hal_ctx->dev = TWAIFD_LL_GET_HW(config->controller_id);
hal_ctx->retry_cnt = config->retry_cnt;
hal_ctx->enable_self_test = config->enable_self_test;
hal_ctx->enable_loopback = config->enable_loopback;
hal_ctx->enable_listen_only = config->enable_listen_only;
twaifd_ll_reset(hal_ctx->dev);
twaifd_ll_enable_hw(hal_ctx->dev, false); //mode should be changed under disabled
twaifd_ll_set_mode(hal_ctx->dev, config->enable_listen_only, config->enable_self_test, config->enable_loopback);
twaifd_ll_set_tx_retrans_limit(hal_ctx->dev, config->retry_cnt);
twaifd_ll_filter_block_rtr(hal_ctx->dev, config->no_receive_rtr);
twaifd_ll_enable_filter_mode(hal_ctx->dev, true); // each filter still has independent enable control
twaifd_ll_enable_fd_mode(hal_ctx->dev, true); // fd frame still controlled by `header.fdf`
twaifd_ll_enable_rxfifo_auto_incrase(hal_ctx->dev, true);
twaifd_ll_enable_intr(hal_ctx->dev, config->intr_mask);
return true;
}
void twai_hal_deinit(twai_hal_context_t *hal_ctx)
{
twaifd_ll_set_operate_cmd(hal_ctx->dev, TWAIFD_LL_HW_CMD_RST_TX_CNT);
twaifd_ll_set_operate_cmd(hal_ctx->dev, TWAIFD_LL_HW_CMD_RST_RX_CNT);
memset(hal_ctx, 0, sizeof(twai_hal_context_t));
hal_ctx->dev = NULL;
}
bool twai_hal_check_brp_validation(twai_hal_context_t *hal_ctx, uint32_t brp)
{
return twaifd_ll_check_brp_validation(brp);
}
void twai_hal_configure_timing(twai_hal_context_t *hal_ctx, const twai_timing_config_t *t_config)
{
twaifd_ll_set_nominal_bitrate(hal_ctx->dev, t_config);
if (t_config->ssp_offset) {
// the underlying hardware calculates the ssp in system clock cycles, not in quanta time
twaifd_ll_config_secondary_sample_point(hal_ctx->dev, TWAIFD_LL_SSP_SRC_MEAS_OFFSET, t_config->ssp_offset * t_config->brp);
}
}
void twai_hal_configure_timing_fd(twai_hal_context_t *hal_ctx, const twai_timing_config_t *t_config_fd)
{
twaifd_ll_set_fd_bitrate(hal_ctx->dev, t_config_fd);
if (t_config_fd->ssp_offset) {
// the underlying hardware calculates the ssp in system clock cycles, not in quanta time
twaifd_ll_config_secondary_sample_point(hal_ctx->dev, TWAIFD_LL_SSP_SRC_MEAS_OFFSET, t_config_fd->ssp_offset * t_config_fd->brp);
}
}
void twai_hal_configure_filter(twai_hal_context_t *hal_ctx, uint8_t filter_id, const twai_mask_filter_config_t *f_config)
{
uint32_t id = f_config->num_of_ids ? f_config->id_list[0] : f_config->id;
bool full_open = (f_config->mask == 0) && (id == 0);
bool full_close = (f_config->mask == UINT32_MAX) && (id == UINT32_MAX);
bool cc_ext = full_open || (!full_close && f_config->is_ext && !f_config->no_classic);
bool fd_ext = full_open || (!full_close && f_config->is_ext && !f_config->no_fd);
bool cc_std = full_open || (!full_close && !f_config->is_ext && !f_config->no_classic);
bool fd_std = full_open || (!full_close && !f_config->is_ext && !f_config->no_fd);
twaifd_ll_filter_enable_basic_ext(hal_ctx->dev, filter_id, false, cc_ext);
twaifd_ll_filter_enable_fd_ext(hal_ctx->dev, filter_id, false, fd_ext);
twaifd_ll_filter_enable_basic_std(hal_ctx->dev, filter_id, false, cc_std);
twaifd_ll_filter_enable_fd_std(hal_ctx->dev, filter_id, false, fd_std);
twaifd_ll_filter_set_id_mask(hal_ctx->dev, filter_id, f_config->is_ext, id, f_config->mask);
}
void twai_hal_configure_range_filter(twai_hal_context_t *hal_ctx, uint8_t filter_id, const twai_range_filter_config_t *f_config)
{
bool cc_ext = f_config->is_ext && !f_config->no_classic;
bool fd_ext = f_config->is_ext && !f_config->no_fd;
bool cc_std = !f_config->is_ext && !f_config->no_classic;
bool fd_std = !f_config->is_ext && !f_config->no_fd;
twaifd_ll_filter_enable_basic_ext(hal_ctx->dev, filter_id, true, cc_ext);
twaifd_ll_filter_enable_fd_ext(hal_ctx->dev, filter_id, true, fd_ext);
twaifd_ll_filter_enable_basic_std(hal_ctx->dev, filter_id, true, cc_std);
twaifd_ll_filter_enable_fd_std(hal_ctx->dev, filter_id, true, fd_std);
twaifd_ll_filter_set_range(hal_ctx->dev, 0, f_config->is_ext, f_config->range_high, f_config->range_low);
}
void twai_hal_start(twai_hal_context_t *hal_ctx)
{
twaifd_ll_enable_hw(hal_ctx->dev, true);
twaifd_ll_waiting_state_change(hal_ctx->dev);
}
void twai_hal_stop(twai_hal_context_t *hal_ctx)
{
twaifd_ll_enable_hw(hal_ctx->dev, false);
}
twai_error_state_t twai_hal_get_err_state(twai_hal_context_t *hal_ctx)
{
return twaifd_ll_get_fault_state(hal_ctx->dev);
}
void twai_hal_start_bus_recovery(twai_hal_context_t *hal_ctx)
{
twaifd_ll_set_operate_cmd(hal_ctx->dev, TWAIFD_LL_HW_CMD_RST_ERR_CNT);
}
// /* ------------------------------------ IRAM Content ------------------------------------ */
void twai_hal_format_frame(const twai_hal_trans_desc_t *trans_desc, twai_hal_frame_t *frame)
{
const twai_frame_header_t *header = trans_desc->frame.header;
int final_dlc = (header->dlc) ? header->dlc : twaifd_len2dlc(trans_desc->frame.buffer_len);
int data_len = (header->dlc) ? twaifd_dlc2len(header->dlc) : trans_desc->frame.buffer_len;
twaifd_ll_format_frame_header(header, final_dlc, frame);
twaifd_ll_format_frame_data(trans_desc->frame.buffer, data_len, frame);
}
void twai_hal_parse_frame(const twai_hal_frame_t *frame, twai_frame_header_t *header, uint8_t *buffer, uint8_t buffer_len)
{
twaifd_ll_parse_frame_header(frame, header);
int frame_data_len = twaifd_dlc2len(header->dlc);
uint8_t final_len = (frame_data_len < buffer_len) ? frame_data_len : buffer_len;
twaifd_ll_parse_frame_data(frame, buffer, final_len);
}
void twai_hal_set_tx_buffer_and_transmit(twai_hal_context_t *hal_ctx, twai_hal_frame_t *tx_frame, uint8_t buffer_idx)
{
twaifd_ll_mount_tx_buffer(hal_ctx->dev, tx_frame, buffer_idx);
twaifd_ll_set_tx_cmd(hal_ctx->dev, buffer_idx, TWAIFD_LL_TX_CMD_READY);
}
uint32_t twai_hal_get_rx_msg_count(twai_hal_context_t *hal_ctx)
{
return twaifd_ll_get_rx_frame_count(hal_ctx->dev);
}
bool twai_hal_read_rx_fifo(twai_hal_context_t *hal_ctx, twai_hal_frame_t *rx_frame)
{
twaifd_ll_get_rx_frame(hal_ctx->dev, rx_frame);
return true;
}
uint32_t twai_hal_get_events(twai_hal_context_t *hal_ctx)
{
uint32_t hal_events = 0;
uint32_t int_stat = twaifd_ll_get_intr_status(hal_ctx->dev);
uint32_t tec = twaifd_ll_get_tec(hal_ctx->dev);
uint32_t rec = twaifd_ll_get_rec(hal_ctx->dev);
twaifd_ll_clr_intr_status(hal_ctx->dev, int_stat);
if (int_stat & (TWAIFD_LL_INTR_TX_DONE)) {
hal_events |= TWAI_HAL_EVENT_TX_BUFF_FREE;
if (int_stat & TWAIFD_LL_INTR_TX_SUCCESS) {
hal_events |= TWAI_HAL_EVENT_TX_SUCCESS;
}
}
if (int_stat & TWAIFD_LL_INTR_RX_NOT_EMPTY) {
hal_events |= TWAI_HAL_EVENT_RX_BUFF_FRAME;
}
if (int_stat & (TWAIFD_LL_INTR_BUS_ERR | TWAIFD_LL_INTR_DATA_OVERRUN | TWAIFD_LL_INTR_RX_FULL)) {
hal_ctx->errors = twaifd_ll_get_err_reason(hal_ctx->dev);
hal_events |= TWAI_HAL_EVENT_BUS_ERR;
}
if (int_stat & TWAIFD_LL_INTR_ARBI_LOST) {
hal_events |= TWAI_HAL_EVENT_ARB_LOST;
}
if (int_stat & (TWAIFD_LL_INTR_FSM_CHANGE | TWAIFD_LL_INTR_ERR_WARN)) {
twai_error_state_t curr_sta = twaifd_ll_get_fault_state(hal_ctx->dev);
uint32_t limit = twaifd_ll_get_err_warn_limit(hal_ctx->dev);
if (curr_sta == TWAI_ERROR_BUS_OFF) {
hal_events |= TWAI_HAL_EVENT_BUS_OFF;
} else if (curr_sta == TWAI_ERROR_PASSIVE) {
hal_events |= TWAI_HAL_EVENT_ERROR_PASSIVE;
} else {
if ((tec >= limit) || (rec >= limit)) {
hal_events |= TWAI_HAL_EVENT_ERROR_WARNING;
} else {
hal_events |= TWAI_HAL_EVENT_ERROR_ACTIVE;
}
}
}
return hal_events;
}

View File

@@ -1,203 +0,0 @@
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <stddef.h>
#include <string.h>
#include "sdkconfig.h"
#include "esp_compiler.h"
#include "hal/twai_hal.h"
#ifdef CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT
//Errata condition occurs at 64 messages. Threshold set to 62 to prevent the chance of failing to detect errata condition.
#define TWAI_RX_FIFO_CORRUPT_THRESH 62
#endif
/* ----------------------------- Event Handling ----------------------------- */
#if !SOC_TWAI_SUPPORT_FD
/**
* Helper functions that can decode what events have been triggered based on
* the values of the interrupt, status, TEC and REC registers. The HAL context's
* state flags are also updated based on the events that have triggered.
*/
static inline uint32_t twai_hal_decode_interrupt(twai_hal_context_t *hal_ctx)
{
uint32_t events = 0;
uint32_t interrupts = twai_ll_get_and_clear_intrs(hal_ctx->dev);
uint32_t status = twai_ll_get_status(hal_ctx->dev);
uint32_t tec = twai_ll_get_tec(hal_ctx->dev);
uint32_t rec = twai_ll_get_rec(hal_ctx->dev);
uint32_t state_flags = hal_ctx->state_flags;
//Error Warning Interrupt set whenever Error or Bus Status bit changes
if (interrupts & TWAI_LL_INTR_EI) {
if (status & TWAI_LL_STATUS_BS) { //Currently in BUS OFF state
if (status & TWAI_LL_STATUS_ES) { //EWL is exceeded, thus must have entered BUS OFF
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_BUS_OFF);
TWAI_HAL_SET_BITS(state_flags, TWAI_HAL_STATE_FLAG_BUS_OFF);
//Any TX would have been halted by entering bus off. Reset its flag
TWAI_HAL_CLEAR_BITS(state_flags, TWAI_HAL_STATE_FLAG_RUNNING | TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED);
} else {
//Below EWL. Therefore TEC is counting down in bus recovery
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_BUS_RECOV_PROGRESS);
}
} else { //Not in BUS OFF
if (status & TWAI_LL_STATUS_ES) { //Just Exceeded EWL
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_ABOVE_EWL);
TWAI_HAL_SET_BITS(state_flags, TWAI_HAL_STATE_FLAG_ERR_WARN);
} else if (hal_ctx->state_flags & TWAI_HAL_STATE_FLAG_RECOVERING) {
//Previously undergoing bus recovery. Thus means bus recovery complete
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_BUS_RECOV_CPLT);
TWAI_HAL_CLEAR_BITS(state_flags, TWAI_HAL_STATE_FLAG_RECOVERING | TWAI_HAL_STATE_FLAG_BUS_OFF);
} else { //Just went below EWL
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_BELOW_EWL);
TWAI_HAL_CLEAR_BITS(state_flags, TWAI_HAL_STATE_FLAG_ERR_WARN);
}
}
}
//Receive Interrupt set whenever RX FIFO is not empty
if (interrupts & TWAI_LL_INTR_RI) {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_RX_BUFF_FRAME);
}
//Transmit interrupt set whenever TX buffer becomes free
#ifdef CONFIG_TWAI_ERRATA_FIX_TX_INTR_LOST
if ((interrupts & TWAI_LL_INTR_TI || hal_ctx->state_flags & TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED) && status & TWAI_LL_STATUS_TBS) {
#else
if (interrupts & TWAI_LL_INTR_TI) {
#endif
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_TX_BUFF_FREE);
TWAI_HAL_CLEAR_BITS(state_flags, TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED);
}
//Error Passive Interrupt on transition from error active to passive or vice versa
if (interrupts & TWAI_LL_INTR_EPI) {
if (tec >= TWAI_ERR_PASS_THRESH || rec >= TWAI_ERR_PASS_THRESH) {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_ERROR_PASSIVE);
TWAI_HAL_SET_BITS(state_flags, TWAI_HAL_STATE_FLAG_ERR_PASSIVE);
} else {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_ERROR_ACTIVE);
TWAI_HAL_CLEAR_BITS(state_flags, TWAI_HAL_STATE_FLAG_ERR_PASSIVE);
}
}
//Bus error interrupt triggered on a bus error (e.g. bit, ACK, stuff etc)
if (interrupts & TWAI_LL_INTR_BEI) {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_BUS_ERR);
}
//Arbitration Lost Interrupt triggered on losing arbitration
if (interrupts & TWAI_LL_INTR_ALI) {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_ARB_LOST);
}
hal_ctx->state_flags = state_flags;
return events;
}
uint32_t twai_hal_get_events(twai_hal_context_t *hal_ctx)
{
uint32_t events = twai_hal_decode_interrupt(hal_ctx);
//Handle low latency events
if (events & TWAI_HAL_EVENT_BUS_OFF) {
twai_ll_set_mode(hal_ctx->dev, TWAI_MODE_LISTEN_ONLY); //Freeze TEC/REC by entering LOM
#ifdef CONFIG_TWAI_ERRATA_FIX_BUS_OFF_REC
//Errata workaround: Force REC to 0 by re-triggering bus-off (by setting TEC to 0 then 255)
twai_ll_set_tec(hal_ctx->dev, 0);
twai_ll_set_tec(hal_ctx->dev, 255);
(void) twai_ll_get_and_clear_intrs(hal_ctx->dev); //Clear the re-triggered bus-off interrupt
#endif
}
if (events & TWAI_HAL_EVENT_BUS_RECOV_CPLT) {
twai_ll_enter_reset_mode(hal_ctx->dev); //Enter reset mode to stop the controller
}
if (events & TWAI_HAL_EVENT_BUS_ERR) {
#ifdef CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID
twai_ll_err_type_t type;
twai_ll_err_dir_t dir;
twai_ll_err_seg_t seg;
twai_ll_parse_err_code_cap(hal_ctx->dev, &type, &dir, &seg); //Decode error interrupt
//Check for errata condition (RX message has bus error at particular segments)
if (dir == TWAI_LL_ERR_DIR_RX &&
((seg == TWAI_LL_ERR_SEG_DATA || seg == TWAI_LL_ERR_SEG_CRC_SEQ) ||
(seg == TWAI_LL_ERR_SEG_ACK_DELIM && type == TWAI_LL_ERR_OTHER))) {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_NEED_PERIPH_RESET);
}
#endif
twai_ll_clear_err_code_cap(hal_ctx->dev);
}
if (events & TWAI_HAL_EVENT_ARB_LOST) {
twai_ll_clear_arb_lost_cap(hal_ctx->dev);
}
#ifdef CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT
//Check for errata condition (rx_msg_count >= corruption_threshold)
if (events & TWAI_HAL_EVENT_RX_BUFF_FRAME && twai_ll_get_rx_msg_count(hal_ctx->dev) >= TWAI_RX_FIFO_CORRUPT_THRESH) {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_NEED_PERIPH_RESET);
}
#endif
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
if (events & TWAI_HAL_EVENT_NEED_PERIPH_RESET) {
//A peripheral reset will invalidate an RX event;
TWAI_HAL_CLEAR_BITS(events, (TWAI_HAL_EVENT_RX_BUFF_FRAME));
}
#endif
return events;
}
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
void twai_hal_prepare_for_reset(twai_hal_context_t *hal_ctx)
{
uint32_t status = twai_ll_get_status(hal_ctx->dev);
if (!(status & TWAI_LL_STATUS_TBS)) { //Transmit buffer is NOT free, indicating an Ongoing TX will be cancelled by the HW reset
TWAI_HAL_SET_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_TX_NEED_RETRY);
//Note: Even if the TX completes right after this, we still consider it will be retried.
//Worst case the same message will get sent twice.
}
//Some register must saved before entering reset mode
hal_ctx->rx_msg_cnt_save = (uint8_t) twai_ll_get_rx_msg_count(hal_ctx->dev);
twai_ll_enter_reset_mode(hal_ctx->dev); //Enter reset mode to stop the controller
twai_ll_save_reg(hal_ctx->dev, &hal_ctx->reg_save); //Save remaining registers after entering reset mode
}
void twai_hal_recover_from_reset(twai_hal_context_t *hal_ctx)
{
twai_ll_enter_reset_mode(hal_ctx->dev);
twai_ll_enable_extended_reg_layout(hal_ctx->dev);
twai_ll_restore_reg(hal_ctx->dev, &hal_ctx->reg_save);
twai_ll_exit_reset_mode(hal_ctx->dev);
(void) twai_ll_get_and_clear_intrs(hal_ctx->dev);
if (hal_ctx->state_flags & TWAI_HAL_STATE_FLAG_TX_NEED_RETRY) {
//HW reset has cancelled a TX. Re-transmit here
twai_hal_set_tx_buffer_and_transmit(hal_ctx, &hal_ctx->tx_frame_save);
TWAI_HAL_CLEAR_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_TX_NEED_RETRY);
}
}
#endif //defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
void twai_hal_set_tx_buffer_and_transmit(twai_hal_context_t *hal_ctx, twai_hal_frame_t *tx_frame)
{
//Copy frame into tx buffer
twai_ll_set_tx_buffer(hal_ctx->dev, tx_frame);
//Hit the send command
if (tx_frame->self_reception) {
if (tx_frame->single_shot) {
twai_ll_set_cmd_self_rx_single_shot(hal_ctx->dev);
} else {
twai_ll_set_cmd_self_rx_request(hal_ctx->dev);
}
} else if (tx_frame->single_shot){
twai_ll_set_cmd_tx_single_shot(hal_ctx->dev);
} else {
twai_ll_set_cmd_tx(hal_ctx->dev);
}
TWAI_HAL_SET_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED);
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
if (&hal_ctx->tx_frame_save == tx_frame) {
return;
}
//Save transmitted frame in case we need to retry
ESP_COMPILER_DIAGNOSTIC_PUSH_IGNORE("-Wanalyzer-overlapping-buffers") // TODO IDF-11085
memcpy(&hal_ctx->tx_frame_save, tx_frame, sizeof(twai_hal_frame_t));
ESP_COMPILER_DIAGNOSTIC_POP("-Wanalyzer-overlapping-buffers")
#endif //defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
}
#endif // !SOC_TWAI_SUPPORT_FD

View File

@@ -0,0 +1,470 @@
/*
* SPDX-FileCopyrightText: 2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <stddef.h>
#include "sdkconfig.h"
#include "esp_compiler.h"
#include "hal/twai_hal.h"
#include "hal/twai_ll.h"
#include "soc/soc_caps.h"
//Default values written to various registers on initialization
#define TWAI_HAL_INIT_TEC 0
#define TWAI_HAL_INIT_REC 0
#define TWAI_HAL_INIT_EWL 96
#if CONFIG_IDF_TARGET_ESP32 // only esp32 have this errata, TODO: IDF-13002 check errata runtime
typedef struct twai_hal_errata_ctx_t {
twai_hal_frame_t tx_frame_save;
twai_ll_reg_save_t reg_save;
uint8_t rx_msg_cnt_save;
} twai_hal_errata_ctx_t;
#endif
size_t twai_hal_get_mem_requirment(void) {
#if CONFIG_IDF_TARGET_ESP32 // only esp32 have this errata, TODO: IDF-13002 check errata runtime
return sizeof(twai_hal_context_t) + sizeof(twai_hal_errata_ctx_t);
#else
return sizeof(twai_hal_context_t);
#endif
}
/* ---------------------------- Init and Config ----------------------------- */
bool twai_hal_init(twai_hal_context_t *hal_ctx, const twai_hal_config_t *config)
{
//Initialize HAL context
hal_ctx->dev = TWAI_LL_GET_HW(config->controller_id);
hal_ctx->state_flags = 0;
hal_ctx->clock_source_hz = config->clock_source_hz;
hal_ctx->retry_cnt = config->retry_cnt;
hal_ctx->enable_self_test = config->enable_self_test;
hal_ctx->enable_loopback = config->enable_loopback;
hal_ctx->enable_listen_only = config->enable_listen_only;
//Initialize TWAI controller, and set default values to registers
twai_ll_enter_reset_mode(hal_ctx->dev);
if (!twai_ll_is_in_reset_mode(hal_ctx->dev)) { //Must enter reset mode to write to config registers
return false;
}
#if CONFIG_IDF_TARGET_ESP32 // only esp32 have this errata, TODO: IDF-13002 check errata runtime
hal_ctx->errata_ctx = (twai_hal_errata_ctx_t *)(hal_ctx + 1); //errata context is place at end of hal_ctx
#endif
#if SOC_TWAI_SUPPORT_MULTI_ADDRESS_LAYOUT
twai_ll_enable_extended_reg_layout(hal_ctx->dev); //Changes the address layout of the registers
#endif
twai_ll_set_mode(hal_ctx->dev, true, false, false); //Freeze REC by changing to LOM mode
twai_ll_set_acc_filter(hal_ctx->dev, 0, 0xFFFFFFFF, true); //receive all by default if no additional filter config later
//Both TEC and REC should start at 0
twai_ll_set_tec(hal_ctx->dev, TWAI_HAL_INIT_TEC);
twai_ll_set_rec(hal_ctx->dev, TWAI_HAL_INIT_REC);
twai_ll_set_err_warn_lim(hal_ctx->dev, TWAI_HAL_INIT_EWL); //Set default value of for EWL
twai_ll_set_enabled_intrs(hal_ctx->dev, config->intr_mask);
(void) twai_ll_get_and_clear_intrs(hal_ctx->dev); //Clear any latched interrupts
return true;
}
void twai_hal_deinit(twai_hal_context_t *hal_ctx)
{
//Clear any pending registers
(void) twai_ll_get_and_clear_intrs(hal_ctx->dev);
twai_ll_set_enabled_intrs(hal_ctx->dev, 0);
twai_ll_clear_arb_lost_cap(hal_ctx->dev);
hal_ctx->dev = NULL;
}
void twai_hal_configure(twai_hal_context_t *hal_ctx, const twai_timing_config_t *t_config, const twai_filter_config_t *f_config, uint32_t clkout_divider)
{
uint32_t brp = t_config->brp;
// both quanta_resolution_hz and brp can affect the baud rate
// but a non-zero quanta_resolution_hz takes higher priority
if (t_config->quanta_resolution_hz) {
brp = hal_ctx->clock_source_hz / t_config->quanta_resolution_hz;
}
//Configure bus timing, acceptance filter, CLKOUT, and interrupts
twai_ll_set_bus_timing(hal_ctx->dev, brp, t_config->sjw, t_config->tseg_1, t_config->tseg_2, t_config->triple_sampling);
twai_ll_set_acc_filter(hal_ctx->dev, f_config->acceptance_code, f_config->acceptance_mask, f_config->single_filter);
twai_ll_set_clkout(hal_ctx->dev, clkout_divider);
}
bool twai_hal_check_brp_validation(twai_hal_context_t *hal_ctx, uint32_t brp)
{
return twai_ll_check_brp_validation(brp);
}
void twai_hal_configure_timing(twai_hal_context_t *hal_ctx, const twai_timing_advanced_config_t *t_config)
{
uint32_t brp = t_config->brp;
// both quanta_resolution_hz and brp can affect the baud rate
// but a non-zero quanta_resolution_hz takes higher priority
if (t_config->quanta_resolution_hz) {
brp = hal_ctx->clock_source_hz / t_config->quanta_resolution_hz;
}
//Configure bus timing
twai_ll_set_bus_timing(hal_ctx->dev, brp, t_config->sjw, t_config->tseg_1 + t_config->prop_seg, t_config->tseg_2, !!t_config->ssp_offset);
twai_ll_set_clkout(hal_ctx->dev, brp);
}
void twai_hal_configure_filter(twai_hal_context_t *hal_ctx, uint8_t filter_id, const twai_mask_filter_config_t *f_config)
{
uint32_t id = f_config->num_of_ids ? f_config->id_list[0] : f_config->id;
bool full_open = (f_config->mask == 0) && (id == 0);
bool full_close = (f_config->mask == UINT32_MAX) && (id == UINT32_MAX);
// shift id/mask bits adopt to hardware bits define (3=32-29, 21=32-11), shift for dual filter is done in `DUAL_16BIT_FILTER()`
uint8_t bit_shift = (f_config->dual_filter || full_close) ? 0 : f_config->is_ext ? 3 : 21;
uint32_t code = id << bit_shift;
uint32_t mask = f_config->mask << bit_shift;
// save the id type strategy, see comment of `sja1000_filter_id_type`
hal_ctx->sja1000_filter_id_type = (full_open) ? 0 : f_config->is_ext ? 2 : 1;
twai_ll_set_acc_filter(hal_ctx->dev, code, ~mask, !f_config->dual_filter);
}
twai_error_state_t twai_hal_get_err_state(twai_hal_context_t *hal_ctx)
{
uint32_t hw_state = twai_ll_get_status(hal_ctx->dev);
return (hw_state & TWAI_LL_STATUS_BS) ? TWAI_ERROR_BUS_OFF : (hw_state & TWAI_LL_STATUS_ES) ? TWAI_ERROR_PASSIVE : TWAI_ERROR_ACTIVE;
}
uint32_t twai_hal_get_tec(twai_hal_context_t *hal_ctx)
{
return twai_ll_get_tec((hal_ctx)->dev);
}
uint32_t twai_hal_get_rec(twai_hal_context_t *hal_ctx)
{
return twai_ll_get_rec((hal_ctx)->dev);
}
/* -------------------------------- Actions --------------------------------- */
void twai_hal_start(twai_hal_context_t *hal_ctx)
{
twai_ll_set_mode(hal_ctx->dev, hal_ctx->enable_listen_only, hal_ctx->enable_self_test, hal_ctx->enable_loopback);
//Clear the TEC and REC
twai_ll_set_tec(hal_ctx->dev, 0);
#ifdef CONFIG_TWAI_ERRATA_FIX_LISTEN_ONLY_DOM
/*
Errata workaround: Prevent transmission of dominant error frame while in listen only mode by setting REC to 128
before exiting reset mode. This forces the controller to be error passive (thus only transmits recessive bits).
The TEC/REC remain frozen in listen only mode thus ensuring we remain error passive.
*/
if (hal_ctx->enable_listen_only) {
twai_ll_set_rec(hal_ctx->dev, 128);
} else
#endif
{
twai_ll_set_rec(hal_ctx->dev, 0);
}
(void) twai_ll_get_and_clear_intrs(hal_ctx->dev); //Clear any latched interrupts
TWAI_HAL_SET_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_RUNNING);
twai_ll_exit_reset_mode(hal_ctx->dev);
}
void twai_hal_stop(twai_hal_context_t *hal_ctx)
{
twai_ll_enter_reset_mode(hal_ctx->dev);
(void) twai_ll_get_and_clear_intrs(hal_ctx->dev);
twai_ll_set_mode(hal_ctx->dev, true, false, false); //Freeze REC by changing to LOM mode
//Any TX is immediately halted on entering reset mode
TWAI_HAL_CLEAR_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED | TWAI_HAL_STATE_FLAG_RUNNING);
}
void twai_hal_start_bus_recovery(twai_hal_context_t *hal_ctx)
{
TWAI_HAL_CLEAR_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED);
TWAI_HAL_SET_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_RECOVERING);
twai_ll_exit_reset_mode(hal_ctx->dev);
}
/* ------------------------------------ IRAM Content ------------------------------------ */
#ifdef CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT
//Errata condition occurs at 64 messages. Threshold set to 62 to prevent the chance of failing to detect errata condition.
#define TWAI_RX_FIFO_CORRUPT_THRESH 62
#endif
/* ----------------------------- Event Handling ----------------------------- */
/**
* Helper functions that can decode what events have been triggered based on
* the values of the interrupt, status, TEC and REC registers. The HAL context's
* state flags are also updated based on the events that have triggered.
*/
static inline uint32_t twai_hal_decode_interrupt(twai_hal_context_t *hal_ctx)
{
uint32_t events = 0;
uint32_t interrupts = twai_ll_get_and_clear_intrs(hal_ctx->dev);
uint32_t status = twai_ll_get_status(hal_ctx->dev);
uint32_t tec = twai_ll_get_tec(hal_ctx->dev);
uint32_t rec = twai_ll_get_rec(hal_ctx->dev);
uint32_t state_flags = hal_ctx->state_flags;
//Error Warning Interrupt set whenever Error or Bus Status bit changes
if (interrupts & TWAI_LL_INTR_EI) {
if (status & TWAI_LL_STATUS_BS) { //Currently in BUS OFF state
if (status & TWAI_LL_STATUS_ES) { //EWL is exceeded, thus must have entered BUS OFF
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_BUS_OFF);
TWAI_HAL_SET_BITS(state_flags, TWAI_HAL_STATE_FLAG_BUS_OFF);
//Any TX would have been halted by entering bus off. Reset its flag
TWAI_HAL_CLEAR_BITS(state_flags, TWAI_HAL_STATE_FLAG_RUNNING | TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED);
} else {
//Below EWL. Therefore TEC is counting down in bus recovery
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_BUS_RECOV_PROGRESS);
}
} else { //Not in BUS OFF
if (status & TWAI_LL_STATUS_ES) { //Just Exceeded EWL
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_ERROR_WARNING);
TWAI_HAL_SET_BITS(state_flags, TWAI_HAL_STATE_FLAG_ERR_WARN);
} else if (hal_ctx->state_flags & TWAI_HAL_STATE_FLAG_RECOVERING) {
//Previously undergoing bus recovery. Thus means bus recovery complete
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_BUS_RECOV_CPLT);
TWAI_HAL_CLEAR_BITS(state_flags, TWAI_HAL_STATE_FLAG_RECOVERING | TWAI_HAL_STATE_FLAG_BUS_OFF);
} else { //Just went below EWL
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_BELOW_EWL);
TWAI_HAL_CLEAR_BITS(state_flags, TWAI_HAL_STATE_FLAG_ERR_WARN);
}
}
}
//Receive Interrupt set whenever RX FIFO is not empty
if (interrupts & TWAI_LL_INTR_RI) {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_RX_BUFF_FRAME);
}
//Transmit interrupt set whenever TX buffer becomes free
#ifdef CONFIG_TWAI_ERRATA_FIX_TX_INTR_LOST
if ((interrupts & TWAI_LL_INTR_TI || hal_ctx->state_flags & TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED) && status & TWAI_LL_STATUS_TBS) {
#else
if (interrupts & TWAI_LL_INTR_TI) {
#endif
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_TX_BUFF_FREE);
TWAI_HAL_CLEAR_BITS(state_flags, TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED);
if (status & TWAI_LL_STATUS_TCS) {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_TX_SUCCESS);
}
}
//Error Passive Interrupt on transition from error active to passive or vice versa
if (interrupts & TWAI_LL_INTR_EPI) {
if (tec >= TWAI_ERR_PASS_THRESH || rec >= TWAI_ERR_PASS_THRESH) {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_ERROR_PASSIVE);
TWAI_HAL_SET_BITS(state_flags, TWAI_HAL_STATE_FLAG_ERR_PASSIVE);
} else {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_ERROR_ACTIVE);
TWAI_HAL_CLEAR_BITS(state_flags, TWAI_HAL_STATE_FLAG_ERR_PASSIVE);
}
}
//Bus error interrupt triggered on a bus error (e.g. bit, ACK, stuff etc)
if (interrupts & TWAI_LL_INTR_BEI) {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_BUS_ERR);
}
//Arbitration Lost Interrupt triggered on losing arbitration
if (interrupts & TWAI_LL_INTR_ALI) {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_ARB_LOST);
}
hal_ctx->state_flags = state_flags;
return events;
}
uint32_t twai_hal_get_events(twai_hal_context_t *hal_ctx)
{
uint32_t events = twai_hal_decode_interrupt(hal_ctx);
//Handle low latency events
if (events & TWAI_HAL_EVENT_BUS_OFF) {
twai_ll_set_mode(hal_ctx->dev, true, false, false); //Freeze TEC/REC by entering LOM
#ifdef CONFIG_TWAI_ERRATA_FIX_BUS_OFF_REC
//Errata workaround: Force REC to 0 by re-triggering bus-off (by setting TEC to 0 then 255)
twai_ll_set_tec(hal_ctx->dev, 0);
twai_ll_set_tec(hal_ctx->dev, 255);
(void) twai_ll_get_and_clear_intrs(hal_ctx->dev); //Clear the re-triggered bus-off interrupt
#endif
}
if (events & TWAI_HAL_EVENT_BUS_RECOV_CPLT) {
twai_ll_enter_reset_mode(hal_ctx->dev); //Enter reset mode to stop the controller
}
if (events & TWAI_HAL_EVENT_BUS_ERR) {
twai_ll_err_type_t type;
twai_ll_err_dir_t dir;
twai_ll_err_seg_t seg;
twai_ll_parse_err_code_cap(hal_ctx->dev, &type, &dir, &seg); //Decode error interrupt
twai_error_flags_t errors = {
.bit_err = (type == TWAI_LL_ERR_BIT),
.form_err = (type == TWAI_LL_ERR_FORM),
.stuff_err = (type == TWAI_LL_ERR_STUFF),
.ack_err = (type == TWAI_LL_ERR_OTHER) && (seg == TWAI_LL_ERR_SEG_ACK_SLOT),
};
hal_ctx->errors = errors;
#ifdef CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID
//Check for errata condition (RX message has bus error at particular segments)
if (dir == TWAI_LL_ERR_DIR_RX &&
((seg == TWAI_LL_ERR_SEG_DATA || seg == TWAI_LL_ERR_SEG_CRC_SEQ) ||
(seg == TWAI_LL_ERR_SEG_ACK_DELIM && type == TWAI_LL_ERR_OTHER))) {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_NEED_PERIPH_RESET);
}
#endif
}
if (events & TWAI_HAL_EVENT_ARB_LOST) {
twai_ll_clear_arb_lost_cap(hal_ctx->dev);
}
#ifdef CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT
//Check for errata condition (rx_msg_count >= corruption_threshold)
if (events & TWAI_HAL_EVENT_RX_BUFF_FRAME && twai_ll_get_rx_msg_count(hal_ctx->dev) >= TWAI_RX_FIFO_CORRUPT_THRESH) {
TWAI_HAL_SET_BITS(events, TWAI_HAL_EVENT_NEED_PERIPH_RESET);
}
#endif
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
if (events & TWAI_HAL_EVENT_NEED_PERIPH_RESET) {
//A peripheral reset will invalidate an RX event;
TWAI_HAL_CLEAR_BITS(events, (TWAI_HAL_EVENT_RX_BUFF_FRAME));
}
#endif
return events;
}
#if CONFIG_IDF_TARGET_ESP32 // only esp32 have this errata, TODO: IDF-13002 check errata runtime
bool twai_hal_is_hw_busy(twai_hal_context_t *hal_ctx)
{
return (TWAI_LL_STATUS_TS | TWAI_LL_STATUS_RS) & twai_ll_get_status(hal_ctx->dev);
}
void twai_hal_backup_config(twai_hal_context_t *hal_ctx)
{
//Some register must saved before entering reset mode
hal_ctx->errata_ctx->rx_msg_cnt_save = (uint8_t) twai_ll_get_rx_msg_count(hal_ctx->dev);
twai_ll_enter_reset_mode(hal_ctx->dev); //Enter reset mode to stop the controller
twai_ll_save_reg(hal_ctx->dev, &hal_ctx->errata_ctx->reg_save); //Save remaining registers after entering reset mode
}
uint32_t twai_hal_get_reset_lost_rx_cnt(twai_hal_context_t *hal_ctx)
{
return hal_ctx->errata_ctx->rx_msg_cnt_save;
}
void twai_hal_restore_config(twai_hal_context_t *hal_ctx)
{
twai_ll_enter_reset_mode(hal_ctx->dev);
twai_ll_enable_extended_reg_layout(hal_ctx->dev);
twai_ll_restore_reg(hal_ctx->dev, &hal_ctx->errata_ctx->reg_save);
}
void twai_hal_prepare_for_reset(twai_hal_context_t *hal_ctx)
{
uint32_t status = twai_ll_get_status(hal_ctx->dev);
if (!(status & TWAI_LL_STATUS_TBS)) { //Transmit buffer is NOT free, indicating an Ongoing TX will be cancelled by the HW reset
TWAI_HAL_SET_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_TX_NEED_RETRY);
//Note: Even if the TX completes right after this, we still consider it will be retried.
//Worst case the same message will get sent twice.
}
twai_hal_backup_config(hal_ctx);
}
void twai_hal_recover_from_reset(twai_hal_context_t *hal_ctx)
{
twai_hal_restore_config(hal_ctx);
twai_ll_exit_reset_mode(hal_ctx->dev);
(void) twai_ll_get_and_clear_intrs(hal_ctx->dev);
if (hal_ctx->state_flags & TWAI_HAL_STATE_FLAG_TX_NEED_RETRY) {
//HW reset has cancelled a TX. Re-transmit here
twai_hal_set_tx_buffer_and_transmit(hal_ctx, &hal_ctx->errata_ctx->tx_frame_save, 0);
TWAI_HAL_CLEAR_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_TX_NEED_RETRY);
}
}
#endif // CONFIG_IDF_TARGET_ESP32
void twai_hal_format_frame(const twai_hal_trans_desc_t *trans_desc, twai_hal_frame_t *frame)
{
const twai_frame_header_t *header = trans_desc->frame.header;
twai_message_t msg_flags = {
.extd = header->ide,
.rtr = header->rtr,
.ss = trans_desc->config.retry_cnt != -1,
.self = trans_desc->config.loopback,
};
uint16_t final_dlc = (header->dlc) ? header->dlc : twaifd_len2dlc(trans_desc->frame.buffer_len);
twai_ll_format_frame_buffer(header->id, final_dlc, trans_desc->frame.buffer, msg_flags.flags, frame);
}
void twai_hal_parse_frame(const twai_hal_frame_t *frame, twai_frame_header_t *header, uint8_t *buffer, uint8_t buffer_len)
{
twai_message_t msg_flags = {0};
twai_ll_parse_frame_buffer((twai_hal_frame_t *)frame, &header->id, (uint8_t *)&header->dlc, buffer, buffer_len, &msg_flags.flags);
header->ide = msg_flags.extd;
header->rtr = msg_flags.rtr;
}
void twai_hal_set_tx_buffer_and_transmit(twai_hal_context_t *hal_ctx, twai_hal_frame_t *tx_frame, uint8_t buffer_idx)
{
//Copy frame into tx buffer
twai_ll_set_tx_buffer(hal_ctx->dev, tx_frame);
//Hit the send command
if (tx_frame->self_reception) {
if (tx_frame->single_shot) {
twai_ll_set_cmd_self_rx_single_shot(hal_ctx->dev);
} else {
twai_ll_set_cmd_self_rx_request(hal_ctx->dev);
}
} else if (tx_frame->single_shot){
twai_ll_set_cmd_tx_single_shot(hal_ctx->dev);
} else {
twai_ll_set_cmd_tx(hal_ctx->dev);
}
TWAI_HAL_SET_BITS(hal_ctx->state_flags, TWAI_HAL_STATE_FLAG_TX_BUFF_OCCUPIED);
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
if (&hal_ctx->errata_ctx->tx_frame_save == tx_frame) {
return;
}
//Save transmitted frame in case we need to retry
ESP_COMPILER_DIAGNOSTIC_PUSH_IGNORE("-Wanalyzer-overlapping-buffers") // TODO IDF-11085
memcpy(&hal_ctx->errata_ctx->tx_frame_save, tx_frame, sizeof(twai_hal_frame_t));
ESP_COMPILER_DIAGNOSTIC_POP("-Wanalyzer-overlapping-buffers")
#endif //defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
}
uint32_t twai_hal_get_rx_msg_count(twai_hal_context_t *hal_ctx)
{
return twai_ll_get_rx_msg_count((hal_ctx)->dev);
}
bool twai_hal_read_rx_fifo(twai_hal_context_t *hal_ctx, twai_hal_frame_t *rx_frame)
{
#ifdef SOC_TWAI_SUPPORTS_RX_STATUS
if (twai_ll_get_status(hal_ctx->dev) & TWAI_LL_STATUS_MS) {
//Release the buffer for this particular overrun frame
twai_ll_set_cmd_release_rx_buffer(hal_ctx->dev);
return false;
}
#else
if (twai_ll_get_status(hal_ctx->dev) & TWAI_LL_STATUS_DOS) {
//No need to release RX buffer as we'll be releasing all RX frames in continuously later
return false;
}
#endif
twai_ll_get_rx_buffer(hal_ctx->dev, rx_frame);
twai_ll_set_cmd_release_rx_buffer(hal_ctx->dev);
return true;
}
bool twai_hal_soft_filter_check_msg(twai_hal_context_t *hal_ctx, twai_hal_frame_t *rx_frame)
{
if (hal_ctx->sja1000_filter_id_type && (hal_ctx->sja1000_filter_id_type - 1) != twai_ll_frame_is_ext_format(rx_frame)) {
return false; // if filter enabled and frame don't match, drop the frame
}
return true;
}
bool twai_hal_check_state_flags(twai_hal_context_t *hal_ctx, uint32_t check_flags)
{
return hal_ctx->state_flags & check_flags;
}
uint32_t twai_hal_clear_rx_fifo_overrun(twai_hal_context_t *hal_ctx)
{
uint32_t msg_cnt = 0;
//Note: Need to keep polling th rx message counter in case another message arrives whilst clearing
while (twai_ll_get_rx_msg_count(hal_ctx->dev) > 0) {
twai_ll_set_cmd_release_rx_buffer(hal_ctx->dev);
msg_cnt++;
}
//Set a clear data overrun command to clear the data overrun status bit
twai_ll_set_cmd_clear_data_overrun(hal_ctx->dev);
return msg_cnt;
}

View File

@@ -755,6 +755,10 @@ config SOC_TWAI_CONTROLLER_NUM
int
default 1
config SOC_TWAI_MASK_FILTER_NUM
int
default 1
config SOC_TWAI_BRP_MIN
int
default 2

View File

@@ -342,7 +342,8 @@
#define SOC_TOUCH_SAMPLE_CFG_NUM (1U) /*!< The sample configuration number in total, each sampler can be used to sample on one frequency */
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL
#define SOC_TWAI_CONTROLLER_NUM 1U
#define SOC_TWAI_MASK_FILTER_NUM 1U
#define SOC_TWAI_BRP_MIN 2
#if SOC_CAPS_ECO_VER >= 200
# define SOC_TWAI_BRP_MAX 256

View File

@@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@@ -19,9 +19,9 @@ extern "C" {
* the least significant byte of every 32bits.
*/
typedef volatile struct twai_dev_s {
typedef struct twai_dev_t {
//Configuration and Control Registers
union {
volatile union {
struct {
uint32_t rm: 1; /* MOD.0 Reset Mode */
uint32_t lom: 1; /* MOD.1 Listen Only Mode */
@@ -31,7 +31,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} mode_reg; /* Address 0x0000 */
union {
volatile union {
struct {
uint32_t tr: 1; /* CMR.0 Transmission Request */
uint32_t at: 1; /* CMR.1 Abort Transmission */
@@ -42,7 +42,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} command_reg; /* Address 0x0004 */
union {
volatile union {
struct {
uint32_t rbs: 1; /* SR.0 Receive Buffer Status */
uint32_t dos: 1; /* SR.1 Data Overrun Status */
@@ -56,7 +56,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} status_reg; /* Address 0x0008 */
union {
volatile union {
struct {
uint32_t ri: 1; /* IR.0 Receive Interrupt */
uint32_t ti: 1; /* IR.1 Transmit Interrupt */
@@ -70,7 +70,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} interrupt_reg; /* Address 0x000C */
union {
volatile union {
struct {
uint32_t rie: 1; /* IER.0 Receive Interrupt Enable */
uint32_t tie: 1; /* IER.1 Transmit Interrupt Enable */
@@ -85,7 +85,7 @@ typedef volatile struct twai_dev_s {
uint32_t val;
} interrupt_enable_reg; /* Address 0x0010 */
uint32_t reserved_14;
union {
volatile union {
struct {
uint32_t brp: 6; /* BTR0[5:0] Baud Rate Prescaler */
uint32_t sjw: 2; /* BTR0[7:6] Synchronization Jump Width*/
@@ -93,7 +93,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} bus_timing_0_reg; /* Address 0x0018 */
union {
volatile union {
struct {
uint32_t tseg1: 4; /* BTR1[3:0] Timing Segment 1 */
uint32_t tseg2: 3; /* BTR1[6:4] Timing Segment 2 */
@@ -107,14 +107,14 @@ typedef volatile struct twai_dev_s {
uint32_t reserved_28; /* Address 0x0028 */
//Capture and Counter Registers
union {
volatile union {
struct {
uint32_t alc: 5; /* ALC[4:0] Arbitration lost capture */
uint32_t reserved5: 27; /* Internal Reserved */
};
uint32_t val;
} arbitration_lost_captue_reg; /* Address 0x002C */
union {
volatile union {
struct {
uint32_t seg: 5; /* ECC[4:0] Error Code Segment 0 to 5 */
uint32_t dir: 1; /* ECC.5 Error Direction (TX/RX) */
@@ -123,21 +123,21 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} error_code_capture_reg; /* Address 0x0030 */
union {
volatile union {
struct {
uint32_t ewl: 8; /* EWL[7:0] Error Warning Limit */
uint32_t reserved8: 24; /* Internal Reserved */
};
uint32_t val;
} error_warning_limit_reg; /* Address 0x0034 */
union {
volatile union {
struct {
uint32_t rxerr: 8; /* RXERR[7:0] Receive Error Counter */
uint32_t reserved8: 24; /* Internal Reserved */
};
uint32_t val;
} rx_error_counter_reg; /* Address 0x0038 */
union {
volatile union {
struct {
uint32_t txerr: 8; /* TXERR[7:0] Receive Error Counter */
uint32_t reserved8: 24; /* Internal Reserved */
@@ -146,7 +146,7 @@ typedef volatile struct twai_dev_s {
} tx_error_counter_reg; /* Address 0x003C */
//Shared Registers (TX Buff/RX Buff/Acc Filter)
union {
volatile union {
struct {
union {
struct {
@@ -178,7 +178,7 @@ typedef volatile struct twai_dev_s {
}; /* Address 0x0040 - 0x0070 */
//Misc Registers
union {
volatile union {
struct {
uint32_t rmc: 7; /* RMC[6:0] RX Message Counter */
uint32_t reserved7: 25; /* Internal Reserved */
@@ -186,7 +186,7 @@ typedef volatile struct twai_dev_s {
uint32_t val;
} rx_message_counter_reg; /* Address 0x0074 */
uint32_t reserved_78; /* Address 0x0078 (RX Buffer Start Address not supported) */
union {
volatile union {
struct {
uint32_t cd: 3; /* CDR[2:0] CLKOUT frequency selector based of fOSC */
uint32_t co: 1; /* CDR.3 CLKOUT enable/disable */

View File

@@ -899,6 +899,10 @@ config SOC_TWAI_CONTROLLER_NUM
int
default 1
config SOC_TWAI_MASK_FILTER_NUM
int
default 1
config SOC_TWAI_CLK_SUPPORT_APB
bool
default y

View File

@@ -378,7 +378,8 @@
#define SOC_MWDT_SUPPORT_XTAL (1)
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL
#define SOC_TWAI_CONTROLLER_NUM 1U
#define SOC_TWAI_MASK_FILTER_NUM 1U
#define SOC_TWAI_CLK_SUPPORT_APB 1
#define SOC_TWAI_BRP_MIN 2
#define SOC_TWAI_BRP_MAX 16384

View File

@@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@@ -19,9 +19,9 @@ extern "C" {
* the least significant byte of every 32bits.
*/
typedef volatile struct twai_dev_s {
typedef struct twai_dev_t {
//Configuration and Control Registers
union {
volatile union {
struct {
uint32_t rm: 1; /* MOD.0 Reset Mode */
uint32_t lom: 1; /* MOD.1 Listen Only Mode */
@@ -31,7 +31,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} mode_reg; /* Address 0x0000 */
union {
volatile union {
struct {
uint32_t tr: 1; /* CMR.0 Transmission Request */
uint32_t at: 1; /* CMR.1 Abort Transmission */
@@ -42,7 +42,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} command_reg; /* Address 0x0004 */
union {
volatile union {
struct {
uint32_t rbs: 1; /* SR.0 Receive Buffer Status */
uint32_t dos: 1; /* SR.1 Data Overrun Status */
@@ -57,7 +57,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} status_reg; /* Address 0x0008 */
union {
volatile union {
struct {
uint32_t ri: 1; /* IR.0 Receive Interrupt */
uint32_t ti: 1; /* IR.1 Transmit Interrupt */
@@ -71,7 +71,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} interrupt_reg; /* Address 0x000C */
union {
volatile union {
struct {
uint32_t rie: 1; /* IER.0 Receive Interrupt Enable */
uint32_t tie: 1; /* IER.1 Transmit Interrupt Enable */
@@ -86,7 +86,7 @@ typedef volatile struct twai_dev_s {
uint32_t val;
} interrupt_enable_reg; /* Address 0x0010 */
uint32_t reserved_14;
union {
volatile union {
struct {
uint32_t brp: 13; /* BTR0[12:0] Baud Rate Prescaler */
uint32_t reserved13: 1; /* Internal Reserved */
@@ -95,7 +95,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} bus_timing_0_reg; /* Address 0x0018 */
union {
volatile union {
struct {
uint32_t tseg1: 4; /* BTR1[3:0] Timing Segment 1 */
uint32_t tseg2: 3; /* BTR1[6:4] Timing Segment 2 */
@@ -109,14 +109,14 @@ typedef volatile struct twai_dev_s {
uint32_t reserved_28; /* Address 0x0028 */
//Capture and Counter Registers
union {
volatile union {
struct {
uint32_t alc: 5; /* ALC[4:0] Arbitration lost capture */
uint32_t reserved5: 27; /* Internal Reserved */
};
uint32_t val;
} arbitration_lost_captue_reg; /* Address 0x002C */
union {
volatile union {
struct {
uint32_t seg: 5; /* ECC[4:0] Error Code Segment 0 to 5 */
uint32_t dir: 1; /* ECC.5 Error Direction (TX/RX) */
@@ -125,21 +125,21 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} error_code_capture_reg; /* Address 0x0030 */
union {
volatile union {
struct {
uint32_t ewl: 8; /* EWL[7:0] Error Warning Limit */
uint32_t reserved8: 24; /* Internal Reserved */
};
uint32_t val;
} error_warning_limit_reg; /* Address 0x0034 */
union {
volatile union {
struct {
uint32_t rxerr: 8; /* RXERR[7:0] Receive Error Counter */
uint32_t reserved8: 24; /* Internal Reserved */
};
uint32_t val;
} rx_error_counter_reg; /* Address 0x0038 */
union {
volatile union {
struct {
uint32_t txerr: 8; /* TXERR[7:0] Receive Error Counter */
uint32_t reserved8: 24; /* Internal Reserved */
@@ -148,7 +148,7 @@ typedef volatile struct twai_dev_s {
} tx_error_counter_reg; /* Address 0x003C */
//Shared Registers (TX Buff/RX Buff/Acc Filter)
union {
volatile union {
struct {
union {
struct {
@@ -180,7 +180,7 @@ typedef volatile struct twai_dev_s {
}; /* Address 0x0040 - 0x0070 */
//Misc Registers
union {
volatile union {
struct {
uint32_t rmc: 7; /* RMC[6:0] RX Message Counter */
uint32_t reserved7: 25; /* Internal Reserved */
@@ -188,7 +188,7 @@ typedef volatile struct twai_dev_s {
uint32_t val;
} rx_message_counter_reg; /* Address 0x0074 */
uint32_t reserved_78; /* Address 0x0078 (RX Buffer Start Address not supported) */
union {
volatile union {
struct {
uint32_t cd: 8; /* CDR[7:0] CLKOUT frequency selector based of fOSC */
uint32_t co: 1; /* CDR.8 CLKOUT enable/disable */

View File

@@ -1755,7 +1755,7 @@ typedef struct {
/**
* @brief TWAI frame buffer register types
*/
typedef union {
typedef union twaifd_frame_buffer_t {
struct {
union {
struct {
@@ -1796,7 +1796,7 @@ typedef struct {
uint32_t reserved_50[44];
} twaifd_frame_mem_t;
typedef struct {
typedef struct twaifd_dev_t {
volatile twaifd_device_id_version_reg_t device_id_version;
volatile twaifd_mode_settings_reg_t mode_settings;
volatile twaifd_status_reg_t status;

View File

@@ -1207,6 +1207,10 @@ config SOC_TWAI_CONTROLLER_NUM
int
default 2
config SOC_TWAI_MASK_FILTER_NUM
int
default 1
config SOC_TWAI_CLK_SUPPORT_XTAL
bool
default y

View File

@@ -469,6 +469,7 @@
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 2
#define SOC_TWAI_MASK_FILTER_NUM 1U
#define SOC_TWAI_CLK_SUPPORT_XTAL 1
#define SOC_TWAI_BRP_MIN 2
#define SOC_TWAI_BRP_MAX 32768

View File

@@ -525,7 +525,7 @@ typedef struct {
} acceptance_filter_reg_t;
typedef struct twai_dev_s {
typedef struct twai_dev_t {
volatile twai_mode_reg_t mode;
volatile twai_cmd_reg_t cmd;
volatile twai_status_reg_t status;

View File

@@ -1223,6 +1223,10 @@ config SOC_TWAI_CONTROLLER_NUM
int
default 1
config SOC_TWAI_MASK_FILTER_NUM
int
default 1
config SOC_TWAI_CLK_SUPPORT_XTAL
bool
default y

View File

@@ -486,7 +486,8 @@
#define SOC_MWDT_SUPPORT_SLEEP_RETENTION (1)
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL
#define SOC_TWAI_CONTROLLER_NUM 1U
#define SOC_TWAI_MASK_FILTER_NUM 1U
#define SOC_TWAI_CLK_SUPPORT_XTAL 1
#define SOC_TWAI_BRP_MIN 2
#define SOC_TWAI_BRP_MAX 32768

View File

@@ -525,7 +525,7 @@ typedef struct {
} acceptance_filter_reg_t;
typedef struct twai_dev_s {
typedef struct twai_dev_t {
volatile twai_mode_reg_t mode;
volatile twai_cmd_reg_t cmd;
volatile twai_status_reg_t status;

View File

@@ -695,7 +695,7 @@ typedef union {
} twai_data_12_reg_t;
typedef struct {
typedef struct twai_dev_t {
volatile twai_mode_reg_t mode;
volatile twai_cmd_reg_t cmd;
volatile twai_status_reg_t status;

View File

@@ -1779,6 +1779,10 @@ config SOC_TWAI_CONTROLLER_NUM
int
default 3
config SOC_TWAI_MASK_FILTER_NUM
int
default 1
config SOC_TWAI_CLK_SUPPORT_XTAL
bool
default y

View File

@@ -653,6 +653,7 @@
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 3
#define SOC_TWAI_MASK_FILTER_NUM 1U
#define SOC_TWAI_CLK_SUPPORT_XTAL 1
#define SOC_TWAI_BRP_MIN 2
#define SOC_TWAI_BRP_MAX 32768

View File

@@ -574,7 +574,7 @@ typedef union {
} twai_timestamp_cfg_reg_t;
typedef struct {
typedef struct twai_dev_t {
volatile twai_mode_reg_t mode;
volatile twai_cmd_reg_t cmd;
volatile twai_status_reg_t status;

View File

@@ -871,6 +871,10 @@ config SOC_TWAI_CONTROLLER_NUM
int
default 1
config SOC_TWAI_MASK_FILTER_NUM
int
default 1
config SOC_TWAI_CLK_SUPPORT_APB
bool
default y

View File

@@ -361,7 +361,8 @@
#define SOC_TOUCH_SAMPLE_CFG_NUM (1U) /*!< The sample configuration number in total, each sampler can be used to sample on one frequency */
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL
#define SOC_TWAI_CONTROLLER_NUM 1U
#define SOC_TWAI_MASK_FILTER_NUM 1U
#define SOC_TWAI_CLK_SUPPORT_APB 1
#define SOC_TWAI_BRP_MIN 2
#define SOC_TWAI_BRP_MAX 32768

View File

@@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@@ -19,9 +19,9 @@ extern "C" {
* the least significant byte of every 32bits.
*/
typedef volatile struct twai_dev_s {
typedef struct twai_dev_t {
//Configuration and Control Registers
union {
volatile union {
struct {
uint32_t rm: 1; /* MOD.0 Reset Mode */
uint32_t lom: 1; /* MOD.1 Listen Only Mode */
@@ -31,7 +31,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} mode_reg; /* Address 0x0000 */
union {
volatile union {
struct {
uint32_t tr: 1; /* CMR.0 Transmission Request */
uint32_t at: 1; /* CMR.1 Abort Transmission */
@@ -42,7 +42,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} command_reg; /* Address 0x0004 */
union {
volatile union {
struct {
uint32_t rbs: 1; /* SR.0 Receive Buffer Status */
uint32_t dos: 1; /* SR.1 Data Overrun Status */
@@ -57,7 +57,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} status_reg; /* Address 0x0008 */
union {
volatile union {
struct {
uint32_t ri: 1; /* IR.0 Receive Interrupt */
uint32_t ti: 1; /* IR.1 Transmit Interrupt */
@@ -71,7 +71,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} interrupt_reg; /* Address 0x000C */
union {
volatile union {
struct {
uint32_t rie: 1; /* IER.0 Receive Interrupt Enable */
uint32_t tie: 1; /* IER.1 Transmit Interrupt Enable */
@@ -86,7 +86,7 @@ typedef volatile struct twai_dev_s {
uint32_t val;
} interrupt_enable_reg; /* Address 0x0010 */
uint32_t reserved_14;
union {
volatile union {
struct {
uint32_t brp: 14; /* BTR0[13:0] Baud Rate Prescaler */
uint32_t sjw: 2; /* BTR0[15:14] Synchronization Jump Width*/
@@ -94,7 +94,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} bus_timing_0_reg; /* Address 0x0018 */
union {
volatile union {
struct {
uint32_t tseg1: 4; /* BTR1[3:0] Timing Segment 1 */
uint32_t tseg2: 3; /* BTR1[6:4] Timing Segment 2 */
@@ -108,14 +108,14 @@ typedef volatile struct twai_dev_s {
uint32_t reserved_28; /* Address 0x0028 */
//Capture and Counter Registers
union {
volatile union {
struct {
uint32_t alc: 5; /* ALC[4:0] Arbitration lost capture */
uint32_t reserved5: 27; /* Internal Reserved */
};
uint32_t val;
} arbitration_lost_captue_reg; /* Address 0x002C */
union {
volatile union {
struct {
uint32_t seg: 5; /* ECC[4:0] Error Code Segment 0 to 5 */
uint32_t dir: 1; /* ECC.5 Error Direction (TX/RX) */
@@ -124,21 +124,21 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} error_code_capture_reg; /* Address 0x0030 */
union {
volatile union {
struct {
uint32_t ewl: 8; /* EWL[7:0] Error Warning Limit */
uint32_t reserved8: 24; /* Internal Reserved */
};
uint32_t val;
} error_warning_limit_reg; /* Address 0x0034 */
union {
volatile union {
struct {
uint32_t rxerr: 8; /* RXERR[7:0] Receive Error Counter */
uint32_t reserved8: 24; /* Internal Reserved */
};
uint32_t val;
} rx_error_counter_reg; /* Address 0x0038 */
union {
volatile union {
struct {
uint32_t txerr: 8; /* TXERR[7:0] Receive Error Counter */
uint32_t reserved8: 24; /* Internal Reserved */
@@ -147,7 +147,7 @@ typedef volatile struct twai_dev_s {
} tx_error_counter_reg; /* Address 0x003C */
//Shared Registers (TX Buff/RX Buff/Acc Filter)
union {
volatile union {
struct {
union {
struct {
@@ -179,7 +179,7 @@ typedef volatile struct twai_dev_s {
}; /* Address 0x0040 - 0x0070 */
//Misc Registers
union {
volatile union {
struct {
uint32_t rmc: 7; /* RMC[6:0] RX Message Counter */
uint32_t reserved7: 25; /* Internal Reserved */
@@ -187,7 +187,7 @@ typedef volatile struct twai_dev_s {
uint32_t val;
} rx_message_counter_reg; /* Address 0x0074 */
uint32_t reserved_78; /* Address 0x0078 (RX Buffer Start Address not supported) */
union {
volatile union {
struct {
uint32_t cd: 8; /* CDR[7:0] CLKOUT frequency selector based of fOSC */
uint32_t co: 1; /* CDR.8 CLKOUT enable/disable */

View File

@@ -1075,6 +1075,10 @@ config SOC_TWAI_CONTROLLER_NUM
int
default 1
config SOC_TWAI_MASK_FILTER_NUM
int
default 1
config SOC_TWAI_CLK_SUPPORT_APB
bool
default y

View File

@@ -413,7 +413,8 @@
#define SOC_TOUCH_SAMPLE_CFG_NUM (1U) /*!< The sample configuration number in total, each sampler can be used to sample on one frequency */
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL
#define SOC_TWAI_CONTROLLER_NUM 1U
#define SOC_TWAI_MASK_FILTER_NUM 1U
#define SOC_TWAI_CLK_SUPPORT_APB 1
#define SOC_TWAI_BRP_MIN 2
#define SOC_TWAI_BRP_MAX 16384

View File

@@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@@ -20,9 +20,9 @@ extern "C" {
* the least significant byte of every 32bits.
*/
typedef volatile struct twai_dev_s {
typedef struct twai_dev_t {
//Configuration and Control Registers
union {
volatile union {
struct {
uint32_t rm: 1; /* MOD.0 Reset Mode */
uint32_t lom: 1; /* MOD.1 Listen Only Mode */
@@ -32,7 +32,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} mode_reg; /* Address 0x0000 */
union {
volatile union {
struct {
uint32_t tr: 1; /* CMR.0 Transmission Request */
uint32_t at: 1; /* CMR.1 Abort Transmission */
@@ -43,7 +43,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} command_reg; /* Address 0x0004 */
union {
volatile union {
struct {
uint32_t rbs: 1; /* SR.0 Receive Buffer Status */
uint32_t dos: 1; /* SR.1 Data Overrun Status */
@@ -58,7 +58,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} status_reg; /* Address 0x0008 */
union {
volatile union {
struct {
uint32_t ri: 1; /* IR.0 Receive Interrupt */
uint32_t ti: 1; /* IR.1 Transmit Interrupt */
@@ -72,7 +72,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} interrupt_reg; /* Address 0x000C */
union {
volatile union {
struct {
uint32_t rie: 1; /* IER.0 Receive Interrupt Enable */
uint32_t tie: 1; /* IER.1 Transmit Interrupt Enable */
@@ -87,7 +87,7 @@ typedef volatile struct twai_dev_s {
uint32_t val;
} interrupt_enable_reg; /* Address 0x0010 */
uint32_t reserved_14;
union {
volatile union {
struct {
uint32_t brp: 13; /* BTR0[12:0] Baud Rate Prescaler */
uint32_t reserved13: 1; /* Internal Reserved */
@@ -96,7 +96,7 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} bus_timing_0_reg; /* Address 0x0018 */
union {
volatile union {
struct {
uint32_t tseg1: 4; /* BTR1[3:0] Timing Segment 1 */
uint32_t tseg2: 3; /* BTR1[6:4] Timing Segment 2 */
@@ -110,14 +110,14 @@ typedef volatile struct twai_dev_s {
uint32_t reserved_28; /* Address 0x0028 */
//Capture and Counter Registers
union {
volatile union {
struct {
uint32_t alc: 5; /* ALC[4:0] Arbitration lost capture */
uint32_t reserved5: 27; /* Internal Reserved */
};
uint32_t val;
} arbitration_lost_captue_reg; /* Address 0x002C */
union {
volatile union {
struct {
uint32_t seg: 5; /* ECC[4:0] Error Code Segment 0 to 5 */
uint32_t dir: 1; /* ECC.5 Error Direction (TX/RX) */
@@ -126,21 +126,21 @@ typedef volatile struct twai_dev_s {
};
uint32_t val;
} error_code_capture_reg; /* Address 0x0030 */
union {
volatile union {
struct {
uint32_t ewl: 8; /* EWL[7:0] Error Warning Limit */
uint32_t reserved8: 24; /* Internal Reserved */
};
uint32_t val;
} error_warning_limit_reg; /* Address 0x0034 */
union {
volatile union {
struct {
uint32_t rxerr: 8; /* RXERR[7:0] Receive Error Counter */
uint32_t reserved8: 24; /* Internal Reserved */
};
uint32_t val;
} rx_error_counter_reg; /* Address 0x0038 */
union {
volatile union {
struct {
uint32_t txerr: 8; /* TXERR[7:0] Receive Error Counter */
uint32_t reserved8: 24; /* Internal Reserved */
@@ -149,7 +149,7 @@ typedef volatile struct twai_dev_s {
} tx_error_counter_reg; /* Address 0x003C */
//Shared Registers (TX Buff/RX Buff/Acc Filter)
union {
volatile union {
struct {
union {
struct {
@@ -181,7 +181,7 @@ typedef volatile struct twai_dev_s {
}; /* Address 0x0040 - 0x0070 */
//Misc Registers
union {
volatile union {
struct {
uint32_t rmc: 7; /* RMC[6:0] RX Message Counter */
uint32_t reserved7: 25; /* Internal Reserved */
@@ -189,7 +189,7 @@ typedef volatile struct twai_dev_s {
uint32_t val;
} rx_message_counter_reg; /* Address 0x0074 */
uint32_t reserved_78; /* Address 0x0078 (RX Buffer Start Address not supported) */
union {
volatile union {
struct {
uint32_t cd: 8; /* CDR[7:0] CLKOUT frequency selector based of fOSC */
uint32_t co: 1; /* CDR.8 CLKOUT enable/disable */

View File

@@ -21,8 +21,7 @@ ignores:
- "components/hal/spi_flash_encrypt_hal_iram.c"
- "components/hal/spi_flash_hal_iram.c"
- "components/hal/spi_flash_hal.c"
- "components/hal/twai_hal_iram.c"
- "components/hal/twai_hal.c"
- "components/hal/twai_hal_sja1000.c"
- "components/hal/usb_dwc_hal.c"
- "components/hal/wdt_hal_iram.c"
- "components/hal/esp32/efuse_hal.c"
@@ -80,8 +79,7 @@ ignores:
- "components/hal/mmu_hal.c"
- "components/hal/mpi_hal.c"
- "components/hal/spi_flash_hal_iram.c"
- "components/hal/twai_hal_iram.c"
- "components/hal/twai_hal.c"
- "components/hal/twai_hal_sja1000.c"
- "components/hal/usb_dwc_hal.c"
- "components/hal/efuse_hal.c"
- "components/hal/esp32/include/hal/twai_ll.h"