Merge branch 'feat/twai_esp32h4' into 'master'

feat(twai): add driver support on esp32h4

Closes IDF-12352 and IDF-12354

See merge request espressif/esp-idf!41434
This commit is contained in:
morris
2025-08-25 23:30:11 +08:00
25 changed files with 1237 additions and 167 deletions

View File

@@ -22,7 +22,7 @@ from pytest_embedded_idf.utils import idf_parametrize
@idf_parametrize(
'target', ['esp32', 'esp32c3', 'esp32c6', 'esp32h2', 'esp32s2', 'esp32s3', 'esp32p4'], indirect=['target']
)
def test_twai_self(dut: Dut) -> None:
def test_legacy_twai_self(dut: Dut) -> None:
dut.run_all_single_board_cases(group='twai-loop-back')
@@ -31,11 +31,11 @@ def fixture_create_socket_can() -> Bus:
# Set up the socket CAN with the bitrate
start_command = 'sudo ip link set can0 up type can bitrate 250000 restart-ms 100'
stop_command = 'sudo ip link set can0 down'
subprocess.run(start_command, shell=True, stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True)
subprocess.run(start_command, shell=True, capture_output=True, text=True)
bus = Bus(interface='socketcan', channel='can0', bitrate=250000)
yield bus # test invoked here
bus.shutdown()
subprocess.run(stop_command, shell=True, stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True)
subprocess.run(stop_command, shell=True, capture_output=True, text=True)
@pytest.mark.twai_std
@@ -49,7 +49,7 @@ def fixture_create_socket_can() -> Bus:
@idf_parametrize(
'target', ['esp32', 'esp32c3', 'esp32c6', 'esp32h2', 'esp32s2', 'esp32s3', 'esp32p4'], indirect=['target']
)
def test_twai_listen_only(dut: Dut, socket_can: Bus) -> None:
def test_legacy_twai_listen_only(dut: Dut, socket_can: Bus) -> None:
dut.serial.hard_reset()
dut.expect_exact('Press ENTER to see the list of tests')
@@ -79,7 +79,7 @@ def test_twai_listen_only(dut: Dut, socket_can: Bus) -> None:
@idf_parametrize(
'target', ['esp32', 'esp32c3', 'esp32c6', 'esp32h2', 'esp32s2', 'esp32s3', 'esp32p4'], indirect=['target']
)
def test_twai_remote_request(dut: Dut, socket_can: Bus) -> None:
def test_legacy_twai_remote_request(dut: Dut, socket_can: Bus) -> None:
dut.serial.hard_reset()
dut.expect_exact('Press ENTER to see the list of tests')

View File

@@ -127,8 +127,10 @@ static esp_err_t _node_config_io(twai_onchip_ctx_t *node, const twai_onchip_node
{
ESP_RETURN_ON_FALSE(GPIO_IS_VALID_OUTPUT_GPIO(node_config->io_cfg.tx) || (node_config->flags.enable_listen_only && (node_config->io_cfg.tx == -1)), ESP_ERR_INVALID_ARG, TAG, "Invalid tx gpio num");
ESP_RETURN_ON_FALSE(GPIO_IS_VALID_GPIO(node_config->io_cfg.rx), ESP_ERR_INVALID_ARG, TAG, "Invalid rx gpio num");
uint64_t reserve_mask = 0;
ESP_RETURN_ON_FALSE(!(GPIO_IS_VALID_OUTPUT_GPIO(node_config->io_cfg.quanta_clk_out) && (twai_periph_signals[node->ctrlr_id].clk_out_sig < 0)), ESP_ERR_NOT_SUPPORTED, TAG, "quanta_clk_out is not supported");
ESP_RETURN_ON_FALSE(!(GPIO_IS_VALID_OUTPUT_GPIO(node_config->io_cfg.bus_off_indicator) && (twai_periph_signals[node->ctrlr_id].bus_off_sig < 0)), ESP_ERR_NOT_SUPPORTED, TAG, "bus_off_indicator is not supported");
uint64_t reserve_mask = 0;
// Set RX pin
gpio_set_pull_mode(node_config->io_cfg.rx, GPIO_PULLUP_ONLY); // pullup to avoid noise if no connection to transceiver
gpio_matrix_input(node_config->io_cfg.rx, twai_periph_signals[node->ctrlr_id].rx_sig, false);

View File

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

View File

@@ -33,7 +33,7 @@ static IRAM_ATTR bool test_driver_install_rx_cb(twai_node_handle_t handle, const
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);
esp_rom_printf("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
@@ -113,6 +113,8 @@ static void test_twai_baudrate_correctness(twai_clock_source_t clk_src, uint32_t
twai_onchip_node_config_t node_config = {};
node_config.io_cfg.tx = TEST_TX_GPIO;
node_config.io_cfg.rx = TEST_TX_GPIO;
node_config.io_cfg.quanta_clk_out = GPIO_NUM_NC;
node_config.io_cfg.bus_off_indicator = GPIO_NUM_NC;
node_config.clk_src = clk_src;
node_config.bit_timing.bitrate = test_bitrate;
node_config.tx_queue_depth = 1;
@@ -497,6 +499,8 @@ TEST_CASE("twai bus off recovery (loopback)", "[twai]")
twai_onchip_node_config_t node_config = {};
node_config.io_cfg.tx = TEST_TX_GPIO;
node_config.io_cfg.rx = TEST_TX_GPIO; // Using same pin for test without transceiver
node_config.io_cfg.quanta_clk_out = GPIO_NUM_NC;
node_config.io_cfg.bus_off_indicator = GPIO_NUM_NC;
node_config.bit_timing.bitrate = 50000; //slow bitrate to ensure soft error trigger
node_config.tx_queue_depth = 1;
node_config.flags.enable_self_test = true;
@@ -568,6 +572,8 @@ TEST_CASE("twai tx_wait_all_done thread safe", "[twai]")
twai_onchip_node_config_t node_config = {};
node_config.io_cfg.tx = TEST_TX_GPIO;
node_config.io_cfg.rx = TEST_TX_GPIO; //Using same pin for test without transceiver
node_config.io_cfg.quanta_clk_out = GPIO_NUM_NC;
node_config.io_cfg.bus_off_indicator = GPIO_NUM_NC;
node_config.bit_timing.bitrate = 100000; //slow bitrate to ensure transmite finish during wait_all_done
node_config.tx_queue_depth = TEST_FRAME_NUM;
node_config.flags.enable_self_test = true;

View File

@@ -66,6 +66,8 @@ TEST_CASE("twai range filter (loopback)", "[twai]")
twai_onchip_node_config_t node_config = {};
node_config.io_cfg.tx = TEST_TX_GPIO;
node_config.io_cfg.rx = TEST_TX_GPIO; // Using same pin for test without transceiver
node_config.io_cfg.quanta_clk_out = GPIO_NUM_NC;
node_config.io_cfg.bus_off_indicator = GPIO_NUM_NC;
node_config.bit_timing.bitrate = 1000000;
node_config.tx_queue_depth = TEST_TWAI_QUEUE_DEPTH;
node_config.flags.enable_self_test = true;
@@ -139,6 +141,8 @@ TEST_CASE("twai fd transmit time (loopback)", "[twai]")
twai_onchip_node_config_t node_config = {};
node_config.io_cfg.tx = TEST_TX_GPIO;
node_config.io_cfg.rx = TEST_TX_GPIO; // Using same pin for test without transceiver
node_config.io_cfg.quanta_clk_out = GPIO_NUM_NC;
node_config.io_cfg.bus_off_indicator = GPIO_NUM_NC;
node_config.bit_timing.bitrate = 1000000;
node_config.data_timing.bitrate = 4000000;
node_config.data_timing.ssp_permill = 700; // ssp 70.0%

View File

@@ -31,6 +31,8 @@ TEST_CASE("twai_listen_only", "[twai_net]")
twai_onchip_node_config_t node_config = {};
node_config.io_cfg.tx = TEST_TX_GPIO;
node_config.io_cfg.rx = TEST_RX_GPIO;
node_config.io_cfg.quanta_clk_out = GPIO_NUM_NC;
node_config.io_cfg.bus_off_indicator = GPIO_NUM_NC;
node_config.bit_timing.bitrate = 250000;
node_config.tx_queue_depth = 3;
node_config.flags.enable_listen_only = true;
@@ -71,6 +73,8 @@ TEST_CASE("twai_remote_request", "[twai_net]")
twai_onchip_node_config_t node_config = {};
node_config.io_cfg.tx = TEST_TX_GPIO;
node_config.io_cfg.rx = TEST_RX_GPIO;
node_config.io_cfg.quanta_clk_out = GPIO_NUM_NC;
node_config.io_cfg.bus_off_indicator = GPIO_NUM_NC;
node_config.bit_timing.bitrate = 250000;
node_config.tx_queue_depth = 3;
node_config.fail_retry_cnt = -1; // retry forever if send remote frame failed

View File

@@ -26,17 +26,17 @@ def fixture_create_socket_can() -> Bus:
start_command = 'sudo ip link set can0 up type can bitrate 250000'
stop_command = 'sudo ip link set can0 down'
try:
subprocess.run(start_command, shell=True, stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True)
subprocess.run(start_command, shell=True, capture_output=True, text=True)
except Exception as e:
print(f'Open bus Error: {e}')
bus = Bus(interface='socketcan', channel='can0', bitrate=250000)
yield bus # test invoked here
bus.shutdown()
subprocess.run(stop_command, shell=True, stdout=subprocess.PIPE, stderr=subprocess.PIPE, text=True)
subprocess.run(stop_command, shell=True, capture_output=True, text=True)
@pytest.mark.twai_std
@pytest.mark.temp_skip_ci(targets=['esp32c5'], reason='no runner')
@pytest.mark.temp_skip_ci(targets=['esp32c5', 'esp32h4'], reason='no runner')
@pytest.mark.parametrize('config', ['release'], indirect=True)
@idf_parametrize('target', soc_filtered_targets('SOC_TWAI_SUPPORTED == 1'), indirect=['target'])
def test_driver_twai_listen_only(dut: Dut, socket_can: Bus) -> None:
@@ -59,7 +59,7 @@ def test_driver_twai_listen_only(dut: Dut, socket_can: Bus) -> None:
@pytest.mark.twai_std
@pytest.mark.temp_skip_ci(targets=['esp32c5'], reason='no runner')
@pytest.mark.temp_skip_ci(targets=['esp32c5', 'esp32h4'], reason='no runner')
@pytest.mark.parametrize('config', ['release'], indirect=True)
@idf_parametrize('target', soc_filtered_targets('SOC_TWAI_SUPPORTED == 1'), indirect=['target'])
def test_driver_twai_remote_request(dut: Dut, socket_can: Bus) -> None:

View File

@@ -98,7 +98,16 @@ static inline void twaifd_ll_reset_register(uint8_t twai_id)
*/
static inline void twaifd_ll_set_clock_source(uint8_t twai_id, twai_clock_source_t clk_src)
{
PCR.twai[twai_id].twai_func_clk_conf.twai_func_clk_sel = (clk_src == TWAI_CLK_SRC_XTAL) ? 0 : 1;
switch (clk_src) {
case TWAI_CLK_SRC_PLL_F80M:
PCR.twai[twai_id].twai_func_clk_conf.twai_func_clk_sel = 1;
break;
case TWAI_CLK_SRC_XTAL:
PCR.twai[twai_id].twai_func_clk_conf.twai_func_clk_sel = 0;
break;
default:
HAL_ASSERT(false);
}
}
/**

View File

@@ -0,0 +1,967 @@
/*
* SPDX-FileCopyrightText: 2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
/*******************************************************************************
* NOTICE
* The Lowlevel layer for TWAI is not public api, don't use in application code.
******************************************************************************/
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <string.h>
#include "soc/pcr_reg.h"
#include "soc/pcr_struct.h"
#include "soc/twaifd_reg.h"
#include "soc/twaifd_struct.h"
#include "hal/twai_types.h"
#include "hal/assert.h"
#include "hal/misc.h"
#define TWAIFD_LL_GET_HW(num) (((num) == 0) ? (&TWAI0) : NULL)
#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
#define TWAI_LL_TSEG2_MAX TWAIFD_PH2
#define TWAI_LL_SJW_MAX TWAIFD_SJW
#define TWAIFD_IDENTIFIER_BASE_S 18 // Start bit of std_id in IDENTIFIER_W of TX buffer or RX buffer
#define TWAIFD_LL_ERR_BIT_ERR 0x0 // Bit Error
#define TWAIFD_LL_ERR_CRC_ERR 0x1 // CRC Error
#define TWAIFD_LL_ERR_FRM_ERR 0x2 // Form Error
#define TWAIFD_LL_ERR_ACK_ERR 0x3 // Acknowledge Error
#define TWAIFD_LL_ERR_STUF_ERR 0x4 // Stuff Error
#define TWAIFD_LL_SSP_SRC_MEAS_OFFSET 0x0 // Using Measured Transmitter delay + SSP_OFFSET
#define TWAIFD_LL_SSP_SRC_NO_SSP 0x1 // SSP is disabled
#define TWAIFD_LL_SSP_SRC_OFFSET_ONLY 0x2 // Using SSP_OFFSET only
#define TWAIFD_LL_TX_CMD_EMPTY TWAIFD_TXCE // Set tx buffer to "Empty" state
#define TWAIFD_LL_TX_CMD_READY TWAIFD_TXCR // Set tx buffer to "Ready" state
#define TWAIFD_LL_TX_CMD_ABORT TWAIFD_TXCA // Set tx buffer to "Aborted" state
#define TWAIFD_LL_HW_CMD_RST_ERR_CNT TWAIFD_ERCRST // Error Counters Reset
#define TWAIFD_LL_HW_CMD_RST_RX_CNT TWAIFD_RXFCRST // Clear RX bus traffic counter
#define TWAIFD_LL_HW_CMD_RST_TX_CNT TWAIFD_TXFCRST // Clear TX bus traffic counter
#define TWAIFD_LL_INTR_TX_DONE TWAIFD_TXBHCI_INT_ST// Transmit finish (ok or error)
#define TWAIFD_LL_INTR_TX_SUCCESS TWAIFD_TXI_INT_ST // Transmit success without error
#define TWAIFD_LL_INTR_RX_NOT_EMPTY TWAIFD_RBNEI_INT_ST // RX buffer not empty interrupt
#define TWAIFD_LL_INTR_RX_FULL TWAIFD_RXFI_INT_ST // RX buffer full interrupt
#define TWAIFD_LL_INTR_ERR_WARN TWAIFD_EWLI_INT_ST // Error Interrupt
#define TWAIFD_LL_INTR_BUS_ERR TWAIFD_BEI_INT_ST // Bus error interrupt
#define TWAIFD_LL_INTR_FSM_CHANGE TWAIFD_FCSI_INT_ST // Fault confinement state changed interrupt
#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
*
* @param twai_id Hardware ID
* @param enable true to enable, false to disable
*/
static inline void twaifd_ll_enable_bus_clock(uint8_t twai_id, bool enable)
{
PCR.twai0_conf.twai0_clk_en = enable;
}
/**
* @brief Reset the twai module
*
* @param twai_id Hardware ID
*/
static inline void twaifd_ll_reset_register(uint8_t twai_id)
{
PCR.twai0_conf.twai0_rst_en = 1;
PCR.twai0_conf.twai0_rst_en = 0;
}
/**
* @brief Set clock source for TWAI module
*
* @param twai_id Hardware ID
* @param clk_src Clock source
*/
static inline void twaifd_ll_set_clock_source(uint8_t twai_id, twai_clock_source_t clk_src)
{
switch (clk_src) {
case TWAI_CLK_SRC_XTAL:
PCR.twai0_func_clk_conf.twai0_func_clk_sel = 0;
break;
case TWAI_CLK_SRC_PLL_F96M:
PCR.twai0_func_clk_conf.twai0_func_clk_sel = 2;
break;
// We do not plan to support the TWAI_CLK_SRC_RC_FAST clock source,
// as the accuracy of this clock does not meet the requirements for the baud rate
// case TWAI_CLK_SRC_RC_FAST:
// PCR.twai0_func_clk_conf.twai0_func_clk_sel = 1;
// break;
default:
HAL_ASSERT(false);
}
}
/**
* @brief Enable TWAI module clock source
*
* @param twai_id Hardware ID
* @param enable true to enable, false to disable
*/
static inline void twaifd_ll_enable_clock(uint8_t twai_id, bool enable)
{
PCR.twai0_func_clk_conf.twai0_func_clk_en = enable;
if (enable) {
while (!PCR.twai0_conf.twai0_ready);
}
}
/**
* @brief Waits for pending changes to take effect in the hardware.
*
* @param hw Pointer to the hardware structure.
*/
static inline void twaifd_ll_waiting_state_change(twaifd_dev_t *hw)
{
while (!hw->int_stat.fcsi_int_st); // Wait until the change is applied
}
/* ---------------------------- Mode Register ------------------------------- */
// WARNING!! Following 'mode_settings' should in same spin_lock` !!!
/**
* @brief Reset hardware.
*
* @param hw Pointer to hardware structure.
*/
static inline void twaifd_ll_reset(twaifd_dev_t *hw)
{
hw->mode_settings.rst = 1;
}
/**
* @brief Enable or disable hardware.
*
* @param hw Pointer to hardware structure.
* @param enable Boolean flag to enable (true) or disable (false).
*/
static inline void twaifd_ll_enable_hw(twaifd_dev_t *hw, bool enable)
{
hw->mode_settings.ena = enable;
}
/**
* @brief Set operating mode of TWAI controller
*
* @param hw Start address of the TWAI registers
* @param listen_only Listen only mode (a.k.a. bus monitoring mode)
* @param self_test Self test mode
* @param loopback Loopback mode
*/
static inline void twaifd_ll_set_mode(twaifd_dev_t *hw, bool listen_only, bool self_test, bool loopback)
{
//mode should be changed under disabled
HAL_ASSERT(hw->mode_settings.ena == 0);
twaifd_mode_settings_reg_t opmode = {.val = hw->mode_settings.val};
opmode.stm = self_test;
opmode.bmm = listen_only;
opmode.ilbp = loopback;
hw->mode_settings.val = opmode.val;
}
/**
* @brief Set the TX retransmission limit.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param limit Retransmission limit (0-15, or negative for infinite).
*/
static inline void twaifd_ll_set_tx_retrans_limit(twaifd_dev_t *hw, int8_t limit)
{
HAL_ASSERT(limit <= (int8_t)TWAIFD_RTRTH_V); // Check the limit is valid
hw->mode_settings.rtrle = (limit >= 0); // Enable/disable retransmissions
hw->mode_settings.rtrth = limit; // Set the limit
}
/**
* set bit rate flexible between nominal field and data field
* when set this bit, all frame will be regarded as CANFD frame, even though nominal bit rate and data bit rate are the same
*/
static inline void twaifd_ll_enable_fd_mode(twaifd_dev_t *hw, bool ena)
{
hw->mode_settings.fde = ena;
}
/**
* @brief Enable or disable the RX fifo automatic increase when read to register
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param ena Set to true to enable RX automatic mode, false to disable.
*/
static inline void twaifd_ll_enable_rxfifo_auto_incrase(twaifd_dev_t *hw, bool ena)
{
hw->mode_settings.rxbam = ena;
}
/**
* @brief Enable or disable the filter.
*
* @param hw Pointer to hardware structure.
* @param enable `true` to enable, `false` to disable.
*/
static inline void twaifd_ll_enable_filter_mode(twaifd_dev_t* hw, bool enable)
{
// Must be called when hardware is disabled.
HAL_ASSERT(hw->mode_settings.ena == 0);
hw->mode_settings.afm = enable;
}
/**
* @brief Set remote frame filtering behaviour.
*
* @param hw Pointer to hardware structure.
* @param en True to drop, false to Receive to next filter
*/
static inline void twaifd_ll_filter_block_rtr(twaifd_dev_t* hw, bool en)
{
hw->mode_settings.fdrf = en;
}
/**
* @brief Enable or disable the time-triggered transmission mode for the TWAI-FD peripheral.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param enable Set to true to enable time-triggered transmission mode, false to disable.
*/
static inline void twaifd_ll_enable_time_trig_trans_mode(twaifd_dev_t* hw, bool enable)
{
hw->mode_settings.tttm = enable;
}
/* --------------------------- Command Register ----------------------------- */
/**
* @brief Set command to TWAIFD hardware
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param commands command code refer to `TWAIFD_LL_HW_CMD_`.
*/
static inline void twaifd_ll_set_operate_cmd(twaifd_dev_t *hw, uint32_t commands)
{
hw->command.val = commands;
while (hw->command.val & commands);
}
/* -------------------------- Interrupt Register ---------------------------- */
/**
* @brief Set which interrupts are enabled
*
* @param hw Start address of the TWAI registers
* @param intr_mask mask of interrupts to enable
*/
static inline void twaifd_ll_enable_intr(twaifd_dev_t *hw, uint32_t intr_mask)
{
hw->int_ena_set.val = intr_mask;
hw->int_ena_clr.val = ~intr_mask;
}
/**
* @brief Get the interrupt status of the TWAI-FD peripheral.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @return The current interrupt status as a 32-bit value, used with `TWAIFD_LL_INTR_`.
*/
__attribute__((always_inline))
static inline uint32_t twaifd_ll_get_intr_status(twaifd_dev_t *hw)
{
return hw->int_stat.val;
}
/**
* @brief Clear the specified interrupt status of the TWAI-FD peripheral.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param intr_mask The interrupt mask specifying which interrupts to clear.
*/
__attribute__((always_inline))
static inline void twaifd_ll_clr_intr_status(twaifd_dev_t *hw, uint32_t intr_mask)
{
// this register is write to clear
hw->int_stat.val = intr_mask;
}
/* ------------------------ 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
*
* @param hw Start address of the TWAI registers
* @param timing_param timing params
*/
static inline void twaifd_ll_set_nominal_bitrate(twaifd_dev_t *hw, const twai_timing_advanced_config_t *timing_param)
{
twaifd_btr_reg_t reg_w = {.val = 0};
HAL_FORCE_MODIFY_U32_REG_FIELD(reg_w, brp, timing_param->brp);
reg_w.prop = timing_param->prop_seg;
reg_w.ph1 = timing_param->tseg_1;
reg_w.ph2 = timing_param->tseg_2;
reg_w.sjw = timing_param->sjw;
hw->btr.val = reg_w.val;
}
/**
* @brief Set bus timing for FD data section bit rate
*
* @param hw Start address of the TWAI registers
* @param timing_param_fd FD timing params
*/
static inline void twaifd_ll_set_fd_bitrate(twaifd_dev_t *hw, const twai_timing_advanced_config_t *timing_param_fd)
{
twaifd_btr_fd_reg_t reg_w = {.val = 0};
HAL_FORCE_MODIFY_U32_REG_FIELD(reg_w, brp_fd, timing_param_fd->brp);
reg_w.prop_fd = timing_param_fd->prop_seg;
reg_w.ph1_fd = timing_param_fd->tseg_1;
reg_w.ph2_fd = timing_param_fd->tseg_2;
reg_w.sjw_fd = timing_param_fd->sjw;
hw->btr_fd.val = reg_w.val;
}
/**
* @brief Secondary Sample Point (SSP) config for data bitrate
*
* @param hw Start address of the TWAI registers
* @param ssp_src_code Secondary point mode config, see TWAIFD_LL_SSP_SRC_xxx.
* @param offset_val Secondary sampling point position is configured as delay from Sync_Seg in multiples of System clock
*/
static inline void twaifd_ll_config_secondary_sample_point(twaifd_dev_t *hw, uint8_t ssp_src_code, uint8_t offset_val)
{
hw->trv_delay_ssp_cfg.ssp_src = ssp_src_code;
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->trv_delay_ssp_cfg, ssp_offset, offset_val);
}
/* ----------------------------- ERR Capt Register ------------------------------- */
/**
* @brief Get the error reason flags from the TWAI-FD peripheral.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @return The error reasons, see `twai_error_flags_t`
*/
__attribute__((always_inline))
static inline twai_error_flags_t twaifd_ll_get_err_reason(twaifd_dev_t *hw)
{
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 ------------------------------- */
// this func can only use in TWAIFD_MODE_TEST, and 'mode_settings.ena' must be zero
static inline void twaifd_ll_set_err_warn_limit(twaifd_dev_t *hw, uint32_t ewl)
{
HAL_ASSERT(hw->mode_settings.tstm);
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->ewl_erp_fault_state, ew_limit, ewl);
}
/**
* @brief Get Error Warning Limit
*
* @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);
}
/**
* @brief Get the current fault state of the TWAI-FD peripheral.
*
* @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) {
return TWAI_ERROR_BUS_OFF;
}
if (hw->ewl_erp_fault_state.erp) {
return TWAI_ERROR_PASSIVE;
}
return TWAI_ERROR_ACTIVE;
}
/**
* @brief Get the error count in normal mode for the TWAI-FD peripheral.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @return Error count in normal mode.
*/
static inline uint32_t twaifd_ll_get_err_count_norm(twaifd_dev_t *hw)
{
return HAL_FORCE_READ_U32_REG_FIELD(hw->err_norm_err_fd, err_norm_val);
}
/**
* @brief Get the error count in FD mode for the TWAI-FD peripheral.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @return Error count in FD mode.
*/
static inline uint32_t twaifd_ll_get_err_count_fd(twaifd_dev_t *hw)
{
return HAL_FORCE_READ_U32_REG_FIELD(hw->err_norm_err_fd, err_fd_val);
}
/* ------------------------ RX Error Count Register ------------------------- */
/**
* @brief Get RX Error Counter
*
* @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;
}
/* ------------------------ TX Error Count Register ------------------------- */
/**
* @brief Get TX Error Counter
*
* @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;
}
/* ---------------------- Acceptance Filter Registers ----------------------- */
/**
* @brief Enable or disable filter to receive basic frame with std id
*
* @param hw Pointer to the TWAI FD hardware instance
* @param filter_id The unique ID of the filter to configure
* @param is_range Setting for range filter or mask filter
* @param en True to receive, False to drop
*/
static inline void twaifd_ll_filter_enable_basic_std(twaifd_dev_t* hw, uint8_t filter_id, bool is_range, bool en)
{
HAL_ASSERT(filter_id < (is_range ? SOC_TWAI_RANGE_FILTER_NUM : SOC_TWAI_MASK_FILTER_NUM));
// The hw_filter_id of range_filter is indexed after mask_filter
uint8_t hw_filter_id = is_range ? filter_id + SOC_TWAI_MASK_FILTER_NUM : filter_id;
if (en) {
hw->filter_control_filter_status.val |= TWAIFD_FANB << (hw_filter_id * TWAIFD_FBNB_S);
} else {
hw->filter_control_filter_status.val &= ~(TWAIFD_FANB << (hw_filter_id * TWAIFD_FBNB_S));
}
}
/**
* @brief Enable or disable filter to receive basic frame with ext id
*
* @param hw Pointer to the TWAI FD hardware instance
* @param filter_id The unique ID of the filter to configure
* @param is_range Setting for range filter or mask filter
* @param en True to receive, False to drop
*/
static inline void twaifd_ll_filter_enable_basic_ext(twaifd_dev_t* hw, uint8_t filter_id, bool is_range, bool en)
{
HAL_ASSERT(filter_id < (is_range ? SOC_TWAI_RANGE_FILTER_NUM : SOC_TWAI_MASK_FILTER_NUM));
// The hw_filter_id of range_filter is indexed after mask_filter
uint8_t hw_filter_id = is_range ? filter_id + SOC_TWAI_MASK_FILTER_NUM : filter_id;
if (en) {
hw->filter_control_filter_status.val |= TWAIFD_FANE << (hw_filter_id * TWAIFD_FBNB_S);
} else {
hw->filter_control_filter_status.val &= ~(TWAIFD_FANE << (hw_filter_id * TWAIFD_FBNB_S));
}
}
/**
* @brief Enable or disable filter to receive fd frame with std id
*
* @param hw Pointer to the TWAI FD hardware instance
* @param filter_id The unique ID of the filter to configure
* @param is_range Setting for range filter or mask filter
* @param en True to receive, False to drop
*/
static inline void twaifd_ll_filter_enable_fd_std(twaifd_dev_t* hw, uint8_t filter_id, bool is_range, bool en)
{
HAL_ASSERT(filter_id < (is_range ? SOC_TWAI_RANGE_FILTER_NUM : SOC_TWAI_MASK_FILTER_NUM));
// The hw_filter_id of range_filter is indexed after mask_filter
uint8_t hw_filter_id = is_range ? filter_id + SOC_TWAI_MASK_FILTER_NUM : filter_id;
if (en) {
hw->filter_control_filter_status.val |= TWAIFD_FAFB << (hw_filter_id * TWAIFD_FBNB_S);
} else {
hw->filter_control_filter_status.val &= ~(TWAIFD_FAFB << (hw_filter_id * TWAIFD_FBNB_S));
}
}
/**
* @brief Enable or disable filter to receive fd frame with ext id
*
* @param hw Pointer to the TWAI FD hardware instance
* @param filter_id The unique ID of the filter to configure
* @param is_range Setting for range filter or mask filter
* @param en True to receive, False to drop
*/
static inline void twaifd_ll_filter_enable_fd_ext(twaifd_dev_t* hw, uint8_t filter_id, bool is_range, bool en)
{
HAL_ASSERT(filter_id < (is_range ? SOC_TWAI_RANGE_FILTER_NUM : SOC_TWAI_MASK_FILTER_NUM));
// The hw_filter_id of range_filter is indexed after mask_filter
uint8_t hw_filter_id = is_range ? filter_id + SOC_TWAI_MASK_FILTER_NUM : filter_id;
if (en) {
hw->filter_control_filter_status.val |= TWAIFD_FAFE << (hw_filter_id * TWAIFD_FBNB_S);
} else {
hw->filter_control_filter_status.val &= ~(TWAIFD_FAFE << (hw_filter_id * TWAIFD_FBNB_S));
}
}
/**
* @brief Set Bit Acceptance Filter
* @param hw Start address of the TWAI registers
* @param filter_id Filter number id
* @param is_ext Filter for ext_id or std_id
* @param code Acceptance Code
* @param mask Acceptance Mask
*/
static inline void twaifd_ll_filter_set_id_mask(twaifd_dev_t* hw, uint8_t filter_id, bool is_ext, uint32_t code, uint32_t mask)
{
hw->mask_filters[filter_id].filter_mask.bit_mask_val = is_ext ? mask : (mask << TWAIFD_IDENTIFIER_BASE_S);
hw->mask_filters[filter_id].filter_val.bit_val = is_ext ? code : (code << TWAIFD_IDENTIFIER_BASE_S);
}
/**
* @brief Set Range Acceptance Filter
* @param hw Start address of the TWAI registers
* @param filter_id Filter number id
* @param is_ext Filter for ext_id or std_id
* @param high The id range high limit
* @param low The id range low limit
*/
static inline void twaifd_ll_filter_set_range(twaifd_dev_t* hw, uint8_t filter_id, bool is_ext, uint32_t high, uint32_t low)
{
hw->range_filters[filter_id].ran_low.bit_ran_low_val = is_ext ? low : (low << TWAIFD_IDENTIFIER_BASE_S);
hw->range_filters[filter_id].ran_high.bit_ran_high_val = is_ext ? high : (high << TWAIFD_IDENTIFIER_BASE_S);
}
/* ------------------------- TX Buffer Registers ------------------------- */
/**
* @brief Get the number of TX buffers available.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @return The number of TX buffers available.
*/
static inline uint32_t twaifd_ll_get_tx_buffer_quantity(twaifd_dev_t *hw)
{
return hw->tx_command_txtb_info.txt_buffer_count;
}
/**
* @brief Get the status of a specific TX buffer.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param buffer_idx Index of the TX buffer (0-7).
* @return The status of the selected TX buffer.
*/
static inline uint32_t twaifd_ll_get_tx_buffer_status(twaifd_dev_t *hw, uint8_t buffer_idx)
{
HAL_ASSERT(buffer_idx < twaifd_ll_get_tx_buffer_quantity(hw)); // Ensure buffer index is valid
uint32_t reg_val = hw->tx_status.val;
return reg_val & (TWAIFD_TX2S_V << (TWAIFD_TX2S_S * buffer_idx)); // Get status for buffer
}
/**
* @brief Set TX Buffer command
*
* Setting the TX command will cause the TWAI controller to attempt to transmit
* the frame stored in the TX buffer. The TX buffer will be occupied (i.e.,
* locked) until TX completes.
*
* @param hw Start address of the TWAI registers
* @param buffer_idx
* @param cmd The command want to set, see `TWAIFD_LL_TX_CMD_`
*/
__attribute__((always_inline))
static inline void twaifd_ll_set_tx_cmd(twaifd_dev_t *hw, uint8_t buffer_idx, uint32_t cmd)
{
hw->tx_command_txtb_info.val = (cmd | BIT(buffer_idx + TWAIFD_TXB1_S));
}
/**
* @brief Set the priority for a specific TX buffer.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param buffer_idx Index of the TX buffer (0-7).
* @param priority The priority level to set for the buffer.
*/
static inline void twaifd_ll_set_tx_buffer_priority(twaifd_dev_t *hw, uint8_t buffer_idx, uint32_t priority)
{
HAL_ASSERT(buffer_idx < twaifd_ll_get_tx_buffer_quantity(hw)); // Ensure buffer index is valid
uint32_t reg_val = hw->tx_priority.val;
reg_val &= ~(TWAIFD_TXT1P_V << (TWAIFD_TXT2P_S * buffer_idx)); // Clear old priority
reg_val |= priority << (TWAIFD_TXT2P_S * buffer_idx); // Set new priority
hw->tx_priority.val = reg_val;
}
/**
* @brief Copy a formatted TWAI frame into TX buffer for transmission
*
* @param hw Start address of the TWAI registers
* @param tx_frame Pointer to formatted frame
* @param buffer_idx The tx buffer index to copy in
*
* @note Call twaifd_ll_format_frame_header() and twaifd_ll_format_frame_data() to format a frame
*/
__attribute__((always_inline))
static inline void twaifd_ll_mount_tx_buffer(twaifd_dev_t *hw, twaifd_frame_buffer_t *tx_frame, uint8_t buffer_idx)
{
//Copy formatted frame into TX buffer
for (int i = 0; i < sizeof(twaifd_frame_buffer_t) / sizeof(uint32_t); i++) {
hw->txt_mem_cell[buffer_idx].txt_buffer.words[i] = tx_frame->words[i];
}
}
/* ------------------------- RX Buffer Registers ------------------------- */
/**
* @brief Get the size of the RX buffer.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @return Size of the RX buffer.
*/
static inline uint32_t twaifd_ll_get_rx_buffer_size(twaifd_dev_t *hw)
{
return hw->rx_mem_info.rx_buff_size;
}
/**
* @brief Get the number of frames in the RX buffer.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @return Number of frames in the RX buffer.
*/
__attribute__((always_inline))
static inline uint32_t twaifd_ll_get_rx_frame_count(twaifd_dev_t *hw)
{
return hw->rx_status_rx_settings.rxfrc;
}
/**
* @brief Check if the RX FIFO is empty.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @return 1 if RX FIFO is empty, 0 otherwise.
*/
static inline uint32_t twaifd_ll_is_rx_buffer_empty(twaifd_dev_t *hw)
{
return hw->rx_status_rx_settings.rxe;
}
/**
* @brief Copy a received frame from the RX buffer for parsing
*
* @param hw Start address of the TWAI registers
* @param rx_frame Pointer to store formatted frame
*
* @note Call twaifd_ll_parse_frame_header() and twaifd_ll_parse_frame_data() to parse the formatted frame
*/
__attribute__((always_inline))
static inline void twaifd_ll_get_rx_frame(twaifd_dev_t *hw, twaifd_frame_buffer_t *rx_frame)
{
// If rx_automatic_mode enabled, hw->rx_data.rx_data should 32bit access
rx_frame->words[0] = hw->rx_data.rx_data;
for (uint8_t i = 1; i <= rx_frame->format.rwcnt; i++) {
rx_frame->words[i] = hw->rx_data.rx_data;
}
HAL_ASSERT(!hw->rx_status_rx_settings.rxmof);
}
/* ------------------------- TWAIFD frame ------------------------- */
/**
* @brief Format contents of a TWAI frame header into layout of TX Buffer
*
* This function encodes a message into a frame structure. The frame structure
* has an identical layout to the TX buffer, allowing the frame structure to be
* directly copied into hardware.
*
* @param[in] header Including DLC, ID, Format, etc.
* @param[in] final_dlc data length code of frame.
* @param[out] tx_frame Pointer to store formatted frame
*/
__attribute__((always_inline))
static inline void twaifd_ll_format_frame_header(const twai_frame_header_t *header, uint8_t final_dlc, twaifd_frame_buffer_t *tx_frame)
{
HAL_ASSERT(final_dlc <= TWAIFD_FRAME_MAX_DLC);
//Set frame information
tx_frame->format.ide = header->ide;
tx_frame->format.rtr = header->rtr;
tx_frame->format.fdf = header->fdf;
tx_frame->format.brs = header->brs;
tx_frame->format.dlc = final_dlc;
tx_frame->timestamp_low = header->timestamp;
tx_frame->timestamp_high = header->timestamp >> 32;
if (tx_frame->format.ide) {
tx_frame->identifier.val = (header->id & TWAI_EXT_ID_MASK);
} else {
tx_frame->identifier.identifier_base = (header->id & TWAI_STD_ID_MASK);
}
}
/**
* @brief Format contents of a TWAI data into layout of TX Buffer
*
* This function encodes a message into a frame structure. The frame structure
* has an identical layout to the TX buffer, allowing the frame structure to be
* directly copied into hardware.
*
* @param[in] buffer Pointer to an 8 byte array containing data.
* @param[in] len data length of data buffer.
* @param[out] tx_frame Pointer to store formatted frame
*/
__attribute__((always_inline))
static inline void twaifd_ll_format_frame_data(const uint8_t *buffer, uint32_t len, twaifd_frame_buffer_t *tx_frame)
{
HAL_ASSERT(len <= TWAIFD_FRAME_MAX_LEN);
memcpy(tx_frame->data, buffer, len);
}
/**
* @brief Parse formatted TWAI frame header (RX Buffer Layout) into its constituent contents
*
* @param[in] rx_frame Pointer to formatted frame
* @param[out] p_frame_header Including DLC, ID, Format, etc.
*/
__attribute__((always_inline))
static inline void twaifd_ll_parse_frame_header(const twaifd_frame_buffer_t *rx_frame, twai_frame_header_t *p_frame_header)
{
//Copy frame information
p_frame_header->ide = rx_frame->format.ide;
p_frame_header->rtr = rx_frame->format.rtr;
p_frame_header->fdf = rx_frame->format.fdf;
p_frame_header->brs = rx_frame->format.brs;
p_frame_header->esi = rx_frame->format.esi;
p_frame_header->dlc = rx_frame->format.dlc;
p_frame_header->timestamp = rx_frame->timestamp_high;
p_frame_header->timestamp <<= 32;
p_frame_header->timestamp |= rx_frame->timestamp_low;
if (p_frame_header->ide) {
p_frame_header->id = (rx_frame->identifier.val & TWAI_EXT_ID_MASK);
} else {
// No check with 'TWAI_STD_ID_MASK' again due to register `identifier_base` already 11 bits len
p_frame_header->id = rx_frame->identifier.identifier_base;
}
}
/**
* @brief Parse formatted TWAI data (RX Buffer Layout) into data buffer
*
* @param[in] rx_frame Pointer to formatted frame
* @param[out] buffer Pointer to an 8 byte array to save data
* @param[in] buffer_len_limit The buffer length limit, If less then frame data length, over length data will dropped
*/
__attribute__((always_inline))
static inline void twaifd_ll_parse_frame_data(const twaifd_frame_buffer_t *rx_frame, uint8_t *buffer, int len_limit)
{
memcpy(buffer, rx_frame->data, len_limit);
}
/* ------------------------- Tx Rx traffic counters Register ------------------------- */
/**
* @brief Get RX Message Counter
*
* @param hw Start address of the TWAI registers
* @return RX Message Counter
*/
static inline uint32_t twaifd_ll_get_rx_traffic_counter(twaifd_dev_t *hw)
{
return hw->rx_fr_ctr.val;
}
/**
* @brief Get TX Message Counter
*
* @param hw Start address of the TWAI registers
* @return TX Message Counter
*/
static inline uint32_t twaifd_ll_get_tx_traffic_counter(twaifd_dev_t *hw)
{
return hw->tx_fr_ctr.val;
}
/* ------------------------- Timestamp Register ------------------------- */
/**
* @brief Enable or disable the timer clock.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param enable True to enable, false to disable.
*/
static inline void twaifd_ll_timer_enable_clock(twaifd_dev_t *hw, bool enable)
{
hw->timer_clk_en.clk_en = enable;
}
/**
* @brief Enable or disable timer power.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param enable True to enable, false to disable.
*/
static inline void twaifd_ll_timer_enable(twaifd_dev_t *hw, bool enable)
{
hw->timer_cfg.timer_ce = enable;
}
/**
* @brief Set the timer step value.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param step Step value to set (actual step = step - 1).
*/
static inline void twaifd_ll_timer_set_step(twaifd_dev_t *hw, uint32_t step)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->timer_cfg, timer_step, (step - 1));
}
/**
* @brief Set timer mode to up or down counter.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param up True for up counter, false for down counter.
*/
static inline void twaifd_ll_timer_set_direction(twaifd_dev_t *hw, bool up)
{
hw->timer_cfg.timer_up_dn = up;
}
/**
* @brief Clear or reset the timer count.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param clear True to clear count, false to set count.
*/
static inline void twaifd_ll_timer_clr_count(twaifd_dev_t *hw, bool clear)
{
hw->timer_cfg.timer_clr = clear;
}
/**
* @brief Set the timer preload value.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param load_value 64-bit load value.
*/
static inline void twaifd_ll_timer_set_preload_value(twaifd_dev_t *hw, uint64_t load_value)
{
hw->timer_ld_val_h.val = (uint32_t)(load_value >> 32);
hw->timer_ld_val_l.val = (uint32_t) load_value;
}
/**
* @brief Apply preload value
*
* @param hw Pointer to the TWAI-FD device hardware.
*/
static inline void twaifd_ll_timer_apply_preload_value(twaifd_dev_t *hw)
{
hw->timer_cfg.timer_set = 1;
}
/**
* @brief Set the timer alarm value.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @param alarm_value 64-bit alarm value.
*/
static inline void twaifd_ll_timer_set_alarm_value(twaifd_dev_t *hw, uint64_t alarm_value)
{
hw->timer_ct_val_h.val = (uint32_t)(alarm_value >> 32);
hw->timer_ct_val_l.val = (uint32_t) alarm_value;
}
/**
* @brief Enable or disable timer interrupt by mask.
*
* @param hw Timer Group register base address
* @param mask Mask of interrupt events
* @param en True: enable interrupt
* False: disable interrupt
*/
static inline void twaifd_ll_timer_enable_intr(twaifd_dev_t *hw, uint32_t mask, bool en)
{
if (en) {
hw->timer_int_ena.val |= mask;
} else {
hw->timer_int_ena.val &= ~mask;
}
}
/**
* @brief Get the current timer interrupt status.
*
* @param hw Pointer to the TWAI-FD device hardware.
* @return Current interrupt status.
*/
static inline uint32_t twaifd_ll_timer_get_intr_status(twaifd_dev_t *hw, uint32_t mask)
{
return hw->timer_int_st.val & mask;
}
/**
* @brief Clear specific timer interrupts.
*
* @param hw Pointer to the TWAI-FD device hardware.
*/
static inline void twaifd_ll_timer_clr_intr_status(twaifd_dev_t *hw, uint32_t mask)
{
hw->timer_int_clr.val = mask;
}
#ifdef __cplusplus
}
#endif

