Update IDF, tools and toolchains

This commit is contained in:
me-no-dev
2020-08-24 19:10:52 +03:00
parent 86c87aaeee
commit 394c32ddfc
754 changed files with 33157 additions and 23022 deletions

View File

@ -168,6 +168,20 @@ int adc_hal_convert(adc_ll_num_t adc_n, int channel, int *value);
*/
#define adc_hal_rtc_output_invert(adc_n, inv_en) adc_ll_rtc_output_invert(adc_n, inv_en)
/**
* Enable/disable the output of ADCn's internal reference voltage to one of ADC2's channels.
*
* This function routes the internal reference voltage of ADCn to one of
* ADC2's channels. This reference voltage can then be manually measured
* for calibration purposes.
*
* @note ESP32 only supports output of ADC2's internal reference voltage.
* @param[in] adc ADC unit select
* @param[in] channel ADC2 channel number
* @param[in] en Enable/disable the reference voltage output
*/
#define adc_hal_vref_output(adc, channel, en) adc_ll_vref_output(adc, channel, en)
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/

View File

@ -1,8 +1,22 @@
// Copyright 2020 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
#include "soc/adc_caps.h"
#include "sdkconfig.h"
#include <stdbool.h>
#include <stdint.h>
#include "sdkconfig.h"
#include "soc/adc_caps.h"
/**
* @brief ADC units selected handle.
@ -69,7 +83,7 @@ typedef enum {
ADC_WIDTH_BIT_10 = 1, /*!< ADC capture width is 10Bit. Only ESP32 is supported. */
ADC_WIDTH_BIT_11 = 2, /*!< ADC capture width is 11Bit. Only ESP32 is supported. */
ADC_WIDTH_BIT_12 = 3, /*!< ADC capture width is 12Bit. Only ESP32 is supported. */
#ifdef CONFIG_IDF_TARGET_ESP32S2
#if !CONFIG_IDF_TARGET_ESP32
ADC_WIDTH_BIT_13 = 4, /*!< ADC capture width is 13Bit. Only ESP32S2 is supported. */
#endif
ADC_WIDTH_MAX,
@ -108,11 +122,11 @@ typedef struct {
If (channel > ADC_CHANNEL_MAX), The data is invalid. */
uint16_t unit: 1; /*!<ADC unit index info. 0: ADC1; 1: ADC2. */
} type2; /*!<When the configured output format is 11bit. `ADC_DIGI_FORMAT_11BIT` */
uint16_t val;
uint16_t val; /*!<Raw data value */
};
} adc_digi_output_data_t;
#ifdef CONFIG_IDF_TARGET_ESP32S2
#if !CONFIG_IDF_TARGET_ESP32
/**
* @brief ADC digital controller (DMA mode) clock system setting.
@ -191,10 +205,10 @@ typedef struct {
1: input voltage * 1/1.34;
2: input voltage * 1/2;
3: input voltage * 1/3.6. */
uint8_t reserved: 2; /*!< reserved0 */
uint8_t reserved: 2; /*!< reserved0 */
uint8_t channel: 4; /*!< ADC channel index. */
};
uint8_t val;
uint8_t val; /*!< Raw entry value */
};
} adc_digi_pattern_table_t;
@ -338,4 +352,4 @@ typedef struct {
uint32_t threshold; /*!<Set monitor threshold of adc digital controller. */
} adc_digi_monitor_t;
#endif // CONFIG_IDF_TARGET_ESP32S2
#endif // CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3

View File

@ -40,13 +40,6 @@ typedef struct {
uint32_t version;
} i2s_hal_context_t;
/**
* @brief Reset I2S fifo
*
* @param hal Context of the HAL layer
*/
void i2s_hal_reset_fifo(i2s_hal_context_t *hal);
/**
* @brief Get I2S interrupt status
*
@ -214,7 +207,7 @@ void i2s_hal_set_tx_bits_mod(i2s_hal_context_t *hal, i2s_bits_per_sample_t bits)
void i2s_hal_set_rx_bits_mod(i2s_hal_context_t *hal, i2s_bits_per_sample_t bits);
/**
* @brief Reset I2S tx
* @brief Reset I2S TX & RX module, including DMA and FIFO
*
* @param hal Context of the HAL layer
*/

View File

