twai: bringup on esp32c6

This commit is contained in:
morris 2022-10-19 17:40:32 +08:00
parent 6828c011d9
commit a25123f703
35 changed files with 1521 additions and 261 deletions

View File

@ -1,25 +1,22 @@
/*
* SPDX-FileCopyrightText: 2015-2021 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include "soc/soc_caps.h"
#if SOC_TWAI_SUPPORTED
#include "freertos/FreeRTOS.h"
#include "esp_types.h"
#include "esp_intr_alloc.h"
#include "esp_err.h"
#include "gpio.h"
#include "driver/gpio.h"
#include "hal/twai_types.h"
#ifdef __cplusplus
extern "C" {
#endif
/* -------------------- Default initializers and flags ---------------------- */
/** @cond */ //Doxy command to hide preprocessor definitions from docs
/**
@ -135,7 +132,7 @@ typedef struct {
*
* @return
* - ESP_OK: Successfully installed TWAI driver
* - ESP_ERR_INVALID_ARG: Arguments are invalid
* - ESP_ERR_INVALID_ARG: Arguments are invalid, e.g. invalid clock source, invalid quanta resolution
* - ESP_ERR_NO_MEM: Insufficient memory
* - ESP_ERR_INVALID_STATE: Driver is already installed
*/
@ -341,5 +338,3 @@ esp_err_t twai_clear_receive_queue(void);
#ifdef __cplusplus
}
#endif
#endif //SOC_TWAI_SUPPORTED

View File