View File

@@ -149,12 +149,18 @@ ESP_STATIC_ASSERT(sizeof(twai_ll_frame_buffer_t) == 13, "TX/RX buffer type shoul
*/
static inline void twai_ll_enable_bus_clock(int group_id, bool enable)
{
switch (group_id)
{
case 0: HP_SYS_CLKRST.soc_clk_ctrl2.reg_twai0_apb_clk_en = enable; break;
case 1: HP_SYS_CLKRST.soc_clk_ctrl2.reg_twai1_apb_clk_en = enable; break;
case 2: HP_SYS_CLKRST.soc_clk_ctrl2.reg_twai2_apb_clk_en = enable; break;
default: HAL_ASSERT(false);
switch (group_id) {
case 0:
HP_SYS_CLKRST.soc_clk_ctrl2.reg_twai0_apb_clk_en = enable;
break;
case 1:
HP_SYS_CLKRST.soc_clk_ctrl2.reg_twai1_apb_clk_en = enable;
break;
case 2:
HP_SYS_CLKRST.soc_clk_ctrl2.reg_twai2_apb_clk_en = enable;
break;
default:
HAL_ASSERT(false);
}
}
@@ -172,17 +178,19 @@ static inline void twai_ll_enable_bus_clock(int group_id, bool enable)
*/
static inline void twai_ll_reset_register(int group_id)
{
switch (group_id)
{
case 0: HP_SYS_CLKRST.hp_rst_en1.reg_rst_en_twai0 = 1;
HP_SYS_CLKRST.hp_rst_en1.reg_rst_en_twai0 = 0;
break;
case 1: HP_SYS_CLKRST.hp_rst_en1.reg_rst_en_twai1 = 1;
HP_SYS_CLKRST.hp_rst_en1.reg_rst_en_twai1 = 0;
break;
case 2: HP_SYS_CLKRST.hp_rst_en1.reg_rst_en_twai2 = 1;
HP_SYS_CLKRST.hp_rst_en1.reg_rst_en_twai2 = 0;
break;
switch (group_id) {
case 0:
HP_SYS_CLKRST.hp_rst_en1.reg_rst_en_twai0 = 1;
HP_SYS_CLKRST.hp_rst_en1.reg_rst_en_twai0 = 0;
break;
case 1:
HP_SYS_CLKRST.hp_rst_en1.reg_rst_en_twai1 = 1;
HP_SYS_CLKRST.hp_rst_en1.reg_rst_en_twai1 = 0;
break;
case 2:
HP_SYS_CLKRST.hp_rst_en1.reg_rst_en_twai2 = 1;
HP_SYS_CLKRST.hp_rst_en1.reg_rst_en_twai2 = 0;
break;
default: HAL_ASSERT(false);
}
}
@@ -229,21 +237,23 @@ static inline void twai_ll_enable_clock(int group_id, bool en)
__attribute__((always_inline))
static inline void twai_ll_set_clock_source(int group_id, twai_clock_source_t clk_src)
{
// We do not plan to support the TWAI_CLK_SRC_RC_FAST clock source,
// as the accuracy of this clock does not meet the requirements for the baud rate
HAL_ASSERT(clk_src == TWAI_CLK_SRC_XTAL);
uint32_t clk_id = 0;
switch (clk_src) {
case TWAI_CLK_SRC_XTAL: clk_id = 0; break;
#if SOC_CLK_TREE_SUPPORTED
case TWAI_CLK_SRC_RC_FAST: clk_id = 1; break;
#endif
default: HAL_ASSERT(false);
}
switch (group_id) {
case 0: HP_SYS_CLKRST.peri_clk_ctrl115.reg_twai0_clk_src_sel = clk_id; break;
case 1: HP_SYS_CLKRST.peri_clk_ctrl115.reg_twai1_clk_src_sel = clk_id; break;
case 2: HP_SYS_CLKRST.peri_clk_ctrl115.reg_twai2_clk_src_sel = clk_id; break;
default: HAL_ASSERT(false);
case 0:
HP_SYS_CLKRST.peri_clk_ctrl115.reg_twai0_clk_src_sel = clk_id;
break;
case 1:
HP_SYS_CLKRST.peri_clk_ctrl115.reg_twai1_clk_src_sel = clk_id;
break;
case 2:
HP_SYS_CLKRST.peri_clk_ctrl115.reg_twai2_clk_src_sel = clk_id;
break;
default:
HAL_ASSERT(false);
}
}
@@ -554,9 +564,9 @@ __attribute__((always_inline))
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->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);
*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 ------------------------------- */

View File

@@ -7,16 +7,16 @@
#include "soc/twai_periph.h"
#include "soc/gpio_sig_map.h"
const twai_signal_conn_t twai_periph_signals[SOC_TWAI_CONTROLLER_NUM] = {
const twai_signal_conn_t twai_periph_signals[2] = {
[0] = {
.module_name = "TWAI0",
.irq_id = ETS_TWAI0_INTR_SOURCE,
.timer_irq_id = ETS_TWAI0_TIMER_INTR_SOURCE,
.tx_sig = TWAI0_TX_IDX,
.rx_sig = TWAI0_RX_IDX,
.bus_off_sig = TWAI0_BUS_OFF_ON_IDX,
.clk_out_sig = TWAI0_CLKOUT_IDX,
.stand_by_sig = TWAI0_STANDBY_IDX,
.bus_off_sig = -1,
.clk_out_sig = -1,
.stand_by_sig = -1,
},
[1] = {
.module_name = "TWAI1",
@@ -24,8 +24,8 @@ const twai_signal_conn_t twai_periph_signals[SOC_TWAI_CONTROLLER_NUM] = {
.timer_irq_id = ETS_TWAI1_TIMER_INTR_SOURCE,
.tx_sig = TWAI1_TX_IDX,
.rx_sig = TWAI1_RX_IDX,
.bus_off_sig = TWAI1_BUS_OFF_ON_IDX,
.clk_out_sig = TWAI1_CLKOUT_IDX,
.stand_by_sig = TWAI1_STANDBY_IDX,
.bus_off_sig = -1,
.clk_out_sig = -1,
.stand_by_sig = -1,
},
};

View File

@@ -19,6 +19,10 @@ config SOC_GPTIMER_SUPPORTED
bool
default y
config SOC_TWAI_SUPPORTED
bool
default y
config SOC_ETM_SUPPORTED
bool
default y
@@ -695,6 +699,42 @@ config SOC_MWDT_SUPPORT_XTAL
bool
default y
config SOC_TWAI_CONTROLLER_NUM
int
default 1
config SOC_TWAI_MASK_FILTER_NUM
int
default 3
config SOC_TWAI_RANGE_FILTER_NUM
int
default 1
config SOC_TWAI_BRP_MIN
int
default 1
config SOC_TWAI_BRP_MAX
int
default 255
config SOC_TWAI_CLK_SUPPORT_XTAL
bool
default y
config SOC_TWAI_SUPPORTS_RX_STATUS
bool
default y
config SOC_TWAI_SUPPORT_FD
bool
default y
config SOC_TWAI_SUPPORT_TIMESTAMP
bool
default y
config SOC_EFUSE_DIS_DOWNLOAD_ICACHE
bool
default n

View File

@@ -355,6 +355,22 @@ typedef enum {
SDM_CLK_SRC_DEFAULT = SOC_MOD_CLK_PLL_F48M, /*!< Select PLL_F48M clock as the default clock choice */
} soc_periph_sdm_clk_src_t;
//////////////////////////////////////////////////TWAI//////////////////////////////////////////////////////////////////
/**
* @brief Array initializer for all supported clock sources of TWAI
*/
#define SOC_TWAI_CLKS {(soc_periph_twai_clk_src_t)SOC_MOD_CLK_XTAL, (soc_periph_twai_clk_src_t)SOC_MOD_CLK_PLL_F96M}
/**
* @brief TWAI clock source
*/
typedef enum {
TWAI_CLK_SRC_XTAL = SOC_MOD_CLK_XTAL, /*!< Select XTAL as the source clock */
TWAI_CLK_SRC_PLL_F96M = SOC_MOD_CLK_PLL_F96M, /*!< Select PLL_96M as the source clock */
TWAI_CLK_SRC_DEFAULT = SOC_MOD_CLK_PLL_F96M, /*!< Select PLL_96M as the default clock choice */
} soc_periph_twai_clk_src_t;
#ifdef __cplusplus
}
#endif

View File

@@ -40,7 +40,7 @@
#define SOC_GPTIMER_SUPPORTED 1
// #define SOC_PCNT_SUPPORTED 1 // TODO: [ESP32H4] IDF-12338
// #define SOC_MCPWM_SUPPORTED 1 // TODO: [ESP32H4] IDF-12380
// #define SOC_TWAI_SUPPORTED 1 // TODO: [ESP32H4] IDF-12352
#define SOC_TWAI_SUPPORTED 1
#define SOC_ETM_SUPPORTED 1
// #define SOC_PARLIO_SUPPORTED 1 // TODO: [ESP32H4] IDF-12345 IDF-12347
// #define SOC_BT_SUPPORTED 1
@@ -450,11 +450,15 @@
#define SOC_MWDT_SUPPORT_XTAL (1)
/*-------------------------- TWAI CAPS ---------------------------------------*/
// #define SOC_TWAI_CONTROLLER_NUM 2
// #define SOC_TWAI_CLK_SUPPORT_XTAL 1
// #define SOC_TWAI_BRP_MIN 2
// #define SOC_TWAI_BRP_MAX 32768
// #define SOC_TWAI_SUPPORTS_RX_STATUS 1
#define SOC_TWAI_CONTROLLER_NUM 1U
#define SOC_TWAI_MASK_FILTER_NUM 3
#define SOC_TWAI_RANGE_FILTER_NUM 1U
#define SOC_TWAI_BRP_MIN 1U
#define SOC_TWAI_BRP_MAX 255
#define SOC_TWAI_CLK_SUPPORT_XTAL 1
#define SOC_TWAI_SUPPORTS_RX_STATUS 1
#define SOC_TWAI_SUPPORT_FD 1
#define SOC_TWAI_SUPPORT_TIMESTAMP 1
/*-------------------------- eFuse CAPS----------------------------*/
#define SOC_EFUSE_DIS_DOWNLOAD_ICACHE 0

View File

@@ -1299,107 +1299,39 @@ typedef union {
/** Group: filter register */
/** Type of filter_a_mask register
* TWAI FD filter A mask value register
/** Type of filter_mask register
* TWAI FD filter mask value register
*/
typedef union {
struct {
/** bit_mask_a_val : R/W; bitpos: [28:0]; default: 0;
* Filter A mask. The identifier format is the same as in IDENTIFIER_W of TXT buffer
/** bit_mask_val : R/W; bitpos: [28:0]; default: 0;
* Filter mask. The identifier format is the same as in IDENTIFIER_W of TXT buffer
* or RX
* buffer. If filter A is not present, writes to this register have no effect and read
* buffer. If filter is not present, writes to this register have no effect and read
* will return all zeroes.
*/
uint32_t bit_mask_a_val:29;
uint32_t bit_mask_val:29;
uint32_t reserved_29:3;
};
uint32_t val;
} twaifd_filter_a_mask_reg_t;
} twaifd_filter_mask_reg_t;
/** Type of filter_a_val register
* TWAI FD filter A bit value register
/** Type of filter_val register
* TWAI FD filter bit value register
*/
typedef union {
struct {
/** bit_val_a_val : R/W; bitpos: [28:0]; default: 0;
* Filter A value. The identifier format is the same as in IDENTIFIER_W of TXT buffer
/** bit_val : R/W; bitpos: [28:0]; default: 0;
* Filter value. The identifier format is the same as in IDENTIFIER_W of TXT buffer
* or RX buffer.
* If filter A is not present, writes to this register have no effect and read will
* If filter is not present, writes to this register have no effect and read will
* return all zeroes.
*/
uint32_t bit_val_a_val:29;
uint32_t bit_val:29;
uint32_t reserved_29:3;
};
uint32_t val;
} twaifd_filter_a_val_reg_t;
/** Type of filter_b_mask register
* TWAI FD filter B mask value register
*/
typedef union {
struct {
/** bit_mask_b_val : R/W; bitpos: [28:0]; default: 0;
* Filter B mask. The identifier format is the same as in IDENTIFIER_W of TXT buffer
* or RX
* buffer. If filter A is not present, writes to this register have no effect and read
* will return all zeroes.
*/
uint32_t bit_mask_b_val:29;
uint32_t reserved_29:3;
};
uint32_t val;
} twaifd_filter_b_mask_reg_t;
/** Type of filter_b_val register
* TWAI FD filter B bit value register
*/
typedef union {
struct {
/** bit_val_b_val : R/W; bitpos: [28:0]; default: 0;
* Filter B value. The identifier format is the same as in IDENTIFIER_W of TXT buffer
* or RX buffer.
* If filter A is not present, writes to this register have no effect and read will
* return all zeroes.
*/
uint32_t bit_val_b_val:29;
uint32_t reserved_29:3;
};
uint32_t val;
} twaifd_filter_b_val_reg_t;
/** Type of filter_c_mask register
* TWAI FD filter C mask value register
*/
typedef union {
struct {
/** bit_mask_c_val : R/W; bitpos: [28:0]; default: 0;
* Filter C mask. The identifier format is the same as in IDENTIFIER_W of TXT buffer
* or RX
* buffer. If filter A is not present, writes to this register have no effect and read
* will return all zeroes.
*/
uint32_t bit_mask_c_val:29;
uint32_t reserved_29:3;
};
uint32_t val;
} twaifd_filter_c_mask_reg_t;
/** Type of filter_c_val register
* TWAI FD filter C bit value register
*/
typedef union {
struct {
/** bit_val_c_val : R/W; bitpos: [28:0]; default: 0;
* Filter C value. The identifier format is the same as in IDENTIFIER_W of TXT buffer
* or RX buffer.
* If filter A is not present, writes to this register have no effect and read will
* return all zeroes.
*/
uint32_t bit_val_c_val:29;
uint32_t reserved_29:3;
};
uint32_t val;
} twaifd_filter_c_val_reg_t;
} twaifd_filter_val_reg_t;
/** Type of filter_ran_low register
* TWAI FD filter range low value register
@@ -1806,8 +1738,65 @@ typedef union {
uint32_t val;
} twaifd_date_ver_reg_t;
/** TWAI bits filter register
*/
typedef struct {
volatile twaifd_filter_mask_reg_t filter_mask;
volatile twaifd_filter_val_reg_t filter_val;
} twaifd_mask_filter_reg_t;
/** TWAI range filter register
*/
typedef struct {
volatile twaifd_filter_ran_low_reg_t ran_low;
volatile twaifd_filter_ran_high_reg_t ran_high;
} twaifd_range_filter_reg_t;
/**
* @brief TWAI frame buffer register types
*/
typedef union twaifd_frame_buffer_t {
struct {
union {
struct {
uint32_t dlc: 4; // Data length code (0-15)
uint32_t reserved4: 1; // Reserved bit
uint32_t rtr: 1; // Remote transmission request
uint32_t ide: 1; // Identifier extension bit
uint32_t fdf: 1; // Flexible data-rate format bit
uint32_t reserved8: 1; // Reserved bit
uint32_t brs: 1; // Bit rate switch flag
uint32_t esi: 1; // Error state indicator
uint32_t rwcnt: 5; // Re-transmission counter
uint32_t reserved16: 16; // Reserved bits
};
uint32_t val; // Complete 32-bit register value for format
} format;
union {
struct {
uint32_t identifier_ext: 18; // Extended identifier (18 bits)
uint32_t identifier_base: 11; // Base identifier (11 bits)
uint32_t reserved29: 3; // Reserved bits
};
uint32_t val; // Complete 32-bit register value for identifier
} identifier;
uint32_t timestamp_low; // Lower 32 bits of timestamp
uint32_t timestamp_high; // Upper 32 bits of timestamp
uint32_t data[16]; // Data payload (16 words)
};
uint32_t words[20]; // Raw 32-bit words for direct access
} twaifd_frame_buffer_t;
/** TWAI frame txt buffer registers
*/
typedef struct {
volatile twaifd_frame_buffer_t txt_buffer;
uint32_t reserved_50[44];
} twaifd_frame_mem_t;
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;
@@ -1823,14 +1812,8 @@ typedef struct {
volatile twaifd_rec_tec_reg_t rec_tec;
volatile twaifd_err_norm_err_fd_reg_t err_norm_err_fd;
volatile twaifd_ctr_pres_reg_t ctr_pres;
volatile twaifd_filter_a_mask_reg_t filter_a_mask;
volatile twaifd_filter_a_val_reg_t filter_a_val;
volatile twaifd_filter_b_mask_reg_t filter_b_mask;
volatile twaifd_filter_b_val_reg_t filter_b_val;
volatile twaifd_filter_c_mask_reg_t filter_c_mask;
volatile twaifd_filter_c_val_reg_t filter_c_val;
volatile twaifd_filter_ran_low_reg_t filter_ran_low;
volatile twaifd_filter_ran_high_reg_t filter_ran_high;
volatile twaifd_mask_filter_reg_t mask_filters[3];
volatile twaifd_range_filter_reg_t range_filters[1];
volatile twaifd_filter_control_filter_status_reg_t filter_control_filter_status;
volatile twaifd_rx_mem_info_reg_t rx_mem_info;
volatile twaifd_rx_pointers_reg_t rx_pointers;
@@ -1847,7 +1830,9 @@ typedef struct {
volatile twaifd_yolo_reg_t yolo;
volatile twaifd_timestamp_low_reg_t timestamp_low;
volatile twaifd_timestamp_high_reg_t timestamp_high;
uint32_t reserved_09c[974];
uint32_t reserved_09c[25];
volatile twaifd_frame_mem_t txt_mem_cell[8];
uint32_t reserved_900[437];
volatile twaifd_timer_clk_en_reg_t timer_clk_en;
volatile twaifd_timer_int_raw_reg_t timer_int_raw;
volatile twaifd_timer_int_st_reg_t timer_int_st;
@@ -1861,7 +1846,7 @@ typedef struct {
volatile twaifd_date_ver_reg_t date_ver;
} twaifd_dev_t;
extern twaifd_dev_t TWAIFD;
extern twaifd_dev_t TWAI0;
#ifndef __cplusplus
_Static_assert(sizeof(twaifd_dev_t) == 0x1000, "Invalid size of twaifd_dev_t structure");

View File

@@ -0,0 +1,21 @@
/*
* SPDX-FileCopyrightText: 2025 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include "soc/twai_periph.h"
#include "soc/gpio_sig_map.h"
const twai_signal_conn_t twai_periph_signals[1] = {
[0] = {
.module_name = "TWAI0",
.irq_id = ETS_TWAI0_INTR_SOURCE,
.timer_irq_id = ETS_TWAI0_TIMER_INTR_SOURCE,
.tx_sig = TWAI0_TX_IDX,
.rx_sig = TWAI0_RX_IDX,
.bus_off_sig = -1,
.clk_out_sig = -1,
.stand_by_sig = -1,
}
};

View File

@@ -605,7 +605,6 @@ typedef enum {
*/
typedef enum {
TWAI_CLK_SRC_XTAL = SOC_MOD_CLK_XTAL, /*!< Select XTAL as the source clock */
TWAI_CLK_SRC_RC_FAST = SOC_MOD_CLK_RC_FAST, /*!< Select RC_FAST as the source clock */
TWAI_CLK_SRC_DEFAULT = SOC_MOD_CLK_XTAL, /*!< Select XTAL as the default clock choice */
} soc_periph_twai_clk_src_t;

View File

@@ -145,7 +145,6 @@ api-reference/peripherals/mcpwm.rst
api-reference/peripherals/usb_host.rst
api-reference/peripherals/camera_driver.rst
api-reference/peripherals/adc_oneshot.rst
api-reference/peripherals/twai.rst
api-reference/peripherals/sdspi_share.rst
api-reference/peripherals/ana_cmpr.rst
api-reference/peripherals/adc_continuous.rst

View File

@@ -1,5 +1,5 @@
| Supported Targets | ESP32 | ESP32-C3 | ESP32-C5 | ESP32-C6 | ESP32-H2 | ESP32-H21 | ESP32-P4 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- | -------- | --------- | -------- | -------- | -------- |
| Supported Targets | ESP32 | ESP32-C3 | ESP32-C5 | ESP32-C6 | ESP32-H2 | ESP32-H21 | ESP32-H4 | ESP32-P4 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- | -------- | --------- | -------- | -------- | -------- | -------- |
# TWAI Bus-Off Recovery Example
This example demonstrates how to recover a TWAI node from a Bus-Off error condition and resume communication. The recovery is triggered by physically inducing bus errors and handled using the ESP TWAI on-chip driver with callback support.

View File

@@ -49,8 +49,12 @@ void app_main(void)
{
twai_node_handle_t node_hdl;
twai_onchip_node_config_t node_config = {
.io_cfg.tx = TX_GPIO_NUM,
.io_cfg.rx = RX_GPIO_NUM,
.io_cfg = {
.tx = TX_GPIO_NUM,
.rx = RX_GPIO_NUM,
.quanta_clk_out = GPIO_NUM_NC,
.bus_off_indicator = GPIO_NUM_NC,
},
.bit_timing.bitrate = TWAI_BITRATE,
.tx_queue_depth = 1,
.flags.enable_self_test = true,

View File

@@ -1,5 +1,5 @@
| Supported Targets | ESP32 | ESP32-C3 | ESP32-C5 | ESP32-C6 | ESP32-H2 | ESP32-H21 | ESP32-P4 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- | -------- | --------- | -------- | -------- | -------- |
| Supported Targets | ESP32 | ESP32-C3 | ESP32-C5 | ESP32-C6 | ESP32-H2 | ESP32-H21 | ESP32-H4 | ESP32-P4 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- | -------- | --------- | -------- | -------- | -------- | -------- |
# TWAI Network Example

View File

@@ -94,8 +94,8 @@ void app_main(void)
.io_cfg = {
.tx = TWAI_LISTENER_TX_GPIO,
.rx = TWAI_LISTENER_RX_GPIO,
.quanta_clk_out = -1,
.bus_off_indicator = -1,
.quanta_clk_out = GPIO_NUM_NC,
.bus_off_indicator = GPIO_NUM_NC,
},
.bit_timing.bitrate = TWAI_BITRATE,
.flags.enable_listen_only = true,

View File

@@ -57,8 +57,8 @@ void app_main(void)
.io_cfg = {
.tx = TWAI_SENDER_TX_GPIO,
.rx = TWAI_SENDER_RX_GPIO,
.quanta_clk_out = -1,
.bus_off_indicator = -1,
.quanta_clk_out = GPIO_NUM_NC,
.bus_off_indicator = GPIO_NUM_NC,
},
.bit_timing = {
.bitrate = TWAI_BITRATE,

View File

@@ -1,5 +1,5 @@
| Supported Targets | ESP32 | ESP32-C3 | ESP32-C5 | ESP32-C6 | ESP32-H2 | ESP32-H21 | ESP32-P4 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- | -------- | --------- | -------- | -------- | -------- |
| Supported Targets | ESP32 | ESP32-C3 | ESP32-C5 | ESP32-C6 | ESP32-H2 | ESP32-H21 | ESP32-H4 | ESP32-P4 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- | -------- | --------- | -------- | -------- | -------- | -------- |
# TWAI Console Example

View File

@@ -644,7 +644,7 @@ def test_twai_range_filters(twai: TwaiTestHelper) -> None:
@pytest.mark.twai_std
@pytest.mark.temp_skip_ci(targets=['esp32c5'], reason='no runner')
@pytest.mark.temp_skip_ci(targets=['esp32c5', 'esp32h4'], reason='no runner')
@idf_parametrize('target', soc_filtered_targets('SOC_TWAI_SUPPORTED == 1'), indirect=['target'])
def test_twai_external_communication(twai: TwaiTestHelper, can_manager: CanBusManager) -> None:
"""