@ -81,6 +81,7 @@ typedef enum {
* @brief MCPWM select capture starts from which edge
*/
typedef enum {
MCPWM_NEG_EDGE = BIT(0), /*!<Capture the negative edge*/
MCPWM_POS_EDGE = BIT(1), /*!<Capture the positive edge*/
MCPWM_NEG_EDGE = BIT(0), /*!<Capture the negative edge*/
MCPWM_POS_EDGE = BIT(1), /*!<Capture the positive edge*/
MCPWM_BOTH_EDGE = BIT(1)|BIT(0), /*!<Capture both edges*/
} mcpwm_capture_on_edge_t;

View File

@ -0,0 +1,33 @@
// Copyright 2020 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
#include "hal/gpio_types.h"
#include "hal/rtc_io_ll.h"
#include "hal/rtc_cntl_ll.h"
#define rtc_hal_ext1_get_wakeup_pins() rtc_cntl_ll_ext1_get_wakeup_pins()
#define rtc_hal_ext1_set_wakeup_pins(mask, mode) rtc_cntl_ll_ext1_set_wakeup_pins(mask, mode)
#define rtc_hal_ext1_clear_wakeup_pins() rtc_cntl_ll_ext1_clear_wakeup_pins()
#define rtc_hal_set_wakeup_timer(ticks) rtc_cntl_ll_set_wakeup_timer(ticks)
/*
* Enable wakeup from ULP coprocessor.
*/
#define rtc_hal_ulp_wakeup_enable() rtc_cntl_ll_ulp_wakeup_enable()

View File

@ -219,6 +219,13 @@ void rtcio_hal_set_direction_in_sleep(int rtcio_num, rtc_gpio_mode_t mode);
*/
#define rtcio_hal_wakeup_disable(rtcio_num) rtcio_ll_wakeup_disable(rtcio_num)
/**
* Disable wakeup function from light sleep status for rtcio.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
*/
#define rtcio_hal_ext0_set_wakeup_pin(rtcio_num, level) rtcio_ll_ext0_set_wakeup_pin(rtcio_num, level)
/**
* Helper function to disconnect internal circuits from an RTC IO
* This function disables input, output, pullup, pulldown, and enables

View File

@ -17,12 +17,12 @@
#include <stdint.h>
#include <stdbool.h>
#include "esp_err.h"
#include "soc/soc_caps.h"
#include "hal/cpu_hal.h"
#include "hal/soc_ll.h"
#include "esp_err.h"
#ifdef __cplusplus
extern "C" {
#endif

View File

@ -37,20 +37,22 @@
* implementations that also use the SPI peripheral.
*/
typedef struct {
spi_flash_host_inst_t inst; ///< Host instance, containing host data and function pointer table. May update with the host (hardware version).
spi_dev_t *spi; ///< Pointer to SPI peripheral registers (SP1, SPI2 or SPI3). Set before initialisation.
int cs_num; ///< Which cs pin is used, 0-2.
int extra_dummy;
spi_flash_ll_clock_reg_t clock_conf;
} spi_flash_memspi_data_t;
int extra_dummy; ///< Pre-calculated extra dummy used for compensation
spi_flash_ll_clock_reg_t clock_conf; ///< Pre-calculated clock configuration value
uint32_t reserved_config[2]; ///< The ROM has reserved some memory for configurations with one set of driver code. (e.g. QPI mode, 64-bit address mode, etc.)
} spi_flash_hal_context_t;
/// Configuration structure for the SPI driver.
typedef struct {
spi_host_device_t host_id; ///< SPI peripheral ID.
int cs_num; ///< Which cs pin is used, 0-2.
int cs_num; ///< Which cs pin is used, 0-(SOC_SPI_PERIPH_CS_NUM-1).
bool iomux; ///< Whether the IOMUX is used, used for timing compensation.
int input_delay_ns; ///< Input delay on the MISO pin after the launch clock used for timing compensation.
esp_flash_speed_t speed;///< SPI flash clock speed to work at.
} spi_flash_memspi_config_t;
} spi_flash_hal_config_t;
/**
* Configure SPI flash hal settings.
@ -62,16 +64,16 @@ typedef struct {
* - ESP_OK: success
* - ESP_ERR_INVALID_ARG: the data buffer is not in the DRAM.
*/
esp_err_t spi_flash_hal_init(spi_flash_memspi_data_t *data_out, const spi_flash_memspi_config_t *cfg);
esp_err_t spi_flash_hal_init(spi_flash_hal_context_t *data_out, const spi_flash_hal_config_t *cfg);
/**
* Configure the device-related register before transactions.
*
* @param driver The driver context.
* @param host The driver context.
*
* @return always return ESP_OK.
*/
esp_err_t spi_flash_hal_device_config(spi_flash_host_driver_t *driver);
esp_err_t spi_flash_hal_device_config(spi_flash_host_inst_t *host);
/**
* Send an user-defined spi transaction to the device.
@ -80,60 +82,60 @@ esp_err_t spi_flash_hal_device_config(spi_flash_host_driver_t *driver);
* particular commands. Since this function supports timing compensation, it is
* also used to receive some data when the frequency is high.
*
* @param driver The driver context.
* @param host The driver context.
* @param trans The transaction to send, also holds the received data.
*
* @return always return ESP_OK.
*/
esp_err_t spi_flash_hal_common_command(spi_flash_host_driver_t *driver, spi_flash_trans_t *trans);
esp_err_t spi_flash_hal_common_command(spi_flash_host_inst_t *host, spi_flash_trans_t *trans);
/**
* Erase whole flash chip by using the erase chip (C7h) command.
*
* @param driver The driver context.
* @param host The driver context.
*/
void spi_flash_hal_erase_chip(spi_flash_host_driver_t *driver);
void spi_flash_hal_erase_chip(spi_flash_host_inst_t *host);
/**
* Erase a specific sector by its start address through the sector erase (20h)
* command.
*
* @param driver The driver context.
* @param host The driver context.
* @param start_address Start address of the sector to erase.
*/
void spi_flash_hal_erase_sector(spi_flash_host_driver_t *driver, uint32_t start_address);
void spi_flash_hal_erase_sector(spi_flash_host_inst_t *host, uint32_t start_address);
/**
* Erase a specific 64KB block by its start address through the 64KB block
* erase (D8h) command.
*
* @param driver The driver context.
* @param host The driver context.
* @param start_address Start address of the block to erase.
*/
void spi_flash_hal_erase_block(spi_flash_host_driver_t *driver, uint32_t start_address);
void spi_flash_hal_erase_block(spi_flash_host_inst_t *host, uint32_t start_address);
/**
* Program a page of the flash using the page program (02h) command.
*
* @param driver The driver context.
* @param host The driver context.
* @param address Address of the page to program
* @param buffer Data to program
* @param length Size of the buffer in bytes, no larger than ``SPI_FLASH_HAL_MAX_WRITE_BYTES`` (64) bytes.
*/
void spi_flash_hal_program_page(spi_flash_host_driver_t *driver, const void *buffer, uint32_t address, uint32_t length);
void spi_flash_hal_program_page(spi_flash_host_inst_t *host, const void *buffer, uint32_t address, uint32_t length);
/**
* Read from the flash. Call ``spi_flash_hal_configure_host_read_mode`` to
* configure the read command before calling this function.
*
* @param driver The driver context.
* @param host The driver context.
* @param buffer Buffer to store the read data
* @param address Address to read
* @param length Length to read, no larger than ``SPI_FLASH_HAL_MAX_READ_BYTES`` (64) bytes.
*
* @return always return ESP_OK.
*/
esp_err_t spi_flash_hal_read(spi_flash_host_driver_t *driver, void *buffer, uint32_t address, uint32_t read_len);
esp_err_t spi_flash_hal_read(spi_flash_host_inst_t *host, void *buffer, uint32_t address, uint32_t read_len);
/**
* @brief Send the write enable (06h) or write disable (04h) command to the flash chip.
@ -143,16 +145,16 @@ esp_err_t spi_flash_hal_read(spi_flash_host_driver_t *driver, void *buffer, uint
*
* @return always return ESP_OK.
*/
esp_err_t spi_flash_hal_set_write_protect(spi_flash_host_driver_t *chip_drv, bool wp);
esp_err_t spi_flash_hal_set_write_protect(spi_flash_host_inst_t *host, bool wp);
/**
* Check whether the SPI host is idle and can perform other operations.
*
* @param driver The driver context.
* @param host The driver context.
*
* @return ture if idle, otherwise false.
*/
bool spi_flash_hal_host_idle(spi_flash_host_driver_t *driver);
bool spi_flash_hal_host_idle(spi_flash_host_inst_t *host);
/**
* @brief Configure the SPI host hardware registers for the specified io mode.
@ -177,7 +179,7 @@ bool spi_flash_hal_host_idle(spi_flash_host_driver_t *driver);
* - Common write: set command value, address value (or length to 0 if not
* used), disable dummy phase, and set output data.
*
* @param driver The driver context
* @param host The driver context
* @param io_mode The HW read mode to use
* @param addr_bitlen Length of the address phase, in bits
* @param dummy_cyclelen_base Base cycles of the dummy phase, some extra dummy cycles may be appended to compensate the timing.
@ -185,34 +187,34 @@ bool spi_flash_hal_host_idle(spi_flash_host_driver_t *driver);
*
* @return always return ESP_OK.
*/
esp_err_t spi_flash_hal_configure_host_io_mode(spi_flash_host_driver_t *driver, uint32_t command, uint32_t addr_bitlen,
esp_err_t spi_flash_hal_configure_host_io_mode(spi_flash_host_inst_t *host, uint32_t command, uint32_t addr_bitlen,
int dummy_cyclelen_base, esp_flash_io_mode_t io_mode);
/**
* Poll until the last operation is done.
*
* @param driver The driver context.
* @param host The driver context.
*/
void spi_flash_hal_poll_cmd_done(spi_flash_host_driver_t *driver);
void spi_flash_hal_poll_cmd_done(spi_flash_host_inst_t *host);
/**
* Check whether the given buffer can be used as the write buffer directly. If 'chip' is connected to the main SPI bus, we can only write directly from
* regions that are accessible ith cache disabled. *
*
* @param driver The driver context
* @param host The driver context
* @param p The buffer holding data to send.
*
* @return True if the buffer can be used to send data, otherwise false.
*/
bool spi_flash_hal_supports_direct_write(spi_flash_host_driver_t *driver, const void *p);
bool spi_flash_hal_supports_direct_write(spi_flash_host_inst_t *host, const void *p);
/**
* Check whether the given buffer can be used as the read buffer directly. If 'chip' is connected to the main SPI bus, we can only read directly from
* regions that are accessible ith cache disabled. *
*
* @param driver The driver context
* @param host The driver context
* @param p The buffer to hold the received data.
*
* @return True if the buffer can be used to receive data, otherwise false.
*/
bool spi_flash_hal_supports_direct_read(spi_flash_host_driver_t *driver, const void *p);
bool spi_flash_hal_supports_direct_read(spi_flash_host_inst_t *host, const void *p);

View File

@ -68,84 +68,105 @@ typedef enum {
///Slowest io mode supported by ESP32, currently SlowRd
#define SPI_FLASH_READ_MODE_MIN SPI_FLASH_SLOWRD
struct spi_flash_host_driver_t;
typedef struct spi_flash_host_driver_t spi_flash_host_driver_t;
struct spi_flash_host_driver_s;
typedef struct spi_flash_host_driver_s spi_flash_host_driver_t;
/** SPI Flash Host driver instance */
typedef struct {
const struct spi_flash_host_driver_s* driver; ///< Pointer to the implementation function table
// Implementations can wrap this structure into their own ones, and append other data here
} spi_flash_host_inst_t ;
/** Host driver configuration and context structure. */
struct spi_flash_host_driver_t {
/**
* Configuration and static data used by the specific host driver. The type
* is determined by the host driver.
*/
void *driver_data;
struct spi_flash_host_driver_s {
/**
* Configure the device-related register before transactions. This saves
* some time to re-configure those registers when we send continuously
*/
esp_err_t (*dev_config)(spi_flash_host_driver_t *driver);
esp_err_t (*dev_config)(spi_flash_host_inst_t *host);
/**
* Send an user-defined spi transaction to the device.
*/
esp_err_t (*common_command)(spi_flash_host_driver_t *driver, spi_flash_trans_t *t);
esp_err_t (*common_command)(spi_flash_host_inst_t *host, spi_flash_trans_t *t);
/**
* Read flash ID.
*/
esp_err_t (*read_id)(spi_flash_host_driver_t *driver, uint32_t *id);
esp_err_t (*read_id)(spi_flash_host_inst_t *host, uint32_t *id);
/**
* Erase whole flash chip.
*/
void (*erase_chip)(spi_flash_host_driver_t *driver);
void (*erase_chip)(spi_flash_host_inst_t *host);
/**
* Erase a specific sector by its start address.
*/
void (*erase_sector)(spi_flash_host_driver_t *driver, uint32_t start_address);
void (*erase_sector)(spi_flash_host_inst_t *host, uint32_t start_address);
/**
* Erase a specific block by its start address.
*/
void (*erase_block)(spi_flash_host_driver_t *driver, uint32_t start_address);
void (*erase_block)(spi_flash_host_inst_t *host, uint32_t start_address);
/**
* Read the status of the flash chip.
*/
esp_err_t (*read_status)(spi_flash_host_driver_t *driver, uint8_t *out_sr);
esp_err_t (*read_status)(spi_flash_host_inst_t *host, uint8_t *out_sr);
/**
* Disable write protection.
*/
esp_err_t (*set_write_protect)(spi_flash_host_driver_t *driver, bool wp);
esp_err_t (*set_write_protect)(spi_flash_host_inst_t *host, bool wp);
/**
* Program a page of the flash. Check ``max_write_bytes`` for the maximum allowed writing length.
*/
void (*program_page)(spi_flash_host_driver_t *driver, const void *buffer, uint32_t address, uint32_t length);
/** Check whether need to allocate new buffer to write */
bool (*supports_direct_write)(spi_flash_host_driver_t *driver, const void *p);
/** Check whether need to allocate new buffer to read */
bool (*supports_direct_read)(spi_flash_host_driver_t *driver, const void *p);
/** maximum length of program_page */
int max_write_bytes;
void (*program_page)(spi_flash_host_inst_t *host, const void *buffer, uint32_t address, uint32_t length);
/** Check whether given buffer can be directly used to write */
bool (*supports_direct_write)(spi_flash_host_inst_t *host, const void *p);
/**
* Slicer for write data. The `program_page` should be called iteratively with the return value
* of this function.
*
* @param address Beginning flash address to write
* @param len Length request to write
* @param align_addr Output of the aligned address to write to
* @param page_size Physical page size of the flash chip
* @return Length that can be actually written in one `program_page` call
*/
int (*write_data_slicer)(spi_flash_host_inst_t *host, uint32_t address, uint32_t len, uint32_t *align_addr,
uint32_t page_size);
/**
* Read data from the flash. Check ``max_read_bytes`` for the maximum allowed reading length.
*/
esp_err_t (*read)(spi_flash_host_driver_t *driver, void *buffer, uint32_t address, uint32_t read_len);
/** maximum length of read */
int max_read_bytes;
esp_err_t (*read)(spi_flash_host_inst_t *host, void *buffer, uint32_t address, uint32_t read_len);
/** Check whether given buffer can be directly used to read */
bool (*supports_direct_read)(spi_flash_host_inst_t *host, const void *p);
/**
* Slicer for read data. The `read` should be called iteratively with the return value
* of this function.
*
* @param address Beginning flash address to read
* @param len Length request to read
* @param align_addr Output of the aligned address to read
* @param page_size Physical page size of the flash chip
* @return Length that can be actually read in one `read` call
*/
int (*read_data_slicer)(spi_flash_host_inst_t *host, uint32_t address, uint32_t len, uint32_t *align_addr, uint32_t page_size);
/**
* Check whether the host is idle to perform new operations.
*/
bool (*host_idle)(spi_flash_host_driver_t *driver);
bool (*host_idle)(spi_flash_host_inst_t *host);
/**
* Configure the host to work at different read mode. Responsible to compensate the timing and set IO mode.
*/
esp_err_t (*configure_host_io_mode)(spi_flash_host_driver_t *driver, uint32_t command,
esp_err_t (*configure_host_io_mode)(spi_flash_host_inst_t *host, uint32_t command,
uint32_t addr_bitlen, int dummy_bitlen_base,
esp_flash_io_mode_t io_mode);
/**
* Internal use, poll the HW until the last operation is done.
*/
void (*poll_cmd_done)(spi_flash_host_driver_t *driver);
void (*poll_cmd_done)(spi_flash_host_inst_t *host);
/**
* For some host (SPI1), they are shared with a cache. When the data is
* modified, the cache needs to be flushed. Left NULL if not supported.
*/
esp_err_t (*flush_cache)(spi_flash_host_driver_t* driver, uint32_t addr, uint32_t size);
esp_err_t (*flush_cache)(spi_flash_host_inst_t* host, uint32_t addr, uint32_t size);
};
#ifdef __cplusplus

View File

@ -0,0 +1,212 @@
// Copyright 2015-2020 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.
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
/*
* The HAL layer for SPI Slave HD mode, currently only segment mode is supported
*
* Usage:
* - Firstly, initialize the slave with `slave_hd_hal_init`
*
* - Event handling:
* - (Optional) Call ``spi_slave_hd_hal_enable_event_intr`` to enable the used interrupts
* - (Basic) Call ``spi_slave_hd_hal_check_clear_event`` to check whether an event happen, and also
* clear its interrupt. For events: SPI_EV_BUF_TX, SPI_EV_BUF_RX, SPI_EV_BUF_RX, SPI_EV_CMD9,
* SPI_EV_CMDA.
* - (Advanced) Call ``spi_slave_hd_hal_check_disable_event`` to disable the interrupt of an event,
* so that the task can call ``spi_slave_hd_hal_invoke_event_intr`` later to manually invoke the
* ISR. For SPI_EV_SEND, SPI_EV_RECV.
*
* - TXDMA:
* - To send data through DMA, call `spi_slave_hd_hal_txdma`
* - When the operation is done, SPI_EV_SEND will be triggered.
*
* - RXDMA:
* - To receive data through DMA, call `spi_slave_hd_hal_rxdma`
* - When the operation is done, SPI_EV_RECV will be triggered.
* - Call ``spi_slave_hd_hal_rxdma_get_len`` to get the received length
*
* - Shared buffer:
* - Call ``spi_slave_hd_hal_write_buffer`` to write the shared register buffer. When the buffer is
* read by the master (regardless of the read address), SPI_EV_BUF_TX will be triggered
* - Call ``spi_slave_hd_hal_read_buffer`` to read the shared register buffer. When the buffer is
* written by the master (regardless of the written address), SPI_EV_BUF_RX will be triggered.
*/
#pragma once
#include <esp_types.h>
#include "esp_err.h"
#include "hal/spi_ll.h"
#include "hal/spi_types.h"
/// Configuration of the HAL
typedef struct {
int host_id; ///< Host ID of the spi peripheral
int spics_io_num; ///< CS GPIO pin for this device
uint8_t mode; ///< SPI mode (0-3)
int command_bits; ///< command field bits, multiples of 8 and at least 8.
int address_bits; ///< address field bits, multiples of 8 and at least 8.
int dummy_bits; ///< dummy field bits, multiples of 8 and at least 8.
struct {
uint32_t tx_lsbfirst : 1;///< Whether TX data should be sent with LSB first.
uint32_t rx_lsbfirst : 1;///< Whether RX data should be read with LSB first.
};
int dma_chan; ///< The dma channel used.
} spi_slave_hd_hal_config_t;
/// Context of the HAL, initialized by :cpp:func:`slave_hd_hal_init`.
typedef struct {
spi_dev_t* dev; ///< Beginning address of the peripheral registers.
lldesc_t *dmadesc_tx; /**< Array of DMA descriptor used by the TX DMA.
* The amount should be larger than dmadesc_n. The driver should ensure that
* the data to be sent is shorter than the descriptors can hold.
*/
lldesc_t *dmadesc_rx; /**< Array of DMA descriptor used by the RX DMA.
* The amount should be larger than dmadesc_n. The driver should ensure that
* the data to be sent is shorter than the descriptors can hold.
*/
/* Internal status used by the HAL implementation, initialized as 0. */
uint32_t intr_not_triggered;
} spi_slave_hd_hal_context_t;
/**
* @brief Initialize the hardware and part of the context
*
* @param hal Context of the HAL layer
* @param config Configuration of the HAL
*/
void slave_hd_hal_init(spi_slave_hd_hal_context_t *hal, const spi_slave_hd_hal_config_t *config);
/**
* @brief Check and clear signal of one event
*
* @param hal Context of the HAL layer
* @param ev Event to check
* @return true if event triggered, otherwise false
*/
bool spi_slave_hd_hal_check_clear_event(spi_slave_hd_hal_context_t* hal, spi_event_t ev);
/**
* @brief Check and clear the interrupt of one event.
*
* @note The event source will be kept, so that the interrupt can be invoked by
* :cpp:func:`spi_slave_hd_hal_invoke_event_intr`. If event not triggered, its interrupt source
* will not be disabled either.
*
* @param hal Context of the HAL layer
* @param ev Event to check and disable
* @return true if event triggered, otherwise false
*/
bool spi_slave_hd_hal_check_disable_event(spi_slave_hd_hal_context_t* hal, spi_event_t ev);
/**
* @brief Enable to invole the ISR of corresponding event.
*
* @note The function, compared with :cpp:func:`spi_slave_hd_hal_enable_event_intr`, contains a
* workaround to force trigger the interrupt, even if the interrupt source cannot be initialized
* correctly.
*
* @param hal Context of the HAL layer
* @param ev Event (reason) to invoke the ISR
*/
void spi_slave_hd_hal_invoke_event_intr(spi_slave_hd_hal_context_t* hal, spi_event_t ev);
/**
* @brief Enable the interrupt source of corresponding event.
*
* @param hal Context of the HAL layer
* @param ev Event whose corresponding interrupt source should be enabled.
*/
void spi_slave_hd_hal_enable_event_intr(spi_slave_hd_hal_context_t* hal, spi_event_t ev);
////////////////////////////////////////////////////////////////////////////////
// RX DMA
////////////////////////////////////////////////////////////////////////////////
/**
* @brief Start the RX DMA operation to the specified buffer.
*
* @param hal Context of the HAL layer
* @param[out] out_buf Buffer to receive the data
* @param len Maximul length to receive
*/
void spi_slave_hd_hal_rxdma(spi_slave_hd_hal_context_t *hal, uint8_t *out_buf, size_t len);
/**
* @brief Get the length of total received data
*
* @param hal Context of the HAL layer
* @return The received length
*/
int spi_slave_hd_hal_rxdma_get_len(spi_slave_hd_hal_context_t *hal);
////////////////////////////////////////////////////////////////////////////////
// TX DMA
////////////////////////////////////////////////////////////////////////////////
/**
* @brief Start the TX DMA operation with the specified buffer
*
* @param hal Context of the HAL layer
* @param data Buffer of data to send
* @param len Size of the buffer, also the maximum length to send
*/
void spi_slave_hd_hal_txdma(spi_slave_hd_hal_context_t *hal, uint8_t *data, size_t len);
////////////////////////////////////////////////////////////////////////////////
// Shared buffer
////////////////////////////////////////////////////////////////////////////////
/**
* @brief Read from the shared register buffer
*
* @param hal Context of the HAL layer
* @param addr Address of the shared regsiter to read
* @param out_data Buffer to store the read data
* @param len Length to read from the shared buffer
*/
void spi_slave_hd_hal_read_buffer(spi_slave_hd_hal_context_t *hal, int addr, uint8_t *out_data, size_t len);
/**
* @brief Write the shared register buffer
*
* @param hal Context of the HAL layer
* @param addr Address of the shared register to write
* @param data Buffer of the data to write
* @param len Length to write into the shared buffer
*/
void spi_slave_hd_hal_write_buffer(spi_slave_hd_hal_context_t *hal, int addr, uint8_t *data, size_t len);
/**
* @brief Get the length of previous transaction.
*
* @param hal Context of the HAL layer
* @return The length of previous transaction
*/
int spi_slave_hd_hal_get_rxlen(spi_slave_hd_hal_context_t *hal);
/**
* @brief Get the address of last transaction
*
* @param hal Context of the HAL layer
* @return The address of last transaction
*/
int spi_slave_hd_hal_get_last_addr(spi_slave_hd_hal_context_t *hal);

View File

@ -15,7 +15,9 @@
#pragma once
#include "soc/spi_caps.h"
#include "esp_attr.h"
#include "sdkconfig.h"
#include <esp_bit_defs.h>
/**
* @brief Enum with the three SPI peripherals that are software-accessible in it
@ -27,6 +29,19 @@ typedef enum {
SPI3_HOST=2, ///< SPI3
} spi_host_device_t;
/// SPI Events
typedef enum {
SPI_EV_BUF_TX = BIT(0), ///< The buffer has sent data to master, Slave HD only
SPI_EV_BUF_RX = BIT(1), ///< The buffer has received data from master, Slave HD only
SPI_EV_SEND = BIT(2), ///< Has sent data to master through RDDMA, Slave HD only
SPI_EV_RECV = BIT(3), ///< Has received data from master through WRDMA, Slave HD only
SPI_EV_CMD9 = BIT(4), ///< Received CMD9 from master, Slave HD only
SPI_EV_CMDA = BIT(5), ///< Received CMDA from master, Slave HD only
SPI_EV_TRANS = BIT(6), ///< A transaction has done
} spi_event_t;
FLAG_ATTR(spi_event_t)
/** @cond */ //Doxy command to hide preprocessor definitions from docs */
//alias for different chips
@ -34,7 +49,7 @@ typedef enum {
#define SPI_HOST SPI1_HOST
#define HSPI_HOST SPI2_HOST
#define VSPI_HOST SPI3_HOST
#elif CONFIG_IDF_TARGET_ESP32S2
#elif CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3
// SPI_HOST (SPI1_HOST) is not supported by the SPI Master and SPI Slave driver on ESP32-S2
#define SPI_HOST SPI1_HOST
#define FSPI_HOST SPI2_HOST

View File

@ -71,6 +71,11 @@ void systimer_hal_counter_value_advance(systimer_counter_id_t counter_id, int64_
*/
void systimer_hal_init(void);
/**
* @brief connect alarm unit to selected counter
*/
void systimer_hal_connect_alarm_counter(systimer_alarm_id_t alarm_id, systimer_counter_id_t counter_id);
#ifdef __cplusplus
}
#endif

View File

@ -46,7 +46,7 @@ _Static_assert(sizeof(systimer_counter_value_t) == 8, "systimer_counter_value_t
typedef enum {
SYSTIMER_COUNTER_0, /*!< systimer counter 0 */
#if SOC_SYSTIMER_COUNTER_NUM > 1
SYSTIEMR_COUNTER_1, /*!< systimer counter 1 */
SYSTIMER_COUNTER_1, /*!< systimer counter 1 */
#endif
} systimer_counter_id_t;

View File

@ -14,6 +14,9 @@
#pragma once
#include <stdbool.h>
#include "soc/soc.h"
#include "soc/touch_sensor_caps.h"
#include "sdkconfig.h"
#include "esp_attr.h"
@ -129,7 +132,7 @@ typedef enum {
#define TOUCH_TRIGGER_MODE_DEFAULT (TOUCH_TRIGGER_BELOW) /*!<Interrupts can be triggered if sensor value gets below or above threshold */
#define TOUCH_TRIGGER_SOURCE_DEFAULT (TOUCH_TRIGGER_SOURCE_SET1) /*!<The wakeup trigger source can be SET1 or both SET1 and SET2 */
#elif CONFIG_IDF_TARGET_ESP32S2
#elif CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3
/**
* Excessive total time will slow down the touch response.
* Too small measurement time will not be sampled enough, resulting in inaccurate measurements.
@ -145,7 +148,7 @@ typedef enum {
Range: 0 ~ 0xffff */
#endif // CONFIG_IDF_TARGET_ESP32
#ifdef CONFIG_IDF_TARGET_ESP32S2
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3
typedef enum {
TOUCH_PAD_INTR_MASK_DONE = BIT(0), /*!<Measurement done for one of the enabled channels. */
@ -193,6 +196,7 @@ typedef struct touch_pad_denoise {
from the reading of denoise channel. */
} touch_pad_denoise_t;
/** Touch sensor shield channel drive capability level */
typedef enum {
TOUCH_PAD_SHIELD_DRV_L0 = 0,/*!<The max equivalent capacitance in shield channel is 40pf */
TOUCH_PAD_SHIELD_DRV_L1, /*!<The max equivalent capacitance in shield channel is 80pf */
@ -207,10 +211,13 @@ typedef enum {
/** Touch sensor waterproof configuration */
typedef struct touch_pad_waterproof {
touch_pad_t guard_ring_pad; /*!<Waterproof. Select touch channel use for guard pad */
touch_pad_shield_driver_t shield_driver;/*!<Waterproof. Select max equivalent capacitance for shield pad
Config the Touch14 to the touch sensor and compare the measured
reading to the Touch0 reading to estimate the equivalent capacitance.*/
touch_pad_t guard_ring_pad; /*!<Waterproof. Select touch channel use for guard pad.
Guard pad is used to detect the large area of water covering the touch panel. */
touch_pad_shield_driver_t shield_driver;/*!<Waterproof. Shield channel drive capability configuration.
Shield pad is used to shield the influence of water droplets covering the touch panel.
When the waterproof function is enabled, Touch14 is set as shield channel by default.
The larger the parasitic capacitance on the shielding channel, the higher the drive capability needs to be set.
The equivalent capacitance of the shield channel can be estimated through the reading value of the denoise channel(Touch0).*/
} touch_pad_waterproof_t;
/** Touch sensor proximity detection configuration */
@ -257,33 +264,18 @@ typedef enum {
/** Touch sensor filter configuration */
typedef struct touch_filter_config {
touch_filter_mode_t mode; /*!<Set filter mode. The input to the filter is raw data and the output is the baseline value.
Larger filter coefficients increase the stability of the baseline. */
touch_filter_mode_t mode; /*!<Set filter mode. The input of the filter is the raw value of touch reading,
and the output of the filter is involved in the judgment of the touch state. */
uint32_t debounce_cnt; /*!<Set debounce count, such as `n`. If the measured values continue to exceed
the threshold for `n+1` times, the touch sensor state changes.
Range: 0 ~ 7 */
uint32_t hysteresis_thr; /*!<Hysteresis threshold coefficient. hysteresis = hysteresis coefficient * touch threshold.
If (raw data - baseline) > (touch threshold + hysteresis), the touch channel be touched.
If (raw data - baseline) < (touch threshold - hysteresis), the touch channel be released.
Range: 0 ~ 3. The coefficient is 0: 4/32; 1: 3/32; 2: 1/32; 3: OFF */
uint32_t noise_thr; /*!<Noise threshold coefficient. noise = noise coefficient * touch threshold.
If (raw data - baseline) > (noise), the baseline stop updating.
If (raw data - baseline) < (noise), the baseline start updating.
uint32_t noise_thr; /*!<Noise threshold coefficient. Higher = More noise resistance.
The actual noise should be less than (noise coefficient * touch threshold).
Range: 0 ~ 3. The coefficient is 0: 4/8; 1: 3/8; 2: 2/8; 3: 1; */
uint32_t noise_neg_thr; /*!<Negative noise threshold coefficient. negative noise = noise coefficient * touch threshold.
If (baseline - raw data) > (negative noise), the baseline restart reset process(refer to `baseline_reset`).
If (baseline - raw data) < (negative noise), the baseline stop reset process(refer to `baseline_reset`).
Range: 0 ~ 3. The coefficient is 0: 4/8; 1: 3/8; 2: 2/8; 3: 1/8; */
uint32_t neg_noise_limit; /*!<Set the cumulative number of baseline reset processes. such as `n`. If the measured values continue to exceed
the negative noise threshold for `n+1` times, the baseline reset to raw data.
Range: 0 ~ 15 */
uint32_t jitter_step; /*!<Set jitter filter step size. Range: 0 ~ 15 */
touch_smooth_mode_t smh_lvl;/*!<Level of filter applied on the original data against large noise interference. */
#define TOUCH_DEBOUNCE_CNT_MAX (7)
#define TOUCH_HYSTERESIS_THR_MAX (3)
#define TOUCH_NOISE_THR_MAX (3)
#define TOUCH_NOISE_NEG_THR_MAX (3)
#define TOUCH_NEG_NOISE_CNT_LIMIT (15)
#define TOUCH_JITTER_STEP_MAX (15)
} touch_filter_config_t;

View File

@ -26,54 +26,54 @@ extern "C" {
#include <stddef.h>
#include <stdbool.h>
#include "hal/can_types.h"
#include "hal/can_ll.h"
#include "hal/twai_types.h"
#include "hal/twai_ll.h"
/* ------------------------- Defines and Typedefs --------------------------- */
//Error active interrupt related
#define CAN_HAL_EVENT_BUS_OFF (1 << 0)
#define CAN_HAL_EVENT_BUS_RECOV_CPLT (1 << 1)
#define CAN_HAL_EVENT_BUS_RECOV_PROGRESS (1 << 2)
#define CAN_HAL_EVENT_ABOVE_EWL (1 << 3)
#define CAN_HAL_EVENT_BELOW_EWL (1 << 4)
#define CAN_HAL_EVENT_ERROR_PASSIVE (1 << 5)
#define CAN_HAL_EVENT_ERROR_ACTIVE (1 << 6)
#define CAN_HAL_EVENT_BUS_ERR (1 << 7)
#define CAN_HAL_EVENT_ARB_LOST (1 << 8)
#define CAN_HAL_EVENT_RX_BUFF_FRAME (1 << 9)
#define CAN_HAL_EVENT_TX_BUFF_FREE (1 << 10)
#define TWAI_HAL_EVENT_BUS_OFF (1 << 0)
#define TWAI_HAL_EVENT_BUS_RECOV_CPLT (1 << 1)
#define TWAI_HAL_EVENT_BUS_RECOV_PROGRESS (1 << 2)
#define TWAI_HAL_EVENT_ABOVE_EWL (1 << 3)
#define TWAI_HAL_EVENT_BELOW_EWL (1 << 4)
#define TWAI_HAL_EVENT_ERROR_PASSIVE (1 << 5)
#define TWAI_HAL_EVENT_ERROR_ACTIVE (1 << 6)
#define TWAI_HAL_EVENT_BUS_ERR (1 << 7)
#define TWAI_HAL_EVENT_ARB_LOST (1 << 8)
#define TWAI_HAL_EVENT_RX_BUFF_FRAME (1 << 9)
#define TWAI_HAL_EVENT_TX_BUFF_FREE (1 << 10)
typedef struct {
can_dev_t *dev;
} can_hal_context_t;
twai_dev_t *dev;
} twai_hal_context_t;
typedef can_ll_frame_buffer_t can_hal_frame_t;
typedef twai_ll_frame_buffer_t twai_hal_frame_t;
/* ---------------------------- Init and Config ----------------------------- */
/**
* @brief Initialize CAN peripheral and HAL context
* @brief Initialize TWAI peripheral and HAL context
*
* Sets HAL context, puts CAN peripheral into reset mode, then sets some
* Sets HAL context, puts TWAI peripheral into reset mode, then sets some
* registers with default values.
*
* @param hal_ctx Context of the HAL layer
* @return True if successfully initialized, false otherwise.
*/
bool can_hal_init(can_hal_context_t *hal_ctx);
bool twai_hal_init(twai_hal_context_t *hal_ctx);
/**
* @brief Deinitialize the CAN peripheral and HAL context
* @brief Deinitialize the TWAI peripheral and HAL context
*
* Clears any unhandled interrupts and unsets HAL context
*
* @param hal_ctx Context of the HAL layer
*/
void can_hal_deinit(can_hal_context_t *hal_ctx);
void twai_hal_deinit(twai_hal_context_t *hal_ctx);
/**
* @brief Configure the CAN peripheral
* @brief Configure the TWAI peripheral
*
* @param hal_ctx Context of the HAL layer
* @param t_config Pointer to timing configuration structure
@ -81,32 +81,32 @@ void can_hal_deinit(can_hal_context_t *hal_ctx);
* @param intr_mask Mask of interrupts to enable
* @param clkout_divider Clock divider value for CLKOUT. Set to -1 to disable CLKOUT
*/
void can_hal_configure(can_hal_context_t *hal_ctx, const can_timing_config_t *t_config, const can_filter_config_t *f_config, uint32_t intr_mask, uint32_t clkout_divider);
void twai_hal_configure(twai_hal_context_t *hal_ctx, const twai_timing_config_t *t_config, const twai_filter_config_t *f_config, uint32_t intr_mask, uint32_t clkout_divider);
/* -------------------------------- Actions --------------------------------- */
/**
* @brief Start the CAN peripheral
* @brief Start the TWAI peripheral
*
* Start the CAN peripheral by configuring its operating mode, then exiting
* reset mode so that the CAN peripheral can participate in bus activities.
* Start the TWAI peripheral by configuring its operating mode, then exiting
* reset mode so that the TWAI peripheral can participate in bus activities.
*
* @param hal_ctx Context of the HAL layer
* @param mode Operating mode
* @return True if successfully started, false otherwise.
*/
bool can_hal_start(can_hal_context_t *hal_ctx, can_mode_t mode);
bool twai_hal_start(twai_hal_context_t *hal_ctx, twai_mode_t mode);
/**
* @brief Stop the CAN peripheral
* @brief Stop the TWAI peripheral
*
* Stop the CAN peripheral by entering reset mode to stop any bus activity, then
* Stop the TWAI peripheral by entering reset mode to stop any bus activity, then
* setting the operating mode to Listen Only so that REC is frozen.
*
* @param hal_ctx Context of the HAL layer
* @return True if successfully stopped, false otherwise.
*/
bool can_hal_stop(can_hal_context_t *hal_ctx);
bool twai_hal_stop(twai_hal_context_t *hal_ctx);
/**
* @brief Start bus recovery
@ -114,9 +114,9 @@ bool can_hal_stop(can_hal_context_t *hal_ctx);
* @param hal_ctx Context of the HAL layer
* @return True if successfully started bus recovery, false otherwise.
*/
static inline bool can_hal_start_bus_recovery(can_hal_context_t *hal_ctx)
static inline bool twai_hal_start_bus_recovery(twai_hal_context_t *hal_ctx)
{
return can_ll_exit_reset_mode(hal_ctx->dev);
return twai_ll_exit_reset_mode(hal_ctx->dev);
}
/**
@ -125,9 +125,9 @@ static inline bool can_hal_start_bus_recovery(can_hal_context_t *hal_ctx)
* @param hal_ctx Context of the HAL layer
* @return TX Error Counter Value
*/
static inline uint32_t can_hal_get_tec(can_hal_context_t *hal_ctx)
static inline uint32_t twai_hal_get_tec(twai_hal_context_t *hal_ctx)
{
return can_ll_get_tec((hal_ctx)->dev);
return twai_ll_get_tec((hal_ctx)->dev);
}
/**
@ -136,9 +136,9 @@ static inline uint32_t can_hal_get_tec(can_hal_context_t *hal_ctx)
* @param hal_ctx Context of the HAL layer
* @return RX Error Counter Value
*/
static inline uint32_t can_hal_get_rec(can_hal_context_t *hal_ctx)
static inline uint32_t twai_hal_get_rec(twai_hal_context_t *hal_ctx)
{
return can_ll_get_rec((hal_ctx)->dev);
return twai_ll_get_rec((hal_ctx)->dev);
}
/**
@ -147,9 +147,9 @@ static inline uint32_t can_hal_get_rec(can_hal_context_t *hal_ctx)
* @param hal_ctx Context of the HAL layer
* @return RX message count
*/
static inline uint32_t can_hal_get_rx_msg_count(can_hal_context_t *hal_ctx)
static inline uint32_t twai_hal_get_rx_msg_count(twai_hal_context_t *hal_ctx)
{
return can_ll_get_rx_msg_count((hal_ctx)->dev);
return twai_ll_get_rx_msg_count((hal_ctx)->dev);
}
/**
@ -158,9 +158,9 @@ static inline uint32_t can_hal_get_rx_msg_count(can_hal_context_t *hal_ctx)
* @param hal_ctx Context of the HAL layer
* @return True if successful
*/
static inline bool can_hal_check_last_tx_successful(can_hal_context_t *hal_ctx)
static inline bool twai_hal_check_last_tx_successful(twai_hal_context_t *hal_ctx)
{
return can_ll_is_last_tx_successful((hal_ctx)->dev);
return twai_ll_is_last_tx_successful((hal_ctx)->dev);
}
/* ----------------------------- Event Handling ----------------------------- */
@ -168,15 +168,15 @@ static inline bool can_hal_check_last_tx_successful(can_hal_context_t *hal_ctx)
/**
* @brief Decode current events that triggered an interrupt
*
* This function should be called on every CAN interrupt. It will read (and
* This function should be called on every TWAI interrupt. It will read (and
* thereby clear) the interrupt register, then determine what events have
* occurred to trigger the interrupt.
*
* @param hal_ctx Context of the HAL layer
* @param bus_recovering Whether the CAN peripheral was previous undergoing bus recovery
* @param bus_recovering Whether the TWAI peripheral was previous undergoing bus recovery
* @return Bit mask of events that have occurred
*/
uint32_t can_hal_decode_interrupt_events(can_hal_context_t *hal_ctx, bool bus_recovering);
uint32_t twai_hal_decode_interrupt_events(twai_hal_context_t *hal_ctx, bool bus_recovering);
/**
* @brief Handle bus recovery complete
@ -187,9 +187,9 @@ uint32_t can_hal_decode_interrupt_events(can_hal_context_t *hal_ctx, bool bus_re
* @param hal_ctx Context of the HAL layer
* @return True if successfully handled bus recovery completion, false otherwise.
*/
static inline bool can_hal_handle_bus_recov_cplt(can_hal_context_t *hal_ctx)
static inline bool twai_hal_handle_bus_recov_cplt(twai_hal_context_t *hal_ctx)
{
return can_ll_enter_reset_mode((hal_ctx)->dev);
return twai_ll_enter_reset_mode((hal_ctx)->dev);
}
/**
@ -200,9 +200,9 @@ static inline bool can_hal_handle_bus_recov_cplt(can_hal_context_t *hal_ctx)
*
* @param hal_ctx Context of the HAL layer
*/
static inline void can_hal_handle_arb_lost(can_hal_context_t *hal_ctx)
static inline void twai_hal_handle_arb_lost(twai_hal_context_t *hal_ctx)
{
can_ll_clear_arb_lost_cap((hal_ctx)->dev);
twai_ll_clear_arb_lost_cap((hal_ctx)->dev);
}
/**
@ -213,9 +213,9 @@ static inline void can_hal_handle_arb_lost(can_hal_context_t *hal_ctx)
*
* @param hal_ctx Context of the HAL layer
*/
static inline void can_hal_handle_bus_error(can_hal_context_t *hal_ctx)
static inline void twai_hal_handle_bus_error(twai_hal_context_t *hal_ctx)
{
can_ll_clear_err_code_cap((hal_ctx)->dev);
twai_ll_clear_err_code_cap((hal_ctx)->dev);
}
/**
@ -226,42 +226,42 @@ static inline void can_hal_handle_bus_error(can_hal_context_t *hal_ctx)
*
* @param hal_ctx Context of the HAL layer
*/
static inline void can_hal_handle_bus_off(can_hal_context_t *hal_ctx)
static inline void twai_hal_handle_bus_off(twai_hal_context_t *hal_ctx)
{
can_ll_set_mode((hal_ctx)->dev, CAN_MODE_LISTEN_ONLY);
twai_ll_set_mode((hal_ctx)->dev, TWAI_MODE_LISTEN_ONLY);
}
/* ------------------------------- TX and RX -------------------------------- */
/**
* @brief Format a CAN Frame
* @brief Format a TWAI Frame
*
* This function takes a CAN message structure (containing ID, DLC, data, and
* This function takes a TWAI message structure (containing ID, DLC, data, and
* flags) and formats it to match the layout of the TX frame buffer.
*
* @param message Pointer to CAN message
* @param message Pointer to TWAI message
* @param frame Pointer to empty frame structure
*/
static inline void can_hal_format_frame(const can_message_t *message, can_hal_frame_t *frame)
static inline void twai_hal_format_frame(const twai_message_t *message, twai_hal_frame_t *frame)
{
//Direct call to ll function
can_ll_format_frame_buffer(message->identifier, message->data_length_code, message->data,
twai_ll_format_frame_buffer(message->identifier, message->data_length_code, message->data,
message->flags, frame);
}
/**
* @brief Parse a CAN Frame
* @brief Parse a TWAI Frame
*
* This function takes a CAN frame (in the format of the RX frame buffer) and
* parses it to a CAN message (containing ID, DLC, data and flags).
* This function takes a TWAI frame (in the format of the RX frame buffer) and
* parses it to a TWAI message (containing ID, DLC, data and flags).
*
* @param frame Pointer to frame structure
* @param message Pointer to empty message structure
*/
static inline void can_hal_parse_frame(can_hal_frame_t *frame, can_message_t *message)
static inline void twai_hal_parse_frame(twai_hal_frame_t *frame, twai_message_t *message)
{
//Direct call to ll function
can_ll_prase_frame_buffer(frame, &message->identifier, &message->data_length_code,
twai_ll_prase_frame_buffer(frame, &message->identifier, &message->data_length_code,
message->data, &message->flags);
}
@ -275,7 +275,7 @@ static inline void can_hal_parse_frame(can_hal_frame_t *frame, can_message_t *me
* @param hal_ctx Context of the HAL layer
* @param tx_frame Pointer to structure containing formatted TX frame
*/
void can_hal_set_tx_buffer_and_transmit(can_hal_context_t *hal_ctx, can_hal_frame_t *tx_frame);
void twai_hal_set_tx_buffer_and_transmit(twai_hal_context_t *hal_ctx, twai_hal_frame_t *tx_frame);
/**
* @brief Copy a frame from the RX buffer and release
@ -286,10 +286,10 @@ void can_hal_set_tx_buffer_and_transmit(can_hal_context_t *hal_ctx, can_hal_fram
* @param hal_ctx Context of the HAL layer
* @param rx_frame Pointer to structure to store RX frame
*/
static inline void can_hal_read_rx_buffer_and_clear(can_hal_context_t *hal_ctx, can_hal_frame_t *rx_frame)
static inline void twai_hal_read_rx_buffer_and_clear(twai_hal_context_t *hal_ctx, twai_hal_frame_t *rx_frame)
{
can_ll_get_rx_buffer(hal_ctx->dev, rx_frame);
can_ll_set_cmd_release_rx_buffer(hal_ctx->dev);
twai_ll_get_rx_buffer(hal_ctx->dev, rx_frame);
twai_ll_set_cmd_release_rx_buffer(hal_ctx->dev);
/*
* Todo: Support overrun handling by:
* - Check overrun status bit. Return false if overrun

View File

@ -20,72 +20,78 @@ extern "C" {
#include <stdint.h>
#include <stdbool.h>
#include "sdkconfig.h"
/**
* @brief CAN2.0B Constants
* @brief TWAI Constants
*/
#define CAN_EXTD_ID_MASK 0x1FFFFFFF /**< Bit mask for 29 bit Extended Frame Format ID */
#define CAN_STD_ID_MASK 0x7FF /**< Bit mask for 11 bit Standard Frame Format ID */
#define CAN_FRAME_MAX_DLC 8 /**< Max data bytes allowed in CAN2.0 */
#define CAN_FRAME_EXTD_ID_LEN_BYTES 4 /**< EFF ID requires 4 bytes (29bit) */
#define CAN_FRAME_STD_ID_LEN_BYTES 2 /**< SFF ID requires 2 bytes (11bit) */
#define CAN_ERR_PASS_THRESH 128 /**< Error counter threshold for error passive */
#define TWAI_EXTD_ID_MASK 0x1FFFFFFF /**< Bit mask for 29 bit Extended Frame Format ID */
#define TWAI_STD_ID_MASK 0x7FF /**< Bit mask for 11 bit Standard Frame Format ID */
#define TWAI_FRAME_MAX_DLC 8 /**< Max data bytes allowed in TWAI */
#define TWAI_FRAME_EXTD_ID_LEN_BYTES 4 /**< EFF ID requires 4 bytes (29bit) */
#define TWAI_FRAME_STD_ID_LEN_BYTES 2 /**< SFF ID requires 2 bytes (11bit) */
#define TWAI_ERR_PASS_THRESH 128 /**< Error counter threshold for error passive */
/** @cond */ //Doxy command to hide preprocessor definitions from docs
/**
* @brief CAN Message flags
* @brief TWAI Message flags
*
* The message flags are used to indicate the type of message transmitted/received.
* Some flags also specify the type of transmission.
*/
#define CAN_MSG_FLAG_NONE 0x00 /**< No message flags (Standard Frame Format) */
#define CAN_MSG_FLAG_EXTD 0x01 /**< Extended Frame Format (29bit ID) */
#define CAN_MSG_FLAG_RTR 0x02 /**< Message is a Remote Transmit Request */
#define CAN_MSG_FLAG_SS 0x04 /**< Transmit as a Single Shot Transmission. Unused for received. */
#define CAN_MSG_FLAG_SELF 0x08 /**< Transmit as a Self Reception Request. Unused for received. */
#define CAN_MSG_FLAG_DLC_NON_COMP 0x10 /**< Message's Data length code is larger than 8. This will break compliance with CAN2.0B */
#define TWAI_MSG_FLAG_NONE 0x00 /**< No message flags (Standard Frame Format) */
#define TWAI_MSG_FLAG_EXTD 0x01 /**< Extended Frame Format (29bit ID) */
#define TWAI_MSG_FLAG_RTR 0x02 /**< Message is a Remote Frame */
#define TWAI_MSG_FLAG_SS 0x04 /**< Transmit as a Single Shot Transmission. Unused for received. */
#define TWAI_MSG_FLAG_SELF 0x08 /**< Transmit as a Self Reception Request. Unused for received. */
#define TWAI_MSG_FLAG_DLC_NON_COMP 0x10 /**< Message's Data length code is larger than 8. This will break compliance with TWAI */
/**
* @brief Initializer macros for timing configuration structure
*
* The following initializer macros offer commonly found bit rates.
* 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 20K, 16K and 12.5K bit rates are only available from ESP32 Revision 2 onwards
* @note The available bit rates are dependent on the chip target and revision.
*/
#ifdef CAN_BRP_DIV_SUPPORTED
#define CAN_TIMING_CONFIG_12_5KBITS() {.brp = 256, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define CAN_TIMING_CONFIG_16KBITS() {.brp = 200, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define CAN_TIMING_CONFIG_20KBITS() {.brp = 200, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#if (TWAI_BRP_MAX > 256)
#define TWAI_TIMING_CONFIG_1KBITS() {.brp = 4000, .tseg_1 = 15, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_5KBITS() {.brp = 800, .tseg_1 = 15, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define TWAI_TIMING_CONFIG_10KBITS() {.brp = 400, .tseg_1 = 15, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#endif
#define CAN_TIMING_CONFIG_25KBITS() {.brp = 128, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define CAN_TIMING_CONFIG_50KBITS() {.brp = 80, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define CAN_TIMING_CONFIG_100KBITS() {.brp = 40, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define CAN_TIMING_CONFIG_125KBITS() {.brp = 32, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define CAN_TIMING_CONFIG_250KBITS() {.brp = 16, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define CAN_TIMING_CONFIG_500KBITS() {.brp = 8, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#define CAN_TIMING_CONFIG_800KBITS() {.brp = 4, .tseg_1 = 16, .tseg_2 = 8, .sjw = 3, .triple_sampling = false}
#define CAN_TIMING_CONFIG_1MBITS() {.brp = 4, .tseg_1 = 15, .tseg_2 = 4, .sjw = 3, .triple_sampling = false}
#if (TWAI_BRP_MAX > 128) || (CONFIG_ESP32_REV_MIN >= 2)
#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}
/**
* @brief Initializer macro for filter configuration to accept all IDs
*/
#define CAN_FILTER_CONFIG_ACCEPT_ALL() {.acceptance_code = 0, .acceptance_mask = 0xFFFFFFFF, .single_filter = true}
#define TWAI_FILTER_CONFIG_ACCEPT_ALL() {.acceptance_code = 0, .acceptance_mask = 0xFFFFFFFF, .single_filter = true}
/** @endcond */
/**
* @brief CAN Controller operating modes
* @brief TWAI Controller operating modes
*/
typedef enum {
CAN_MODE_NORMAL, /**< Normal operating mode where CAN controller can send/receive/acknowledge messages */
CAN_MODE_NO_ACK, /**< Transmission does not require acknowledgment. Use this mode for self testing */
CAN_MODE_LISTEN_ONLY, /**< The CAN controller will not influence the bus (No transmissions or acknowledgments) but can receive messages */
} can_mode_t;
TWAI_MODE_NORMAL, /**< Normal operating mode where TWAI controller can send/receive/acknowledge messages */
TWAI_MODE_NO_ACK, /**< Transmission does not require acknowledgment. Use this mode for self testing */
TWAI_MODE_LISTEN_ONLY, /**< The TWAI controller will not influence the bus (No transmissions or acknowledgments) but can receive messages */
} twai_mode_t;
/**
* @brief Structure to store a CAN message
* @brief Structure to store a TWAI message
*
* @note
* @note The flags member is deprecated
*/
typedef struct {
@ -93,36 +99,36 @@ typedef struct {
struct {
//The order of these bits must match deprecated message flags for compatibility reasons
uint32_t extd: 1; /**< Extended Frame Format (29bit ID) */
uint32_t rtr: 1; /**< Message is a Remote Transmit Request */
uint32_t rtr: 1; /**< Message is a Remote Frame */
uint32_t ss: 1; /**< Transmit as a Single Shot Transmission. Unused for received. */
uint32_t self: 1; /**< Transmit as a Self Reception Request. Unused for received. */
uint32_t dlc_non_comp: 1; /**< Message's Data length code is larger than 8. This will break compliance with CAN2.0B. */
uint32_t dlc_non_comp: 1; /**< Message's Data length code is larger than 8. This will break compliance with ISO 11898-1 */
uint32_t reserved: 27; /**< Reserved bits */
};
//Todo: Deprecate flags
uint32_t flags; /**< Alternate way to set message flags using message flag macros (see documentation) */
uint32_t flags; /**< Deprecated: Alternate way to set bits using message flags */
};
uint32_t identifier; /**< 11 or 29 bit identifier */
uint8_t data_length_code; /**< Data length code */
uint8_t data[CAN_FRAME_MAX_DLC]; /**< Data bytes (not relevant in RTR frame) */
} can_message_t;
uint8_t data[TWAI_FRAME_MAX_DLC]; /**< Data bytes (not relevant in RTR frame) */
} twai_message_t;
/**
* @brief Structure for bit timing configuration of the CAN driver
* @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) can be any even number from 2 to 128.
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 */
uint8_t tseg_1; /**< Timing segment 1 (Number of time quanta, between 1 to 16) */
uint8_t tseg_2; /**< Timing segment 2 (Number of time quanta, 1 to 8) */
uint8_t sjw; /**< Synchronization Jump Width (Max time quanta jump for synchronize from 1 to 4) */
bool triple_sampling; /**< Enables triple sampling when the CAN controller samples a bit */
} can_timing_config_t;
bool triple_sampling; /**< Enables triple sampling when the TWAI controller samples a bit */
} twai_timing_config_t;
/**
* @brief Structure for acceptance filter configuration of the CAN driver (see documentation)
* @brief Structure for acceptance filter configuration of the TWAI driver (see documentation)
*
* @note Macro initializers are available for this structure
*/
@ -130,7 +136,7 @@ typedef struct {
uint32_t acceptance_code; /**< 32-bit acceptance code */
uint32_t acceptance_mask; /**< 32-bit acceptance mask */
bool single_filter; /**< Use Single Filter Mode (see documentation) */
} can_filter_config_t;
} twai_filter_config_t;
#ifdef __cplusplus
}

View File

@ -20,6 +20,8 @@
#include "esp32/rom/lldesc.h"
#elif CONFIG_IDF_TARGET_ESP32S2
#include "esp32s2/rom/lldesc.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/rom/lldesc.h"
#endif
//the size field has 12 bits, but 0 not for 4096.
@ -33,13 +35,23 @@
* The caller should ensure there is enough size to hold the array, by calling
* ``lldesc_get_required_num``.
*
* @param out_desc_array Output of a descriptor array, the head should be fed to the DMA.
* @param[out] out_desc_array Output of a descriptor array, the head should be fed to the DMA.
* @param buffer Buffer for the descriptors to point to.
* @param size Size (or length for TX) of the buffer
* @param isrx The RX DMA may require the buffer to be word-aligned, set to true for a RX link, otherwise false.
*/
void lldesc_setup_link(lldesc_t *out_desc_array, const void *buffer, int size, bool isrx);
/**
* @brief Get the received length of a linked list, until end of the link or eof.
*
* @param head The head of the linked list.
* @param[out] out_next Output of the next descriptor of the EOF descriptor. Return NULL if there's no
* EOF. Can be set to NULL if next descriptor is not needed.
* @return The accumulation of the `len` field of all descriptors until EOF or the end of the link.
*/
int lldesc_get_received_len(lldesc_t* head, lldesc_t** out_next);
/**
* Get the number of descriptors required for a given buffer size.
*

View File

@ -211,10 +211,10 @@ inline static bool IRAM_ATTR esp_ptr_external_ram(const void *p) {
}
inline static bool IRAM_ATTR esp_ptr_in_iram(const void *p) {
#if !CONFIG_FREERTOS_UNICORE || CONFIG_IDF_TARGET_ESP32S2
return ((intptr_t)p >= SOC_IRAM_LOW && (intptr_t)p < SOC_IRAM_HIGH);
#else
#if CONFIG_IDF_TARGET_ESP32 && CONFIG_FREERTOS_UNICORE
return ((intptr_t)p >= SOC_CACHE_APP_LOW && (intptr_t)p < SOC_IRAM_HIGH);
#else
return ((intptr_t)p >= SOC_IRAM_LOW && (intptr_t)p < SOC_IRAM_HIGH);
#endif
}

View File

@ -13,7 +13,7 @@
// limitations under the License.
#pragma once
#include "esp_rom_sys.h"
/**
* @file soc_log.h
* @brief SOC library logging functions
@ -33,14 +33,16 @@
#else
#include "sdkconfig.h"
#ifdef CONFIG_IDF_TARGET_ESP32
#include "esp32/rom/ets_sys.h"
#include "esp32/rom/ets_sys.h" // will be removed in idf v5.0
#elif CONFIG_IDF_TARGET_ESP32S2
#include "esp32s2/rom/ets_sys.h"
#elif CONFIG_IDF_TARGET_ESP32S3
#include "esp32s3/rom/ets_sys.h"
#endif
#define SOC_LOGE(tag, fmt, ...) ets_printf("%s(err): " fmt, tag, ##__VA_ARGS__)
#define SOC_LOGW(tag, fmt, ...) ets_printf("%s(warn): " fmt, tag, ##__VA_ARGS__)
#define SOC_LOGI(tag, fmt, ...) ets_printf("%s(info): " fmt, tag, ##__VA_ARGS__)
#define SOC_LOGD(tag, fmt, ...) ets_printf("%s(dbg): " fmt, tag, ##__VA_ARGS__)
#define SOC_LOGV(tag, fmt, ...) ets_printf("%s: " fmt, tag, ##__VA_ARGS__)
#define SOC_LOGE(tag, fmt, ...) esp_rom_printf("%s(err): " fmt, tag, ##__VA_ARGS__)
#define SOC_LOGW(tag, fmt, ...) esp_rom_printf("%s(warn): " fmt, tag, ##__VA_ARGS__)
#define SOC_LOGI(tag, fmt, ...) esp_rom_printf("%s(info): " fmt, tag, ##__VA_ARGS__)
#define SOC_LOGD(tag, fmt, ...) esp_rom_printf("%s(dbg): " fmt, tag, ##__VA_ARGS__)
#define SOC_LOGV(tag, fmt, ...) esp_rom_printf("%s: " fmt, tag, ##__VA_ARGS__)
#endif //ESP_PLATFORM

View File

@ -18,21 +18,15 @@
extern "C" {
#endif
#include "sdkconfig.h"
#warning soc/can_caps.h is deprecated, please use soc/twai_caps.h instead
#if __DOXYGEN__ || (CONFIG_ESP32_REV_MIN >= 2)
#define CAN_BRP_DIV_SUPPORTED 1
#define CAN_BRP_DIV_THRESH 128
//Any even number from 2 to 128, or multiples of 4 from 132 to 256
#define CAN_BRP_IS_VALID(brp) (((brp) >= 2 && (brp) <= 128 && ((brp) & 0x1) == 0) || ((brp) >= 132 && (brp) <= 256 && ((brp) & 0x3) == 0))
#else
//Any even number from 2 to 128
#define CAN_BRP_IS_VALID(brp) ((brp) >= 2 && (brp) <= 128 && ((brp) & 0x1) == 0)
#endif
/* ---------------------------- Compatibility ------------------------------- */
//Todo: Add FIFO overrun errata workaround
//Todo: Add ECC decode capabilities
//Todo: Add ALC decode capability
#define CAN_BRP_MIN 2
#define CAN_BRP_MAX 128
#define CAN_BRP_MAX_ECO 256
#define CAN_BRP_DIV_THRESH 128
#define CAN_SUPPORT_MULTI_ADDRESS_LAYOUT 1
#ifdef __cplusplus
}

View File

@ -20,6 +20,8 @@
extern "C" {
#endif
#warning soc/can_periph.h is deprecated, please use soc/twai_periph.h instead
#if CONFIG_IDF_TARGET_ESP32
#include "soc/can_struct.h"
#include "soc/can_caps.h"

View File

@ -18,191 +18,11 @@
extern "C" {
#endif
#include <stdint.h>
#warning soc/can_struct.h is deprecated, please use soc/twai_struct.h instead
/* ---------------------------- Register Layout ------------------------------ */
/* The CAN peripheral's registers are 8bits, however the ESP32 can only access
* peripheral registers every 32bits. Therefore each CAN register is mapped to
* the least significant byte of every 32bits.
*/
typedef volatile struct can_dev_s {
//Configuration and Control Registers
union {
struct {
uint32_t rm: 1; /* MOD.0 Reset Mode */
uint32_t lom: 1; /* MOD.1 Listen Only Mode */
uint32_t stm: 1; /* MOD.2 Self Test Mode */
uint32_t afm: 1; /* MOD.3 Acceptance Filter Mode */
uint32_t reserved28: 28; /* Internal Reserved. MOD.4 Sleep Mode not supported */
};
uint32_t val;
} mode_reg; /* Address 0 */
union {
struct {
uint32_t tr: 1; /* CMR.0 Transmission Request */
uint32_t at: 1; /* CMR.1 Abort Transmission */
uint32_t rrb: 1; /* CMR.2 Release Receive Buffer */
uint32_t cdo: 1; /* CMR.3 Clear Data Overrun */
uint32_t srr: 1; /* CMR.4 Self Reception Request */
uint32_t reserved27: 27; /* Internal Reserved */
};
uint32_t val;
} command_reg; /* Address 1 */
union {
struct {
uint32_t rbs: 1; /* SR.0 Receive Buffer Status */
uint32_t dos: 1; /* SR.1 Data Overrun Status */
uint32_t tbs: 1; /* SR.2 Transmit Buffer Status */
uint32_t tcs: 1; /* SR.3 Transmission Complete Status */
uint32_t rs: 1; /* SR.4 Receive Status */
uint32_t ts: 1; /* SR.5 Transmit Status */
uint32_t es: 1; /* SR.6 Error Status */
uint32_t bs: 1; /* SR.7 Bus Status */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} status_reg; /* Address 2 */
union {
struct {
uint32_t ri: 1; /* IR.0 Receive Interrupt */
uint32_t ti: 1; /* IR.1 Transmit Interrupt */
uint32_t ei: 1; /* IR.2 Error Interrupt */
uint32_t reserved2: 2; /* Internal Reserved (Data Overrun interrupt and Wake-up not supported) */
uint32_t epi: 1; /* IR.5 Error Passive Interrupt */
uint32_t ali: 1; /* IR.6 Arbitration Lost Interrupt */
uint32_t bei: 1; /* IR.7 Bus Error Interrupt */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} interrupt_reg; /* Address 3 */
union {
struct {
uint32_t rie: 1; /* IER.0 Receive Interrupt Enable */
uint32_t tie: 1; /* IER.1 Transmit Interrupt Enable */
uint32_t eie: 1; /* IER.2 Error Interrupt Enable */
uint32_t doie: 1; /* IER.3 Data Overrun Interrupt Enable */
uint32_t brp_div: 1; /* THIS IS NOT AN INTERRUPT. brp_div will prescale BRP by 2. Only available on ESP32 Revision 2 or later. Reserved otherwise */
uint32_t epie: 1; /* IER.5 Error Passive Interrupt Enable */
uint32_t alie: 1; /* IER.6 Arbitration Lost Interrupt Enable */
uint32_t beie: 1; /* IER.7 Bus Error Interrupt Enable */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} interrupt_enable_reg; /* Address 4 */
uint32_t reserved_05; /* Address 5 */
union {
struct {
uint32_t brp: 6; /* BTR0[5:0] Baud Rate Prescaler */
uint32_t sjw: 2; /* BTR0[7:6] Synchronization Jump Width*/
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} bus_timing_0_reg; /* Address 6 */
union {
struct {
uint32_t tseg1: 4; /* BTR1[3:0] Timing Segment 1 */
uint32_t tseg2: 3; /* BTR1[6:4] Timing Segment 2 */
uint32_t sam: 1; /* BTR1.7 Sampling*/
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} bus_timing_1_reg; /* Address 7 */
uint32_t reserved_08; /* Address 8 (Output control not supported) */
uint32_t reserved_09; /* Address 9 (Test Register not supported) */
uint32_t reserved_10; /* Address 10 */
//Capture and Counter Registers
union {
struct {
uint32_t alc: 5; /* ALC[4:0] Arbitration lost capture */
uint32_t reserved27: 27; /* Internal Reserved */
};
uint32_t val;
} arbitration_lost_captue_reg; /* Address 11 */
union {
struct {
uint32_t seg: 5; /* ECC[4:0] Error Code Segment 0 to 5 */
uint32_t dir: 1; /* ECC.5 Error Direction (TX/RX) */
uint32_t errc: 2; /* ECC[7:6] Error Code */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} error_code_capture_reg; /* Address 12 */
union {
struct {
uint32_t ewl: 8; /* EWL[7:0] Error Warning Limit */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} error_warning_limit_reg; /* EWLR[7:0] Error Warning Limit: Address 13 */
union {
struct {
uint32_t rxerr: 8; /* RXERR[7:0] Receive Error Counter */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} rx_error_counter_reg; /* Address 12 */
union {
struct {
uint32_t txerr: 8; /* TXERR[7:0] Receive Error Counter */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} tx_error_counter_reg; /* Address 15 */
//Shared Registers (TX Buff/RX Buff/Acc Filter)
union {
struct {
union {
struct {
uint32_t byte: 8; /* ACRx[7:0] Acceptance Code */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} acr[4];
union {
struct {
uint32_t byte: 8; /* AMRx[7:0] Acceptance Mask */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} amr[4];
uint32_t reserved32[5];
} acceptance_filter;
union {
struct {
uint32_t byte: 8;
uint32_t reserved24: 24;
};
uint32_t val;
} tx_rx_buffer[13];
}; /* Address 16-28 TX/RX Buffer and Acc Filter*/;
//Misc Registers
union {
struct {
uint32_t rmc: 5; /* RMC[4:0] RX Message Counter */
uint32_t reserved27: 27; /* Internal Reserved */
};
uint32_t val;
} rx_message_counter_reg; /* Address 29 */
uint32_t reserved_30; /* Address 30 (RX Buffer Start Address not supported) */
union {
struct {
uint32_t cd: 3; /* CDR[2:0] CLKOUT frequency selector based of fOSC */
uint32_t co: 1; /* CDR.3 CLKOUT enable/disable */
uint32_t reserved3: 3; /* Internal Reserved. RXINTEN and CBP not supported */
uint32_t cm: 1; /* CDR.7 BasicCAN:0 PeliCAN:1 */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} clock_divider_reg; /* Address 31 */
} can_dev_t;
_Static_assert(sizeof(can_dev_t) == 128, "CAN registers should be 32 * 4 bytes");
#include "soc/twai_struct.h"
typedef twai_dev_t can_dev_t;
extern can_dev_t CAN;
#ifdef __cplusplus

View File

@ -958,7 +958,8 @@
#define DPORT_SPI_DMA_CLK_EN (BIT(22))
#define DPORT_I2S1_CLK_EN (BIT(21))
#define DPORT_PWM1_CLK_EN (BIT(20))
#define DPORT_CAN_CLK_EN (BIT(19))
#define DPORT_TWAI_CLK_EN (BIT(19))
#define DPORT_CAN_CLK_EN DPORT_TWAI_CLK_EN
#define DPORT_I2C_EXT1_CLK_EN (BIT(18))
#define DPORT_PWM0_CLK_EN (BIT(17))
#define DPORT_SPI3_CLK_EN (BIT(16))
@ -992,7 +993,8 @@
#define DPORT_SPI_DMA_RST (BIT(22))
#define DPORT_I2S1_RST (BIT(21))
#define DPORT_PWM1_RST (BIT(20))
#define DPORT_CAN_RST (BIT(19))
#define DPORT_TWAI_RST (BIT(19))
#define DPORT_CAN_RST DPORT_TWAI_RST
#define DPORT_I2C_EXT1_RST (BIT(18))
#define DPORT_PWM0_RST (BIT(17))
#define DPORT_SPI3_RST (BIT(16))

View File

@ -114,6 +114,7 @@
#define EFUSE_RD_CHIP_VER_PKG_ESP32D2WDQ5 2
#define EFUSE_RD_CHIP_VER_PKG_ESP32PICOD2 4
#define EFUSE_RD_CHIP_VER_PKG_ESP32PICOD4 5
#define EFUSE_RD_CHIP_VER_PKG_ESP32PICOV302 6
/* EFUSE_RD_SPI_PAD_CONFIG_HD : RO ;bitpos:[8:4] ;default: 5'b0 ; */
/*description: read for SPI_pad_config_hd*/
#define EFUSE_RD_SPI_PAD_CONFIG_HD 0x0000001F

View File

@ -43,6 +43,9 @@ extern "C" {
#define GPIO_IS_VALID_OUTPUT_GPIO(gpio_num) ((GPIO_IS_VALID_GPIO(gpio_num)) && (gpio_num < 34)) /*!< Check whether it can be a valid GPIO number of output mode */
#define GPIO_MASK_CONTAIN_INPUT_GPIO(gpio_mask) ((gpio_mask & (GPIO_SEL_34 | GPIO_SEL_35 | GPIO_SEL_36 | GPIO_SEL_37 | GPIO_SEL_38 | GPIO_SEL_39))) /*!< Check whether it contains input io */
#define GPIO_MATRIX_CONST_ONE_INPUT (0x38)
#define GPIO_MATRIX_CONST_ZERO_INPUT (0x30)
#ifdef __cplusplus
}
#endif

View File

@ -194,7 +194,8 @@
#define RMT_SIG_OUT5_IDX 92
#define EXT_ADC_START_IDX 93
#define RMT_SIG_OUT6_IDX 93
#define CAN_RX_IDX 94
#define TWAI_RX_IDX 94
#define CAN_RX_IDX TWAI_RX_IDX
#define RMT_SIG_OUT7_IDX 94
#define I2CEXT1_SCL_IN_IDX 95
#define I2CEXT1_SCL_OUT_IDX 95
@ -252,10 +253,13 @@
#define PWM2_OUT4L_IDX 121
#define PWM3_CAP1_IN_IDX 122
#define PWM3_CAP2_IN_IDX 123
#define CAN_TX_IDX 123
#define TWAI_TX_IDX 123
#define CAN_TX_IDX TWAI_TX_IDX
#define PWM3_CAP3_IN_IDX 124
#define CAN_BUS_OFF_ON_IDX 124
#define CAN_CLKOUT_IDX 125
#define TWAI_BUS_OFF_ON_IDX 124
#define CAN_BUS_OFF_ON_IDX TWAI_BUS_OFF_ON_IDX
#define TWAI_CLKOUT_IDX 125
#define CAN_CLKOUT_IDX TWAI_CLKOUT_IDX
#define SPID4_IN_IDX 128
#define SPID4_OUT_IDX 128
#define SPID5_IN_IDX 129

View File

@ -812,8 +812,6 @@
#define HOST_SLCHOST_STATE4_V 0xFF
#define HOST_SLCHOST_STATE4_S 0
#define HOST_SLCHOST_CONF_W_REG(pos) (HOST_SLCHOST_CONF_W0_REG+pos+(pos>23?4:0)+(pos>31?12:0))
#define HOST_SLCHOST_CONF_W0_REG (DR_REG_SLCHOST_BASE + 0x6C)
/* HOST_SLCHOST_CONF3 : R/W ;bitpos:[31:24] ;default: 8'h0 ; */
/*description: */

View File

@ -44,7 +44,8 @@ typedef enum {
PERIPH_SPI_DMA_MODULE,
PERIPH_SDMMC_MODULE,
PERIPH_SDIO_SLAVE_MODULE,
PERIPH_CAN_MODULE,
PERIPH_TWAI_MODULE,
PERIPH_CAN_MODULE = PERIPH_TWAI_MODULE,
PERIPH_EMAC_MODULE,
PERIPH_RNG_MODULE,
PERIPH_WIFI_MODULE,

View File

@ -645,6 +645,8 @@ rtc_vddsdio_config_t rtc_vddsdio_get_config(void);
*/
void rtc_vddsdio_set_config(rtc_vddsdio_config_t config);
#ifdef __cplusplus
}
#endif

View File

@ -327,7 +327,8 @@
#define ETS_PWM3_INTR_SOURCE 42/**< interruot of PWM3, level*/
#define ETS_LEDC_INTR_SOURCE 43/**< interrupt of LED PWM, level*/
#define ETS_EFUSE_INTR_SOURCE 44/**< interrupt of efuse, level, not likely to use*/
#define ETS_CAN_INTR_SOURCE 45/**< interrupt of can, level*/
#define ETS_TWAI_INTR_SOURCE 45/**< interrupt of twai, level*/
#define ETS_CAN_INTR_SOURCE ETS_TWAI_INTR_SOURCE
#define ETS_RTC_CORE_INTR_SOURCE 46/**< interrupt of rtc core, level, include rtc watchdog*/
#define ETS_RMT_INTR_SOURCE 47/**< interrupt of remote controller, level*/
#define ETS_PCNT_INTR_SOURCE 48/**< interrupt of pluse count, level*/

View File

@ -9,7 +9,8 @@
#define SOC_SDMMC_HOST_SUPPORTED 1
#define SOC_BT_SUPPORTED 1
#define SOC_SDIO_SLAVE_SUPPORTED 1
#define SOC_CAN_SUPPORTED 1
#define SOC_TWAI_SUPPORTED 1
#define SOC_CAN_SUPPORTED SOC_TWAI_SUPPORTED
#define SOC_EMAC_SUPPORTED 1
#define SOC_RISCV_COPROC_SUPPORTED 0
#define SOC_CPU_CORES_NUM 2

View File

@ -0,0 +1,29 @@
// 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 TWAI_BRP_MIN 2
#define TWAI_BRP_MAX 128
#define TWAI_BRP_MAX_ECO 256
#define TWAI_BRP_DIV_THRESH 128
#define TWAI_SUPPORT_MULTI_ADDRESS_LAYOUT 1
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,210 @@
// 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.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
/* ---------------------------- Register Layout ------------------------------ */
/* The TWAI peripheral's registers are 8bits, however the ESP32 can only access
* peripheral registers every 32bits. Therefore each TWAI register is mapped to
* the least significant byte of every 32bits.
*/
typedef volatile struct twai_dev_s {
//Configuration and Control Registers
union {
struct {
uint32_t rm: 1; /* MOD.0 Reset Mode */
uint32_t lom: 1; /* MOD.1 Listen Only Mode */
uint32_t stm: 1; /* MOD.2 Self Test Mode */
uint32_t afm: 1; /* MOD.3 Acceptance Filter Mode */
uint32_t reserved28: 28; /* Internal Reserved. MOD.4 Sleep Mode not supported */
};
uint32_t val;
} mode_reg; /* Address 0 */
union {
struct {
uint32_t tr: 1; /* CMR.0 Transmission Request */
uint32_t at: 1; /* CMR.1 Abort Transmission */
uint32_t rrb: 1; /* CMR.2 Release Receive Buffer */
uint32_t cdo: 1; /* CMR.3 Clear Data Overrun */
uint32_t srr: 1; /* CMR.4 Self Reception Request */
uint32_t reserved27: 27; /* Internal Reserved */
};
uint32_t val;
} command_reg; /* Address 1 */
union {
struct {
uint32_t rbs: 1; /* SR.0 Receive Buffer Status */
uint32_t dos: 1; /* SR.1 Data Overrun Status */
uint32_t tbs: 1; /* SR.2 Transmit Buffer Status */
uint32_t tcs: 1; /* SR.3 Transmission Complete Status */
uint32_t rs: 1; /* SR.4 Receive Status */
uint32_t ts: 1; /* SR.5 Transmit Status */
uint32_t es: 1; /* SR.6 Error Status */
uint32_t bs: 1; /* SR.7 Bus Status */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} status_reg; /* Address 2 */
union {
struct {
uint32_t ri: 1; /* IR.0 Receive Interrupt */
uint32_t ti: 1; /* IR.1 Transmit Interrupt */
uint32_t ei: 1; /* IR.2 Error Interrupt */
uint32_t reserved2: 2; /* Internal Reserved (Data Overrun interrupt and Wake-up not supported) */
uint32_t epi: 1; /* IR.5 Error Passive Interrupt */
uint32_t ali: 1; /* IR.6 Arbitration Lost Interrupt */
uint32_t bei: 1; /* IR.7 Bus Error Interrupt */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} interrupt_reg; /* Address 3 */
union {
struct {
uint32_t rie: 1; /* IER.0 Receive Interrupt Enable */
uint32_t tie: 1; /* IER.1 Transmit Interrupt Enable */
uint32_t eie: 1; /* IER.2 Error Interrupt Enable */
uint32_t doie: 1; /* IER.3 Data Overrun Interrupt Enable */
uint32_t brp_div: 1; /* THIS IS NOT AN INTERRUPT. brp_div will prescale BRP by 2. Only available on ESP32 Revision 2 or later. Reserved otherwise */
uint32_t epie: 1; /* IER.5 Error Passive Interrupt Enable */
uint32_t alie: 1; /* IER.6 Arbitration Lost Interrupt Enable */
uint32_t beie: 1; /* IER.7 Bus Error Interrupt Enable */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} interrupt_enable_reg; /* Address 4 */
uint32_t reserved_05; /* Address 5 */
union {
struct {
uint32_t brp: 6; /* BTR0[5:0] Baud Rate Prescaler */
uint32_t sjw: 2; /* BTR0[7:6] Synchronization Jump Width*/
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} bus_timing_0_reg; /* Address 6 */
union {
struct {
uint32_t tseg1: 4; /* BTR1[3:0] Timing Segment 1 */
uint32_t tseg2: 3; /* BTR1[6:4] Timing Segment 2 */
uint32_t sam: 1; /* BTR1.7 Sampling*/
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} bus_timing_1_reg; /* Address 7 */
uint32_t reserved_08; /* Address 8 (Output control not supported) */
uint32_t reserved_09; /* Address 9 (Test Register not supported) */
uint32_t reserved_10; /* Address 10 */
//Capture and Counter Registers
union {
struct {
uint32_t alc: 5; /* ALC[4:0] Arbitration lost capture */
uint32_t reserved27: 27; /* Internal Reserved */
};
uint32_t val;
} arbitration_lost_captue_reg; /* Address 11 */
union {
struct {
uint32_t seg: 5; /* ECC[4:0] Error Code Segment 0 to 5 */
uint32_t dir: 1; /* ECC.5 Error Direction (TX/RX) */
uint32_t errc: 2; /* ECC[7:6] Error Code */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} error_code_capture_reg; /* Address 12 */
union {
struct {
uint32_t ewl: 8; /* EWL[7:0] Error Warning Limit */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} error_warning_limit_reg; /* EWLR[7:0] Error Warning Limit: Address 13 */
union {
struct {
uint32_t rxerr: 8; /* RXERR[7:0] Receive Error Counter */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} rx_error_counter_reg; /* Address 12 */
union {
struct {
uint32_t txerr: 8; /* TXERR[7:0] Receive Error Counter */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} tx_error_counter_reg; /* Address 15 */
//Shared Registers (TX Buff/RX Buff/Acc Filter)
union {
struct {
union {
struct {
uint32_t byte: 8; /* ACRx[7:0] Acceptance Code */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} acr[4];
union {
struct {
uint32_t byte: 8; /* AMRx[7:0] Acceptance Mask */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} amr[4];
uint32_t reserved32[5];
} acceptance_filter;
union {
struct {
uint32_t byte: 8;
uint32_t reserved24: 24;
};
uint32_t val;
} tx_rx_buffer[13];
}; /* Address 16-28 TX/RX Buffer and Acc Filter*/;
//Misc Registers
union {
struct {
uint32_t rmc: 7; /* RMC[6:0] RX Message Counter */
uint32_t reserved25: 25; /* Internal Reserved */
};
uint32_t val;
} rx_message_counter_reg; /* Address 29 */
uint32_t reserved_30; /* Address 30 (RX Buffer Start Address not supported) */
union {
struct {
uint32_t cd: 3; /* CDR[2:0] CLKOUT frequency selector based of fOSC */
uint32_t co: 1; /* CDR.3 CLKOUT enable/disable */
uint32_t reserved3: 3; /* Internal Reserved. RXINTEN and CBP not supported */
uint32_t cm: 1; /* CDR.7 Register Layout. Basic:0 Extended:1 */
uint32_t reserved24: 24; /* Internal Reserved */
};
uint32_t val;
} clock_divider_reg; /* Address 31 */
} twai_dev_t;
_Static_assert(sizeof(twai_dev_t) == 128, "TWAI registers should be 32 * 4 bytes");
extern twai_dev_t TWAI;
#ifdef __cplusplus
}
#endif

View File

@ -14,6 +14,7 @@
#pragma once
#include <stdint.h>
#include "sdkconfig.h"
#include "soc/soc.h"
#include "soc/periph_defs.h"
@ -22,8 +23,7 @@
#include "soc/spi_reg.h"
#include "soc/spi_struct.h"
#include "soc/gpio_sig_map.h"
#include "sdkconfig.h"
#if CONFIG_IDF_TARGET_ESP32S2
#if SOC_MEMSPI_IS_INDEPENDENT
#include "soc/spi_mem_struct.h"
#include "soc/spi_mem_reg.h"
#endif

View File

@ -0,0 +1,28 @@
// 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
#include "sdkconfig.h"
#ifdef __cplusplus
extern "C" {
#endif
#include "soc/twai_struct.h"
#include "soc/twai_caps.h"
#ifdef __cplusplus
}
#endif

View File

@ -100,19 +100,6 @@ void adc_hal_digi_deinit(void);
*/
int adc_hal_hall_convert(void);
/**
* @brief Output ADC2 reference voltage to gpio
*
* This function utilizes the testing mux exclusive to ADC2 to route the
* reference voltage one of ADC2's channels.
*
* @param[in] io GPIO number
* @return
* - true: v_ref successfully routed to selected gpio
* - false: Unsupported gpio
*/
#define adc_hal_vref_output(io) adc_ll_vref_output(io)
#ifdef __cplusplus
}
#endif

View File

@ -673,43 +673,43 @@ static inline void adc_ll_set_hall_controller(adc_ll_hall_controller_t hall_ctrl
}
/**
* Output ADC2 reference voltage to gpio 25 or 26 or 27
* Output ADC internal reference voltage to channels, only available for ADC2 on ESP32.
*
* This function utilizes the testing mux exclusive to ADC 2 to route the
* reference voltage one of ADC2's channels. Supported gpios are gpios
* 25, 26, and 27. This refernce voltage can be manually read from the pin
* and used in the esp_adc_cal component.
* This function routes the internal reference voltage of ADCn to one of
* ADC2's channels. This reference voltage can then be manually measured
* for calibration purposes.
*
* @param[in] io GPIO number (gpios 25,26,27 supported)
*
* @return
* - true: v_ref successfully routed to selected gpio
* - false: Unsupported gpio
* @param[in] adc ADC unit select
* @param[in] channel ADC2 channel number
* @param[in] en Enable/disable the reference voltage output
*/
static inline bool adc_ll_vref_output(int io)
static inline void adc_ll_vref_output(adc_ll_num_t adc, adc_channel_t channel, bool en)
{
int channel;
if (io == 25) {
channel = 8; //Channel 8 bit
} else if (io == 26) {
channel = 9; //Channel 9 bit
} else if (io == 27) {
channel = 7; //Channel 7 bit
if (adc != ADC_NUM_2) return;
if (en) {
RTCCNTL.bias_conf.dbg_atten = 0; //Check DBG effect outside sleep mode
//set dtest (MUX_SEL : 0 -> RTC; 1-> vdd_sar2)
RTCCNTL.test_mux.dtest_rtc = 1; //Config test mux to route v_ref to ADC2 Channels
//set ent
RTCCNTL.test_mux.ent_rtc = 1;
//set sar2_en_test
SENS.sar_start_force.sar2_en_test = 1;
//set sar2 en force
SENS.sar_meas_start2.sar2_en_pad_force = 1; //Pad bitmap controlled by SW
//set en_pad for channels 7,8,9 (bits 0x380)
SENS.sar_meas_start2.sar2_en_pad = 1 << channel;
} else {
return false;
RTCCNTL.test_mux.dtest_rtc = 0; //Config test mux to route v_ref to ADC2 Channels
//set ent
RTCCNTL.test_mux.ent_rtc = 0;
//set sar2_en_test
SENS.sar_start_force.sar2_en_test = 0;
//set sar2 en force
SENS.sar_meas_start2.sar2_en_pad_force = 0; //Pad bitmap controlled by SW
//set en_pad for channels 7,8,9 (bits 0x380)
SENS.sar_meas_start2.sar2_en_pad = 0;
}
RTCCNTL.bias_conf.dbg_atten = 0; //Check DBG effect outside sleep mode
//set dtest (MUX_SEL : 0 -> RTC; 1-> vdd_sar2)
RTCCNTL.test_mux.dtest_rtc = 1; //Config test mux to route v_ref to ADC2 Channels
//set ent
RTCCNTL.test_mux.ent_rtc = 1;
//set sar2_en_test
SENS.sar_start_force.sar2_en_test = 1;
//set sar2 en force
SENS.sar_meas_start2.sar2_en_pad_force = 1; //Pad bitmap controlled by SW
//set en_pad for channels 7,8,9 (bits 0x380)
SENS.sar_meas_start2.sar2_en_pad = 1 << channel;
return true;
}
#ifdef __cplusplus

View File

@ -0,0 +1,154 @@
// 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.
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#warning hal/can_hal.h is deprecated, please use hal/twai_hal.h instead
#include "hal/twai_hal.h"
#include "hal/can_types.h"
/* ------------------------- Defines and Typedefs --------------------------- */
//Error active interrupt related
#define CAN_HAL_EVENT_BUS_OFF TWAI_HAL_EVENT_BUS_OFF
#define CAN_HAL_EVENT_BUS_RECOV_CPLT TWAI_HAL_EVENT_BUS_RECOV_CPLT
#define CAN_HAL_EVENT_BUS_RECOV_PROGRESS TWAI_HAL_EVENT_BUS_RECOV_PROGRESS
#define CAN_HAL_EVENT_ABOVE_EWL TWAI_HAL_EVENT_ABOVE_EWL
#define CAN_HAL_EVENT_BELOW_EWL TWAI_HAL_EVENT_BELOW_EWL
#define CAN_HAL_EVENT_ERROR_PASSIVE TWAI_HAL_EVENT_ERROR_PASSIVE
#define CAN_HAL_EVENT_ERROR_ACTIVE TWAI_HAL_EVENT_ERROR_ACTIVE
#define CAN_HAL_EVENT_BUS_ERR TWAI_HAL_EVENT_BUS_ERR
#define CAN_HAL_EVENT_ARB_LOST TWAI_HAL_EVENT_ARB_LOST
#define CAN_HAL_EVENT_RX_BUFF_FRAME TWAI_HAL_EVENT_RX_BUFF_FRAME
#define CAN_HAL_EVENT_TX_BUFF_FREE TWAI_HAL_EVENT_TX_BUFF_FREE
typedef twai_hal_context_t can_hal_context_t;
typedef twai_hal_frame_t can_hal_frame_t;
/* ---------------------------- Init and Config ----------------------------- */
static inline bool can_hal_init(can_hal_context_t *hal_ctx){
return twai_hal_init(hal_ctx);
}
static inline void can_hal_deinit(can_hal_context_t *hal_ctx)
{
twai_hal_deinit(hal_ctx);
}
static inline void can_hal_configure(can_hal_context_t *hal_ctx, const can_timing_config_t *t_config, const can_filter_config_t *f_config, uint32_t intr_mask, uint32_t clkout_divider)
{
twai_hal_configure(hal_ctx, t_config, f_config, intr_mask, clkout_divider);
}
/* -------------------------------- Actions --------------------------------- */
static inline bool can_hal_start(can_hal_context_t *hal_ctx, can_mode_t mode)
{
return twai_hal_start(hal_ctx, mode);
}
static inline bool can_hal_stop(can_hal_context_t *hal_ctx)
{
return twai_hal_stop(hal_ctx);
}
static inline bool can_hal_start_bus_recovery(can_hal_context_t *hal_ctx)
{
return twai_hal_start_bus_recovery(hal_ctx);
}
static inline uint32_t can_hal_get_tec(can_hal_context_t *hal_ctx)
{
return twai_hal_get_tec(hal_ctx);
}
static inline uint32_t can_hal_get_rec(can_hal_context_t *hal_ctx)
{
return twai_hal_get_rec(hal_ctx);
}
static inline uint32_t can_hal_get_rx_msg_count(can_hal_context_t *hal_ctx)
{
return twai_hal_get_rx_msg_count(hal_ctx);
}
static inline bool can_hal_check_last_tx_successful(can_hal_context_t *hal_ctx)
{
return twai_hal_check_last_tx_successful(hal_ctx);
}
/* ----------------------------- Event Handling ----------------------------- */
static inline uint32_t can_hal_decode_interrupt_events(can_hal_context_t *hal_ctx, bool bus_recovering) {
return twai_hal_decode_interrupt_events(hal_ctx, bus_recovering);
}
static inline bool can_hal_handle_bus_recov_cplt(can_hal_context_t *hal_ctx)
{
return twai_hal_handle_bus_recov_cplt(hal_ctx);
}
static inline void can_hal_handle_arb_lost(can_hal_context_t *hal_ctx)
{
twai_hal_handle_arb_lost(hal_ctx);
}
static inline void can_hal_handle_bus_error(can_hal_context_t *hal_ctx)
{
twai_hal_handle_bus_error(hal_ctx);
}
static inline void can_hal_handle_bus_off(can_hal_context_t *hal_ctx)
{
twai_hal_handle_bus_off(hal_ctx);
}
/* ------------------------------- TX and RX -------------------------------- */
static inline void can_hal_format_frame(const can_message_t *message, can_hal_frame_t *frame)
{
twai_hal_format_frame(message, frame);
}
static inline void can_hal_parse_frame(can_hal_frame_t *frame, can_message_t *message)
{
twai_hal_parse_frame(frame, message);
}
static inline void can_hal_set_tx_buffer_and_transmit(can_hal_context_t *hal_ctx, can_hal_frame_t *tx_frame)
{
twai_hal_set_tx_buffer_and_transmit(hal_ctx, tx_frame);
}
static inline void can_hal_read_rx_buffer_and_clear(can_hal_context_t *hal_ctx, can_hal_frame_t *rx_frame)
{
twai_hal_read_rx_buffer_and_clear(hal_ctx, rx_frame);
}
#ifdef __cplusplus
}
#endif

View File

@ -26,676 +26,227 @@
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#warning hal/can_ll.h is deprecated, please use hal/twai_ll.h instead
#include "hal/twai_ll.h"
#include "hal/can_types.h"
#include "soc/can_periph.h"
/* ------------------------- Defines and Typedefs --------------------------- */
#define CAN_LL_STATUS_RBS (0x1 << 0)
#define CAN_LL_STATUS_DOS (0x1 << 1)
#define CAN_LL_STATUS_TBS (0x1 << 2)
#define CAN_LL_STATUS_TCS (0x1 << 3)
#define CAN_LL_STATUS_RS (0x1 << 4)
#define CAN_LL_STATUS_TS (0x1 << 5)
#define CAN_LL_STATUS_ES (0x1 << 6)
#define CAN_LL_STATUS_BS (0x1 << 7)
#define CAN_LL_STATUS_RBS TWAI_LL_STATUS_RBS
#define CAN_LL_STATUS_DOS TWAI_LL_STATUS_DOS
#define CAN_LL_STATUS_TBS TWAI_LL_STATUS_TBS
#define CAN_LL_STATUS_TCS TWAI_LL_STATUS_TCS
#define CAN_LL_STATUS_RS TWAI_LL_STATUS_RS
#define CAN_LL_STATUS_TS TWAI_LL_STATUS_TS
#define CAN_LL_STATUS_ES TWAI_LL_STATUS_ES
#define CAN_LL_STATUS_BS TWAI_LL_STATUS_BS
#define CAN_LL_INTR_RI (0x1 << 0)
#define CAN_LL_INTR_TI (0x1 << 1)
#define CAN_LL_INTR_EI (0x1 << 2)
//Data overrun interrupt not supported in SW due to HW peculiarities
#define CAN_LL_INTR_EPI (0x1 << 5)
#define CAN_LL_INTR_ALI (0x1 << 6)
#define CAN_LL_INTR_BEI (0x1 << 7)
#define CAN_LL_INTR_RI TWAI_LL_INTR_RI
#define CAN_LL_INTR_TI TWAI_LL_INTR_TI
#define CAN_LL_INTR_EI TWAI_LL_INTR_EI
#define CAN_LL_INTR_EPI TWAI_LL_INTR_EPI
#define CAN_LL_INTR_ALI TWAI_LL_INTR_ALI
#define CAN_LL_INTR_BEI TWAI_LL_INTR_BEI
/*
* The following frame structure has an NEARLY identical bit field layout to
* each byte of the TX buffer. This allows for formatting and parsing frames to
* 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)) can_ll_frame_buffer_t;
typedef twai_ll_frame_buffer_t can_ll_frame_buffer_t;
/* ---------------------------- Mode Register ------------------------------- */
/**
* @brief Enter reset mode
*
* When in reset mode, the CAN controller is effectively disconnected from the
* CAN 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 CAN registers
* @return true if reset mode was entered successfully
*
* @note Reset mode is automatically entered on BUS OFF condition
*/
static inline bool can_ll_enter_reset_mode(can_dev_t *hw)
{
hw->mode_reg.rm = 1;
return hw->mode_reg.rm;
return twai_ll_enter_reset_mode(hw);
}
/**
* @brief Exit reset mode
*
* When not in reset mode, the CAN 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 CAN registers
* @return true if reset mode was exit successfully
*
* @note Reset mode must be exit to initiate BUS OFF recovery
*/
static inline bool can_ll_exit_reset_mode(can_dev_t *hw)
{
hw->mode_reg.rm = 0;
return !(hw->mode_reg.rm);
return twai_ll_exit_reset_mode(hw);
}
/**
* @brief Check if in reset mode
* @param hw Start address of the CAN registers
* @return true if in reset mode
*/
static inline bool can_ll_is_in_reset_mode(can_dev_t *hw)
{
return hw->mode_reg.rm;
return twai_ll_is_in_reset_mode(hw);
}
/**
* @brief Set operating mode of CAN controller
*
* @param hw Start address of the CAN registers
* @param mode Operating mode
*
* @note Must be called in reset mode
*/
static inline void can_ll_set_mode(can_dev_t *hw, can_mode_t mode)
{
if (mode == CAN_MODE_NORMAL) { //Normal Operating mode
hw->mode_reg.lom = 0;
hw->mode_reg.stm = 0;
} else if (mode == CAN_MODE_NO_ACK) { //Self Test Mode (No Ack)
hw->mode_reg.lom = 0;
hw->mode_reg.stm = 1;
} else if (mode == CAN_MODE_LISTEN_ONLY) { //Listen Only Mode
hw->mode_reg.lom = 1;
hw->mode_reg.stm = 0;
}
twai_ll_set_mode(hw, mode);
}
/* --------------------------- Command Register ----------------------------- */
/**
* @brief Set TX command
*
* Setting the TX command will cause the CAN 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 CAN 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.
*/
static inline void can_ll_set_cmd_tx(can_dev_t *hw)
{
hw->command_reg.tr = 1;
twai_ll_set_cmd_tx(hw);
}
/**
* @brief Set single shot TX command
*
* Similar to setting TX command, but the CAN controller will not automatically
* retry transmission upon an error (e.g., due to an acknowledgement error).
*
* @param hw Start address of the CAN 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.
*/
static inline void can_ll_set_cmd_tx_single_shot(can_dev_t *hw)
{
hw->command_reg.val = 0x03; //Writing to TR and AT simultaneously
twai_ll_set_cmd_tx_single_shot(hw);
}
/**
* @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 CAN controller will not automatically
* retry transmission upon an error (e.g., due to acknowledge error).
*
* @param hw Start address of the CAN 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.
*/
static inline void can_ll_set_cmd_abort_tx(can_dev_t *hw)
{
hw->command_reg.at = 1;
twai_ll_set_cmd_abort_tx(hw);
}
/**
* @brief Release RX buffer
*
* Rotates RX buffer to the next frame in the RX FIFO.
*
* @param hw Start address of the CAN registers
*/
static inline void can_ll_set_cmd_release_rx_buffer(can_dev_t *hw)
{
hw->command_reg.rrb = 1;
twai_ll_set_cmd_release_rx_buffer(hw);
}
/**
* @brief Clear data overrun
*
* Clears the data overrun status bit
*
* @param hw Start address of the CAN registers
*/
static inline void can_ll_set_cmd_clear_data_overrun(can_dev_t *hw)
{
hw->command_reg.cdo = 1;
twai_ll_set_cmd_clear_data_overrun(hw);
}
/**
* @brief Set self reception single shot command
*
* Similar to setting TX command, but the CAN controller also simultaneously
* receive the transmitted frame and is generally used for self testing
* purposes. The CAN controller will not ACK the received message, so consider
* using the NO_ACK operating mode.
*
* @param hw Start address of the CAN 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.
*/
static inline void can_ll_set_cmd_self_rx_request(can_dev_t *hw)
{
hw->command_reg.srr = 1;
twai_ll_set_cmd_self_rx_request(hw);
}
/**
* @brief Set self reception request command
*
* Similar to setting the self reception request, but the CAN controller will
* not automatically retry transmission upon an error (e.g., due to and
* acknowledgement error).
*
* @param hw Start address of the CAN 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.
*/
static inline void can_ll_set_cmd_self_rx_single_shot(can_dev_t *hw)
{
hw->command_reg.val = 0x12;
twai_ll_set_cmd_self_rx_single_shot(hw);
}
/* --------------------------- Status Register ------------------------------ */
/**
* @brief Get all status bits
*
* @param hw Start address of the CAN registers
* @return Status bits
*/
static inline uint32_t can_ll_get_status(can_dev_t *hw)
{
return hw->status_reg.val;
return twai_ll_get_status(hw);
}
/**
* @brief Check if RX FIFO overrun status bit is set
*
* @param hw Start address of the CAN registers
* @return Overrun status bit
*/
static inline bool can_ll_is_fifo_overrun(can_dev_t *hw)
{
return hw->status_reg.dos;
return twai_ll_is_fifo_overrun(hw);
}
/**
* @brief Check if previously TX was successful
*
* @param hw Start address of the CAN registers
* @return Whether previous TX was successful
*/
static inline bool can_ll_is_last_tx_successful(can_dev_t *hw)
{
return hw->status_reg.tcs;
return twai_ll_is_last_tx_successful(hw);
}
//Todo: Add stand alone status bit check functions when necessary
/* -------------------------- 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 CAN registers
* @return Bit mask of set interrupts
*/
static inline uint32_t can_ll_get_and_clear_intrs(can_dev_t *hw)
{
return hw->interrupt_reg.val;
return twai_ll_get_and_clear_intrs(hw);
}
/* ----------------------- Interrupt Enable Register ------------------------ */
/**
* @brief Set which interrupts are enabled
*
* @param hw Start address of the CAN registers
* @param Bit mask of interrupts to enable
*
* @note Must be called in reset mode
*/
static inline void can_ll_set_enabled_intrs(can_dev_t *hw, uint32_t intr_mask)
{
#ifdef CAN_BRP_DIV_SUPPORTED
//ESP32 Rev 2 has brp div. Need to mask when setting
hw->interrupt_enable_reg.val = (hw->interrupt_enable_reg.val & 0x10) | intr_mask;
#else
hw->interrupt_enable_reg.val = intr_mask;
#endif
twai_ll_set_enabled_intrs(hw, intr_mask);
}
/* ------------------------ Bus Timing Registers --------------------------- */
/**
* @brief Set bus timing
*
* @param hw Start address of the CAN 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 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.
*/
static inline void can_ll_set_bus_timing(can_dev_t *hw, uint32_t brp, uint32_t sjw, uint32_t tseg1, uint32_t tseg2, bool triple_sampling)
{
#ifdef CAN_BRP_DIV_SUPPORTED
if (brp > CAN_BRP_DIV_THRESH) {
//Need to set brp_div bit
hw->interrupt_enable_reg.brp_div = 1;
brp /= 2;
}
#endif
hw->bus_timing_0_reg.brp = (brp / 2) - 1;
hw->bus_timing_0_reg.sjw = sjw - 1;
hw->bus_timing_1_reg.tseg1 = tseg1 - 1;
hw->bus_timing_1_reg.tseg2 = tseg2 - 1;
hw->bus_timing_1_reg.sam = triple_sampling;
twai_ll_set_bus_timing(hw, brp, sjw, tseg1, tseg2, 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 CAN registers
*/
static inline void can_ll_clear_arb_lost_cap(can_dev_t *hw)
{
(void)hw->arbitration_lost_captue_reg.val;
//Todo: Decode ALC register
twai_ll_clear_arb_lost_cap(hw);
}
/* ----------------------------- ECC Register ------------------------------- */
/**
* @brief Clear Error Code Capture register
*
* Reading the ECC register rearms the Bus Error Interrupt
*
* @param hw Start address of the CAN registers
*/
static inline void can_ll_clear_err_code_cap(can_dev_t *hw)
{
(void)hw->error_code_capture_reg.val;
//Todo: Decode error code capture
twai_ll_clear_err_code_cap(hw);
}
/* ----------------------------- EWL Register ------------------------------- */
/**
* @brief Set Error Warning Limit
*
* @param hw Start address of the CAN registers
* @param ewl Error Warning Limit
*
* @note Must be called in reset mode
*/
static inline void can_ll_set_err_warn_lim(can_dev_t *hw, uint32_t ewl)
{
hw->error_warning_limit_reg.ewl = ewl;
twai_ll_set_err_warn_lim(hw, ewl);
}
/**
* @brief Get Error Warning Limit
*
* @param hw Start address of the CAN registers
* @return Error Warning Limit
*/
static inline uint32_t can_ll_get_err_warn_lim(can_dev_t *hw)
{
return hw->error_warning_limit_reg.val;
return twai_ll_get_err_warn_lim(hw);
}
/* ------------------------ RX Error Count Register ------------------------- */
/**
* @brief Get RX Error Counter
*
* @param hw Start address of the CAN 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.
*/
static inline uint32_t can_ll_get_rec(can_dev_t *hw)
{
return hw->rx_error_counter_reg.val;
return twai_ll_get_rec(hw);
}
/**
* @brief Set RX Error Counter
*
* @param hw Start address of the CAN registers
* @param rec REC value
*
* @note Must be called in reset mode
*/
static inline void can_ll_set_rec(can_dev_t *hw, uint32_t rec)
{
hw->rx_error_counter_reg.rxerr = rec;
twai_ll_set_rec(hw, rec);
}
/* ------------------------ TX Error Count Register ------------------------- */
/**
* @brief Get TX Error Counter
*
* @param hw Start address of the CAN registers
* @return TEC value
*
* @note A BUS OFF condition will automatically set this to 128
*/
static inline uint32_t can_ll_get_tec(can_dev_t *hw)
{
return hw->tx_error_counter_reg.val;
return twai_ll_get_tec(hw);
}
/**
* @brief Set TX Error Counter
*
* @param hw Start address of the CAN registers
* @param tec TEC value
*
* @note Must be called in reset mode
*/
static inline void can_ll_set_tec(can_dev_t *hw, uint32_t tec)
{
hw->tx_error_counter_reg.txerr = tec;
twai_ll_set_tec(hw, tec);
}
/* ---------------------- Acceptance Filter Registers ----------------------- */
/**
* @brief Set Acceptance Filter
* @param hw Start address of the CAN 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
*/
static inline void can_ll_set_acc_filter(can_dev_t* hw, uint32_t code, uint32_t mask, bool single_filter)
{
uint32_t code_swapped = __builtin_bswap32(code);
uint32_t mask_swapped = __builtin_bswap32(mask);
for (int i = 0; i < 4; i++) {
hw->acceptance_filter.acr[i].byte = ((code_swapped >> (i * 8)) & 0xFF);
hw->acceptance_filter.amr[i].byte = ((mask_swapped >> (i * 8)) & 0xFF);
}
hw->mode_reg.afm = single_filter;
twai_ll_set_acc_filter(hw, code, mask, single_filter);
}
/* ------------------------- TX/RX Buffer Registers ------------------------- */
/**
* @brief Copy a formatted CAN frame into TX buffer for transmission
*
* @param hw Start address of the CAN registers
* @param tx_frame Pointer to formatted frame
*
* @note Call can_ll_format_frame_buffer() to format a frame
*/
static inline void can_ll_set_tx_buffer(can_dev_t *hw, can_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];
}
twai_ll_set_tx_buffer(hw, tx_frame);
}
/**
* @brief Copy a received frame from the RX buffer for parsing
*
* @param hw Start address of the CAN registers
* @param rx_frame Pointer to store formatted frame
*
* @note Call can_ll_prase_frame_buffer() to parse the formatted frame
*/
static inline void can_ll_get_rx_buffer(can_dev_t *hw, can_ll_frame_buffer_t *rx_frame)
{
//Copy RX buffer registers into frame
for (int i = 0; i < 13; i++) {
rx_frame->bytes[i] = hw->tx_rx_buffer[i].byte;
}
twai_ll_get_rx_buffer(hw, rx_frame);
}
/**
* @brief Format contents of a CAN frame into layout of TX Buffer
*
* @param[in] id 11 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 CAN 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
*/
static inline void can_ll_format_frame_buffer(uint32_t id, uint8_t dlc, const uint8_t *data,
uint32_t flags, can_ll_frame_buffer_t *tx_frame)
{
/* 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. */
bool is_extd = flags & CAN_MSG_FLAG_EXTD;
bool is_rtr = flags & CAN_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 & CAN_MSG_FLAG_SELF) ? 1 : 0;
tx_frame->single_shot = (flags & CAN_MSG_FLAG_SS) ? 1 : 0;
//Set ID
if (is_extd) {
uint32_t id_temp = __builtin_bswap32((id & CAN_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 = __builtin_bswap16((id & CAN_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;
}
}
//Set Data
uint8_t *data_buffer = (is_extd) ? tx_frame->extended.data : tx_frame->standard.data;
if (!is_rtr) {
for (int i = 0; (i < dlc) && (i < CAN_FRAME_MAX_DLC); i++) {
data_buffer[i] = data[i];
}
}
twai_ll_format_frame_buffer(id, dlc, data, flags, tx_frame);
}
/**
* @brief Parse formatted CAN frame (RX Buffer Layout) into its 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 CAN frame
*/
static inline void can_ll_prase_frame_buffer(can_ll_frame_buffer_t *rx_frame, uint32_t *id, uint8_t *dlc,
uint8_t *data, uint32_t *flags)
{
//This function decodes a frame structure into it's constituent components.
//Copy frame information
*dlc = rx_frame->dlc;
uint32_t flags_temp = 0;
flags_temp |= (rx_frame->frame_format) ? CAN_MSG_FLAG_EXTD : 0;
flags_temp |= (rx_frame->rtr) ? CAN_MSG_FLAG_RTR : 0;
flags_temp |= (rx_frame->dlc > CAN_FRAME_MAX_DLC) ? CAN_MSG_FLAG_DLC_NON_COMP : 0;
*flags = flags_temp;
//Copy ID
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 = __builtin_bswap32(id_temp) >> 3; //((byte[i] << 8*(3-i)) >> 3)
*id = id_temp & CAN_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 = __builtin_bswap16(id_temp) >> 5; //((byte[i] << 8*(1-i)) >> 5)
*id = id_temp & CAN_STD_ID_MASK;
}
//Copy data
uint8_t *data_buffer = (rx_frame->frame_format) ? rx_frame->extended.data : rx_frame->standard.data;
int data_length = (rx_frame->rtr) ? 0 : ((rx_frame->dlc > CAN_FRAME_MAX_DLC) ? CAN_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 < CAN_FRAME_MAX_DLC; i++) {
data[i] = 0;
}
twai_ll_prase_frame_buffer(rx_frame, id, dlc, data, flags);
}
/* ----------------------- RX Message Count Register ------------------------ */
/**
* @brief Get RX Message Counter
*
* @param hw Start address of the CAN registers
* @return RX Message Counter
*/
static inline uint32_t can_ll_get_rx_msg_count(can_dev_t *hw)
{
return hw->rx_message_counter_reg.val;
return twai_ll_get_rx_msg_count(hw);
}
/* ------------------------- Clock Divider Register ------------------------- */
/**
* @brief Set CLKOUT Divider and enable/disable
*
* @param hw Start address of the CAN registers
* @param divider Divider for CLKOUT. Set to 0 to disable CLKOUT
*/
static inline void can_ll_set_clkout(can_dev_t *hw, uint32_t divider)
{
/* Configure CLKOUT. CLKOUT is a pre-scaled version of APB CLK. Divider can be
1, or any even number from 2 to 14. Set to out of range value (0) to disable
CLKOUT. */
if (divider >= 2 && divider <= 14) {
CAN.clock_divider_reg.co = 0;
CAN.clock_divider_reg.cd = (divider / 2) - 1;
} else if (divider == 1) {
CAN.clock_divider_reg.co = 0;
CAN.clock_divider_reg.cd = 7;
} else {
CAN.clock_divider_reg.co = 1;
CAN.clock_divider_reg.cd = 0;
}
twai_ll_set_clkout(hw, divider);
}
/**
* @brief Set register address mapping to extended mode
*
* Extended mode register address mapping consists of more registers and extra
* features.
*
* @param hw Start address of the CAN registers
*
* @note Must be called before setting any configuration
* @note Must be called in reset mode
*/
static inline void can_ll_enable_extended_reg_layout(can_dev_t *hw)
{
hw->clock_divider_reg.cm = 1;
twai_ll_enable_extended_reg_layout(hw);
}
#ifdef __cplusplus

View File

@ -0,0 +1,68 @@
// 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.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#warning hal/can_types.h is deprecated, please use hal/twai_types.h instead
#include "hal/twai_types.h"
/* ---------------------------- Compatibility ------------------------------- */
#define CAN_EXTD_ID_MASK TWAI_EXTD_ID_MASK
#define CAN_STD_ID_MASK TWAI_STD_ID_MASK
#define CAN_FRAME_MAX_DLC TWAI_FRAME_MAX_DLC
#define CAN_FRAME_EXTD_ID_LEN_BYTES TWAI_FRAME_EXTD_ID_LEN_BYTES
#define CAN_FRAME_STD_ID_LEN_BYTES TWAI_FRAME_STD_ID_LEN_BYTES
#define CAN_ERR_PASS_THRESH TWAI_ERR_PASS_THRESH
#define CAN_MSG_FLAG_NONE TWAI_MSG_FLAG_NONE
#define CAN_MSG_FLAG_EXTD TWAI_MSG_FLAG_EXTD
#define CAN_MSG_FLAG_RTR TWAI_MSG_FLAG_RTR
#define CAN_MSG_FLAG_SS TWAI_MSG_FLAG_SS
#define CAN_MSG_FLAG_SELF TWAI_MSG_FLAG_SELF
#define CAN_MSG_FLAG_DLC_NON_COMP TWAI_MSG_FLAG_DLC_NON_COMP
#if (TWAI_BRP_MAX > 128) || (CONFIG_ESP32_REV_MIN >= 2)
#define CAN_TIMING_CONFIG_12_5KBITS() TWAI_TIMING_CONFIG_12_5KBITS()
#define CAN_TIMING_CONFIG_16KBITS() TWAI_TIMING_CONFIG_16KBITS()
#define CAN_TIMING_CONFIG_20KBITS() TWAI_TIMING_CONFIG_20KBITS()
#endif
#define CAN_TIMING_CONFIG_25KBITS() TWAI_TIMING_CONFIG_25KBITS()
#define CAN_TIMING_CONFIG_50KBITS() TWAI_TIMING_CONFIG_50KBITS()
#define CAN_TIMING_CONFIG_100KBITS() TWAI_TIMING_CONFIG_100KBITS()
#define CAN_TIMING_CONFIG_125KBITS() TWAI_TIMING_CONFIG_125KBITS()
#define CAN_TIMING_CONFIG_250KBITS() TWAI_TIMING_CONFIG_250KBITS()
#define CAN_TIMING_CONFIG_500KBITS() TWAI_TIMING_CONFIG_500KBITS()
#define CAN_TIMING_CONFIG_800KBITS() TWAI_TIMING_CONFIG_800KBITS()
#define CAN_TIMING_CONFIG_1MBITS() TWAI_TIMING_CONFIG_1MBITS()
#define CAN_FILTER_CONFIG_ACCEPT_ALL() TWAI_FILTER_CONFIG_ACCEPT_ALL()
typedef twai_mode_t can_mode_t;
#define CAN_MODE_NORMAL TWAI_MODE_NORMAL
#define CAN_MODE_NO_ACK TWAI_MODE_NO_ACK
#define CAN_MODE_LISTEN_ONLY TWAI_MODE_LISTEN_ONLY
typedef twai_message_t can_message_t;
typedef twai_timing_config_t can_timing_config_t;
typedef twai_filter_config_t can_filter_config_t;
#ifdef __cplusplus
}
#endif

View File

@ -75,8 +75,8 @@ static inline uint32_t periph_ll_get_clk_en_mask(periph_module_t periph)
return DPORT_WIFI_CLK_SDIO_HOST_EN;
case PERIPH_SDIO_SLAVE_MODULE:
return DPORT_WIFI_CLK_SDIOSLAVE_EN;
case PERIPH_CAN_MODULE:
return DPORT_CAN_CLK_EN;
case PERIPH_TWAI_MODULE:
return DPORT_TWAI_CLK_EN;
case PERIPH_EMAC_MODULE:
return DPORT_WIFI_CLK_EMAC_EN;
case PERIPH_RNG_MODULE:
@ -153,8 +153,8 @@ static inline uint32_t periph_ll_get_rst_en_mask(periph_module_t periph, bool en
return DPORT_SDIO_HOST_RST;
case PERIPH_SDIO_SLAVE_MODULE:
return DPORT_SDIO_RST;
case PERIPH_CAN_MODULE:
return DPORT_CAN_RST;
case PERIPH_TWAI_MODULE:
return DPORT_TWAI_RST;
case PERIPH_EMAC_MODULE:
return DPORT_EMAC_RST;
case PERIPH_AES_MODULE:
@ -242,12 +242,30 @@ static inline void periph_ll_disable_clk_set_rst(periph_module_t periph)
DPORT_SET_PERI_REG_MASK(periph_ll_get_rst_en_reg(periph), periph_ll_get_rst_en_mask(periph, false));
}
static inline void IRAM_ATTR periph_ll_wifi_bt_module_enable_clk_clear_rst(void)
{
DPORT_SET_PERI_REG_MASK(DPORT_WIFI_CLK_EN_REG, DPORT_WIFI_CLK_WIFI_BT_COMMON_M);
DPORT_CLEAR_PERI_REG_MASK(DPORT_CORE_RST_EN_REG, 0);
}
static inline void IRAM_ATTR periph_ll_wifi_bt_module_disable_clk_set_rst(void)
{
DPORT_CLEAR_PERI_REG_MASK(DPORT_WIFI_CLK_EN_REG, DPORT_WIFI_CLK_WIFI_BT_COMMON_M);
DPORT_SET_PERI_REG_MASK(DPORT_CORE_RST_EN_REG, 0);
}
static inline void periph_ll_reset(periph_module_t periph)
{
DPORT_SET_PERI_REG_MASK(periph_ll_get_rst_en_reg(periph), periph_ll_get_rst_en_mask(periph, false));
DPORT_CLEAR_PERI_REG_MASK(periph_ll_get_rst_en_reg(periph), periph_ll_get_rst_en_mask(periph, false));
}
static inline bool IRAM_ATTR periph_ll_periph_enabled(periph_module_t periph)
{
return DPORT_REG_GET_BIT(periph_ll_get_rst_en_reg(periph), periph_ll_get_rst_en_mask(periph, false)) == 0 &&
DPORT_REG_GET_BIT(periph_ll_get_clk_en_reg(periph), periph_ll_get_clk_en_mask(periph)) != 0;
}
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,55 @@
// Copyright 2020 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
#include "soc/soc.h"
#include "soc/rtc.h"
#ifdef __cplusplus
extern "C" {
#endif
static inline void rtc_cntl_ll_set_wakeup_timer(uint64_t t)
{
WRITE_PERI_REG(RTC_CNTL_SLP_TIMER0_REG, t & UINT32_MAX);
WRITE_PERI_REG(RTC_CNTL_SLP_TIMER1_REG, t >> 32);
}
static inline void rtc_cntl_ll_ext1_clear_wakeup_pins(void)
{
REG_SET_BIT(RTC_CNTL_EXT_WAKEUP1_REG, RTC_CNTL_EXT_WAKEUP1_STATUS_CLR);
}
static inline uint32_t rtc_cntl_ll_ext1_get_wakeup_pins(void)
{
return REG_GET_FIELD(RTC_CNTL_EXT_WAKEUP1_STATUS_REG, RTC_CNTL_EXT_WAKEUP1_STATUS);
}
static inline void rtc_cntl_ll_ext1_set_wakeup_pins(uint32_t mask, int mode)
{
REG_SET_FIELD(RTC_CNTL_EXT_WAKEUP1_REG, RTC_CNTL_EXT_WAKEUP1_SEL, mask);
SET_PERI_REG_BITS(RTC_CNTL_EXT_WAKEUP_CONF_REG, 0x1,
mode, RTC_CNTL_EXT_WAKEUP1_LV_S);
}
static inline void rtc_cntl_ll_ulp_wakeup_enable(void)
{
SET_PERI_REG_MASK(RTC_CNTL_STATE0_REG, RTC_CNTL_ULP_CP_WAKEUP_FORCE_EN);
}
#ifdef __cplusplus
}
#endif

View File

@ -353,6 +353,14 @@ static inline void rtcio_ll_disable_sleep_setting(gpio_num_t gpio_num)
CLEAR_PERI_REG_MASK(rtc_io_desc[gpio_num].reg, rtc_io_desc[gpio_num].slpsel);
}
static inline void rtcio_ll_ext0_set_wakeup_pin(int rtcio_num, int level)
{
REG_SET_FIELD(RTC_IO_EXT_WAKEUP0_REG, RTC_IO_EXT_WAKEUP0_SEL, rtcio_num);
// Set level which will trigger wakeup
SET_PERI_REG_BITS(RTC_CNTL_EXT_WAKEUP_CONF_REG, 0x1,
level , RTC_CNTL_EXT_WAKEUP0_LV_S);
}
#ifdef __cplusplus
}
#endif

View File

@ -16,6 +16,7 @@
#include "soc/soc.h"
#include "soc/rtc_cntl_reg.h"
#include "soc/soc_caps.h"
#include "soc/rtc.h"
#ifdef __cplusplus
extern "C" {

View File

@ -238,9 +238,9 @@ static inline bool spi_flash_ll_host_idle(const spi_dev_t *dev)
*/
static inline void spi_flash_ll_set_cs_pin(spi_dev_t *dev, int pin)
{
dev->pin.cs0_dis = (pin == 0) ? 0 : 1;
dev->pin.cs1_dis = (pin == 1) ? 0 : 1;
dev->pin.cs2_dis = (pin == 2) ? 0 : 1;
dev->pin.cs0_dis = (pin != 0);
dev->pin.cs1_dis = (pin != 1);
dev->pin.cs2_dis = (pin != 2);
}
/**

View File

@ -0,0 +1,706 @@
// 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.
/*******************************************************************************
* NOTICE
* The ll is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
// The Lowlevel layer for TWAI
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include "sdkconfig.h"
#include "hal/twai_types.h"
#include "soc/twai_periph.h"
/* ------------------------- Defines and Typedefs --------------------------- */
#define TWAI_LL_STATUS_RBS (0x1 << 0)
#define TWAI_LL_STATUS_DOS (0x1 << 1)
#define TWAI_LL_STATUS_TBS (0x1 << 2)
#define TWAI_LL_STATUS_TCS (0x1 << 3)
#define TWAI_LL_STATUS_RS (0x1 << 4)
#define TWAI_LL_STATUS_TS (0x1 << 5)
#define TWAI_LL_STATUS_ES (0x1 << 6)
#define TWAI_LL_STATUS_BS (0x1 << 7)
#define TWAI_LL_INTR_RI (0x1 << 0)
#define TWAI_LL_INTR_TI (0x1 << 1)
#define TWAI_LL_INTR_EI (0x1 << 2)
//Data overrun interrupt not supported in SW due to HW peculiarities
#define TWAI_LL_INTR_EPI (0x1 << 5)
#define TWAI_LL_INTR_ALI (0x1 << 6)
#define TWAI_LL_INTR_BEI (0x1 << 7)
/*
* 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");
/* ---------------------------- 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
* @return true if reset mode was entered successfully
*
* @note Reset mode is automatically entered on BUS OFF condition
*/
static inline bool twai_ll_enter_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 1;
return hw->mode_reg.rm;
}
/**
* @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
* @return true if reset mode was exit successfully
*
* @note Reset mode must be exit to initiate BUS OFF recovery
*/
static inline bool twai_ll_exit_reset_mode(twai_dev_t *hw)
{
hw->mode_reg.rm = 0;
return !(hw->mode_reg.rm);
}
/**
* @brief Check if in reset mode
* @param hw Start address of the TWAI registers
* @return true if in reset mode
*/
static inline bool twai_ll_is_in_reset_mode(twai_dev_t *hw)
{
return hw->mode_reg.rm;
}
/**
* @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
*/
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_reg.lom = 0;
hw->mode_reg.stm = 0;
} else if (mode == TWAI_MODE_NO_ACK) { //Self Test Mode (No Ack)
hw->mode_reg.lom = 0;
hw->mode_reg.stm = 1;
} else if (mode == TWAI_MODE_LISTEN_ONLY) { //Listen Only Mode
hw->mode_reg.lom = 1;
hw->mode_reg.stm = 0;
}
}
/* --------------------------- 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.
*/
static inline void twai_ll_set_cmd_tx(twai_dev_t *hw)
{
hw->command_reg.tr = 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.
*/
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
}
/**
* @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.
*/
static inline void twai_ll_set_cmd_abort_tx(twai_dev_t *hw)
{
hw->command_reg.at = 1;
}
/**
* @brief Release RX buffer
*
* Rotates RX buffer to the next frame in the RX FIFO.
*
* @param hw Start address of the TWAI registers
*/
static inline void twai_ll_set_cmd_release_rx_buffer(twai_dev_t *hw)
{
hw->command_reg.rrb = 1;
}
/**
* @brief Clear data overrun
*
* Clears the data overrun status bit
*
* @param hw Start address of the TWAI registers
*/
static inline void twai_ll_set_cmd_clear_data_overrun(twai_dev_t *hw)
{
hw->command_reg.cdo = 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.
*/
static inline void twai_ll_set_cmd_self_rx_request(twai_dev_t *hw)
{
hw->command_reg.srr = 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.
*/
static inline void twai_ll_set_cmd_self_rx_single_shot(twai_dev_t *hw)
{
hw->command_reg.val = 0x12;
}
/* --------------------------- Status Register ------------------------------ */
/**
* @brief Get all status bits
*
* @param hw Start address of the TWAI registers
* @return Status bits
*/
static inline uint32_t twai_ll_get_status(twai_dev_t *hw)
{
return hw->status_reg.val;
}
/**
* @brief Check if RX FIFO overrun status bit is set
*
* @param hw Start address of the TWAI registers
* @return Overrun status bit
*/
static inline bool twai_ll_is_fifo_overrun(twai_dev_t *hw)
{
return hw->status_reg.dos;
}
/**
* @brief Check if previously TX was successful
*
* @param hw Start address of the TWAI registers
* @return Whether previous TX was successful
*/
static inline bool twai_ll_is_last_tx_successful(twai_dev_t *hw)
{
return hw->status_reg.tcs;
}
//Todo: Add stand alone status bit check functions when necessary
/* -------------------------- 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
*/
static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
{
return hw->interrupt_reg.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
*/
static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
{
#if (CONFIG_ESP32_REV_MIN >= 2)
//ESP32 Rev 2 or later has brp div field. Need to mask it out
hw->interrupt_enable_reg.val = (hw->interrupt_enable_reg.val & 0x10) | intr_mask;
#else
hw->interrupt_enable_reg.val = intr_mask;
#endif
}
/* ------------------------ Bus Timing Registers --------------------------- */
/**
* @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 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.
*/
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 (CONFIG_ESP32_REV_MIN >= 2)
if (brp > TWAI_BRP_DIV_THRESH) {
//Need to set brp_div bit
hw->interrupt_enable_reg.brp_div = 1;
brp /= 2;
} else {
hw->interrupt_enable_reg.brp_div = 0;
}
#endif
hw->bus_timing_0_reg.brp = (brp / 2) - 1;
hw->bus_timing_0_reg.sjw = sjw - 1;
hw->bus_timing_1_reg.tseg1 = tseg1 - 1;
hw->bus_timing_1_reg.tseg2 = tseg2 - 1;
hw->bus_timing_1_reg.sam = 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
*/
static inline void twai_ll_clear_arb_lost_cap(twai_dev_t *hw)
{
(void)hw->arbitration_lost_captue_reg.val;
//Todo: Decode ALC register
}
/* ----------------------------- 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
*/
static inline void twai_ll_clear_err_code_cap(twai_dev_t *hw)
{
(void)hw->error_code_capture_reg.val;
//Todo: Decode error code capture
}
/* ----------------------------- 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
*/
static inline void twai_ll_set_err_warn_lim(twai_dev_t *hw, uint32_t ewl)
{
hw->error_warning_limit_reg.ewl = ewl;
}
/**
* @brief Get Error Warning Limit
*
* @param hw Start address of the TWAI registers
* @return Error Warning Limit
*/
static inline uint32_t twai_ll_get_err_warn_lim(twai_dev_t *hw)
{
return hw->error_warning_limit_reg.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.
*/
static inline uint32_t twai_ll_get_rec(twai_dev_t *hw)
{
return hw->rx_error_counter_reg.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
*/
static inline void twai_ll_set_rec(twai_dev_t *hw, uint32_t rec)
{
hw->rx_error_counter_reg.rxerr = 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
*/
static inline uint32_t twai_ll_get_tec(twai_dev_t *hw)
{
return hw->tx_error_counter_reg.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
*/
static inline void twai_ll_set_tec(twai_dev_t *hw, uint32_t tec)
{
hw->tx_error_counter_reg.txerr = 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
*/
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);
uint32_t mask_swapped = __builtin_bswap32(mask);
for (int i = 0; i < 4; i++) {
hw->acceptance_filter.acr[i].byte = ((code_swapped >> (i * 8)) & 0xFF);
hw->acceptance_filter.amr[i].byte = ((mask_swapped >> (i * 8)) & 0xFF);
}
hw->mode_reg.afm = 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
*/
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_prase_frame_buffer() to parse the formatted frame
*/
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] = 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
*/
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 = __builtin_bswap32((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 = __builtin_bswap16((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 RTR)
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
*/
static inline void twai_ll_prase_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 = __builtin_bswap32(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 = __builtin_bswap16(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
*/
static inline uint32_t twai_ll_get_rx_msg_count(twai_dev_t *hw)
{
return hw->rx_message_counter_reg.val;
}
/* ------------------------- Clock Divider Register ------------------------- */
/**
* @brief Set CLKOUT Divider and enable/disable
*
* Configure CLKOUT. CLKOUT is a pre-scaled version of APB CLK. Divider can be
* 1, or any even number from 2 to 14. Set the divider to 0 to disable CLKOUT.
*
* @param hw Start address of the TWAI registers
* @param divider Divider for CLKOUT. Set to 0 to disable CLKOUT
*/
static inline void twai_ll_set_clkout(twai_dev_t *hw, uint32_t divider)
{
if (divider >= 2 && divider <= 14) {
hw->clock_divider_reg.co = 0;
hw->clock_divider_reg.cd = (divider / 2) - 1;
} else if (divider == 1) {
//Setting the divider reg to max value (7) means a divider of 1
hw->clock_divider_reg.co = 0;
hw->clock_divider_reg.cd = 7;
} else {
hw->clock_divider_reg.co = 1;
hw->clock_divider_reg.cd = 0;
}
}
/**
* @brief Set register address mapping to extended mode
*
* Extended mode register address mapping consists of more registers and extra
* features.
*
* @param hw Start address of the TWAI registers
*
* @note Must be called before setting any configuration
* @note Must be called in reset mode
*/
static inline void twai_ll_enable_extended_reg_layout(twai_dev_t *hw)
{
hw->clock_divider_reg.cm = 1;
}
#ifdef __cplusplus
}
#endif

View File

@ -1,40 +0,0 @@
// Copyright 2016-2017 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
/**
* @file soc_log.h
* @brief SOC library logging functions
*
* To make SOC library compatible with environments which don't use ESP-IDF,
* this header file provides wrappers for logging functions.
*/
#ifdef ESP_PLATFORM
#include "esp_log.h"
#define SOC_LOGE(tag, fmt, ...) ESP_EARLY_LOGE(tag, fmt, ##__VA_ARGS__)
#define SOC_LOGW(tag, fmt, ...) ESP_EARLY_LOGW(tag, fmt, ##__VA_ARGS__)
#define SOC_LOGI(tag, fmt, ...) ESP_EARLY_LOGI(tag, fmt, ##__VA_ARGS__)
#define SOC_LOGD(tag, fmt, ...) ESP_EARLY_LOGD(tag, fmt, ##__VA_ARGS__)
#define SOC_LOGV(tag, fmt, ...) ESP_EARLY_LOGV(tag, fmt, ##__VA_ARGS__)
#else
#include "esp32/rom/ets_sys.h"
#define SOC_LOGE(tag, fmt, ...) ets_printf("%s(err): " fmt, tag, ##__VA_ARGS__)
#define SOC_LOGW(tag, fmt, ...) ets_printf("%s(warn): " fmt, tag, ##__VA_ARGS__)
#define SOC_LOGI(tag, fmt, ...) ets_printf("%s(info): " fmt, tag, ##__VA_ARGS__)
#define SOC_LOGD(tag, fmt, ...) ets_printf("%s(dbg): " fmt, tag, ##__VA_ARGS__)
#define SOC_LOGV(tag, fmt, ...) ets_printf("%s: " fmt, tag, ##__VA_ARGS__)
#endif //ESP_PLATFORM