@ -18,6 +18,7 @@
#include "esp_heap_caps.h"
#include "driver/gpio.h"
#include "esp_private/periph_ctrl.h"
#include "esp_private/esp_clk.h"
#include "driver/twai.h"
#include "soc/soc_caps.h"
#include "soc/soc.h"
@ -59,6 +60,8 @@
//Control structure for TWAI driver
typedef struct {
int controller_id;
periph_module_t module; // peripheral module
//Control and status members
twai_state_t state;
twai_mode_t mode;
@ -84,10 +87,8 @@ typedef struct {
SemaphoreHandle_t alert_semphr;
uint32_t alerts_enabled;
uint32_t alerts_triggered;
#ifdef CONFIG_PM_ENABLE
//Power Management
//Power Management Lock
esp_pm_lock_handle_t pm_lock;
#endif
} twai_obj_t;
static twai_obj_t *p_twai_obj = NULL;
@ -121,6 +122,7 @@ TWAI_ISR_ATTR static void twai_alert_handler(uint32_t alert_code, int *alert_req
}
}
TWAI_ISR_ATTR
static inline void twai_handle_rx_buffer_frames(BaseType_t *task_woken, int *alert_req)
{
#ifdef SOC_TWAI_SUPPORTS_RX_STATUS
@ -170,6 +172,7 @@ static inline void twai_handle_rx_buffer_frames(BaseType_t *task_woken, int *ale
#endif //SOC_TWAI_SUPPORTS_RX_STATUS
}
TWAI_ISR_ATTR
static inline void twai_handle_tx_buffer_frame(BaseType_t *task_woken, int *alert_req)
{
//Handle previously transmitted frame
@ -214,7 +217,7 @@ TWAI_ISR_ATTR static void twai_intr_handler_main(void *arg)
#if defined(CONFIG_TWAI_ERRATA_FIX_RX_FRAME_INVALID) || defined(CONFIG_TWAI_ERRATA_FIX_RX_FIFO_CORRUPT)
if (events & TWAI_HAL_EVENT_NEED_PERIPH_RESET) {
twai_hal_prepare_for_reset(&twai_context);
periph_module_reset(PERIPH_TWAI_MODULE);
periph_module_reset(p_twai_obj->module);
twai_hal_recover_from_reset(&twai_context);
p_twai_obj->rx_missed_count += twai_hal_get_reset_lost_rx_cnt(&twai_context);
twai_alert_handler(TWAI_ALERT_PERIPH_RESET, &alert_req);
@ -281,28 +284,37 @@ TWAI_ISR_ATTR static void twai_intr_handler_main(void *arg)
static void twai_configure_gpio(gpio_num_t tx, gpio_num_t rx, gpio_num_t clkout, gpio_num_t bus_status)
{
//Set TX pin
gpio_set_pull_mode(tx, GPIO_FLOATING);
esp_rom_gpio_connect_out_signal(tx, TWAI_TX_IDX, false, false);
esp_rom_gpio_pad_select_gpio(tx);
int controller_id = p_twai_obj->controller_id;
// if TX and RX set to the same GPIO, which means we want to create a loop-back in the GPIO matrix
bool io_loop_back = (tx == rx);
gpio_config_t gpio_conf = {
.intr_type = GPIO_INTR_DISABLE,
.pull_down_en = false,
.pull_up_en = false,
};
//Set RX pin
gpio_set_pull_mode(rx, GPIO_FLOATING);
esp_rom_gpio_connect_in_signal(rx, TWAI_RX_IDX, false);
esp_rom_gpio_pad_select_gpio(rx);
gpio_set_direction(rx, GPIO_MODE_INPUT);
gpio_conf.mode = GPIO_MODE_INPUT | (io_loop_back ? GPIO_MODE_OUTPUT : 0);
gpio_conf.pin_bit_mask = 1ULL << rx;
gpio_config(&gpio_conf);
esp_rom_gpio_connect_in_signal(rx, twai_controller_periph_signals.controllers[controller_id].rx_sig, false);
//Set TX pin
gpio_conf.mode = GPIO_MODE_OUTPUT | (io_loop_back ? GPIO_MODE_INPUT : 0);
gpio_conf.pin_bit_mask = 1ULL << tx;
gpio_config(&gpio_conf);
esp_rom_gpio_connect_out_signal(tx, twai_controller_periph_signals.controllers[controller_id].tx_sig, false, false);
//Configure output clock pin (Optional)
if (clkout >= 0 && clkout < GPIO_NUM_MAX) {
gpio_set_pull_mode(clkout, GPIO_FLOATING);
esp_rom_gpio_connect_out_signal(clkout, TWAI_CLKOUT_IDX, false, false);
esp_rom_gpio_connect_out_signal(clkout, twai_controller_periph_signals.controllers[controller_id].clk_out_sig, false, false);
esp_rom_gpio_pad_select_gpio(clkout);
}
//Configure bus status pin (Optional)
if (bus_status >= 0 && bus_status < GPIO_NUM_MAX) {
gpio_set_pull_mode(bus_status, GPIO_FLOATING);
esp_rom_gpio_connect_out_signal(bus_status, TWAI_BUS_OFF_ON_IDX, false, false);
esp_rom_gpio_connect_out_signal(bus_status, twai_controller_periph_signals.controllers[controller_id].bus_off_sig, false, false);
esp_rom_gpio_pad_select_gpio(bus_status);
}
}
@ -310,11 +322,9 @@ static void twai_configure_gpio(gpio_num_t tx, gpio_num_t rx, gpio_num_t clkout,
static void twai_free_driver_obj(twai_obj_t *p_obj)
{
//Free driver object and any dependent SW resources it uses (queues, semaphores etc)
#ifdef CONFIG_PM_ENABLE
if (p_obj->pm_lock != NULL) {
ESP_ERROR_CHECK(esp_pm_lock_delete(p_obj->pm_lock));
}
#endif
//Delete queues and semaphores
if (p_obj->tx_queue != NULL) {
vQueueDelete(p_obj->tx_queue);
@ -382,12 +392,6 @@ static twai_obj_t *twai_alloc_driver_obj(uint32_t tx_queue_len, uint32_t rx_queu
}
#endif //CONFIG_TWAI_ISR_IN_IRAM
#ifdef CONFIG_PM_ENABLE
esp_err_t pm_err = esp_pm_lock_create(ESP_PM_APB_FREQ_MAX, 0, "twai", &(p_obj->pm_lock));
if (pm_err != ESP_OK ) {
goto cleanup;
}
#endif
return p_obj;
cleanup:
@ -406,7 +410,6 @@ esp_err_t twai_driver_install(const twai_general_config_t *g_config, const twai_
TWAI_CHECK(g_config->rx_queue_len > 0, ESP_ERR_INVALID_ARG);
TWAI_CHECK(g_config->tx_io >= 0 && g_config->tx_io < GPIO_NUM_MAX, ESP_ERR_INVALID_ARG);
TWAI_CHECK(g_config->rx_io >= 0 && g_config->rx_io < GPIO_NUM_MAX, ESP_ERR_INVALID_ARG);
TWAI_CHECK(t_config->brp >= SOC_TWAI_BRP_MIN && t_config->brp <= SOC_TWAI_BRP_MAX, ESP_ERR_INVALID_ARG);
#ifndef CONFIG_TWAI_ISR_IN_IRAM
TWAI_CHECK(!(g_config->intr_flags & ESP_INTR_FLAG_IRAM), ESP_ERR_INVALID_ARG);
#endif
@ -414,6 +417,40 @@ esp_err_t twai_driver_install(const twai_general_config_t *g_config, const twai_
TWAI_CHECK_FROM_CRIT(p_twai_obj == NULL, ESP_ERR_INVALID_STATE);
TWAI_EXIT_CRITICAL();
//Get clock source resolution
uint32_t clock_source_hz = 0;
twai_clock_source_t clk_src = t_config->clk_src;
//Fall back to default clock source
if (clk_src == 0) {
clk_src = TWAI_CLK_SRC_DEFAULT;
}
switch (clk_src) {
#if SOC_TWAI_CLK_SUPPORT_APB
case TWAI_CLK_SRC_APB:
clock_source_hz = esp_clk_apb_freq();
break;
#endif //SOC_TWAI_CLK_SUPPORT_APB
#if SOC_TWAI_CLK_SUPPORT_XTAL
case TWAI_CLK_SRC_XTAL:
clock_source_hz = esp_clk_xtal_freq();
break;
#endif //SOC_TWAI_CLK_SUPPORT_XTAL
default:
//Invalid clock source
TWAI_CHECK(false, ESP_ERR_INVALID_ARG);
}
//Check brp validation
uint32_t brp = t_config->brp;
if (t_config->quanta_resolution_hz) {
TWAI_CHECK(clock_source_hz % t_config->quanta_resolution_hz == 0, ESP_ERR_INVALID_ARG);
brp = clock_source_hz / t_config->quanta_resolution_hz;
}
TWAI_CHECK(twai_ll_check_brp_validation(brp), ESP_ERR_INVALID_ARG);
esp_err_t ret;
twai_obj_t *p_twai_obj_dummy;
@ -421,10 +458,25 @@ esp_err_t twai_driver_install(const twai_general_config_t *g_config, const twai_
p_twai_obj_dummy = twai_alloc_driver_obj(g_config->tx_queue_len, g_config->rx_queue_len);
TWAI_CHECK(p_twai_obj_dummy != NULL, ESP_ERR_NO_MEM);
// TODO: Currently only controller 0 is supported by the driver. IDF-4775
int controller_id = p_twai_obj_dummy->controller_id;
//Initialize flags and variables. All other members are already set to zero by twai_alloc_driver_obj()
p_twai_obj_dummy->state = TWAI_STATE_STOPPED;
p_twai_obj_dummy->mode = g_config->mode;
p_twai_obj_dummy->alerts_enabled = g_config->alerts_enabled;
p_twai_obj_dummy->module = twai_controller_periph_signals.controllers[controller_id].module;
#ifdef CONFIG_PM_ENABLE
if (clk_src == TWAI_CLK_SRC_APB) {
// TODO: pm_lock name should also reflect the controller ID
ret = esp_pm_lock_create(ESP_PM_APB_FREQ_MAX, 0, "twai", &(p_twai_obj_dummy->pm_lock));
if (ret != ESP_OK) {
goto err;
}
}
#endif //CONFIG_PM_ENABLE
//Initialize TWAI peripheral registers, and allocate interrupt
TWAI_ENTER_CRITICAL();
@ -436,21 +488,28 @@ esp_err_t twai_driver_install(const twai_general_config_t *g_config, const twai_
ret = ESP_ERR_INVALID_STATE;
goto err;
}
periph_module_reset(PERIPH_TWAI_MODULE);
periph_module_enable(PERIPH_TWAI_MODULE); //Enable APB CLK to TWAI peripheral
bool init = twai_hal_init(&twai_context);
assert(init);
(void)init;
//Enable TWAI peripheral register clock
periph_module_reset(p_twai_obj_dummy->module);
periph_module_enable(p_twai_obj_dummy->module);
//Initialize TWAI HAL layer
twai_hal_config_t hal_config = {
.clock_source_hz = clock_source_hz,
.controller_id = controller_id,
};
bool res = twai_hal_init(&twai_context, &hal_config);
assert(res);
twai_hal_configure(&twai_context, t_config, f_config, DRIVER_DEFAULT_INTERRUPTS, g_config->clkout_divider);
TWAI_EXIT_CRITICAL();
//Allocate GPIO and Interrupts
twai_configure_gpio(g_config->tx_io, g_config->rx_io, g_config->clkout_io, g_config->bus_off_io);
ESP_ERROR_CHECK(esp_intr_alloc(ETS_TWAI_INTR_SOURCE, g_config->intr_flags, twai_intr_handler_main, NULL, &p_twai_obj->isr_handle));
ESP_ERROR_CHECK(esp_intr_alloc(twai_controller_periph_signals.controllers[controller_id].irq_id, g_config->intr_flags,
twai_intr_handler_main, NULL, &p_twai_obj->isr_handle));
#ifdef CONFIG_PM_ENABLE
ESP_ERROR_CHECK(esp_pm_lock_acquire(p_twai_obj->pm_lock)); //Acquire pm_lock to keep APB clock at 80MHz
#endif
if (p_twai_obj->pm_lock) {
ESP_ERROR_CHECK(esp_pm_lock_acquire(p_twai_obj->pm_lock)); //Acquire pm_lock during the whole driver lifetime
}
return ESP_OK; //TWAI module is still in reset mode, users need to call twai_start() afterwards
err:
@ -468,17 +527,18 @@ esp_err_t twai_driver_uninstall(void)
TWAI_CHECK_FROM_CRIT(p_twai_obj->state == TWAI_STATE_STOPPED || p_twai_obj->state == TWAI_STATE_BUS_OFF, ESP_ERR_INVALID_STATE);
//Clear registers by reading
twai_hal_deinit(&twai_context);
periph_module_disable(PERIPH_TWAI_MODULE); //Disable TWAI peripheral
periph_module_disable(p_twai_obj->module); //Disable TWAI peripheral
p_twai_obj_dummy = p_twai_obj; //Use dummy to shorten critical section
p_twai_obj = NULL;
TWAI_EXIT_CRITICAL();
ESP_ERROR_CHECK(esp_intr_free(p_twai_obj_dummy->isr_handle)); //Free interrupt
#ifdef CONFIG_PM_ENABLE
//Release and delete power management lock
ESP_ERROR_CHECK(esp_pm_lock_release(p_twai_obj_dummy->pm_lock));
#endif
if (p_twai_obj_dummy->pm_lock) {
//Release and delete power management lock
ESP_ERROR_CHECK(esp_pm_lock_release(p_twai_obj_dummy->pm_lock));
}
//Free can driver object
twai_free_driver_obj(p_twai_obj_dummy);
return ESP_OK;

View File

@ -14,18 +14,24 @@
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include "sdkconfig.h"
#include "hal/misc.h"
#include "hal/assert.h"
#include "hal/twai_types.h"
#include "soc/twai_periph.h"
#include "soc/twai_struct.h"
#define TWAI_LL_GET_HW(controller_id) ((controller_id == 0) ? (&TWAI) : NULL)
#define TWAI_LL_BRP_DIV_THRESH 128
#ifdef __cplusplus
extern "C" {
#endif
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
@ -143,6 +149,33 @@ typedef enum {
} twai_ll_err_seg_t;
#endif
/* ---------------------------- Peripheral Control Register ----------------- */
/**
* @brief Enable TWAI module clock
*
* @param hw Start address of the TWAI registers
* @param en true to enable, false to disable
*/
__attribute__((always_inline))
static inline void twai_ll_enable_clock(twai_dev_t *hw, bool en)
{
(void)hw;
}
/**
* @brief Set clock source for TWAI module
*
* @param hw Start address of the TWAI registers
* @param clk_src Clock source
*/
__attribute__((always_inline))
static inline void twai_ll_set_clock_source(twai_dev_t *hw, twai_clock_source_t clk_src)
{
(void)hw;
HAL_ASSERT(clk_src == TWAI_CLK_SRC_APB);
}
/* ---------------------------- Mode Register ------------------------------- */
/**
@ -156,6 +189,7 @@ typedef enum {
*
* @note Reset mode is automatically entered on BUS OFF condition
*/
__attribute__((always_inline))
static inline void twai_ll_enter_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 1;
@ -172,6 +206,7 @@ static inline void twai_ll_enter_reset_mode(twai_dev_t *hw)
*
* @note Reset mode must be exit to initiate BUS OFF recovery
*/
__attribute__((always_inline))
static inline void twai_ll_exit_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 0;
@ -182,6 +217,7 @@ static inline void twai_ll_exit_reset_mode(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return true if in reset mode
*/
__attribute__((always_inline))
static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
{
return hw->mode_reg.rm;
@ -195,6 +231,7 @@ static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
@ -224,6 +261,7 @@ static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_tx(twai_dev_t *hw)
{
hw->command_reg.tr = 1;
@ -241,6 +279,7 @@ static inline void twai_ll_set_cmd_tx(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_tx_single_shot(twai_dev_t *hw)
{
hw->command_reg.val = 0x03; //Writing to TR and AT simultaneously
@ -260,6 +299,7 @@ static inline void twai_ll_set_cmd_tx_single_shot(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_abort_tx(twai_dev_t *hw)
{
hw->command_reg.at = 1;
@ -272,6 +312,7 @@ static inline void twai_ll_set_cmd_abort_tx(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_release_rx_buffer(twai_dev_t *hw)
{
hw->command_reg.rrb = 1;
@ -284,6 +325,7 @@ static inline void twai_ll_set_cmd_release_rx_buffer(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_clear_data_overrun(twai_dev_t *hw)
{
hw->command_reg.cdo = 1;
@ -303,6 +345,7 @@ static inline void twai_ll_set_cmd_clear_data_overrun(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_self_rx_request(twai_dev_t *hw)
{
hw->command_reg.srr = 1;
@ -321,6 +364,7 @@ static inline void twai_ll_set_cmd_self_rx_request(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_self_rx_single_shot(twai_dev_t *hw)
{
hw->command_reg.val = 0x12;
@ -334,6 +378,7 @@ static inline void twai_ll_set_cmd_self_rx_single_shot(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Status bits
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
{
return hw->status_reg.val;
@ -345,6 +390,7 @@ static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
__attribute__((always_inline))
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status_reg.dos;
@ -356,6 +402,7 @@ static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
__attribute__((always_inline))
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status_reg.tcs;
@ -372,6 +419,7 @@ static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Bit mask of set interrupts
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
{
return hw->interrupt_reg.val;
@ -387,6 +435,7 @@ static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
{
#if SOC_TWAI_BRP_DIV_SUPPORTED
@ -399,6 +448,25 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
/* ------------------------ Bus Timing Registers --------------------------- */
/**
* @brief Check if the brp value valid
*
* @param brp Bit rate prescaler value
* @return true or False
*/
__attribute__((always_inline))
static inline bool twai_ll_check_brp_validation(uint32_t brp)
{
bool valid = (brp >= SOC_TWAI_BRP_MIN) && (brp <= SOC_TWAI_BRP_MAX);
// should be an even number
valid = valid && !(brp & 0x01);
if (brp > TWAI_LL_BRP_DIV_THRESH) {
// should be multiple of 4
valid = valid && !(brp & 0x03);
}
return valid;
}
/**
* @brief Set bus timing
*
@ -413,10 +481,11 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
* @note ESP32 rev 2 or later can support a x2 brp by setting a brp_div bit,
* allowing the brp to go from a maximum of 128 to 256.
*/
__attribute__((always_inline))
static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t sjw, uint32_t tseg1, uint32_t tseg2, bool triple_sampling)
{
#if SOC_TWAI_BRP_DIV_SUPPORTED
if (brp > SOC_TWAI_BRP_DIV_THRESH) {
if (brp > TWAI_LL_BRP_DIV_THRESH) {
//Need to set brp_div bit
hw->interrupt_enable_reg.brp_div = 1;
brp /= 2;
@ -440,6 +509,7 @@ static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
{
(void)hw->arbitration_lost_captue_reg.val;
@ -454,6 +524,7 @@ static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
{
(void)hw->error_code_capture_reg.val;
@ -482,6 +553,7 @@ static inline void twai_ll_parse_err_code_cap(twai_dev_t *hw,
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_err_warn_lim(twai_dev_t *hw, uint32_t ewl)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->error_warning_limit_reg, ewl, ewl);
@ -493,6 +565,7 @@ static inline void twai_ll_set_err_warn_lim(twai_dev_t *hw, uint32_t ewl)
* @param hw Start address of the TWAI registers
* @return Error Warning Limit
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_err_warn_lim(twai_dev_t *hw)
{
return hw->error_warning_limit_reg.val;
@ -509,6 +582,7 @@ static inline uint32_t twai_ll_get_err_warn_lim(twai_dev_t *hw)
* @note REC is not frozen in reset mode. Listen only mode will freeze it. A BUS
* OFF condition automatically sets the REC to 0.
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_rec(twai_dev_t *hw)
{
return hw->rx_error_counter_reg.val;
@ -522,6 +596,7 @@ static inline uint32_t twai_ll_get_rec(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_rec(twai_dev_t *hw, uint32_t rec)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->rx_error_counter_reg, rxerr, rec);
@ -537,6 +612,7 @@ static inline void twai_ll_set_rec(twai_dev_t *hw, uint32_t rec)
*
* @note A BUS OFF condition will automatically set this to 128
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_tec(twai_dev_t *hw)
{
return hw->tx_error_counter_reg.val;
@ -550,6 +626,7 @@ static inline uint32_t twai_ll_get_tec(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_tec(twai_dev_t *hw, uint32_t tec)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->tx_error_counter_reg, txerr, tec);
@ -566,7 +643,8 @@ static inline void twai_ll_set_tec(twai_dev_t *hw, uint32_t tec)
*
* @note Must be called in reset mode
*/
static inline void twai_ll_set_acc_filter(twai_dev_t* hw, uint32_t code, uint32_t mask, bool single_filter)
__attribute__((always_inline))
static inline void twai_ll_set_acc_filter(twai_dev_t *hw, uint32_t code, uint32_t mask, bool single_filter)
{
uint32_t code_swapped = HAL_SWAP32(code);
uint32_t mask_swapped = HAL_SWAP32(mask);
@ -587,6 +665,7 @@ static inline void twai_ll_set_acc_filter(twai_dev_t* hw, uint32_t code, uint32_
*
* @note Call twai_ll_format_frame_buffer() to format a frame
*/
__attribute__((always_inline))
static inline void twai_ll_set_tx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *tx_frame)
{
//Copy formatted frame into TX buffer
@ -603,6 +682,7 @@ static inline void twai_ll_set_tx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t
*
* @note Call twai_ll_parse_frame_buffer() to parse the formatted frame
*/
__attribute__((always_inline))
static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *rx_frame)
{
//Copy RX buffer registers into frame
@ -626,6 +706,7 @@ static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t
* @param[in] self_rx Frame will also be simultaneously received
* @param[out] tx_frame Pointer to store formatted frame
*/
__attribute__((always_inline))
static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const uint8_t *data,
uint32_t flags, twai_ll_frame_buffer_t *tx_frame)
{
@ -669,6 +750,7 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
* @param[out] data Data. Left over bytes set to 0.
* @param[out] format Type of TWAI frame
*/
__attribute__((always_inline))
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
{
@ -717,6 +799,7 @@ static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame,
* @param hw Start address of the TWAI registers
* @return RX Message Counter
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_rx_msg_count(twai_dev_t *hw)
{
return hw->rx_message_counter_reg.val;
@ -733,6 +816,7 @@ static inline uint32_t twai_ll_get_rx_msg_count(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @param divider Divider for CLKOUT. Set to 0 to disable CLKOUT
*/
__attribute__((always_inline))
static inline void twai_ll_set_clkout(twai_dev_t *hw, uint32_t divider)
{
if (divider >= 2 && divider <= 14) {
@ -759,6 +843,7 @@ static inline void twai_ll_set_clkout(twai_dev_t *hw, uint32_t divider)
* @note Must be called before setting any configuration
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_enable_extended_reg_layout(twai_dev_t *hw)
{
hw->clock_divider_reg.cm = 1;
@ -779,6 +864,7 @@ static inline void twai_ll_enable_extended_reg_layout(twai_dev_t *hw)
* @note Some registers are cleared on entering reset mode so must be saved
* separate from this function.
*/
__attribute__((always_inline))
static inline void twai_ll_save_reg(twai_dev_t *hw, twai_ll_reg_save_t *reg_save)
{
reg_save->mode_reg = (uint8_t) hw->mode_reg.val;
@ -806,6 +892,7 @@ static inline void twai_ll_save_reg(twai_dev_t *hw, twai_ll_reg_save_t *reg_save
* @note Must be called in reset mode so that config registers become accessible
* @note Some registers are read only thus cannot be restored
*/
__attribute__((always_inline))
static inline void twai_ll_restore_reg(twai_dev_t *hw, twai_ll_reg_save_t *reg_save)
{
hw->mode_reg.val = reg_save->mode_reg;

View File

@ -14,17 +14,21 @@
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include "hal/misc.h"
#include "hal/assert.h"
#include "hal/twai_types.h"
#include "soc/twai_periph.h"
#include "soc/twai_struct.h"
#define TWAI_LL_GET_HW(controller_id) ((controller_id == 0) ? (&TWAI) : NULL)
#ifdef __cplusplus
extern "C" {
#endif
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
@ -79,6 +83,33 @@ typedef union {
_Static_assert(sizeof(twai_ll_frame_buffer_t) == 13, "TX/RX buffer type should be 13 bytes");
/* ---------------------------- Peripheral Control Register ----------------- */
/**
* @brief Enable TWAI module clock
*
* @param hw Start address of the TWAI registers
* @param en true to enable, false to disable
*/
__attribute__((always_inline))
static inline void twai_ll_enable_clock(twai_dev_t *hw, bool en)
{
(void)hw;
}
/**
* @brief Set clock source for TWAI module
*
* @param hw Start address of the TWAI registers
* @param clk_src Clock source
*/
__attribute__((always_inline))
static inline void twai_ll_set_clock_source(twai_dev_t *hw, twai_clock_source_t clk_src)
{
(void)hw;
HAL_ASSERT(clk_src == TWAI_CLK_SRC_APB);
}
/* ---------------------------- Mode Register ------------------------------- */
/**
@ -92,6 +123,7 @@ _Static_assert(sizeof(twai_ll_frame_buffer_t) == 13, "TX/RX buffer type should b
*
* @note Reset mode is automatically entered on BUS OFF condition
*/
__attribute__((always_inline))
static inline void twai_ll_enter_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 1;
@ -108,6 +140,7 @@ static inline void twai_ll_enter_reset_mode(twai_dev_t *hw)
*
* @note Reset mode must be exit to initiate BUS OFF recovery
*/
__attribute__((always_inline))
static inline void twai_ll_exit_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 0;
@ -118,6 +151,7 @@ static inline void twai_ll_exit_reset_mode(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return true if in reset mode
*/
__attribute__((always_inline))
static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
{
return hw->mode_reg.rm;
@ -131,6 +165,7 @@ static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
@ -160,6 +195,7 @@ static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_tx(twai_dev_t *hw)
{
hw->command_reg.tr = 1;
@ -177,6 +213,7 @@ static inline void twai_ll_set_cmd_tx(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__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
@ -196,6 +233,7 @@ static inline void twai_ll_set_cmd_tx_single_shot(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_abort_tx(twai_dev_t *hw)
{
hw->command_reg.at = 1;
@ -208,6 +246,7 @@ static inline void twai_ll_set_cmd_abort_tx(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_release_rx_buffer(twai_dev_t *hw)
{
hw->command_reg.rrb = 1;
@ -220,6 +259,7 @@ static inline void twai_ll_set_cmd_release_rx_buffer(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_clear_data_overrun(twai_dev_t *hw)
{
hw->command_reg.cdo = 1;
@ -239,6 +279,7 @@ static inline void twai_ll_set_cmd_clear_data_overrun(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_self_rx_request(twai_dev_t *hw)
{
hw->command_reg.srr = 1;
@ -257,6 +298,7 @@ static inline void twai_ll_set_cmd_self_rx_request(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_self_rx_single_shot(twai_dev_t *hw)
{
hw->command_reg.val = 0x12; //Set command_reg.srr and command_reg.at simultaneously for single shot self reception request
@ -270,6 +312,7 @@ static inline void twai_ll_set_cmd_self_rx_single_shot(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Status bits
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
{
return hw->status_reg.val;
@ -281,6 +324,7 @@ static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
__attribute__((always_inline))
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status_reg.dos;
@ -292,6 +336,7 @@ static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
__attribute__((always_inline))
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status_reg.tcs;
@ -308,6 +353,7 @@ static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Bit mask of set interrupts
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
{
return hw->interrupt_reg.val;
@ -323,6 +369,7 @@ static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
{
hw->interrupt_enable_reg.val = intr_mask;
@ -330,6 +377,21 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
/* ------------------------ Bus Timing Registers --------------------------- */
/**
* @brief Check if the brp value valid
*
* @param brp Bit rate prescaler value
* @return true or False
*/
__attribute__((always_inline))
static inline bool twai_ll_check_brp_validation(uint32_t brp)
{
bool valid = (brp >= SOC_TWAI_BRP_MIN) && (brp <= SOC_TWAI_BRP_MAX);
// should be an even number
valid = valid && !(brp & 0x01);
return valid;
}
/**
* @brief Set bus timing
*
@ -343,6 +405,7 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
* @note Must be called in reset mode
* @note ESP32C3 brp can be any even number between 2 to 32768
*/
__attribute__((always_inline))
static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t sjw, uint32_t tseg1, uint32_t tseg2, bool triple_sampling)
{
hw->bus_timing_0_reg.brp = (brp / 2) - 1;
@ -361,6 +424,7 @@ static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
{
(void)hw->arbitration_lost_captue_reg.val;
@ -375,6 +439,7 @@ static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
{
(void)hw->error_code_capture_reg.val;
@ -390,6 +455,7 @@ static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_err_warn_lim(twai_dev_t *hw, uint32_t ewl)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->error_warning_limit_reg, ewl, ewl);
@ -401,6 +467,7 @@ static inline void twai_ll_set_err_warn_lim(twai_dev_t *hw, uint32_t ewl)
* @param hw Start address of the TWAI registers
* @return Error Warning Limit
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_err_warn_lim(twai_dev_t *hw)
{
return hw->error_warning_limit_reg.val;
@ -417,6 +484,7 @@ static inline uint32_t twai_ll_get_err_warn_lim(twai_dev_t *hw)
* @note REC is not frozen in reset mode. Listen only mode will freeze it. A BUS
* OFF condition automatically sets the REC to 0.
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_rec(twai_dev_t *hw)
{
return hw->rx_error_counter_reg.val;
@ -430,6 +498,7 @@ static inline uint32_t twai_ll_get_rec(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_rec(twai_dev_t *hw, uint32_t rec)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->rx_error_counter_reg, rxerr, rec);
@ -445,6 +514,7 @@ static inline void twai_ll_set_rec(twai_dev_t *hw, uint32_t rec)
*
* @note A BUS OFF condition will automatically set this to 128
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_tec(twai_dev_t *hw)
{
return hw->tx_error_counter_reg.val;
@ -458,6 +528,7 @@ static inline uint32_t twai_ll_get_tec(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_tec(twai_dev_t *hw, uint32_t tec)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->tx_error_counter_reg, txerr, tec);
@ -474,6 +545,7 @@ static inline void twai_ll_set_tec(twai_dev_t *hw, uint32_t tec)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_acc_filter(twai_dev_t* hw, uint32_t code, uint32_t mask, bool single_filter)
{
uint32_t code_swapped = HAL_SWAP32(code);
@ -495,6 +567,7 @@ static inline void twai_ll_set_acc_filter(twai_dev_t* hw, uint32_t code, uint32_
*
* @note Call twai_ll_format_frame_buffer() to format a frame
*/
__attribute__((always_inline))
static inline void twai_ll_set_tx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *tx_frame)
{
//Copy formatted frame into TX buffer
@ -511,6 +584,7 @@ static inline void twai_ll_set_tx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t
*
* @note Call twai_ll_parse_frame_buffer() to parse the formatted frame
*/
__attribute__((always_inline))
static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *rx_frame)
{
//Copy RX buffer registers into frame
@ -534,6 +608,7 @@ static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t
* @param[in] self_rx Frame will also be simultaneously received
* @param[out] tx_frame Pointer to store formatted frame
*/
__attribute__((always_inline))
static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const uint8_t *data,
uint32_t flags, twai_ll_frame_buffer_t *tx_frame)
{
@ -577,6 +652,7 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
* @param[out] data Data. Left over bytes set to 0.
* @param[out] format Type of TWAI frame
*/
__attribute__((always_inline))
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
{
@ -625,6 +701,7 @@ static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame,
* @param hw Start address of the TWAI registers
* @return RX Message Counter
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_rx_msg_count(twai_dev_t *hw)
{
return hw->rx_message_counter_reg.val;
@ -641,6 +718,7 @@ static inline uint32_t twai_ll_get_rx_msg_count(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @param divider Divider for CLKOUT (any even number from 2 to 490). Set to 0 to disable CLKOUT
*/
__attribute__((always_inline))
static inline void twai_ll_set_clkout(twai_dev_t *hw, uint32_t divider)
{
if (divider >= 2 && divider <= 490) {

View File

@ -0,0 +1,761 @@
/*
* SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
/*******************************************************************************
* NOTICE
* The ll is not public api, don't use in application code.
* See readme.md in hal/include/hal/readme.md
******************************************************************************/
// The Lowlevel layer for TWAI
#pragma once
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include "hal/misc.h"
#include "hal/assert.h"
#include "hal/twai_types.h"
#include "soc/twai_struct.h"
#include "soc/pcr_struct.h"
#define TWAI_LL_GET_HW(controller_id) ((controller_id == 0) ? (&TWAI0) : (&TWAI1))
#ifdef __cplusplus
extern "C" {
#endif
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
#define TWAI_LL_STATUS_DOS (0x1 << 1) //Data Overrun Status
#define TWAI_LL_STATUS_TBS (0x1 << 2) //Transmit Buffer Status
#define TWAI_LL_STATUS_TCS (0x1 << 3) //Transmission Complete Status
#define TWAI_LL_STATUS_RS (0x1 << 4) //Receive Status
#define TWAI_LL_STATUS_TS (0x1 << 5) //Transmit Status
#define TWAI_LL_STATUS_ES (0x1 << 6) //Error Status
#define TWAI_LL_STATUS_BS (0x1 << 7) //Bus Status
#define TWAI_LL_STATUS_MS (0x1 << 8) //Miss Status
#define TWAI_LL_INTR_RI (0x1 << 0) //Receive Interrupt
#define TWAI_LL_INTR_TI (0x1 << 1) //Transmit Interrupt
#define TWAI_LL_INTR_EI (0x1 << 2) //Error Interrupt
//Data overrun interrupt not supported in SW due to HW peculiarities
#define TWAI_LL_INTR_EPI (0x1 << 5) //Error Passive Interrupt
#define TWAI_LL_INTR_ALI (0x1 << 6) //Arbitration Lost Interrupt
#define TWAI_LL_INTR_BEI (0x1 << 7) //Bus Error Interrupt
#define TWAI_LL_INTR_BISI (0x1 << 8) //Bus Idle Status Interrupt
/*
* The following frame structure has an NEARLY identical bit field layout to
* each byte of the TX buffer. This allows for formatting and parsing frames to
* be done outside of time critical regions (i.e., ISRs). All the ISR needs to
* do is to copy byte by byte to/from the TX/RX buffer. The two reserved bits in
* TX buffer are used in the frame structure to store the self_reception and
* single_shot flags which in turn indicate the type of transmission to execute.
*/
typedef union {
struct {
struct {
uint8_t dlc: 4; //Data length code (0 to 8) of the frame
uint8_t self_reception: 1; //This frame should be transmitted using self reception command
uint8_t single_shot: 1; //This frame should be transmitted using single shot command
uint8_t rtr: 1; //This frame is a remote transmission request
uint8_t frame_format: 1; //Format of the frame (1 = extended, 0 = standard)
};
union {
struct {
uint8_t id[2]; //11 bit standard frame identifier
uint8_t data[8]; //Data bytes (0 to 8)
uint8_t reserved8[2];
} standard;
struct {
uint8_t id[4]; //29 bit extended frame identifier
uint8_t data[8]; //Data bytes (0 to 8)
} extended;
};
};
uint8_t bytes[13];
} __attribute__((packed)) twai_ll_frame_buffer_t;
_Static_assert(sizeof(twai_ll_frame_buffer_t) == 13, "TX/RX buffer type should be 13 bytes");
/* ---------------------------- Peripheral Control Register ----------------- */
/**
* @brief Enable TWAI module clock
*
* @param hw Start address of the TWAI registers
* @param en true to enable, false to disable
*/
__attribute__((always_inline))
static inline void twai_ll_enable_clock(twai_dev_t *hw, bool en)
{
if (hw == &TWAI0) {
PCR.twai0_func_clk_conf.twai0_func_clk_en = en;
} else {
PCR.twai1_func_clk_conf.twai1_func_clk_en = en;
}
}
/**
* @brief Set clock source for TWAI module
*
* @param hw Start address of the TWAI registers
* @param clk_src Clock source
*/
__attribute__((always_inline))
static inline void twai_ll_set_clock_source(twai_dev_t *hw, twai_clock_source_t clk_src)
{
uint32_t clk_id = 0;
bool valid = true;
switch (clk_src) {
case TWAI_CLK_SRC_XTAL:
clk_id = 0;
break;
default:
valid = false;
HAL_ASSERT(false);
}
if (valid) {
if (hw == &TWAI0) {
PCR.twai0_func_clk_conf.twai0_func_clk_sel = clk_id;
} else {
PCR.twai1_func_clk_conf.twai1_func_clk_sel = clk_id;
}
}
}
/* ---------------------------- Mode Register ------------------------------- */
/**
* @brief Enter reset mode
*
* When in reset mode, the TWAI controller is effectively disconnected from the
* TWAI bus and will not participate in any bus activates. Reset mode is required
* in order to write the majority of configuration registers.
*
* @param hw Start address of the TWAI registers
*
* @note Reset mode is automatically entered on BUS OFF condition
*/
__attribute__((always_inline))
static inline void twai_ll_enter_reset_mode(twai_dev_t *hw)
{
hw->mode.reset_mode = 1;
}
/**
* @brief Exit reset mode
*
* When not in reset mode, the TWAI controller will take part in bus activities
* (e.g., send/receive/acknowledge messages and error frames) depending on the
* operating mode.
*
* @param hw Start address of the TWAI registers
*
* @note Reset mode must be exit to initiate BUS OFF recovery
*/
__attribute__((always_inline))
static inline void twai_ll_exit_reset_mode(twai_dev_t *hw)
{
hw->mode.reset_mode = 0;
}
/**
* @brief Check if in reset mode
* @param hw Start address of the TWAI registers
* @return true if in reset mode
*/
__attribute__((always_inline))
static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
{
return hw->mode.reset_mode;
}
/**
* @brief Set operating mode of TWAI controller
*
* @param hw Start address of the TWAI registers
* @param mode Operating mode
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
hw->mode.listen_only_mode = 0;
hw->mode.self_test_mode = 0;
} else if (mode == TWAI_MODE_NO_ACK) { //Self Test Mode (No Ack)
hw->mode.listen_only_mode = 0;
hw->mode.self_test_mode = 1;
} else if (mode == TWAI_MODE_LISTEN_ONLY) { //Listen Only Mode
hw->mode.listen_only_mode = 1;
hw->mode.self_test_mode = 0;
}
}
/* --------------------------- Command Register ----------------------------- */
/**
* @brief Set TX 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
*
* @note Transmit commands should be called last (i.e., after handling buffer
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_tx(twai_dev_t *hw)
{
hw->cmd.tx_request = 1;
}
/**
* @brief Set single shot TX command
*
* Similar to setting TX command, but the TWAI controller will not automatically
* retry transmission upon an error (e.g., due to an acknowledgement error).
*
* @param hw Start address of the TWAI registers
*
* @note Transmit commands should be called last (i.e., after handling buffer
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_tx_single_shot(twai_dev_t *hw)
{
hw->cmd.val = 0x03; //Set cmd.tx_request and cmd.abort_tx simultaneously for single shot transmitting request
}
/**
* @brief Aborts TX
*
* Frames awaiting TX will be aborted. Frames already being TX are not aborted.
* Transmission Complete Status bit is automatically set to 1.
* Similar to setting TX command, but the TWAI controller will not automatically
* retry transmission upon an error (e.g., due to acknowledge error).
*
* @param hw Start address of the TWAI registers
*
* @note Transmit commands should be called last (i.e., after handling buffer
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_abort_tx(twai_dev_t *hw)
{
hw->cmd.abort_tx = 1;
}
/**
* @brief Release RX buffer
*
* Rotates RX buffer to the next frame in the RX FIFO.
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_release_rx_buffer(twai_dev_t *hw)
{
hw->cmd.release_buffer = 1;
}
/**
* @brief Clear data overrun
*
* Clears the data overrun status bit
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_clear_data_overrun(twai_dev_t *hw)
{
hw->cmd.clear_data_overrun = 1;
}
/**
* @brief Set self reception single shot command
*
* Similar to setting TX command, but the TWAI controller also simultaneously
* receive the transmitted frame and is generally used for self testing
* purposes. The TWAI controller will not ACK the received message, so consider
* using the NO_ACK operating mode.
*
* @param hw Start address of the TWAI registers
*
* @note Transmit commands should be called last (i.e., after handling buffer
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_self_rx_request(twai_dev_t *hw)
{
hw->cmd.self_rx_request = 1;
}
/**
* @brief Set self reception request command
*
* Similar to setting the self reception request, but the TWAI controller will
* not automatically retry transmission upon an error (e.g., due to and
* acknowledgement error).
*
* @param hw Start address of the TWAI registers
*
* @note Transmit commands should be called last (i.e., after handling buffer
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_self_rx_single_shot(twai_dev_t *hw)
{
hw->cmd.val = 0x12; //Set cmd.self_rx_request and cmd.abort_tx simultaneously for single shot self reception request
}
/* --------------------------- Status Register ------------------------------ */
/**
* @brief Get all status bits
*
* @param hw Start address of the TWAI registers
* @return Status bits
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
{
return hw->status.val;
}
/**
* @brief Check if RX FIFO overrun status bit is set
*
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
__attribute__((always_inline))
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status.status_overrun;
}
/**
* @brief Check if previously TX was successful
*
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
__attribute__((always_inline))
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status.status_transmission_complete;
}
/* -------------------------- Interrupt Register ---------------------------- */
/**
* @brief Get currently set interrupts
*
* Reading the interrupt registers will automatically clear all interrupts
* except for the Receive Interrupt.
*
* @param hw Start address of the TWAI registers
* @return Bit mask of set interrupts
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
{
return hw->interrupt.val;
}
/* ----------------------- Interrupt Enable Register ------------------------ */
/**
* @brief Set which interrupts are enabled
*
* @param hw Start address of the TWAI registers
* @param Bit mask of interrupts to enable
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
{
hw->interrupt_enable.val = intr_mask;
}
/* ------------------------ Bus Timing Registers --------------------------- */
/**
* @brief Check if the brp value valid
*
* @param brp Bit rate prescaler value
* @return true or False
*/
__attribute__((always_inline))
static inline bool twai_ll_check_brp_validation(uint32_t brp)
{
bool valid = (brp >= SOC_TWAI_BRP_MIN) && (brp <= SOC_TWAI_BRP_MAX);
// should be an even number
valid = valid && !(brp & 0x01);
return valid;
}
/**
* @brief Set bus timing
*
* @param hw Start address of the TWAI registers
* @param brp Baud Rate Prescaler
* @param sjw Synchronization Jump Width
* @param tseg1 Timing Segment 1
* @param tseg2 Timing Segment 2
* @param triple_sampling Triple Sampling enable/disable
*
* @note Must be called in reset mode
* @note ESP32C6 brp can be any even number between 2 to 32768
*/
__attribute__((always_inline))
static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t sjw, uint32_t tseg1, uint32_t tseg2, bool triple_sampling)
{
hw->bus_timing_0.baud_presc = (brp / 2) - 1;
hw->bus_timing_0.sync_jump_width = sjw - 1;
hw->bus_timing_1.time_segment1 = tseg1 - 1;
hw->bus_timing_1.time_segment2 = tseg2 - 1;
hw->bus_timing_1.time_sampling = triple_sampling;
}
/* ----------------------------- ALC Register ------------------------------- */
/**
* @brief Clear Arbitration Lost Capture Register
*
* Reading the ALC register rearms the Arbitration Lost Interrupt
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
{
(void)hw->arb_lost_cap.val;
}
/* ----------------------------- ECC Register ------------------------------- */
/**
* @brief Clear Error Code Capture register
*
* Reading the ECC register rearms the Bus Error Interrupt
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
{
(void)hw->err_code_cap.val;
}
/* ----------------------------- EWL Register ------------------------------- */
/**
* @brief Set Error Warning Limit
*
* @param hw Start address of the TWAI registers
* @param ewl Error Warning Limit
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_err_warn_lim(twai_dev_t *hw, uint32_t ewl)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->err_warning_limit, err_warning_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 twai_ll_get_err_warn_lim(twai_dev_t *hw)
{
return hw->err_warning_limit.val;
}
/* ------------------------ RX Error Count Register ------------------------- */
/**
* @brief Get RX Error Counter
*
* @param hw Start address of the TWAI registers
* @return REC value
*
* @note REC is not frozen in reset mode. Listen only mode will freeze it. A BUS
* OFF condition automatically sets the REC to 0.
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_rec(twai_dev_t *hw)
{
return hw->rx_err_cnt.val;
}
/**
* @brief Set RX Error Counter
*
* @param hw Start address of the TWAI registers
* @param rec REC value
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_rec(twai_dev_t *hw, uint32_t rec)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->rx_err_cnt, rx_err_cnt, rec);
}
/* ------------------------ TX Error Count Register ------------------------- */
/**
* @brief Get TX Error Counter
*
* @param hw Start address of the TWAI registers
* @return TEC value
*
* @note A BUS OFF condition will automatically set this to 128
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_tec(twai_dev_t *hw)
{
return hw->tx_err_cnt.val;
}
/**
* @brief Set TX Error Counter
*
* @param hw Start address of the TWAI registers
* @param tec TEC value
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_tec(twai_dev_t *hw, uint32_t tec)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->tx_err_cnt, tx_err_cnt, tec);
}
/* ---------------------- Acceptance Filter Registers ----------------------- */
/**
* @brief Set Acceptance Filter
* @param hw Start address of the TWAI registers
* @param code Acceptance Code
* @param mask Acceptance Mask
* @param single_filter Whether to enable single filter mode
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_acc_filter(twai_dev_t *hw, uint32_t code, uint32_t mask, bool single_filter)
{
uint32_t code_swapped = HAL_SWAP32(code);
uint32_t mask_swapped = HAL_SWAP32(mask);
for (int i = 0; i < 4; i++) {
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->acceptance_filter.acr[i], byte, ((code_swapped >> (i * 8)) & 0xFF));
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->acceptance_filter.amr[i], byte, ((mask_swapped >> (i * 8)) & 0xFF));
}
hw->mode.acceptance_filter_mode = single_filter;
}
/* ------------------------- TX/RX Buffer Registers ------------------------- */
/**
* @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
*
* @note Call twai_ll_format_frame_buffer() to format a frame
*/
__attribute__((always_inline))
static inline void twai_ll_set_tx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *tx_frame)
{
//Copy formatted frame into TX buffer
for (int i = 0; i < 13; i++) {
hw->tx_rx_buffer[i].val = tx_frame->bytes[i];
}
}
/**
* @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 twai_ll_parse_frame_buffer() to parse the formatted frame
*/
__attribute__((always_inline))
static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *rx_frame)
{
//Copy RX buffer registers into frame
for (int i = 0; i < 13; i++) {
rx_frame->bytes[i] = HAL_FORCE_READ_U32_REG_FIELD(hw->tx_rx_buffer[i], byte);
}
}
/**
* @brief Format contents of a TWAI frame 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 TX buffer.
*
* @param[in] 11bit or 29bit ID
* @param[in] dlc Data length code
* @param[in] data Pointer to an 8 byte array containing data. NULL if no data
* @param[in] format Type of TWAI frame
* @param[in] single_shot Frame will not be retransmitted on failure
* @param[in] self_rx Frame will also be simultaneously received
* @param[out] tx_frame Pointer to store formatted frame
*/
__attribute__((always_inline))
static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const uint8_t *data,
uint32_t flags, twai_ll_frame_buffer_t *tx_frame)
{
bool is_extd = flags & TWAI_MSG_FLAG_EXTD;
bool is_rtr = flags & TWAI_MSG_FLAG_RTR;
//Set frame information
tx_frame->dlc = dlc;
tx_frame->frame_format = is_extd;
tx_frame->rtr = is_rtr;
tx_frame->self_reception = (flags & TWAI_MSG_FLAG_SELF) ? 1 : 0;
tx_frame->single_shot = (flags & TWAI_MSG_FLAG_SS) ? 1 : 0;
//Set ID. The ID registers are big endian and left aligned, therefore a bswap will be required
if (is_extd) {
uint32_t id_temp = HAL_SWAP32((id & TWAI_EXTD_ID_MASK) << 3); //((id << 3) >> 8*(3-i))
for (int i = 0; i < 4; i++) {
tx_frame->extended.id[i] = (id_temp >> (8 * i)) & 0xFF;
}
} else {
uint32_t id_temp = HAL_SWAP16((id & TWAI_STD_ID_MASK) << 5); //((id << 5) >> 8*(1-i))
for (int i = 0; i < 2; i++) {
tx_frame->standard.id[i] = (id_temp >> (8 * i)) & 0xFF;
}
}
uint8_t *data_buffer = (is_extd) ? tx_frame->extended.data : tx_frame->standard.data;
if (!is_rtr) { //Only copy data if the frame is a data frame (i.e not a remote frame)
for (int i = 0; (i < dlc) && (i < TWAI_FRAME_MAX_DLC); i++) {
data_buffer[i] = data[i];
}
}
}
/**
* @brief Parse formatted TWAI frame (RX Buffer Layout) into its constituent contents
*
* @param[in] rx_frame Pointer to formatted frame
* @param[out] id 11 or 29bit ID
* @param[out] dlc Data length code
* @param[out] data Data. Left over bytes set to 0.
* @param[out] format Type of TWAI frame
*/
__attribute__((always_inline))
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
{
//Copy frame information
*dlc = rx_frame->dlc;
uint32_t flags_temp = 0;
flags_temp |= (rx_frame->frame_format) ? TWAI_MSG_FLAG_EXTD : 0;
flags_temp |= (rx_frame->rtr) ? TWAI_MSG_FLAG_RTR : 0;
flags_temp |= (rx_frame->dlc > TWAI_FRAME_MAX_DLC) ? TWAI_MSG_FLAG_DLC_NON_COMP : 0;
*flags = flags_temp;
//Copy ID. The ID registers are big endian and left aligned, therefore a bswap will be required
if (rx_frame->frame_format) {
uint32_t id_temp = 0;
for (int i = 0; i < 4; i++) {
id_temp |= rx_frame->extended.id[i] << (8 * i);
}
id_temp = HAL_SWAP32(id_temp) >> 3; //((byte[i] << 8*(3-i)) >> 3)
*id = id_temp & TWAI_EXTD_ID_MASK;
} else {
uint32_t id_temp = 0;
for (int i = 0; i < 2; i++) {
id_temp |= rx_frame->standard.id[i] << (8 * i);
}
id_temp = HAL_SWAP16(id_temp) >> 5; //((byte[i] << 8*(1-i)) >> 5)
*id = id_temp & TWAI_STD_ID_MASK;
}
uint8_t *data_buffer = (rx_frame->frame_format) ? rx_frame->extended.data : rx_frame->standard.data;
//Only copy data if the frame is a data frame (i.e. not a remote frame)
int data_length = (rx_frame->rtr) ? 0 : ((rx_frame->dlc > TWAI_FRAME_MAX_DLC) ? TWAI_FRAME_MAX_DLC : rx_frame->dlc);
for (int i = 0; i < data_length; i++) {
data[i] = data_buffer[i];
}
//Set remaining bytes of data to 0
for (int i = data_length; i < TWAI_FRAME_MAX_DLC; i++) {
data[i] = 0;
}
}
/* ----------------------- RX Message Count Register ------------------------ */
/**
* @brief Get RX Message Counter
*
* @param hw Start address of the TWAI registers
* @return RX Message Counter
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_rx_msg_count(twai_dev_t *hw)
{
return hw->rx_message_counter.val;
}
/* ------------------------- Clock Divider Register ------------------------- */
/**
* @brief Set CLKOUT Divider and enable/disable
*
* Configure CLKOUT. CLKOUT is a pre-scaled version of peripheral source clock. Divider can be
* 1, or any even number from 2 to 490. Set the divider to 0 to disable CLKOUT.
*
* @param hw Start address of the TWAI registers
* @param divider Divider for CLKOUT (any even number from 2 to 490). Set to 0 to disable CLKOUT
*/
__attribute__((always_inline))
static inline void twai_ll_set_clkout(twai_dev_t *hw, uint32_t divider)
{
if (divider >= 2 && divider <= 490) {
hw->clock_divider.clock_off = 0;
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->clock_divider, cd, (divider / 2) - 1);
} else if (divider == 1) {
//Setting the divider reg to max value (255) means a divider of 1
hw->clock_divider.clock_off = 0;
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->clock_divider, cd, 255);
} else {
hw->clock_divider.clock_off = 1;
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->clock_divider, cd, 0);
}
}
#ifdef __cplusplus
}
#endif

View File

@ -14,17 +14,22 @@
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include "hal/misc.h"
#include "hal/assert.h"
#include "hal/twai_types.h"
#include "soc/twai_periph.h"
#include "soc/twai_struct.h"
#define TWAI_LL_GET_HW(controller_id) ((controller_id == 0) ? (&TWAI) : NULL)
#ifdef __cplusplus
extern "C" {
#endif
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
@ -79,6 +84,33 @@ typedef union {
_Static_assert(sizeof(twai_ll_frame_buffer_t) == 13, "TX/RX buffer type should be 13 bytes");
/* ---------------------------- Peripheral Control Register ----------------- */
/**
* @brief Enable TWAI module clock
*
* @param hw Start address of the TWAI registers
* @param en true to enable, false to disable
*/
__attribute__((always_inline))
static inline void twai_ll_enable_clock(twai_dev_t *hw, bool en)
{
(void)hw;
}
/**
* @brief Set clock source for TWAI module
*
* @param hw Start address of the TWAI registers
* @param clk_src Clock source
*/
__attribute__((always_inline))
static inline void twai_ll_set_clock_source(twai_dev_t *hw, twai_clock_source_t clk_src)
{
(void)hw;
HAL_ASSERT(clk_src == TWAI_CLK_SRC_APB);
}
/* ---------------------------- Mode Register ------------------------------- */
/**
@ -92,6 +124,7 @@ _Static_assert(sizeof(twai_ll_frame_buffer_t) == 13, "TX/RX buffer type should b
*
* @note Reset mode is automatically entered on BUS OFF condition
*/
__attribute__((always_inline))
static inline void twai_ll_enter_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 1;
@ -108,6 +141,7 @@ static inline void twai_ll_enter_reset_mode(twai_dev_t *hw)
*
* @note Reset mode must be exit to initiate BUS OFF recovery
*/
__attribute__((always_inline))
static inline void twai_ll_exit_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 0;
@ -118,6 +152,7 @@ static inline void twai_ll_exit_reset_mode(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return true if in reset mode
*/
__attribute__((always_inline))
static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
{
return hw->mode_reg.rm;
@ -131,6 +166,7 @@ static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
@ -160,6 +196,7 @@ static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_tx(twai_dev_t *hw)
{
hw->command_reg.tr = 1;
@ -177,6 +214,7 @@ static inline void twai_ll_set_cmd_tx(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__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
@ -196,6 +234,7 @@ static inline void twai_ll_set_cmd_tx_single_shot(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_abort_tx(twai_dev_t *hw)
{
hw->command_reg.at = 1;
@ -208,6 +247,7 @@ static inline void twai_ll_set_cmd_abort_tx(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_release_rx_buffer(twai_dev_t *hw)
{
hw->command_reg.rrb = 1;
@ -220,6 +260,7 @@ static inline void twai_ll_set_cmd_release_rx_buffer(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_clear_data_overrun(twai_dev_t *hw)
{
hw->command_reg.cdo = 1;
@ -239,6 +280,7 @@ static inline void twai_ll_set_cmd_clear_data_overrun(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_self_rx_request(twai_dev_t *hw)
{
hw->command_reg.srr = 1;
@ -257,6 +299,7 @@ static inline void twai_ll_set_cmd_self_rx_request(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_self_rx_single_shot(twai_dev_t *hw)
{
hw->command_reg.val = 0x12; //Set command_reg.srr and command_reg.at simultaneously for single shot self reception request
@ -270,6 +313,7 @@ static inline void twai_ll_set_cmd_self_rx_single_shot(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Status bits
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
{
return hw->status_reg.val;
@ -281,6 +325,7 @@ static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
__attribute__((always_inline))
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status_reg.dos;
@ -292,6 +337,7 @@ static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
__attribute__((always_inline))
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status_reg.tcs;
@ -308,6 +354,7 @@ static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Bit mask of set interrupts
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
{
return hw->interrupt_reg.val;
@ -323,6 +370,7 @@ static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
{
hw->interrupt_enable_reg.val = intr_mask;
@ -330,6 +378,21 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
/* ------------------------ Bus Timing Registers --------------------------- */
/**
* @brief Check if the brp value valid
*
* @param brp Bit rate prescaler value
* @return true or False
*/
__attribute__((always_inline))
static inline bool twai_ll_check_brp_validation(uint32_t brp)
{
bool valid = (brp >= SOC_TWAI_BRP_MIN) && (brp <= SOC_TWAI_BRP_MAX);
// should be an even number
valid = valid && !(brp & 0x01);
return valid;
}
/**
* @brief Set bus timing
*
@ -343,6 +406,7 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
* @note Must be called in reset mode
* @note ESP32H2 brp can be any even number between 2 to 32768
*/
__attribute__((always_inline))
static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t sjw, uint32_t tseg1, uint32_t tseg2, bool triple_sampling)
{
hw->bus_timing_0_reg.brp = (brp / 2) - 1;
@ -361,6 +425,7 @@ static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
{
(void)hw->arbitration_lost_captue_reg.val;
@ -375,6 +440,7 @@ static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
{
(void)hw->error_code_capture_reg.val;
@ -390,6 +456,7 @@ static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_err_warn_lim(twai_dev_t *hw, uint32_t ewl)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->error_warning_limit_reg, ewl, ewl);
@ -401,6 +468,7 @@ static inline void twai_ll_set_err_warn_lim(twai_dev_t *hw, uint32_t ewl)
* @param hw Start address of the TWAI registers
* @return Error Warning Limit
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_err_warn_lim(twai_dev_t *hw)
{
return hw->error_warning_limit_reg.val;
@ -417,6 +485,7 @@ static inline uint32_t twai_ll_get_err_warn_lim(twai_dev_t *hw)
* @note REC is not frozen in reset mode. Listen only mode will freeze it. A BUS
* OFF condition automatically sets the REC to 0.
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_rec(twai_dev_t *hw)
{
return hw->rx_error_counter_reg.val;
@ -430,6 +499,7 @@ static inline uint32_t twai_ll_get_rec(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_rec(twai_dev_t *hw, uint32_t rec)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->rx_error_counter_reg, rxerr, rec);
@ -445,6 +515,7 @@ static inline void twai_ll_set_rec(twai_dev_t *hw, uint32_t rec)
*
* @note A BUS OFF condition will automatically set this to 128
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_tec(twai_dev_t *hw)
{
return hw->tx_error_counter_reg.val;
@ -458,6 +529,7 @@ static inline uint32_t twai_ll_get_tec(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_tec(twai_dev_t *hw, uint32_t tec)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->tx_error_counter_reg, txerr, tec);
@ -474,6 +546,7 @@ static inline void twai_ll_set_tec(twai_dev_t *hw, uint32_t tec)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_acc_filter(twai_dev_t* hw, uint32_t code, uint32_t mask, bool single_filter)
{
uint32_t code_swapped = __builtin_bswap32(code);
@ -495,6 +568,7 @@ static inline void twai_ll_set_acc_filter(twai_dev_t* hw, uint32_t code, uint32_
*
* @note Call twai_ll_format_frame_buffer() to format a frame
*/
__attribute__((always_inline))
static inline void twai_ll_set_tx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *tx_frame)
{
//Copy formatted frame into TX buffer
@ -511,6 +585,7 @@ static inline void twai_ll_set_tx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t
*
* @note Call twai_ll_parse_frame_buffer() to parse the formatted frame
*/
__attribute__((always_inline))
static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *rx_frame)
{
//Copy RX buffer registers into frame
@ -534,6 +609,7 @@ static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t
* @param[in] self_rx Frame will also be simultaneously received
* @param[out] tx_frame Pointer to store formatted frame
*/
__attribute__((always_inline))
static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const uint8_t *data,
uint32_t flags, twai_ll_frame_buffer_t *tx_frame)
{
@ -577,6 +653,7 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
* @param[out] data Data. Left over bytes set to 0.
* @param[out] format Type of TWAI frame
*/
__attribute__((always_inline))
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
{
@ -625,6 +702,7 @@ static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame,
* @param hw Start address of the TWAI registers
* @return RX Message Counter
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_rx_msg_count(twai_dev_t *hw)
{
return hw->rx_message_counter_reg.val;
@ -641,6 +719,7 @@ static inline uint32_t twai_ll_get_rx_msg_count(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @param divider Divider for CLKOUT (any even number from 2 to 490). Set to 0 to disable CLKOUT
*/
__attribute__((always_inline))
static inline void twai_ll_set_clkout(twai_dev_t *hw, uint32_t divider)
{
if (divider >= 2 && divider <= 490) {

View File

@ -14,17 +14,21 @@
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include "hal/misc.h"
#include "hal/assert.h"
#include "hal/twai_types.h"
#include "soc/twai_periph.h"
#include "soc/twai_struct.h"
#define TWAI_LL_GET_HW(controller_id) ((controller_id == 0) ? (&TWAI) : NULL)
#ifdef __cplusplus
extern "C" {
#endif
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
@ -79,6 +83,33 @@ typedef union {
_Static_assert(sizeof(twai_ll_frame_buffer_t) == 13, "TX/RX buffer type should be 13 bytes");
/* ---------------------------- Peripheral Control Register ----------------- */
/**
* @brief Enable TWAI module clock
*
* @param hw Start address of the TWAI registers
* @param en true to enable, false to disable
*/
__attribute__((always_inline))
static inline void twai_ll_enable_clock(twai_dev_t *hw, bool en)
{
(void)hw;
}
/**
* @brief Set clock source for TWAI module
*
* @param hw Start address of the TWAI registers
* @param clk_src Clock source
*/
__attribute__((always_inline))
static inline void twai_ll_set_clock_source(twai_dev_t *hw, twai_clock_source_t clk_src)
{
(void)hw;
HAL_ASSERT(clk_src == TWAI_CLK_SRC_APB);
}
/* ---------------------------- Mode Register ------------------------------- */
/**
@ -92,6 +123,7 @@ _Static_assert(sizeof(twai_ll_frame_buffer_t) == 13, "TX/RX buffer type should b
*
* @note Reset mode is automatically entered on BUS OFF condition
*/
__attribute__((always_inline))
static inline void twai_ll_enter_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 1;
@ -108,6 +140,7 @@ static inline void twai_ll_enter_reset_mode(twai_dev_t *hw)
*
* @note Reset mode must be exit to initiate BUS OFF recovery
*/
__attribute__((always_inline))
static inline void twai_ll_exit_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 0;
@ -118,6 +151,7 @@ static inline void twai_ll_exit_reset_mode(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return true if in reset mode
*/
__attribute__((always_inline))
static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
{
return hw->mode_reg.rm;
@ -131,6 +165,7 @@ static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
@ -160,6 +195,7 @@ static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_tx(twai_dev_t *hw)
{
hw->command_reg.tr = 1;
@ -177,6 +213,7 @@ static inline void twai_ll_set_cmd_tx(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__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
@ -196,6 +233,7 @@ static inline void twai_ll_set_cmd_tx_single_shot(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_abort_tx(twai_dev_t *hw)
{
hw->command_reg.at = 1;
@ -208,6 +246,7 @@ static inline void twai_ll_set_cmd_abort_tx(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_release_rx_buffer(twai_dev_t *hw)
{
hw->command_reg.rrb = 1;
@ -220,6 +259,7 @@ static inline void twai_ll_set_cmd_release_rx_buffer(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_clear_data_overrun(twai_dev_t *hw)
{
hw->command_reg.cdo = 1;
@ -239,6 +279,7 @@ static inline void twai_ll_set_cmd_clear_data_overrun(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_self_rx_request(twai_dev_t *hw)
{
hw->command_reg.srr = 1;
@ -257,6 +298,7 @@ static inline void twai_ll_set_cmd_self_rx_request(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_self_rx_single_shot(twai_dev_t *hw)
{
hw->command_reg.val = 0x12; //Set command_reg.srr and command_reg.at simultaneously for single shot self reception request
@ -270,6 +312,7 @@ static inline void twai_ll_set_cmd_self_rx_single_shot(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Status bits
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
{
return hw->status_reg.val;
@ -281,6 +324,7 @@ static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
__attribute__((always_inline))
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status_reg.dos;
@ -292,6 +336,7 @@ static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
__attribute__((always_inline))
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status_reg.tcs;
@ -308,6 +353,7 @@ static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Bit mask of set interrupts
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
{
return hw->interrupt_reg.val;
@ -323,6 +369,7 @@ static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
{
hw->interrupt_enable_reg.val = intr_mask;
@ -330,6 +377,21 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
/* ------------------------ Bus Timing Registers --------------------------- */
/**
* @brief Check if the brp value valid
*
* @param brp Bit rate prescaler value
* @return true or False
*/
__attribute__((always_inline))
static inline bool twai_ll_check_brp_validation(uint32_t brp)
{
bool valid = (brp >= SOC_TWAI_BRP_MIN) && (brp <= SOC_TWAI_BRP_MAX);
// should be an even number
valid = valid && !(brp & 0x01);
return valid;
}
/**
* @brief Set bus timing
*
@ -343,6 +405,7 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
* @note Must be called in reset mode
* @note ESP32S2 brp can be any even number between 2 to 32768
*/
__attribute__((always_inline))
static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t sjw, uint32_t tseg1, uint32_t tseg2, bool triple_sampling)
{
hw->bus_timing_0_reg.brp = (brp / 2) - 1;
@ -361,6 +424,7 @@ static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
{
(void)hw->arbitration_lost_captue_reg.val;
@ -375,6 +439,7 @@ static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
{
(void)hw->error_code_capture_reg.val;
@ -390,6 +455,7 @@ static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_err_warn_lim(twai_dev_t *hw, uint32_t ewl)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->error_warning_limit_reg, ewl, ewl);
@ -401,6 +467,7 @@ static inline void twai_ll_set_err_warn_lim(twai_dev_t *hw, uint32_t ewl)
* @param hw Start address of the TWAI registers
* @return Error Warning Limit
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_err_warn_lim(twai_dev_t *hw)
{
return hw->error_warning_limit_reg.val;
@ -417,6 +484,7 @@ static inline uint32_t twai_ll_get_err_warn_lim(twai_dev_t *hw)
* @note REC is not frozen in reset mode. Listen only mode will freeze it. A BUS
* OFF condition automatically sets the REC to 0.
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_rec(twai_dev_t *hw)
{
return hw->rx_error_counter_reg.val;
@ -430,6 +498,7 @@ static inline uint32_t twai_ll_get_rec(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_rec(twai_dev_t *hw, uint32_t rec)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->rx_error_counter_reg, rxerr, rec);
@ -445,6 +514,7 @@ static inline void twai_ll_set_rec(twai_dev_t *hw, uint32_t rec)
*
* @note A BUS OFF condition will automatically set this to 128
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_tec(twai_dev_t *hw)
{
return hw->tx_error_counter_reg.val;
@ -458,6 +528,7 @@ static inline uint32_t twai_ll_get_tec(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_tec(twai_dev_t *hw, uint32_t tec)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->tx_error_counter_reg, txerr, tec);
@ -474,6 +545,7 @@ static inline void twai_ll_set_tec(twai_dev_t *hw, uint32_t tec)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_acc_filter(twai_dev_t* hw, uint32_t code, uint32_t mask, bool single_filter)
{
uint32_t code_swapped = HAL_SWAP32(code);
@ -495,6 +567,7 @@ static inline void twai_ll_set_acc_filter(twai_dev_t* hw, uint32_t code, uint32_
*
* @note Call twai_ll_format_frame_buffer() to format a frame
*/
__attribute__((always_inline))
static inline void twai_ll_set_tx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *tx_frame)
{
//Copy formatted frame into TX buffer
@ -511,6 +584,7 @@ static inline void twai_ll_set_tx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t
*
* @note Call twai_ll_parse_frame_buffer() to parse the formatted frame
*/
__attribute__((always_inline))
static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *rx_frame)
{
//Copy RX buffer registers into frame
@ -534,6 +608,7 @@ static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t
* @param[in] self_rx Frame will also be simultaneously received
* @param[out] tx_frame Pointer to store formatted frame
*/
__attribute__((always_inline))
static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const uint8_t *data,
uint32_t flags, twai_ll_frame_buffer_t *tx_frame)
{
@ -577,6 +652,7 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
* @param[out] data Data. Left over bytes set to 0.
* @param[out] format Type of TWAI frame
*/
__attribute__((always_inline))
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
{
@ -625,6 +701,7 @@ static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame,
* @param hw Start address of the TWAI registers
* @return RX Message Counter
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_rx_msg_count(twai_dev_t *hw)
{
return hw->rx_message_counter_reg.val;
@ -641,6 +718,7 @@ static inline uint32_t twai_ll_get_rx_msg_count(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @param divider Divider for CLKOUT (any even number from 2 to 490). Set to 0 to disable CLKOUT
*/
__attribute__((always_inline))
static inline void twai_ll_set_clkout(twai_dev_t *hw, uint32_t divider)
{
if (divider >= 2 && divider <= 490) {

View File

@ -14,17 +14,21 @@
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include "hal/misc.h"
#include "hal/assert.h"
#include "hal/twai_types.h"
#include "soc/twai_periph.h"
#include "soc/twai_struct.h"
#define TWAI_LL_GET_HW(controller_id) ((controller_id == 0) ? (&TWAI) : NULL)
#ifdef __cplusplus
extern "C" {
#endif
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_STATUS_RBS (0x1 << 0) //Receive Buffer Status
@ -79,6 +83,33 @@ typedef union {
_Static_assert(sizeof(twai_ll_frame_buffer_t) == 13, "TX/RX buffer type should be 13 bytes");
/* ---------------------------- Peripheral Control Register ----------------- */
/**
* @brief Enable TWAI module clock
*
* @param hw Start address of the TWAI registers
* @param en true to enable, false to disable
*/
__attribute__((always_inline))
static inline void twai_ll_enable_clock(twai_dev_t *hw, bool en)
{
(void)hw;
}
/**
* @brief Set clock source for TWAI module
*
* @param hw Start address of the TWAI registers
* @param clk_src Clock source
*/
__attribute__((always_inline))
static inline void twai_ll_set_clock_source(twai_dev_t *hw, twai_clock_source_t clk_src)
{
(void)hw;
HAL_ASSERT(clk_src == TWAI_CLK_SRC_APB);
}
/* ---------------------------- Mode Register ------------------------------- */
/**
@ -92,6 +123,7 @@ _Static_assert(sizeof(twai_ll_frame_buffer_t) == 13, "TX/RX buffer type should b
*
* @note Reset mode is automatically entered on BUS OFF condition
*/
__attribute__((always_inline))
static inline void twai_ll_enter_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 1;
@ -108,6 +140,7 @@ static inline void twai_ll_enter_reset_mode(twai_dev_t *hw)
*
* @note Reset mode must be exit to initiate BUS OFF recovery
*/
__attribute__((always_inline))
static inline void twai_ll_exit_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 0;
@ -118,6 +151,7 @@ static inline void twai_ll_exit_reset_mode(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return true if in reset mode
*/
__attribute__((always_inline))
static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
{
return hw->mode_reg.rm;
@ -131,6 +165,7 @@ static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
{
if (mode == TWAI_MODE_NORMAL) { //Normal Operating mode
@ -160,6 +195,7 @@ static inline void twai_ll_set_mode(twai_dev_t *hw, twai_mode_t mode)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_tx(twai_dev_t *hw)
{
hw->command_reg.tr = 1;
@ -177,6 +213,7 @@ static inline void twai_ll_set_cmd_tx(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__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
@ -196,6 +233,7 @@ static inline void twai_ll_set_cmd_tx_single_shot(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_abort_tx(twai_dev_t *hw)
{
hw->command_reg.at = 1;
@ -208,6 +246,7 @@ static inline void twai_ll_set_cmd_abort_tx(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_release_rx_buffer(twai_dev_t *hw)
{
hw->command_reg.rrb = 1;
@ -220,6 +259,7 @@ static inline void twai_ll_set_cmd_release_rx_buffer(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_clear_data_overrun(twai_dev_t *hw)
{
hw->command_reg.cdo = 1;
@ -239,6 +279,7 @@ static inline void twai_ll_set_cmd_clear_data_overrun(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_self_rx_request(twai_dev_t *hw)
{
hw->command_reg.srr = 1;
@ -257,6 +298,7 @@ static inline void twai_ll_set_cmd_self_rx_request(twai_dev_t *hw)
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
__attribute__((always_inline))
static inline void twai_ll_set_cmd_self_rx_single_shot(twai_dev_t *hw)
{
hw->command_reg.val = 0x12; //Set command_reg.srr and command_reg.at simultaneously for single shot self reception request
@ -270,6 +312,7 @@ static inline void twai_ll_set_cmd_self_rx_single_shot(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Status bits
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
{
return hw->status_reg.val;
@ -281,6 +324,7 @@ static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
__attribute__((always_inline))
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status_reg.dos;
@ -292,6 +336,7 @@ static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
__attribute__((always_inline))
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status_reg.tcs;
@ -308,6 +353,7 @@ static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @return Bit mask of set interrupts
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
{
return hw->interrupt_reg.val;
@ -323,6 +369,7 @@ static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
{
hw->interrupt_enable_reg.val = intr_mask;
@ -330,6 +377,21 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
/* ------------------------ Bus Timing Registers --------------------------- */
/**
* @brief Check if the brp value valid
*
* @param brp Bit rate prescaler value
* @return true or False
*/
__attribute__((always_inline))
static inline bool twai_ll_check_brp_validation(uint32_t brp)
{
bool valid = (brp >= SOC_TWAI_BRP_MIN) && (brp <= SOC_TWAI_BRP_MAX);
// should be an even number
valid = valid && !(brp & 0x01);
return valid;
}
/**
* @brief Set bus timing
*
@ -343,6 +405,7 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
* @note Must be called in reset mode
* @note ESP32S3 brp can be any even number between 2 to 32768
*/
__attribute__((always_inline))
static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t sjw, uint32_t tseg1, uint32_t tseg2, bool triple_sampling)
{
hw->bus_timing_0_reg.brp = (brp / 2) - 1;
@ -361,6 +424,7 @@ static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
{
(void)hw->arbitration_lost_captue_reg.val;
@ -375,6 +439,7 @@ static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
*
* @param hw Start address of the TWAI registers
*/
__attribute__((always_inline))
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
{
(void)hw->error_code_capture_reg.val;
@ -390,6 +455,7 @@ static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_err_warn_lim(twai_dev_t *hw, uint32_t ewl)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->error_warning_limit_reg, ewl, ewl);
@ -401,6 +467,7 @@ static inline void twai_ll_set_err_warn_lim(twai_dev_t *hw, uint32_t ewl)
* @param hw Start address of the TWAI registers
* @return Error Warning Limit
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_err_warn_lim(twai_dev_t *hw)
{
return hw->error_warning_limit_reg.val;
@ -417,6 +484,7 @@ static inline uint32_t twai_ll_get_err_warn_lim(twai_dev_t *hw)
* @note REC is not frozen in reset mode. Listen only mode will freeze it. A BUS
* OFF condition automatically sets the REC to 0.
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_rec(twai_dev_t *hw)
{
return hw->rx_error_counter_reg.val;
@ -430,6 +498,7 @@ static inline uint32_t twai_ll_get_rec(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_rec(twai_dev_t *hw, uint32_t rec)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->rx_error_counter_reg, rxerr, rec);
@ -445,6 +514,7 @@ static inline void twai_ll_set_rec(twai_dev_t *hw, uint32_t rec)
*
* @note A BUS OFF condition will automatically set this to 128
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_tec(twai_dev_t *hw)
{
return hw->tx_error_counter_reg.val;
@ -458,6 +528,7 @@ static inline uint32_t twai_ll_get_tec(twai_dev_t *hw)
*
* @note Must be called in reset mode
*/
__attribute__((always_inline))
static inline void twai_ll_set_tec(twai_dev_t *hw, uint32_t tec)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(hw->tx_error_counter_reg, txerr, tec);
@ -474,7 +545,8 @@ static inline void twai_ll_set_tec(twai_dev_t *hw, uint32_t tec)
*
* @note Must be called in reset mode
*/
static inline void twai_ll_set_acc_filter(twai_dev_t* hw, uint32_t code, uint32_t mask, bool single_filter)
__attribute__((always_inline))
static inline void twai_ll_set_acc_filter(twai_dev_t *hw, uint32_t code, uint32_t mask, bool single_filter)
{
uint32_t code_swapped = HAL_SWAP32(code);
uint32_t mask_swapped = HAL_SWAP32(mask);
@ -495,6 +567,7 @@ static inline void twai_ll_set_acc_filter(twai_dev_t* hw, uint32_t code, uint32_
*
* @note Call twai_ll_format_frame_buffer() to format a frame
*/
__attribute__((always_inline))
static inline void twai_ll_set_tx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *tx_frame)
{
//Copy formatted frame into TX buffer
@ -511,6 +584,7 @@ static inline void twai_ll_set_tx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t
*
* @note Call twai_ll_parse_frame_buffer() to parse the formatted frame
*/
__attribute__((always_inline))
static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t *rx_frame)
{
//Copy RX buffer registers into frame
@ -534,6 +608,7 @@ static inline void twai_ll_get_rx_buffer(twai_dev_t *hw, twai_ll_frame_buffer_t
* @param[in] self_rx Frame will also be simultaneously received
* @param[out] tx_frame Pointer to store formatted frame
*/
__attribute__((always_inline))
static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const uint8_t *data,
uint32_t flags, twai_ll_frame_buffer_t *tx_frame)
{
@ -577,6 +652,7 @@ static inline void twai_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const u
* @param[out] data Data. Left over bytes set to 0.
* @param[out] format Type of TWAI frame
*/
__attribute__((always_inline))
static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
{
@ -625,6 +701,7 @@ static inline void twai_ll_parse_frame_buffer(twai_ll_frame_buffer_t *rx_frame,
* @param hw Start address of the TWAI registers
* @return RX Message Counter
*/
__attribute__((always_inline))
static inline uint32_t twai_ll_get_rx_msg_count(twai_dev_t *hw)
{
return hw->rx_message_counter_reg.val;
@ -641,6 +718,7 @@ static inline uint32_t twai_ll_get_rx_msg_count(twai_dev_t *hw)
* @param hw Start address of the TWAI registers
* @param divider Divider for CLKOUT (any even number from 2 to 490). Set to 0 to disable CLKOUT
*/
__attribute__((always_inline))
static inline void twai_ll_set_clkout(twai_dev_t *hw, uint32_t divider)
{
if (divider >= 2 && divider <= 490) {

View File

@ -12,16 +12,16 @@
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stddef.h>
#include <stdbool.h>
#include "sdkconfig.h"
#include "hal/twai_types.h"
#include "hal/twai_ll.h"
#ifdef __cplusplus
extern "C" {
#endif
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_HAL_SET_BITS(var, flag) ((var) |= (flag))
@ -59,6 +59,7 @@ typedef twai_ll_frame_buffer_t twai_hal_frame_t;
typedef struct {
twai_dev_t *dev;
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)
twai_hal_frame_t tx_frame_save;
twai_ll_reg_save_t reg_save;
@ -68,6 +69,11 @@ typedef struct {
/* ---------------------------- Init and Config ----------------------------- */
typedef struct {
int controller_id;
uint32_t clock_source_hz;
} twai_hal_config_t;
/**
* @brief Initialize TWAI peripheral and HAL context
*
@ -75,9 +81,10 @@ typedef struct {
* registers with default values.
*
* @param hal_ctx Context of the HAL layer
* @param config HAL driver configuration
* @return True if successfully initialized, false otherwise.
*/
bool twai_hal_init(twai_hal_context_t *hal_ctx);
bool twai_hal_init(twai_hal_context_t *hal_ctx, const twai_hal_config_t *config);
/**
* @brief Deinitialize the TWAI peripheral and HAL context
@ -161,6 +168,7 @@ static inline uint32_t twai_hal_get_rec(twai_hal_context_t *hal_ctx)
* @param hal_ctx Context of the HAL layer
* @return RX message count
*/
__attribute__((always_inline))
static inline uint32_t twai_hal_get_rx_msg_count(twai_hal_context_t *hal_ctx)
{
return twai_ll_get_rx_msg_count((hal_ctx)->dev);
@ -172,6 +180,7 @@ static inline uint32_t twai_hal_get_rx_msg_count(twai_hal_context_t *hal_ctx)
* @param hal_ctx Context of the HAL layer
* @return True if successful
*/
__attribute__((always_inline))
static inline bool twai_hal_check_last_tx_successful(twai_hal_context_t *hal_ctx)
{
return twai_ll_is_last_tx_successful((hal_ctx)->dev);
@ -230,7 +239,7 @@ static inline void twai_hal_format_frame(const twai_message_t *message, twai_hal
{
//Direct call to ll function
twai_ll_format_frame_buffer(message->identifier, message->data_length_code, message->data,
message->flags, frame);
message->flags, frame);
}
/**
@ -246,7 +255,7 @@ static inline void twai_hal_parse_frame(twai_hal_frame_t *frame, twai_message_t
{
//Direct call to ll function
twai_ll_parse_frame_buffer(frame, &message->identifier, &message->data_length_code,
message->data, &message->flags);
message->data, &message->flags);
}
/**
@ -275,6 +284,7 @@ void twai_hal_set_tx_buffer_and_transmit(twai_hal_context_t *hal_ctx, twai_hal_f
* @param rx_frame Pointer to structure to store RX frame
* @return True if a valid frame was copied and released. False if overrun.
*/
__attribute__((always_inline))
static inline bool twai_hal_read_rx_buffer_and_clear(twai_hal_context_t *hal_ctx, twai_hal_frame_t *rx_frame)
{
#ifdef SOC_TWAI_SUPPORTS_RX_STATUS
@ -304,6 +314,7 @@ static inline bool twai_hal_read_rx_buffer_and_clear(twai_hal_context_t *hal_ctx
* @param hal_ctx Context of the HAL layer
* @return Number of overrun messages cleared from RX FIFO
*/
__attribute__((always_inline))
static inline uint32_t twai_hal_clear_rx_fifo_overrun(twai_hal_context_t *hal_ctx)
{
uint32_t msg_cnt = 0;
@ -359,6 +370,7 @@ void twai_hal_recover_from_reset(twai_hal_context_t *hal_ctx);
* @param hal_ctx Context of the HAL layer
* @return uint32_t Number of RX messages lost due to HW reset
*/
__attribute__((always_inline))
static inline uint32_t twai_hal_get_reset_lost_rx_cnt(twai_hal_context_t *hal_ctx)
{
return hal_ctx->rx_msg_cnt_save;

View File

@ -6,14 +6,15 @@
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include "sdkconfig.h"
#include "soc/soc_caps.h"
#include "soc/clk_tree_defs.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief TWAI Constants
@ -49,27 +50,28 @@ extern "C" {
* The following initializer macros offer commonly found bit rates. These macros
* place the sample point at 80% or 67% of a bit time.
*
* @note These timing values are based on the assumption APB clock is at 80MHz
* @note The available bit rates are dependent on the chip target and revision.
* @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() {.brp = 4000, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_5KBITS() {.brp = 800, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_10KBITS() {.brp = 400, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#endif
#if SOC_TWAI_BRP_MAX > 256
#define TWAI_TIMING_CONFIG_1KBITS() {.quanta_resolution_hz = 20000, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_5KBITS() {.quanta_resolution_hz = 100000, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_10KBITS() {.quanta_resolution_hz = 200000, .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() {.brp = 256, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_16KBITS() {.brp = 200, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_20KBITS() {.brp = 200, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#endif
#define TWAI_TIMING_CONFIG_25KBITS() {.brp = 128, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_50KBITS() {.brp = 80, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_100KBITS() {.brp = 40, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_125KBITS() {.brp = 32, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_250KBITS() {.brp = 16, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_500KBITS() {.brp = 8, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_800KBITS() {.brp = 4, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_1MBITS() {.brp = 4, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_12_5KBITS() {.quanta_resolution_hz = 312500, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_16KBITS() {.quanta_resolution_hz = 400000, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_20KBITS() {.quanta_resolution_hz = 400000, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#endif // (SOC_TWAI_BRP_MAX > 128) || (CONFIG_ESP32_REV_MIN_FULL >= 200)
#define TWAI_TIMING_CONFIG_25KBITS() {.quanta_resolution_hz = 625000, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_50KBITS() {.quanta_resolution_hz = 1000000, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_100KBITS() {.quanta_resolution_hz = 2000000, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_125KBITS() {.quanta_resolution_hz = 2500000, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_250KBITS() {.quanta_resolution_hz = 5000000, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_500KBITS() {.quanta_resolution_hz = 10000000, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_800KBITS() {.quanta_resolution_hz = 20000000, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_1MBITS() {.quanta_resolution_hz = 20000000, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
/**
* @brief Initializer macro for filter configuration to accept all IDs
@ -110,14 +112,27 @@ typedef struct {
uint8_t data[TWAI_FRAME_MAX_DLC]; /**< Data bytes (not relevant in RTR frame) */
} twai_message_t;
/**
* @brief RMT group clock source
* @note User should select the clock source based on the power and resolution requirement
*/
#if SOC_TWAI_SUPPORTED
typedef soc_periph_twai_clk_src_t twai_clock_source_t;
#else
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
*/
typedef struct {
uint32_t brp; /**< Baudrate prescaler (i.e., APB clock divider). Any even number from 2 to 128 for ESP32, 2 to 32768 for ESP32S2.
For ESP32 Rev 2 or later, multiples of 4 from 132 to 256 are also supported */
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) */

View File

@ -1,20 +1,13 @@
// Copyright 2015-2019 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <stddef.h>
#include "sdkconfig.h"
#include "hal/twai_hal.h"
#include "hal/efuse_hal.h"
#include "soc/soc_caps.h"
//Default values written to various registers on initialization
@ -24,11 +17,14 @@
/* ---------------------------- Init and Config ----------------------------- */
bool twai_hal_init(twai_hal_context_t *hal_ctx)
bool twai_hal_init(twai_hal_context_t *hal_ctx, const twai_hal_config_t *config)
{
//Initialize HAL context
hal_ctx->dev = &TWAI;
hal_ctx->dev = TWAI_LL_GET_HW(config->controller_id);
hal_ctx->state_flags = 0;
hal_ctx->clock_source_hz = config->clock_source_hz;
//Enable functional clock
twai_ll_enable_clock(hal_ctx->dev, true);
//Initialize TWAI controller, and set default values to registers
twai_ll_enter_reset_mode(hal_ctx->dev);
if (!twai_ll_is_in_reset_mode(hal_ctx->dev)) { //Must enter reset mode to write to config registers
@ -52,13 +48,30 @@ void twai_hal_deinit(twai_hal_context_t *hal_ctx)
twai_ll_set_enabled_intrs(hal_ctx->dev, 0);
twai_ll_clear_arb_lost_cap(hal_ctx->dev);
twai_ll_clear_err_code_cap(hal_ctx->dev);
//Disable functional clock
twai_ll_enable_clock(hal_ctx->dev, false);
hal_ctx->dev = NULL;
}
void twai_hal_configure(twai_hal_context_t *hal_ctx, const twai_timing_config_t *t_config, const twai_filter_config_t *f_config, uint32_t intr_mask, uint32_t clkout_divider)
{
uint32_t brp = t_config->brp;
// both quanta_resolution_hz and brp can affect the baud rate
// but a non-zero quanta_resolution_hz takes higher priority
if (t_config->quanta_resolution_hz) {
brp = hal_ctx->clock_source_hz / t_config->quanta_resolution_hz;
}
// set clock source
twai_clock_source_t clk_src = t_config->clk_src;
//for backward compatible, zero value means default a default clock source
if (t_config->clk_src == 0) {
clk_src = TWAI_CLK_SRC_DEFAULT;
}
twai_ll_set_clock_source(hal_ctx->dev, clk_src);
//Configure bus timing, acceptance filter, CLKOUT, and interrupts
twai_ll_set_bus_timing(hal_ctx->dev, t_config->brp, t_config->sjw, t_config->tseg_1, t_config->tseg_2, t_config->triple_sampling);
twai_ll_set_bus_timing(hal_ctx->dev, brp, t_config->sjw, t_config->tseg_1, t_config->tseg_2, t_config->triple_sampling);
twai_ll_set_acc_filter(hal_ctx->dev, f_config->acceptance_code, f_config->acceptance_mask, f_config->single_filter);
twai_ll_set_clkout(hal_ctx->dev, clkout_divider);
twai_ll_set_enabled_intrs(hal_ctx->dev, intr_mask);

View File

@ -1,16 +1,8 @@
// Copyright 2015-2019 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <stddef.h>
#include <string.h>

View File

@ -587,10 +587,18 @@ config SOC_TOUCH_PAD_THRESHOLD_MAX
bool
default n
config SOC_TWAI_CONTROLLER_NUM
int
default 1
config SOC_TWAI_BRP_MIN
int
default 2
config SOC_TWAI_CLK_SUPPORT_APB
bool
default y
config SOC_TWAI_SUPPORT_MULTI_ADDRESS_LAYOUT
bool
default y

View File

@ -294,14 +294,15 @@
#define SOC_TOUCH_PAD_THRESHOLD_MAX (0) /*!<If set touch threshold max value, The touch sensor can't be in touched status */
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_BRP_MIN 2
#define SOC_TWAI_CONTROLLER_NUM 1UL
#define SOC_TWAI_BRP_MIN 2
#if SOC_CAPS_ECO_VER >= 200
# define SOC_TWAI_BRP_MAX 256
# define SOC_TWAI_BRP_DIV_SUPPORTED 1
# define SOC_TWAI_BRP_DIV_THRESH 128
#else
# define SOC_TWAI_BRP_MAX 128
#endif
#define SOC_TWAI_CLK_SUPPORT_APB 1
#define SOC_TWAI_SUPPORT_MULTI_ADDRESS_LAYOUT 1
/*-------------------------- UART CAPS ---------------------------------------*/

View File

@ -1,16 +1,8 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once

View File

@ -679,6 +679,14 @@ config SOC_TIMER_GROUP_TOTAL_TIMERS
int
default 2
config SOC_TWAI_CONTROLLER_NUM
int
default 1
config SOC_TWAI_CLK_SUPPORT_APB
bool
default y
config SOC_TWAI_BRP_MIN
int
default 2

View File

@ -314,6 +314,8 @@
#define SOC_TIMER_GROUP_TOTAL_TIMERS (2)
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL
#define SOC_TWAI_CLK_SUPPORT_APB 1
#define SOC_TWAI_BRP_MIN 2
#define SOC_TWAI_BRP_MAX 16384
#define SOC_TWAI_SUPPORTS_RX_STATUS 1

View File

@ -1,16 +1,8 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once

View File

@ -19,6 +19,10 @@ config SOC_MCPWM_SUPPORTED
bool
default y
config SOC_TWAI_SUPPORTED
bool
default y
config SOC_BT_SUPPORTED
bool
default y
@ -687,13 +691,21 @@ config SOC_TIMER_SUPPORT_ETM
bool
default y
config SOC_TWAI_CONTROLLER_NUM
int
default 2
config SOC_TWAI_CLK_SUPPORT_XTAL
bool
default y
config SOC_TWAI_BRP_MIN
int
default 2
config SOC_TWAI_BRP_MAX
int
default 16384
default 32768
config SOC_TWAI_SUPPORTS_RX_STATUS
bool

View File

@ -30,7 +30,7 @@
#define SOC_GDMA_SUPPORTED 1
#define SOC_PCNT_SUPPORTED 1
#define SOC_MCPWM_SUPPORTED 1
// #define SOC_TWAI_SUPPORTED 1 // TODO: IDF-5313
#define SOC_TWAI_SUPPORTED 1
#define SOC_BT_SUPPORTED 1
#define SOC_ASYNC_MEMCPY_SUPPORTED 1
#define SOC_USB_SERIAL_JTAG_SUPPORTED 1
@ -350,10 +350,11 @@
#define SOC_TIMER_GROUP_TOTAL_TIMERS (2)
#define SOC_TIMER_SUPPORT_ETM (1)
// TODO: IDF-5313 (Copy from esp32c3, need check)
/*-------------------------- 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 16384
#define SOC_TWAI_BRP_MAX 32768
#define SOC_TWAI_SUPPORTS_RX_STATUS 1
// TODO: IDF-5357 (Copy from esp32c3, need check)

View File

@ -502,6 +502,28 @@ typedef union {
uint32_t val;
} twai_tx_rx_buffer_reg_t;
typedef struct {
union {
struct {
uint32_t byte: 8; /* ACRx[7:0] Acceptance Code */
uint32_t reserved8: 24; /* Internal Reserved */
};
uint32_t val;
} acr[4];
union {
struct {
uint32_t byte: 8; /* AMRx[7:0] Acceptance Mask */
uint32_t reserved8: 24; /* Internal Reserved */
};
uint32_t val;
} amr[4];
uint32_t reserved_60;
uint32_t reserved_64;
uint32_t reserved_68;
uint32_t reserved_6c;
uint32_t reserved_70;
} acceptance_filter_reg_t;
typedef struct twai_dev_s {
volatile twai_mode_reg_t mode;
@ -518,7 +540,10 @@ typedef struct twai_dev_s {
volatile twai_err_warning_limit_reg_t err_warning_limit;
volatile twai_rx_err_cnt_reg_t rx_err_cnt;
volatile twai_tx_err_cnt_reg_t tx_err_cnt;
volatile twai_tx_rx_buffer_reg_t tx_rx_buffer[13];
volatile union {
acceptance_filter_reg_t acceptance_filter;
twai_tx_rx_buffer_reg_t tx_rx_buffer[13];
};
volatile twai_rx_message_counter_reg_t rx_message_counter;
uint32_t reserved_078;
volatile twai_clock_divider_reg_t clock_divider;

View File

@ -651,6 +651,14 @@ config SOC_TIMER_GROUP_TOTAL_TIMERS
int
default 2
config SOC_TWAI_CONTROLLER_NUM
int
default 1
config SOC_TWAI_CLK_SUPPORT_APB
bool
default y
config SOC_TWAI_BRP_MIN
int
default 2

View File

@ -319,6 +319,8 @@
#define SOC_TIMER_GROUP_TOTAL_TIMERS (2)
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL
#define SOC_TWAI_CLK_SUPPORT_APB 1
#define SOC_TWAI_BRP_MIN 2
#define SOC_TWAI_BRP_MAX 16384
#define SOC_TWAI_SUPPORTS_RX_STATUS 1

View File

@ -1,16 +1,8 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once

View File

@ -667,6 +667,14 @@ config SOC_TOUCH_PAD_MEASURE_WAIT_MAX
hex
default 0xFF
config SOC_TWAI_CONTROLLER_NUM
int
default 1
config SOC_TWAI_CLK_SUPPORT_APB
bool
default y
config SOC_TWAI_BRP_MIN
int
default 2

View File

@ -297,6 +297,8 @@
#define SOC_TOUCH_PAD_MEASURE_WAIT_MAX (0xFF) /*!<The timer frequency is 8Mhz, the max value is 0xff */
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL
#define SOC_TWAI_CLK_SUPPORT_APB 1
#define SOC_TWAI_BRP_MIN 2
#define SOC_TWAI_BRP_MAX 32768
#define SOC_TWAI_SUPPORTS_RX_STATUS 1

View File

@ -1,16 +1,8 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once

View File

@ -799,6 +799,26 @@ config SOC_TOUCH_PAD_MEASURE_WAIT_MAX
hex
default 0xFF
config SOC_TWAI_CONTROLLER_NUM
int
default 1
config SOC_TWAI_CLK_SUPPORT_APB
bool
default y
config SOC_TWAI_BRP_MIN
int
default 2
config SOC_TWAI_BRP_MAX
int
default 16384
config SOC_TWAI_SUPPORTS_RX_STATUS
bool
default y
config SOC_UART_NUM
int
default 3
@ -1082,15 +1102,3 @@ config SOC_BLE_SUPPORTED
config SOC_BLE_MESH_SUPPORTED
bool
default y
config SOC_TWAI_BRP_MIN
int
default 2
config SOC_TWAI_BRP_MAX
int
default 16384
config SOC_TWAI_SUPPORTS_RX_STATUS
bool
default y

View File

@ -323,7 +323,11 @@
#define SOC_TOUCH_PAD_MEASURE_WAIT_MAX (0xFF) /*!<The timer frequency is 8Mhz, the max value is 0xff */
/*-------------------------- TWAI CAPS ---------------------------------------*/
#include "twai_caps.h"
#define SOC_TWAI_CONTROLLER_NUM 1UL
#define SOC_TWAI_CLK_SUPPORT_APB 1
#define SOC_TWAI_BRP_MIN 2
#define SOC_TWAI_BRP_MAX 16384
#define SOC_TWAI_SUPPORTS_RX_STATUS 1
/*-------------------------- UART CAPS ---------------------------------------*/
// ESP32-S3 has 3 UARTs

View File

@ -1,28 +0,0 @@
// Copyright 2019 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#define SOC_TWAI_BRP_MIN 2
#define SOC_TWAI_BRP_MAX 16384
#define SOC_TWAI_SUPPORTS_RX_STATUS 1
#ifdef __cplusplus
}
#endif

View File

@ -1,16 +1,8 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once

View File

@ -1,5 +1,5 @@
| Supported Targets | ESP32 | ESP32-C3 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- |
| Supported Targets | ESP32 | ESP32-C3 | ESP32-C6 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- | -------- |
# TWAI Alert and Recovery Example

View File

@ -1,5 +1,5 @@
| Supported Targets | ESP32 | ESP32-C3 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- |
| Supported Targets | ESP32 | ESP32-C3 | ESP32-C6 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- | -------- |
# TWAI Network Example

View File

@ -1,5 +1,5 @@
| Supported Targets | ESP32 | ESP32-C3 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- |
| Supported Targets | ESP32 | ESP32-C3 | ESP32-C6 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- | -------- |
# TWAI Self Test Example

View File

@ -755,8 +755,6 @@ components/hal/spi_slave_hal_iram.c
components/hal/spi_slave_hd_hal.c
components/hal/test/test_mpu.c
components/hal/touch_sensor_hal.c
components/hal/twai_hal.c
components/hal/twai_hal_iram.c
components/hal/uart_hal_iram.c
components/hal/usb_hal.c
components/heap/include/esp_heap_trace.h
@ -947,7 +945,6 @@ components/soc/esp32/include/soc/spi_struct.h
components/soc/esp32/include/soc/syscon_reg.h
components/soc/esp32/include/soc/syscon_struct.h
components/soc/esp32/include/soc/touch_sensor_channel.h
components/soc/esp32/include/soc/twai_struct.h
components/soc/esp32/include/soc/uart_pins.h
components/soc/esp32/include/soc/uart_reg.h
components/soc/esp32/include/soc/uart_struct.h
@ -989,7 +986,6 @@ components/soc/esp32c3/include/soc/system_reg.h
components/soc/esp32c3/include/soc/system_struct.h
components/soc/esp32c3/include/soc/systimer_reg.h
components/soc/esp32c3/include/soc/systimer_struct.h
components/soc/esp32c3/include/soc/twai_struct.h
components/soc/esp32c3/include/soc/uart_pins.h
components/soc/esp32c3/include/soc/uart_reg.h
components/soc/esp32c3/include/soc/uhci_reg.h
@ -1028,7 +1024,6 @@ components/soc/esp32h2/include/soc/syscon_reg.h
components/soc/esp32h2/include/soc/syscon_struct.h
components/soc/esp32h2/include/soc/system_reg.h
components/soc/esp32h2/include/soc/system_struct.h
components/soc/esp32h2/include/soc/twai_struct.h
components/soc/esp32h2/include/soc/uart_pins.h
components/soc/esp32h2/include/soc/usb_serial_jtag_reg.h
components/soc/esp32h2/include/soc/usb_serial_jtag_struct.h
@ -1072,7 +1067,6 @@ components/soc/esp32s2/include/soc/systimer_reg.h
components/soc/esp32s2/include/soc/systimer_struct.h
components/soc/esp32s2/include/soc/touch_sensor_channel.h
components/soc/esp32s2/include/soc/touch_sensor_pins.h
components/soc/esp32s2/include/soc/twai_struct.h
components/soc/esp32s2/include/soc/uart_pins.h
components/soc/esp32s2/include/soc/uart_reg.h
components/soc/esp32s2/include/soc/uhci_reg.h
@ -1147,9 +1141,6 @@ components/soc/esp32s3/include/soc/systimer_reg.h
components/soc/esp32s3/include/soc/systimer_struct.h
components/soc/esp32s3/include/soc/touch_channel.h
components/soc/esp32s3/include/soc/touch_sensor_caps.h
components/soc/esp32s3/include/soc/twai_caps.h
components/soc/esp32s3/include/soc/twai_struct.h
components/soc/esp32s3/include/soc/uart_caps.h
components/soc/esp32s3/include/soc/uart_pins.h
components/soc/esp32s3/include/soc/uart_reg.h
components/soc/esp32s3/include/soc/uart_struct.h