diff --git a/components/driver/test_apps/twai/main/test_twai_loop_back.c b/components/driver/test_apps/twai/main/test_twai_loop_back.c index dccc922305..324114b1f4 100644 --- a/components/driver/test_apps/twai/main/test_twai_loop_back.c +++ b/components/driver/test_apps/twai/main/test_twai_loop_back.c @@ -172,7 +172,7 @@ static void s_test_sleep_retention(bool allow_pd) // check if the sleep happened as expected TEST_ASSERT_EQUAL(0, sleep_ctx.sleep_request_result); -#if SOC_TWAI_SUPPORT_SLEEP_RETENTION +#if SOC_TWAI_SUPPORT_SLEEP_RETENTION && CONFIG_PM_POWER_DOWN_PERIPHERAL_IN_LIGHT_SLEEP // check if the power domain also is powered down TEST_ASSERT_EQUAL(allow_pd ? PMU_SLEEP_PD_TOP : 0, (sleep_ctx.sleep_flags) & PMU_SLEEP_PD_TOP); #endif diff --git a/components/hal/esp32c3/include/hal/twai_ll.h b/components/hal/esp32c3/include/hal/twai_ll.h index d2d713f206..1c84232cff 100644 --- a/components/hal/esp32c3/include/hal/twai_ll.h +++ b/components/hal/esp32c3/include/hal/twai_ll.h @@ -252,7 +252,7 @@ static inline void twai_ll_set_cmd_tx(twai_dev_t *hw) __attribute__((always_inline)) static inline void twai_ll_set_cmd_tx_single_shot(twai_dev_t *hw) { - hw->command_reg.val = 0x03; //Set command_reg.tr and command_reg.at simultaneously for single shot transmittion request + hw->command_reg.val = 0x03; //Set command_reg.tr and command_reg.at simultaneously for single shot transmission request } /** diff --git a/components/hal/esp32c5/include/hal/twaifd_ll.h b/components/hal/esp32c5/include/hal/twaifd_ll.h new file mode 100644 index 0000000000..6d8fab54c7 --- /dev/null +++ b/components/hal/esp32c5/include/hal/twaifd_ll.h @@ -0,0 +1,948 @@ +/* + * SPDX-FileCopyrightText: 2024 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 +#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) : (&TWAI1)) + +#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_TXI_INT_ST // Transmit Interrupt +#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 + +/** + * @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.twai[twai_id].twai_conf.twai_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.twai[twai_id].twai_conf.twai_rst_en = 1; + while (!PCR.twai[twai_id].twai_conf.twai_ready); +} + +/** + * @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) +{ + PCR.twai[twai_id].twai_func_clk_conf.twai_func_clk_sel = (clk_src == TWAI_CLK_SRC_RC_FAST) ? 1 : 0; +} + +/** + * @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.twai[twai_id].twai_func_clk_conf.twai_func_clk_en = enable; +} + +/** + * @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 modes Operating mode + */ +static inline void twaifd_ll_set_mode(twaifd_dev_t *hw, const twai_mode_t modes) +{ + //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 = (modes == TWAI_MODE_NO_ACK); + opmode.bmm = (modes == TWAI_MODE_LISTEN_ONLY); + + 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 TX loopback + * + * @param hw Pointer to the TWAI-FD device hardware. + * @param ena Set to true to enable loopback, false to disable. + */ +static inline void twaifd_ll_enable_loopback(twaifd_dev_t *hw, bool ena) +{ + hw->mode_settings.ilbp = 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_drop_remote_frame(twaifd_dev_t* hw, bool en) +{ + hw->mode_settings.fdrf = en; +} + +/** + * @brief Get remote frame filtering behaviour. + * + * @param hw Pointer to hardware structure. + */ +static inline bool twaifd_ll_filter_is_drop_remote_frame(twaifd_dev_t* hw) +{ + return hw->mode_settings.fdrf; +} + +/** + * @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_`. + */ +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. + */ +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 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_bit_rate(twaifd_dev_t *hw, const twai_timing_config_t *timing_param) +{ + twaifd_btr_reg_t reg_w = {.val = 0}; + 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_bit_rate(twaifd_dev_t *hw, const twai_timing_config_t *timing_param_fd) +{ + twaifd_btr_fd_reg_t reg_w = {.val = 0}; + 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 point offset based on Sync_Seg, in clock source freq. + */ +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); +} + +/* ----------------------------- ALC Register ------------------------------- */ + +/** + * @brief Get the arbitration lost field from the TWAI-FD peripheral. + * + * @param hw Pointer to the TWAI-FD device hardware. + * @return The arbitration lost ID field. + */ +static inline uint32_t twaifd_ll_get_arb_lost_field(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; +} + +/* ----------------------------- 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 + */ +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). + */ +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 + */ +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 + */ +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 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 en) +{ + HAL_ASSERT(filter_id < (SOC_TWAI_MASK_FILTER_NUM + SOC_TWAI_RANGE_FILTER_NUM)); + if (en) { + hw->filter_control_filter_status.val |= TWAIFD_FANB << (filter_id * TWAIFD_FBNB_S); + } else { + hw->filter_control_filter_status.val &= ~(TWAIFD_FANB << (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 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 en) +{ + HAL_ASSERT(filter_id < (SOC_TWAI_MASK_FILTER_NUM + SOC_TWAI_RANGE_FILTER_NUM)); + if (en) { + hw->filter_control_filter_status.val |= TWAIFD_FANE << (filter_id * TWAIFD_FBNB_S); + } else { + hw->filter_control_filter_status.val &= ~(TWAIFD_FANE << (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 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 en) +{ + HAL_ASSERT(filter_id < (SOC_TWAI_MASK_FILTER_NUM + SOC_TWAI_RANGE_FILTER_NUM)); + if (en) { + hw->filter_control_filter_status.val |= TWAIFD_FAFB << (filter_id * TWAIFD_FBNB_S); + } else { + hw->filter_control_filter_status.val &= ~(TWAIFD_FAFB << (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 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 en) +{ + HAL_ASSERT(filter_id < (SOC_TWAI_MASK_FILTER_NUM + SOC_TWAI_RANGE_FILTER_NUM)); + if (en) { + hw->filter_control_filter_status.val |= TWAIFD_FAFE << (filter_id * TWAIFD_FBNB_S); + } else { + hw->filter_control_filter_status.val &= ~(TWAIFD_FAFE << (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 code Acceptance Code + * @param mask Acceptance Mask + */ +static inline void twaifd_ll_filter_set_id_mask(twaifd_dev_t* hw, uint8_t filter_id, uint32_t code, uint32_t mask) +{ + hw->mask_filters[filter_id].filter_mask.bit_mask_val = mask; + hw->mask_filters[filter_id].filter_val.bit_val = code; +} + +/** + * @brief Set Range Acceptance Filter + * @param hw Start address of the TWAI registers + * @param filter_id Filter number 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, uint32_t high, uint32_t low) +{ + hw->range_filters[filter_id].ran_low.bit_ran_low_val = low; + hw->range_filters[filter_id].ran_high.bit_ran_high_val = high; +} + +/** + * @brief Enable or disable bit or range frame filtering for a specific filter. + * + * @param hw Pointer to the TWAI-FD device hardware. + * @param filter_id The ID of the filter to configure (0-2 for bit filter, 3 for range filter). + * @param enable True to enable the filter, false to disable. + */ +static inline void twaifd_ll_filter_enable(twaifd_dev_t* hw, uint8_t filter_id, bool enable) +{ + HAL_ASSERT(filter_id < (SOC_TWAI_MASK_FILTER_NUM + SOC_TWAI_RANGE_FILTER_NUM)); + twaifd_filter_control_filter_status_reg_t reg_val = {.val = hw->filter_control_filter_status.val}; + + // enable or disable filter selection + if (enable) { + reg_val.val |= BIT(filter_id + TWAIFD_SFA_S); + } else { + reg_val.val &= ~BIT(filter_id + TWAIFD_SFA_S); + } + hw->filter_control_filter_status.val = reg_val.val; +} +/* ------------------------- 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_` + */ +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 + */ +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. + */ +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 + */ +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 + */ +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 + */ +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. + */ +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 + */ +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 diff --git a/components/hal/esp32s2/include/hal/twai_ll.h b/components/hal/esp32s2/include/hal/twai_ll.h index 3d05c5b0be..7068900840 100644 --- a/components/hal/esp32s2/include/hal/twai_ll.h +++ b/components/hal/esp32s2/include/hal/twai_ll.h @@ -255,7 +255,7 @@ static inline void twai_ll_set_cmd_tx(twai_dev_t *hw) __attribute__((always_inline)) static inline void twai_ll_set_cmd_tx_single_shot(twai_dev_t *hw) { - hw->command_reg.val = 0x03; //Set command_reg.tr and command_reg.at simultaneously for single shot transmittion request + hw->command_reg.val = 0x03; //Set command_reg.tr and command_reg.at simultaneously for single shot transmission request } /** diff --git a/components/hal/esp32s3/include/hal/twai_ll.h b/components/hal/esp32s3/include/hal/twai_ll.h index 7f921438fa..e11823397a 100644 --- a/components/hal/esp32s3/include/hal/twai_ll.h +++ b/components/hal/esp32s3/include/hal/twai_ll.h @@ -252,7 +252,7 @@ static inline void twai_ll_set_cmd_tx(twai_dev_t *hw) __attribute__((always_inline)) static inline void twai_ll_set_cmd_tx_single_shot(twai_dev_t *hw) { - hw->command_reg.val = 0x03; //Set command_reg.tr and command_reg.at simultaneously for single shot transmittion request + hw->command_reg.val = 0x03; //Set command_reg.tr and command_reg.at simultaneously for single shot transmission request } /** diff --git a/components/hal/include/hal/twai_hal.h b/components/hal/include/hal/twai_hal.h index 930b687cdc..e50578ff80 100644 --- a/components/hal/include/hal/twai_hal.h +++ b/components/hal/include/hal/twai_hal.h @@ -1,5 +1,5 @@ /* - * SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD + * SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD * * SPDX-License-Identifier: Apache-2.0 */ @@ -16,17 +16,23 @@ #include #include "sdkconfig.h" #include "soc/soc_caps.h" -#if SOC_TWAI_SUPPORTED #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; +#else #include "hal/twai_ll.h" +typedef twai_dev_t* twai_soc_handle_t; +typedef twai_ll_frame_buffer_t twai_hal_frame_t; #endif #ifdef __cplusplus extern "C" { #endif -#if SOC_TWAI_SUPPORTED - /* ------------------------- Defines and Typedefs --------------------------- */ #define TWAI_HAL_SET_BITS(var, flag) ((var) |= (flag)) @@ -59,10 +65,8 @@ extern "C" { #define TWAI_HAL_EVENT_NEED_PERIPH_RESET (1 << 11) #endif -typedef twai_ll_frame_buffer_t twai_hal_frame_t; - typedef struct { - twai_dev_t *dev; + twai_soc_handle_t dev; // TWAI SOC layer handle (i.e. register base address) uint32_t state_flags; uint32_t clock_source_hz; #if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT) @@ -79,6 +83,34 @@ typedef struct { uint32_t clock_source_hz; } 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 + */ +__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; +} + /** * @brief Initialize TWAI peripheral and HAL context * @@ -91,6 +123,7 @@ typedef struct { */ 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 * @@ -300,7 +333,7 @@ static inline bool twai_hal_read_rx_buffer_and_clear(twai_hal_context_t *hal_ctx } #else if (twai_ll_get_status(hal_ctx->dev) & TWAI_LL_STATUS_DOS) { - //No need to release RX buffer as we'll be releaseing all RX frames in continuously later + //No need to release RX buffer as we'll be releasing all RX frames in continuously later return false; } #endif @@ -323,7 +356,7 @@ __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 incase another message arrives whilst clearing + //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++; @@ -347,7 +380,7 @@ static inline uint32_t twai_hal_clear_rx_fifo_overrun(twai_hal_context_t *hal_ct * - Checking if a reset will cancel a TX. If so, mark that we need to retry that message after the reset * - Save how many RX messages were lost due to this reset * - Enter reset mode to stop any the peripheral from receiving any bus activity - * - Store the regsiter state of the peripheral + * - Store the register state of the peripheral * * @param hal_ctx Context of the HAL layer */ @@ -381,9 +414,9 @@ static inline uint32_t twai_hal_get_reset_lost_rx_cnt(twai_hal_context_t *hal_ct 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 +#endif // !SOC_TWAI_SUPPORT_FD #ifdef __cplusplus } #endif +#endif // SOC_TWAI_SUPPORTED diff --git a/components/hal/include/hal/twai_types.h b/components/hal/include/hal/twai_types.h index d22c50d3ff..978f4ec53d 100644 --- a/components/hal/include/hal/twai_types.h +++ b/components/hal/include/hal/twai_types.h @@ -1,5 +1,5 @@ /* - * SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD + * SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD * * SPDX-License-Identifier: Apache-2.0 */ @@ -7,90 +7,35 @@ #pragma once #include -#include -#include "sdkconfig.h" #include "soc/soc_caps.h" #include "soc/clk_tree_defs.h" +#include "hal/twai_types_deprecated.h" //for backward competiblity, remove on 6.0 #ifdef __cplusplus extern "C" { #endif -/** - * @brief TWAI Constants - */ -#define TWAI_EXTD_ID_MASK 0x1FFFFFFF /**< Bit mask for 29 bit Extended Frame Format ID */ -#define TWAI_STD_ID_MASK 0x7FF /**< Bit mask for 11 bit Standard Frame Format ID */ -#define TWAI_FRAME_MAX_DLC 8 /**< Max data bytes allowed in TWAI */ -#define TWAI_FRAME_EXTD_ID_LEN_BYTES 4 /**< EFF ID requires 4 bytes (29bit) */ -#define TWAI_FRAME_STD_ID_LEN_BYTES 2 /**< SFF ID requires 2 bytes (11bit) */ -#define TWAI_ERR_PASS_THRESH 128 /**< Error counter threshold for error passive */ +/* valid bits in TWAI ID for frame formats */ +#define TWAI_STD_ID_MASK 0x000007FFU /* Mask of the ID fields in a standard frame */ +#define TWAI_EXT_ID_MASK 0x1FFFFFFFU /* Mask of the ID fields in an extended frame */ -/** @cond */ //Doxy command to hide preprocessor definitions from docs +/* TWAI payload length and DLC definitions */ +#define TWAI_FRAME_MAX_DLC 8 +#define TWAI_FRAME_MAX_LEN 8 + +/* TWAI FD payload length and DLC definitions */ +#define TWAIFD_FRAME_MAX_DLC 15 +#define TWAIFD_FRAME_MAX_LEN 64 /** - * @brief TWAI Message flags - * - * The message flags are used to indicate the type of message transmitted/received. - * Some flags also specify the type of transmission. + * @brief TWAI error states */ -#define TWAI_MSG_FLAG_NONE 0x00 /**< No message flags (Standard Frame Format) */ -#define TWAI_MSG_FLAG_EXTD 0x01 /**< Extended Frame Format (29bit ID) */ -#define TWAI_MSG_FLAG_RTR 0x02 /**< Message is a Remote Frame */ -#define TWAI_MSG_FLAG_SS 0x04 /**< Transmit as a Single Shot Transmission. Unused for received. */ -#define TWAI_MSG_FLAG_SELF 0x08 /**< Transmit as a Self Reception Request. Unused for received. */ -#define TWAI_MSG_FLAG_DLC_NON_COMP 0x10 /**< Message's Data length code is larger than 8. This will break compliance with TWAI */ - -#define TWAI_BRP_MAX SOC_TWAI_BRP_MAX /**< Maximum configurable BRP value */ -#define TWAI_BRP_MIN SOC_TWAI_BRP_MIN /**< Minimum configurable BRP value */ - - -/** - * @brief Initializer macros for timing configuration structure - * - * The following initializer macros offer commonly found bit rates. These macros - * place the sample point at 80% or 67% of a bit time. - * - * @note The available bit rates are dependent on the chip target and ECO version. - */ -#if SOC_TWAI_BRP_MAX > 256 -#define TWAI_TIMING_CONFIG_1KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 20000, .brp = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_5KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 100000, .brp = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_10KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 200000, .brp = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#endif // SOC_TWAI_BRP_MAX > 256 - -#if (SOC_TWAI_BRP_MAX > 128) || (CONFIG_ESP32_REV_MIN_FULL >= 200) -#define TWAI_TIMING_CONFIG_12_5KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 312500, .brp = 0, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_16KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 400000, .brp = 0, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_20KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 400000, .brp = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#endif // (SOC_TWAI_BRP_MAX > 128) || (CONFIG_ESP32_REV_MIN_FULL >= 200) - -#if CONFIG_XTAL_FREQ == 32 // TWAI_CLK_SRC_XTAL = 32M -#define TWAI_TIMING_CONFIG_25KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 400000, .brp = 0, .tseg_1 = 11, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_50KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 1000000, .brp = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_100KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 2000000, .brp = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_125KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 4000000, .brp = 0, .tseg_1 = 23, .tseg_2 = 8, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_250KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 4000000, .brp = 0, .tseg_1 = 11, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_500KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 8000000, .brp = 0, .tseg_1 = 11, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_800KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 16000000, .brp = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_1MBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 16000000, .brp = 0, .tseg_1 = 11, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} - -#elif CONFIG_XTAL_FREQ == 40 // TWAI_CLK_SRC_XTAL = 40M -#define TWAI_TIMING_CONFIG_25KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 625000, .brp = 0, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_50KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 1000000, .brp = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_100KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 2000000, .brp = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_125KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 2500000, .brp = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_250KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 5000000, .brp = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_500KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 10000000, .brp = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_800KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 20000000, .brp = 0, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false} -#define TWAI_TIMING_CONFIG_1MBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 20000000, .brp = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} -#endif //CONFIG_XTAL_FREQ - -/** - * @brief Initializer macro for filter configuration to accept all IDs - */ -#define TWAI_FILTER_CONFIG_ACCEPT_ALL() {.acceptance_code = 0, .acceptance_mask = 0xFFFFFFFF, .single_filter = true} -/** @endcond */ +typedef enum { + TWAI_ERROR_ACTIVE, /**< Error active state: TEC/REC < 96 */ + TWAI_ERROR_WARNING, /**< Error warning state: TEC/REC >= 96 and < 128 */ + TWAI_ERROR_PASSIVE, /**< Error passive state: TEC/REC >= 128 and < 256 */ + TWAI_ERROR_BUS_OFF, /**< Bus-off state: TEC >= 256 (node disconnected from bus) */ +} twai_error_state_t; /** * @brief TWAI Controller operating modes @@ -102,31 +47,7 @@ typedef enum { } twai_mode_t; /** - * @brief Structure to store a TWAI message - * - * @note The flags member is deprecated - */ -typedef struct { - union { - struct { - //The order of these bits must match deprecated message flags for compatibility reasons - uint32_t extd: 1; /**< Extended Frame Format (29bit ID) */ - uint32_t rtr: 1; /**< Message is a Remote Frame */ - uint32_t ss: 1; /**< Transmit as a Single Shot Transmission. Unused for received. */ - uint32_t self: 1; /**< Transmit as a Self Reception Request. Unused for received. */ - uint32_t dlc_non_comp: 1; /**< Message's Data length code is larger than 8. This will break compliance with ISO 11898-1 */ - uint32_t reserved: 27; /**< Reserved bits */ - }; - //Todo: Deprecate flags - uint32_t flags; /**< Deprecated: Alternate way to set bits using message flags */ - }; - uint32_t identifier; /**< 11 or 29 bit identifier */ - uint8_t data_length_code; /**< Data length code */ - uint8_t data[TWAI_FRAME_MAX_DLC]; /**< Data bytes (not relevant in RTR frame) */ -} twai_message_t; - -/** - * @brief RMT group clock source + * @brief TWAI group clock source * @note User should select the clock source based on the power and resolution requirement */ #if SOC_TWAI_SUPPORTED @@ -136,32 +57,47 @@ typedef int twai_clock_source_t; #endif /** - * @brief Structure for bit timing configuration of the TWAI driver - * - * @note Macro initializers are available for this structure + * @brief TWAI baud rate timing config advanced mode + * @note Setting one of `quanta_resolution_hz` and `brp` is enough, otherwise, `brp` is not used. */ typedef struct { - twai_clock_source_t clk_src; /**< Clock source, set to 0 or TWAI_CLK_SRC_DEFAULT if you want a default clock source */ - uint32_t quanta_resolution_hz; /**< The resolution of one timing quanta, in Hz. - Note: the value of `brp` will reflected by this field if it's non-zero, otherwise, `brp` needs to be set manually */ - uint32_t brp; /**< Baudrate prescale (i.e., clock divider). Any even number from 2 to 128 for ESP32, 2 to 32768 for non-ESP32 chip. - Note: For ESP32 ECO 2 or later, multiples of 4 from 132 to 256 are also supported */ - uint8_t tseg_1; /**< Timing segment 1 (Number of time quanta, between 1 to 16) */ - uint8_t tseg_2; /**< Timing segment 2 (Number of time quanta, 1 to 8) */ - uint8_t sjw; /**< Synchronization Jump Width (Max time quanta jump for synchronize from 1 to 4) */ - bool triple_sampling; /**< Enables triple sampling when the TWAI controller samples a bit */ + twai_clock_source_t clk_src; /**< Optional, clock source, remain 0 to using TWAI_CLK_SRC_DEFAULT by default */ + uint32_t quanta_resolution_hz; /**< The resolution of one timing quanta, in Hz. If setting, brp will be ignored */ + uint32_t brp; /**< Bit rate pre-divider, clock_source_freq / brp = quanta_resolution_hz */ + uint8_t tseg_1; /**< Seg_1 length, in quanta time */ + uint8_t tseg_2; /**< Seg_2 length, in quanta time */ + uint8_t sjw; /**< Sync jump width, in quanta time */ + union { + bool en_multi_samp; /**< Multi-sampling for one bit to avoid noise and detect errors */ + bool triple_sampling; /**< Deprecate, using `en_multi_samp`, Enables triple sampling when the TWAI controller samples a bit, [deprecated("in favor of en_multi_samp")] */ + }; + uint8_t prop_seg; /**< Prop_seg length, in quanta time */ } twai_timing_config_t; /** - * @brief Structure for acceptance filter configuration of the TWAI driver (see documentation) - * - * @note Macro initializers are available for this structure + * @brief TWAI frame header/format struct type */ typedef struct { - uint32_t acceptance_code; /**< 32-bit acceptance code */ - uint32_t acceptance_mask; /**< 32-bit acceptance mask */ - bool single_filter; /**< Use Single Filter Mode (see documentation) */ -} twai_filter_config_t; + union { + struct { + uint32_t ide:1; /**< Extended Frame Format (29bit ID) */ + uint32_t rtr:1; /**< Message is a Remote Frame */ + uint32_t fdf:1; /**< TWAI 2.0: Reserved, FD: FD Frames. */ + uint32_t brs:1; /**< TWAI 2.0: Reserved, FD: Bit Rate Shift. */ + uint32_t esi:1; /**< Transmit side error indicator for received frame */ + uint32_t loopback:1; /**< Temporary transmit as loop back for this trans, if setting `TWAI_MODE_LOOP_BACK`, all transmit is loop back */ + int8_t retrans_count; /**< Re-trans count on transfer fail, -1: infinite, 0: no re-trans, others: re-trans times. */ + uint32_t reserved:18; /**< Reserved */ + }; + uint32_t format_val; /**< Frame format/type integrate value */ + }; + union { + uint64_t timestamp; /**< Timestamp for received message */ + uint64_t trigger_time; /**< Trigger time for transmitting message*/ + }; + uint32_t id; /**< message arbitration identification */ + uint8_t dlc; /**< message data length code */ +} twai_frame_header_t; #ifdef __cplusplus } diff --git a/components/hal/include/hal/twai_types_deprecated.h b/components/hal/include/hal/twai_types_deprecated.h new file mode 100644 index 0000000000..86c18022a0 --- /dev/null +++ b/components/hal/include/hal/twai_types_deprecated.h @@ -0,0 +1,120 @@ +/* + * SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#pragma once + +#include +#include +#include "sdkconfig.h" +#include "soc/soc_caps.h" +#include "soc/clk_tree_defs.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief TWAI Constants + */ +#define TWAI_EXTD_ID_MASK 0x1FFFFFFF /**< Bit mask for 29 bit Extended Frame Format ID */ +#define TWAI_FRAME_EXTD_ID_LEN_BYTES 4 /**< EFF ID requires 4 bytes (29bit) */ +#define TWAI_FRAME_STD_ID_LEN_BYTES 2 /**< SFF ID requires 2 bytes (11bit) */ +#define TWAI_ERR_PASS_THRESH 128 /**< Error counter threshold for error passive */ + +/** @cond */ //Doxy command to hide preprocessor definitions from docs + +/** + * @brief TWAI Message flags + * + * The message flags are used to indicate the type of message transmitted/received. + * Some flags also specify the type of transmission. + */ +#define TWAI_MSG_FLAG_NONE 0x00 /**< No message flags (Standard Frame Format) */ +#define TWAI_MSG_FLAG_EXTD 0x01 /**< Extended Frame Format (29bit ID) */ +#define TWAI_MSG_FLAG_RTR 0x02 /**< Message is a Remote Frame */ +#define TWAI_MSG_FLAG_SS 0x04 /**< Transmit as a Single Shot Transmission. Unused for received. */ +#define TWAI_MSG_FLAG_SELF 0x08 /**< Transmit as a Self Reception Request. Unused for received. */ +#define TWAI_MSG_FLAG_DLC_NON_COMP 0x10 /**< Message's Data length code is larger than 8. This will break compliance with TWAI */ + +#define TWAI_BRP_MAX SOC_TWAI_BRP_MAX /**< Maximum configurable BRP value */ +#define TWAI_BRP_MIN SOC_TWAI_BRP_MIN /**< Minimum configurable BRP value */ + +/** + * @brief Initializer macros for timing configuration structure + * + * The following initializer macros offer commonly found bit rates. These macros + * place the sample point at 80% or 67% of a bit time. + * + * @note The available bit rates are dependent on the chip target and ECO version. + */ +#if SOC_TWAI_BRP_MAX > 256 +#define TWAI_TIMING_CONFIG_1KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 20000, .brp = 0, .prop_seg = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} +#define TWAI_TIMING_CONFIG_5KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 100000, .brp = 0, .prop_seg = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} +#define TWAI_TIMING_CONFIG_10KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 200000, .brp = 0, .prop_seg = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} +#endif // SOC_TWAI_BRP_MAX > 256 + +#if (SOC_TWAI_BRP_MAX > 128) || (CONFIG_ESP32_REV_MIN_FULL >= 200) +#define TWAI_TIMING_CONFIG_12_5KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 312500, .brp = 0, .prop_seg = 0, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false} +#define TWAI_TIMING_CONFIG_16KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 400000, .brp = 0, .prop_seg = 0, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false} +#define TWAI_TIMING_CONFIG_20KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 400000, .brp = 0, .prop_seg = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} +#endif // (SOC_TWAI_BRP_MAX > 128) || (CONFIG_ESP32_REV_MIN_FULL >= 200) + +#if SOC_TWAI_CLK_SUPPORT_XTAL +#define TWAI_TIMING_CONFIG_25KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 500000, .brp = 0, .prop_seg = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} +#else // APB +#define TWAI_TIMING_CONFIG_25KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 625000, .brp = 0, .prop_seg = 0, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false} +#endif +#define TWAI_TIMING_CONFIG_50KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 1000000, .brp = 0, .prop_seg = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} +#define TWAI_TIMING_CONFIG_100KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 2000000, .brp = 0, .prop_seg = 0, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false} +#define TWAI_TIMING_CONFIG_250KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 4000000, .brp = 0, .prop_seg = 0, .tseg_1 = 11, .tseg_2 = 4, .sjw = 2, .triple_sampling = false} +#define TWAI_TIMING_CONFIG_500KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 8000000, .brp = 0, .prop_seg = 0, .tseg_1 = 11, .tseg_2 = 4, .sjw = 2, .triple_sampling = false} +#define TWAI_TIMING_CONFIG_800KBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 8000000, .brp = 0, .prop_seg = 0, .tseg_1 = 6, .tseg_2 = 3, .sjw = 1, .triple_sampling = false} +#define TWAI_TIMING_CONFIG_1MBITS() {.clk_src = TWAI_CLK_SRC_DEFAULT, .quanta_resolution_hz = 8000000, .brp = 0, .prop_seg = 0, .tseg_1 = 5, .tseg_2 = 2, .sjw = 1, .triple_sampling = false} + +/** + * @brief Initializer macro for filter configuration to accept all IDs + */ +#define TWAI_FILTER_CONFIG_ACCEPT_ALL() {.acceptance_code = 0, .acceptance_mask = 0xFFFFFFFF, .single_filter = true} +/** @endcond */ + +/** + * @brief Structure to store a TWAI message + * + * @note The flags member is deprecated + */ +typedef struct { + union { + struct { + //The order of these bits must match deprecated message flags for compatibility reasons + uint32_t extd: 1; /**< Extended Frame Format (29bit ID) */ + uint32_t rtr: 1; /**< Message is a Remote Frame */ + uint32_t ss: 1; /**< Transmit as a Single Shot Transmission. Unused for received. */ + uint32_t self: 1; /**< Transmit as a Self Reception Request. Unused for received. */ + uint32_t dlc_non_comp: 1; /**< Message's Data length code is larger than 8. This will break compliance with ISO 11898-1 */ + uint32_t reserved: 27; /**< Reserved bits */ + }; + //Todo: Deprecate flags + uint32_t flags; /**< Deprecated: Alternate way to set bits using message flags */ + }; + uint32_t identifier; /**< 11 or 29 bit identifier */ + uint8_t data_length_code; /**< Data length code */ + uint8_t data[8]; /**< Data bytes (not relevant in RTR frame) */ +} twai_message_t; + +/** + * @brief Structure for acceptance filter configuration of the TWAI driver (see documentation) + * + * @note Macro initializers are available for this structure + */ +typedef struct { + uint32_t acceptance_code; /**< 32-bit acceptance code */ + uint32_t acceptance_mask; /**< 32-bit acceptance mask */ + bool single_filter; /**< Use Single Filter Mode (see documentation) */ +} twai_filter_config_t; + +#ifdef __cplusplus +} +#endif diff --git a/components/soc/esp32c5/include/soc/Kconfig.soc_caps.in b/components/soc/esp32c5/include/soc/Kconfig.soc_caps.in index bf586f0587..3c8459cdd7 100644 --- a/components/soc/esp32c5/include/soc/Kconfig.soc_caps.in +++ b/components/soc/esp32c5/include/soc/Kconfig.soc_caps.in @@ -1215,6 +1215,42 @@ config SOC_MWDT_SUPPORT_SLEEP_RETENTION bool default y +config SOC_TWAI_CONTROLLER_NUM + int + default 2 + +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_ECDSA_KEY bool default y diff --git a/components/soc/esp32c5/include/soc/clk_tree_defs.h b/components/soc/esp32c5/include/soc/clk_tree_defs.h index 2f7d2e9717..94dbc59579 100644 --- a/components/soc/esp32c5/include/soc/clk_tree_defs.h +++ b/components/soc/esp32c5/include/soc/clk_tree_defs.h @@ -407,14 +407,15 @@ typedef enum { /** * @brief Array initializer for all supported clock sources of TWAI */ -#define SOC_TWAI_CLKS {SOC_MOD_CLK_XTAL} +#define SOC_TWAI_CLKS {SOC_MOD_CLK_XTAL, SOC_MOD_CLK_RC_FAST} /** * @brief TWAI clock source */ -typedef enum { // TODO: [ESP32C5] IDF-8691, IDF-8692 (inherit from C6) - TWAI_CLK_SRC_XTAL = SOC_MOD_CLK_XTAL, /*!< Select XTAL as the source clock */ - TWAI_CLK_SRC_DEFAULT = SOC_MOD_CLK_XTAL, /*!< Select XTAL as the default clock choice */ +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; //////////////////////////////////////////////////ADC/////////////////////////////////////////////////////////////////// diff --git a/components/soc/esp32c5/include/soc/soc_caps.h b/components/soc/esp32c5/include/soc/soc_caps.h index d1323aff17..2fcf8fb1f8 100644 --- a/components/soc/esp32c5/include/soc/soc_caps.h +++ b/components/soc/esp32c5/include/soc/soc_caps.h @@ -494,11 +494,15 @@ #define SOC_MWDT_SUPPORT_SLEEP_RETENTION (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 2 +#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 1 diff --git a/components/soc/esp32c5/register/soc/pcr_struct.h b/components/soc/esp32c5/register/soc/pcr_struct.h index 15acd48aad..299a2da15b 100644 --- a/components/soc/esp32c5/register/soc/pcr_struct.h +++ b/components/soc/esp32c5/register/soc/pcr_struct.h @@ -267,93 +267,49 @@ typedef union { uint32_t val; } pcr_i2c_sclk_conf_reg_t; -/** Type of twai0_conf register - * TWAI0 configuration register +/** Type of twai_conf register + * TWAI configuration register */ typedef union { struct { - /** twai0_clk_en : R/W; bitpos: [0]; default: 0; - * Set 1 to enable twai0 apb clock + /** twai_clk_en : R/W; bitpos: [0]; default: 0; + * Set 1 to enable twai apb clock */ - uint32_t twai0_clk_en:1; - /** twai0_rst_en : R/W; bitpos: [1]; default: 0; - * Set 0 to reset twai0 module + uint32_t twai_clk_en:1; + /** twai_rst_en : R/W; bitpos: [1]; default: 0; + * Set 0 to reset twai module */ - uint32_t twai0_rst_en:1; - /** twai0_ready : RO; bitpos: [2]; default: 1; - * Query this field after reset twai0 module + uint32_t twai_rst_en:1; + /** twai_ready : RO; bitpos: [2]; default: 1; + * Query this field after reset twai module */ - uint32_t twai0_ready:1; + uint32_t twai_ready:1; uint32_t reserved_3:29; }; uint32_t val; -} pcr_twai0_conf_reg_t; +} pcr_twai_conf_reg_t; -/** Type of twai0_func_clk_conf register - * TWAI0_FUNC_CLK configuration register +/** Type of twai_func_clk_conf register + * TWAI_FUNC_CLK configuration register */ typedef union { struct { uint32_t reserved_0:20; - /** twai0_func_clk_sel : R/W; bitpos: [20]; default: 0; - * Configures the clock source of TWAI0.\\ + /** twai_func_clk_sel : R/W; bitpos: [20]; default: 0; + * Configures the clock source of TWAI.\\ * 0 (default): XTAL_CLK\\ * 1: RC_FAST_CLK\\ */ - uint32_t twai0_func_clk_sel:1; + uint32_t twai_func_clk_sel:1; uint32_t reserved_21:1; - /** twai0_func_clk_en : R/W; bitpos: [22]; default: 0; - * Set 1 to enable twai0 function clock + /** twai_func_clk_en : R/W; bitpos: [22]; default: 0; + * Set 1 to enable twai function clock */ - uint32_t twai0_func_clk_en:1; + uint32_t twai_func_clk_en:1; uint32_t reserved_23:9; }; uint32_t val; -} pcr_twai0_func_clk_conf_reg_t; - -/** Type of twai1_conf register - * TWAI1 configuration register - */ -typedef union { - struct { - /** twai1_clk_en : R/W; bitpos: [0]; default: 0; - * Set 1 to enable twai1 apb clock - */ - uint32_t twai1_clk_en:1; - /** twai1_rst_en : R/W; bitpos: [1]; default: 0; - * Set 0 to reset twai1 module - */ - uint32_t twai1_rst_en:1; - /** twai1_ready : RO; bitpos: [2]; default: 1; - * Query this field after reset twai1 module - */ - uint32_t twai1_ready:1; - uint32_t reserved_3:29; - }; - uint32_t val; -} pcr_twai1_conf_reg_t; - -/** Type of twai1_func_clk_conf register - * TWAI1_FUNC_CLK configuration register - */ -typedef union { - struct { - uint32_t reserved_0:20; - /** twai1_func_clk_sel : R/W; bitpos: [20]; default: 0; - * Configures the clock source of TWAI1.\\ - * 0 (default): XTAL_CLK\\ - * 1: RC_FAST_CLK\\ - */ - uint32_t twai1_func_clk_sel:1; - uint32_t reserved_21:1; - /** twai1_func_clk_en : R/W; bitpos: [22]; default: 0; - * Set 1 to enable twai1 function clock - */ - uint32_t twai1_func_clk_en:1; - uint32_t reserved_23:9; - }; - uint32_t val; -} pcr_twai1_func_clk_conf_reg_t; +} pcr_twai_func_clk_conf_reg_t; /** Type of uhci_conf register * UHCI configuration register @@ -2329,6 +2285,14 @@ typedef struct { pcr_i2c_sclk_conf_reg_t i2c_sclk_conf; } pcr_i2c_reg_t; +/** + * @brief The struct of TWAI configuration registers + */ +typedef struct { + pcr_twai_conf_reg_t twai_conf; + pcr_twai_func_clk_conf_reg_t twai_func_clk_conf; +} pcr_twai_reg_t; + typedef struct { volatile pcr_uart0_conf_reg_t uart0_conf; volatile pcr_uart0_sclk_conf_reg_t uart0_sclk_conf; @@ -2339,10 +2303,7 @@ typedef struct { volatile pcr_mspi_conf_reg_t mspi_conf; volatile pcr_mspi_clk_conf_reg_t mspi_clk_conf; volatile pcr_i2c_reg_t i2c[1]; - volatile pcr_twai0_conf_reg_t twai0_conf; - volatile pcr_twai0_func_clk_conf_reg_t twai0_func_clk_conf; - volatile pcr_twai1_conf_reg_t twai1_conf; - volatile pcr_twai1_func_clk_conf_reg_t twai1_func_clk_conf; + volatile pcr_twai_reg_t twai[2]; volatile pcr_uhci_conf_reg_t uhci_conf; volatile pcr_rmt_conf_reg_t rmt_conf; volatile pcr_rmt_sclk_conf_reg_t rmt_sclk_conf; diff --git a/components/soc/esp32c5/register/soc/twaifd_struct.h b/components/soc/esp32c5/register/soc/twaifd_struct.h index 1ab2d31c3b..2da3e6e447 100644 --- a/components/soc/esp32c5/register/soc/twaifd_struct.h +++ b/components/soc/esp32c5/register/soc/twaifd_struct.h @@ -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,6 +1738,63 @@ 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 { + 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 { volatile twaifd_device_id_version_reg_t device_id_version; @@ -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; diff --git a/components/soc/esp32c5/twai_periph.c b/components/soc/esp32c5/twai_periph.c new file mode 100644 index 0000000000..179116ddd2 --- /dev/null +++ b/components/soc/esp32c5/twai_periph.c @@ -0,0 +1,31 @@ +/* + * SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include "soc/twai_periph.h" +#include "soc/gpio_sig_map.h" + +const twai_controller_signal_conn_t twai_controller_periph_signals = { + .controllers = { + [0] = { + .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, + }, + [1] = { + .irq_id = ETS_TWAI1_INTR_SOURCE, + .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, + }, + } +}; diff --git a/components/soc/include/soc/twai_periph.h b/components/soc/include/soc/twai_periph.h index 89ca029f02..8cb7682ebc 100644 --- a/components/soc/include/soc/twai_periph.h +++ b/components/soc/include/soc/twai_periph.h @@ -24,6 +24,9 @@ typedef struct { struct { const periph_module_t module; // peripheral module const int irq_id; // interrupt source ID +#if SOC_TWAI_SUPPORT_TIMESTAMP + const int timer_irq_id; +#endif const int tx_sig; // TX signal ID in GPIO matrix const int rx_sig; // RX signal ID in GPIO matrix const int clk_out_sig; // CLK_OUT signal ID in GPIO matrix diff --git a/docs/doxygen/Doxyfile b/docs/doxygen/Doxyfile index 055c60d164..467394d5f7 100644 --- a/docs/doxygen/Doxyfile +++ b/docs/doxygen/Doxyfile @@ -263,7 +263,7 @@ INPUT = \ $(PROJECT_PATH)/components/hal/include/hal/spi_types.h \ $(PROJECT_PATH)/components/hal/include/hal/temperature_sensor_types.h \ $(PROJECT_PATH)/components/hal/include/hal/timer_types.h \ - $(PROJECT_PATH)/components/hal/include/hal/twai_types.h \ + $(PROJECT_PATH)/components/hal/include/hal/twai_types_deprecated.h \ $(PROJECT_PATH)/components/hal/include/hal/uart_types.h \ $(PROJECT_PATH)/components/hal/include/hal/efuse_hal.h \ $(PROJECT_PATH)/components/hal/include/hal/eth_types.h \ diff --git a/docs/en/api-reference/peripherals/twai.rst b/docs/en/api-reference/peripherals/twai.rst index 310f9126c5..f93e1099e9 100644 --- a/docs/en/api-reference/peripherals/twai.rst +++ b/docs/en/api-reference/peripherals/twai.rst @@ -613,5 +613,5 @@ Application Examples API Reference ------------- -.. include-build-file:: inc/twai_types.inc +.. include-build-file:: inc/twai_types_deprecated.inc .. include-build-file:: inc/twai.inc diff --git a/docs/zh_CN/api-reference/peripherals/twai.rst b/docs/zh_CN/api-reference/peripherals/twai.rst index 4bd78d2fe1..edf8def814 100644 --- a/docs/zh_CN/api-reference/peripherals/twai.rst +++ b/docs/zh_CN/api-reference/peripherals/twai.rst @@ -613,5 +613,5 @@ TWAI 驱动程序通过 :cpp:type:`twai_message_t` 结构体的不同位字段 API 参考 ------------- -.. include-build-file:: inc/twai_types.inc +.. include-build-file:: inc/twai_types_deprecated.inc .. include-build-file:: inc/twai.inc diff --git a/tools/ci/sg_rules/no_kconfig_in_hal_component.yml b/tools/ci/sg_rules/no_kconfig_in_hal_component.yml index bc64f2535a..46e8da761f 100644 --- a/tools/ci/sg_rules/no_kconfig_in_hal_component.yml +++ b/tools/ci/sg_rules/no_kconfig_in_hal_component.yml @@ -41,7 +41,7 @@ ignores: - "components/hal/include/hal/pmu_types.h" - "components/hal/include/hal/sha_types.h" - "components/hal/include/hal/touch_sensor_legacy_types.h" - - "components/hal/include/hal/twai_types.h" + - "components/hal/include/hal/twai_types_deprecated.h" rule: any: - kind: argument_list @@ -95,7 +95,7 @@ ignores: - "components/hal/include/hal/sha_types.h" - "components/hal/include/hal/touch_sensor_legacy_types.h" - "components/hal/include/hal/twai_hal.h" - - "components/hal/include/hal/twai_types.h" + - "components/hal/include/hal/twai_types_deprecated.h" rule: kind: preproc_include has: