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

@ -0,0 +1,25 @@
// 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
#ifdef __cplusplus
extern "C" {
#endif
#define SOC_CP_DMA_MAX_BUFFER_SIZE (4095) /*!< Maximum size of the buffer that can be attached to descriptor */
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,698 @@
/** 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 <stdint.h>
#include "soc/soc.h"
#ifdef __cplusplus
extern "C" {
#endif
/** CP_DMA_INT_RAW_REG register
* Raw interrupt status
*/
#define CP_DMA_INT_RAW_REG (DR_REG_CP_BASE + 0x0)
/** CP_DMA_IN_DONE_INT_RAW : RO; bitpos: [0]; default: 0;
* This is the interrupt raw bit. Triggered when the last data of frame is received or
* the receive buffer is full indicated by inlink descriptor.
*/
#define CP_DMA_IN_DONE_INT_RAW (BIT(0))
#define CP_DMA_IN_DONE_INT_RAW_M (CP_DMA_IN_DONE_INT_RAW_V << CP_DMA_IN_DONE_INT_RAW_S)
#define CP_DMA_IN_DONE_INT_RAW_V 0x00000001
#define CP_DMA_IN_DONE_INT_RAW_S 0
/** CP_DMA_IN_SUC_EOF_INT_RAW : RO; bitpos: [1]; default: 0;
* This is the interrupt raw bit. Triggered when the last data of one frame is
* received.
*/
#define CP_DMA_IN_SUC_EOF_INT_RAW (BIT(1))
#define CP_DMA_IN_SUC_EOF_INT_RAW_M (CP_DMA_IN_SUC_EOF_INT_RAW_V << CP_DMA_IN_SUC_EOF_INT_RAW_S)
#define CP_DMA_IN_SUC_EOF_INT_RAW_V 0x00000001
#define CP_DMA_IN_SUC_EOF_INT_RAW_S 1
/** CP_DMA_OUT_DONE_INT_RAW : RO; bitpos: [2]; default: 0;
* This is the interrupt raw bit. Triggered when all data indicated by one outlink
* descriptor has been pushed into Tx FIFO.
*/
#define CP_DMA_OUT_DONE_INT_RAW (BIT(2))
#define CP_DMA_OUT_DONE_INT_RAW_M (CP_DMA_OUT_DONE_INT_RAW_V << CP_DMA_OUT_DONE_INT_RAW_S)
#define CP_DMA_OUT_DONE_INT_RAW_V 0x00000001
#define CP_DMA_OUT_DONE_INT_RAW_S 2
/** CP_DMA_OUT_EOF_INT_RAW : RO; bitpos: [3]; default: 0;
* This is the interrupt raw bit. Triggered when the last data with EOF flag has been
* pushed into Tx FIFO.
*/
#define CP_DMA_OUT_EOF_INT_RAW (BIT(3))
#define CP_DMA_OUT_EOF_INT_RAW_M (CP_DMA_OUT_EOF_INT_RAW_V << CP_DMA_OUT_EOF_INT_RAW_S)
#define CP_DMA_OUT_EOF_INT_RAW_V 0x00000001
#define CP_DMA_OUT_EOF_INT_RAW_S 3
/** CP_DMA_IN_DSCR_ERR_INT_RAW : RO; bitpos: [4]; default: 0;
* This is the interrupt raw bit. Triggered when detecting inlink descriptor error,
* including owner error, the second and third word error of inlink descriptor.
*/
#define CP_DMA_IN_DSCR_ERR_INT_RAW (BIT(4))
#define CP_DMA_IN_DSCR_ERR_INT_RAW_M (CP_DMA_IN_DSCR_ERR_INT_RAW_V << CP_DMA_IN_DSCR_ERR_INT_RAW_S)
#define CP_DMA_IN_DSCR_ERR_INT_RAW_V 0x00000001
#define CP_DMA_IN_DSCR_ERR_INT_RAW_S 4
/** CP_DMA_OUT_DSCR_ERR_INT_RAW : RO; bitpos: [5]; default: 0;
* This is the interrupt raw bit. Triggered when detecting outlink descriptor error,
* including owner error, the second and third word error of outlink descriptor.
*/
#define CP_DMA_OUT_DSCR_ERR_INT_RAW (BIT(5))
#define CP_DMA_OUT_DSCR_ERR_INT_RAW_M (CP_DMA_OUT_DSCR_ERR_INT_RAW_V << CP_DMA_OUT_DSCR_ERR_INT_RAW_S)
#define CP_DMA_OUT_DSCR_ERR_INT_RAW_V 0x00000001
#define CP_DMA_OUT_DSCR_ERR_INT_RAW_S 5
/** CP_DMA_IN_DSCR_EMPTY_INT_RAW : RO; bitpos: [6]; default: 0;
* This is the interrupt raw bit. Triggered when receiving data is completed and no
* more inlink descriptor.
*/
#define CP_DMA_IN_DSCR_EMPTY_INT_RAW (BIT(6))
#define CP_DMA_IN_DSCR_EMPTY_INT_RAW_M (CP_DMA_IN_DSCR_EMPTY_INT_RAW_V << CP_DMA_IN_DSCR_EMPTY_INT_RAW_S)
#define CP_DMA_IN_DSCR_EMPTY_INT_RAW_V 0x00000001
#define CP_DMA_IN_DSCR_EMPTY_INT_RAW_S 6
/** CP_DMA_OUT_TOTAL_EOF_INT_RAW : RO; bitpos: [7]; default: 0;
* This is the interrupt raw bit. Triggered when data corresponding to all outlink
* descriptor and the last descriptor with valid EOF is transmitted out.
*/
#define CP_DMA_OUT_TOTAL_EOF_INT_RAW (BIT(7))
#define CP_DMA_OUT_TOTAL_EOF_INT_RAW_M (CP_DMA_OUT_TOTAL_EOF_INT_RAW_V << CP_DMA_OUT_TOTAL_EOF_INT_RAW_S)
#define CP_DMA_OUT_TOTAL_EOF_INT_RAW_V 0x00000001
#define CP_DMA_OUT_TOTAL_EOF_INT_RAW_S 7
/** CP_DMA_CRC_DONE_INT_RAW : RO; bitpos: [8]; default: 0;
* This is the interrupt raw bit. Triggered when crc calculation is done.
*/
#define CP_DMA_CRC_DONE_INT_RAW (BIT(8))
#define CP_DMA_CRC_DONE_INT_RAW_M (CP_DMA_CRC_DONE_INT_RAW_V << CP_DMA_CRC_DONE_INT_RAW_S)
#define CP_DMA_CRC_DONE_INT_RAW_V 0x00000001
#define CP_DMA_CRC_DONE_INT_RAW_S 8
/** CP_DMA_INT_ST_REG register
* Masked interrupt status
*/
#define CP_DMA_INT_ST_REG (DR_REG_CP_BASE + 0x4)
/** CP_DMA_IN_DONE_INT_ST : RO; bitpos: [0]; default: 0;
* This is the masked interrupt bit for cp_in_done_int interrupt when
* cp_in_done_int_ena is set to 1.
*/
#define CP_DMA_IN_DONE_INT_ST (BIT(0))
#define CP_DMA_IN_DONE_INT_ST_M (CP_DMA_IN_DONE_INT_ST_V << CP_DMA_IN_DONE_INT_ST_S)
#define CP_DMA_IN_DONE_INT_ST_V 0x00000001
#define CP_DMA_IN_DONE_INT_ST_S 0
/** CP_DMA_IN_SUC_EOF_INT_ST : RO; bitpos: [1]; default: 0;
* This is the masked interrupt bit for cp_in_suc_eof_int interrupt when
* cp_in_suc_eof_int_ena is set to 1.
*/
#define CP_DMA_IN_SUC_EOF_INT_ST (BIT(1))
#define CP_DMA_IN_SUC_EOF_INT_ST_M (CP_DMA_IN_SUC_EOF_INT_ST_V << CP_DMA_IN_SUC_EOF_INT_ST_S)
#define CP_DMA_IN_SUC_EOF_INT_ST_V 0x00000001
#define CP_DMA_IN_SUC_EOF_INT_ST_S 1
/** CP_DMA_OUT_DONE_INT_ST : RO; bitpos: [2]; default: 0;
* This is the masked interrupt bit for cp_out_done_int interrupt when
* cp_out_done_int_ena is set to 1.
*/
#define CP_DMA_OUT_DONE_INT_ST (BIT(2))
#define CP_DMA_OUT_DONE_INT_ST_M (CP_DMA_OUT_DONE_INT_ST_V << CP_DMA_OUT_DONE_INT_ST_S)
#define CP_DMA_OUT_DONE_INT_ST_V 0x00000001
#define CP_DMA_OUT_DONE_INT_ST_S 2
/** CP_DMA_OUT_EOF_INT_ST : RO; bitpos: [3]; default: 0;
* This is the masked interrupt bit for cp_out_eof_int interrupt when
* cp_out_eof_int_ena is set to 1.
*/
#define CP_DMA_OUT_EOF_INT_ST (BIT(3))
#define CP_DMA_OUT_EOF_INT_ST_M (CP_DMA_OUT_EOF_INT_ST_V << CP_DMA_OUT_EOF_INT_ST_S)
#define CP_DMA_OUT_EOF_INT_ST_V 0x00000001
#define CP_DMA_OUT_EOF_INT_ST_S 3
/** CP_DMA_IN_DSCR_ERR_INT_ST : RO; bitpos: [4]; default: 0;
* This is the masked interrupt bit for cp_in_dscr_err_int interrupt when
* cp_in_dscr_err_int_ena is set to 1.
*/
#define CP_DMA_IN_DSCR_ERR_INT_ST (BIT(4))
#define CP_DMA_IN_DSCR_ERR_INT_ST_M (CP_DMA_IN_DSCR_ERR_INT_ST_V << CP_DMA_IN_DSCR_ERR_INT_ST_S)
#define CP_DMA_IN_DSCR_ERR_INT_ST_V 0x00000001
#define CP_DMA_IN_DSCR_ERR_INT_ST_S 4
/** CP_DMA_OUT_DSCR_ERR_INT_ST : RO; bitpos: [5]; default: 0;
* This is the masked interrupt bit for cp_out_dscr_err_int interrupt when
* cp_out_dscr_err_int_ena is set to 1.
*/
#define CP_DMA_OUT_DSCR_ERR_INT_ST (BIT(5))
#define CP_DMA_OUT_DSCR_ERR_INT_ST_M (CP_DMA_OUT_DSCR_ERR_INT_ST_V << CP_DMA_OUT_DSCR_ERR_INT_ST_S)
#define CP_DMA_OUT_DSCR_ERR_INT_ST_V 0x00000001
#define CP_DMA_OUT_DSCR_ERR_INT_ST_S 5
/** CP_DMA_IN_DSCR_EMPTY_INT_ST : RO; bitpos: [6]; default: 0;
* This is the masked interrupt bit for cp_in_dscr_empty_int interrupt when
* cp_in_dscr_empty_int_ena is set to 1.
*/
#define CP_DMA_IN_DSCR_EMPTY_INT_ST (BIT(6))
#define CP_DMA_IN_DSCR_EMPTY_INT_ST_M (CP_DMA_IN_DSCR_EMPTY_INT_ST_V << CP_DMA_IN_DSCR_EMPTY_INT_ST_S)
#define CP_DMA_IN_DSCR_EMPTY_INT_ST_V 0x00000001
#define CP_DMA_IN_DSCR_EMPTY_INT_ST_S 6
/** CP_DMA_OUT_TOTAL_EOF_INT_ST : RO; bitpos: [7]; default: 0;
* This is the masked interrupt bit for cp_out_total_eof_int interrupt when
* cp_out_total_eof_int_ena is set to 1.
*/
#define CP_DMA_OUT_TOTAL_EOF_INT_ST (BIT(7))
#define CP_DMA_OUT_TOTAL_EOF_INT_ST_M (CP_DMA_OUT_TOTAL_EOF_INT_ST_V << CP_DMA_OUT_TOTAL_EOF_INT_ST_S)
#define CP_DMA_OUT_TOTAL_EOF_INT_ST_V 0x00000001
#define CP_DMA_OUT_TOTAL_EOF_INT_ST_S 7
/** CP_DMA_CRC_DONE_INT_ST : RO; bitpos: [8]; default: 0;
* This is the masked interrupt bit for cp_crc_done_int interrupt when
* cp_crc_done_int_ena is set to 1.
*/
#define CP_DMA_CRC_DONE_INT_ST (BIT(8))
#define CP_DMA_CRC_DONE_INT_ST_M (CP_DMA_CRC_DONE_INT_ST_V << CP_DMA_CRC_DONE_INT_ST_S)
#define CP_DMA_CRC_DONE_INT_ST_V 0x00000001
#define CP_DMA_CRC_DONE_INT_ST_S 8
/** CP_DMA_INT_ENA_REG register
* Interrupt enable bits
*/
#define CP_DMA_INT_ENA_REG (DR_REG_CP_BASE + 0x8)
/** CP_DMA_IN_DONE_INT_ENA : R/W; bitpos: [0]; default: 0;
* This is the interrupt enable bit for cp_in_done_int interrupt.
*/
#define CP_DMA_IN_DONE_INT_ENA (BIT(0))
#define CP_DMA_IN_DONE_INT_ENA_M (CP_DMA_IN_DONE_INT_ENA_V << CP_DMA_IN_DONE_INT_ENA_S)
#define CP_DMA_IN_DONE_INT_ENA_V 0x00000001
#define CP_DMA_IN_DONE_INT_ENA_S 0
/** CP_DMA_IN_SUC_EOF_INT_ENA : R/W; bitpos: [1]; default: 0;
* This is the interrupt enable bit for cp_in_suc_eof_int interrupt.
*/
#define CP_DMA_IN_SUC_EOF_INT_ENA (BIT(1))
#define CP_DMA_IN_SUC_EOF_INT_ENA_M (CP_DMA_IN_SUC_EOF_INT_ENA_V << CP_DMA_IN_SUC_EOF_INT_ENA_S)
#define CP_DMA_IN_SUC_EOF_INT_ENA_V 0x00000001
#define CP_DMA_IN_SUC_EOF_INT_ENA_S 1
/** CP_DMA_OUT_DONE_INT_ENA : R/W; bitpos: [2]; default: 0;
* This is the interrupt enable bit for cp_out_done_int interrupt.
*/
#define CP_DMA_OUT_DONE_INT_ENA (BIT(2))
#define CP_DMA_OUT_DONE_INT_ENA_M (CP_DMA_OUT_DONE_INT_ENA_V << CP_DMA_OUT_DONE_INT_ENA_S)
#define CP_DMA_OUT_DONE_INT_ENA_V 0x00000001
#define CP_DMA_OUT_DONE_INT_ENA_S 2
/** CP_DMA_OUT_EOF_INT_ENA : R/W; bitpos: [3]; default: 0;
* This is the interrupt enable bit for cp_out_eof_int interrupt.
*/
#define CP_DMA_OUT_EOF_INT_ENA (BIT(3))
#define CP_DMA_OUT_EOF_INT_ENA_M (CP_DMA_OUT_EOF_INT_ENA_V << CP_DMA_OUT_EOF_INT_ENA_S)
#define CP_DMA_OUT_EOF_INT_ENA_V 0x00000001
#define CP_DMA_OUT_EOF_INT_ENA_S 3
/** CP_DMA_IN_DSCR_ERR_INT_ENA : R/W; bitpos: [4]; default: 0;
* This is the interrupt enable bit for cp_in_dscr_err_int interrupt.
*/
#define CP_DMA_IN_DSCR_ERR_INT_ENA (BIT(4))
#define CP_DMA_IN_DSCR_ERR_INT_ENA_M (CP_DMA_IN_DSCR_ERR_INT_ENA_V << CP_DMA_IN_DSCR_ERR_INT_ENA_S)
#define CP_DMA_IN_DSCR_ERR_INT_ENA_V 0x00000001
#define CP_DMA_IN_DSCR_ERR_INT_ENA_S 4
/** CP_DMA_OUT_DSCR_ERR_INT_ENA : R/W; bitpos: [5]; default: 0;
* This is the interrupt enable bit for cp_out_dscr_err_int interrupt.
*/
#define CP_DMA_OUT_DSCR_ERR_INT_ENA (BIT(5))
#define CP_DMA_OUT_DSCR_ERR_INT_ENA_M (CP_DMA_OUT_DSCR_ERR_INT_ENA_V << CP_DMA_OUT_DSCR_ERR_INT_ENA_S)
#define CP_DMA_OUT_DSCR_ERR_INT_ENA_V 0x00000001
#define CP_DMA_OUT_DSCR_ERR_INT_ENA_S 5
/** CP_DMA_IN_DSCR_EMPTY_INT_ENA : R/W; bitpos: [6]; default: 0;
* This is the interrupt enable bit for cp_in_dscr_empty_int interrupt.
*/
#define CP_DMA_IN_DSCR_EMPTY_INT_ENA (BIT(6))
#define CP_DMA_IN_DSCR_EMPTY_INT_ENA_M (CP_DMA_IN_DSCR_EMPTY_INT_ENA_V << CP_DMA_IN_DSCR_EMPTY_INT_ENA_S)
#define CP_DMA_IN_DSCR_EMPTY_INT_ENA_V 0x00000001
#define CP_DMA_IN_DSCR_EMPTY_INT_ENA_S 6
/** CP_DMA_OUT_TOTAL_EOF_INT_ENA : R/W; bitpos: [7]; default: 0;
* This is the interrupt enable bit for cp_out_total_eof_int interrupt.
*/
#define CP_DMA_OUT_TOTAL_EOF_INT_ENA (BIT(7))
#define CP_DMA_OUT_TOTAL_EOF_INT_ENA_M (CP_DMA_OUT_TOTAL_EOF_INT_ENA_V << CP_DMA_OUT_TOTAL_EOF_INT_ENA_S)
#define CP_DMA_OUT_TOTAL_EOF_INT_ENA_V 0x00000001
#define CP_DMA_OUT_TOTAL_EOF_INT_ENA_S 7
/** CP_DMA_CRC_DONE_INT_ENA : R/W; bitpos: [8]; default: 0;
* This is the interrupt enable bit for cp_crc_done_int interrupt.
*/
#define CP_DMA_CRC_DONE_INT_ENA (BIT(8))
#define CP_DMA_CRC_DONE_INT_ENA_M (CP_DMA_CRC_DONE_INT_ENA_V << CP_DMA_CRC_DONE_INT_ENA_S)
#define CP_DMA_CRC_DONE_INT_ENA_V 0x00000001
#define CP_DMA_CRC_DONE_INT_ENA_S 8
/** CP_DMA_INT_CLR_REG register
* Interrupt clear bits
*/
#define CP_DMA_INT_CLR_REG (DR_REG_CP_BASE + 0xc)
/** CP_DMA_IN_DONE_INT_CLR : WO; bitpos: [0]; default: 0;
* Set this bit to clear cp_in_done_int interrupt.
*/
#define CP_DMA_IN_DONE_INT_CLR (BIT(0))
#define CP_DMA_IN_DONE_INT_CLR_M (CP_DMA_IN_DONE_INT_CLR_V << CP_DMA_IN_DONE_INT_CLR_S)
#define CP_DMA_IN_DONE_INT_CLR_V 0x00000001
#define CP_DMA_IN_DONE_INT_CLR_S 0
/** CP_DMA_IN_SUC_EOF_INT_CLR : WO; bitpos: [1]; default: 0;
* Set this bit to clear cp_in_suc_eof_int interrupt.
*/
#define CP_DMA_IN_SUC_EOF_INT_CLR (BIT(1))
#define CP_DMA_IN_SUC_EOF_INT_CLR_M (CP_DMA_IN_SUC_EOF_INT_CLR_V << CP_DMA_IN_SUC_EOF_INT_CLR_S)
#define CP_DMA_IN_SUC_EOF_INT_CLR_V 0x00000001
#define CP_DMA_IN_SUC_EOF_INT_CLR_S 1
/** CP_DMA_OUT_DONE_INT_CLR : WO; bitpos: [2]; default: 0;
* Set this bit to clear cp_out_done_int interrupt.
*/
#define CP_DMA_OUT_DONE_INT_CLR (BIT(2))
#define CP_DMA_OUT_DONE_INT_CLR_M (CP_DMA_OUT_DONE_INT_CLR_V << CP_DMA_OUT_DONE_INT_CLR_S)
#define CP_DMA_OUT_DONE_INT_CLR_V 0x00000001
#define CP_DMA_OUT_DONE_INT_CLR_S 2
/** CP_DMA_OUT_EOF_INT_CLR : WO; bitpos: [3]; default: 0;
* Set this bit to clear cp_out_eof_int interrupt.
*/
#define CP_DMA_OUT_EOF_INT_CLR (BIT(3))
#define CP_DMA_OUT_EOF_INT_CLR_M (CP_DMA_OUT_EOF_INT_CLR_V << CP_DMA_OUT_EOF_INT_CLR_S)
#define CP_DMA_OUT_EOF_INT_CLR_V 0x00000001
#define CP_DMA_OUT_EOF_INT_CLR_S 3
/** CP_DMA_IN_DSCR_ERR_INT_CLR : WO; bitpos: [4]; default: 0;
* Set this bit to clear cp_in_dscr_err_int interrupt.
*/
#define CP_DMA_IN_DSCR_ERR_INT_CLR (BIT(4))
#define CP_DMA_IN_DSCR_ERR_INT_CLR_M (CP_DMA_IN_DSCR_ERR_INT_CLR_V << CP_DMA_IN_DSCR_ERR_INT_CLR_S)
#define CP_DMA_IN_DSCR_ERR_INT_CLR_V 0x00000001
#define CP_DMA_IN_DSCR_ERR_INT_CLR_S 4
/** CP_DMA_OUT_DSCR_ERR_INT_CLR : WO; bitpos: [5]; default: 0;
* Set this bit to clear cp_out_dscr_err_int interrupt.
*/
#define CP_DMA_OUT_DSCR_ERR_INT_CLR (BIT(5))
#define CP_DMA_OUT_DSCR_ERR_INT_CLR_M (CP_DMA_OUT_DSCR_ERR_INT_CLR_V << CP_DMA_OUT_DSCR_ERR_INT_CLR_S)
#define CP_DMA_OUT_DSCR_ERR_INT_CLR_V 0x00000001
#define CP_DMA_OUT_DSCR_ERR_INT_CLR_S 5
/** CP_DMA_IN_DSCR_EMPTY_INT_CLR : WO; bitpos: [6]; default: 0;
* Set this bit to clear cp_in_dscr_empty_int interrupt.
*/
#define CP_DMA_IN_DSCR_EMPTY_INT_CLR (BIT(6))
#define CP_DMA_IN_DSCR_EMPTY_INT_CLR_M (CP_DMA_IN_DSCR_EMPTY_INT_CLR_V << CP_DMA_IN_DSCR_EMPTY_INT_CLR_S)
#define CP_DMA_IN_DSCR_EMPTY_INT_CLR_V 0x00000001
#define CP_DMA_IN_DSCR_EMPTY_INT_CLR_S 6
/** CP_DMA_OUT_TOTAL_EOF_INT_CLR : WO; bitpos: [7]; default: 0;
* Set this bit to clear cp_out_total_eof_int interrupt.
*/
#define CP_DMA_OUT_TOTAL_EOF_INT_CLR (BIT(7))
#define CP_DMA_OUT_TOTAL_EOF_INT_CLR_M (CP_DMA_OUT_TOTAL_EOF_INT_CLR_V << CP_DMA_OUT_TOTAL_EOF_INT_CLR_S)
#define CP_DMA_OUT_TOTAL_EOF_INT_CLR_V 0x00000001
#define CP_DMA_OUT_TOTAL_EOF_INT_CLR_S 7
/** CP_DMA_CRC_DONE_INT_CLR : WO; bitpos: [8]; default: 0;
* Set this bit to clear cp_crc_done_int interrupt.
*/
#define CP_DMA_CRC_DONE_INT_CLR (BIT(8))
#define CP_DMA_CRC_DONE_INT_CLR_M (CP_DMA_CRC_DONE_INT_CLR_V << CP_DMA_CRC_DONE_INT_CLR_S)
#define CP_DMA_CRC_DONE_INT_CLR_V 0x00000001
#define CP_DMA_CRC_DONE_INT_CLR_S 8
/** CP_DMA_OUT_LINK_REG register
* Link descriptor address and control
*/
#define CP_DMA_OUT_LINK_REG (DR_REG_CP_BASE + 0x10)
/** CP_DMA_OUTLINK_ADDR : R/W; bitpos: [19:0]; default: 0;
* This register is used to specify the least significant 20 bits of the first outlink
* descriptor's address.
*/
#define CP_DMA_OUTLINK_ADDR 0x000FFFFF
#define CP_DMA_OUTLINK_ADDR_M (CP_DMA_OUTLINK_ADDR_V << CP_DMA_OUTLINK_ADDR_S)
#define CP_DMA_OUTLINK_ADDR_V 0x000FFFFF
#define CP_DMA_OUTLINK_ADDR_S 0
/** CP_DMA_OUTLINK_STOP : R/W; bitpos: [28]; default: 0;
* Set this bit to stop dealing with the outlink descriptor.
*/
#define CP_DMA_OUTLINK_STOP (BIT(28))
#define CP_DMA_OUTLINK_STOP_M (CP_DMA_OUTLINK_STOP_V << CP_DMA_OUTLINK_STOP_S)
#define CP_DMA_OUTLINK_STOP_V 0x00000001
#define CP_DMA_OUTLINK_STOP_S 28
/** CP_DMA_OUTLINK_START : R/W; bitpos: [29]; default: 0;
* Set this bit to start a new outlink descriptor.
*/
#define CP_DMA_OUTLINK_START (BIT(29))
#define CP_DMA_OUTLINK_START_M (CP_DMA_OUTLINK_START_V << CP_DMA_OUTLINK_START_S)
#define CP_DMA_OUTLINK_START_V 0x00000001
#define CP_DMA_OUTLINK_START_S 29
/** CP_DMA_OUTLINK_RESTART : R/W; bitpos: [30]; default: 0;
* Set this bit to restart the outlink descriptpr from the last address.
*/
#define CP_DMA_OUTLINK_RESTART (BIT(30))
#define CP_DMA_OUTLINK_RESTART_M (CP_DMA_OUTLINK_RESTART_V << CP_DMA_OUTLINK_RESTART_S)
#define CP_DMA_OUTLINK_RESTART_V 0x00000001
#define CP_DMA_OUTLINK_RESTART_S 30
/** CP_DMA_OUTLINK_PARK : RO; bitpos: [31]; default: 0;
* 1: the outlink descriptor's FSM is in idle state.
* 0: the outlink descriptor's FSM is working.
*/
#define CP_DMA_OUTLINK_PARK (BIT(31))
#define CP_DMA_OUTLINK_PARK_M (CP_DMA_OUTLINK_PARK_V << CP_DMA_OUTLINK_PARK_S)
#define CP_DMA_OUTLINK_PARK_V 0x00000001
#define CP_DMA_OUTLINK_PARK_S 31
/** CP_DMA_IN_LINK_REG register
* Link descriptor address and control
*/
#define CP_DMA_IN_LINK_REG (DR_REG_CP_BASE + 0x14)
/** CP_DMA_INLINK_ADDR : R/W; bitpos: [19:0]; default: 0;
* This register is used to specify the least significant 20 bits of the first inlink
* descriptor's address.
*/
#define CP_DMA_INLINK_ADDR 0x000FFFFF
#define CP_DMA_INLINK_ADDR_M (CP_DMA_INLINK_ADDR_V << CP_DMA_INLINK_ADDR_S)
#define CP_DMA_INLINK_ADDR_V 0x000FFFFF
#define CP_DMA_INLINK_ADDR_S 0
/** CP_DMA_INLINK_STOP : R/W; bitpos: [28]; default: 0;
* Set this bit to stop dealing with the inlink descriptors.
*/
#define CP_DMA_INLINK_STOP (BIT(28))
#define CP_DMA_INLINK_STOP_M (CP_DMA_INLINK_STOP_V << CP_DMA_INLINK_STOP_S)
#define CP_DMA_INLINK_STOP_V 0x00000001
#define CP_DMA_INLINK_STOP_S 28
/** CP_DMA_INLINK_START : R/W; bitpos: [29]; default: 0;
* Set this bit to start dealing with the inlink descriptors.
*/
#define CP_DMA_INLINK_START (BIT(29))
#define CP_DMA_INLINK_START_M (CP_DMA_INLINK_START_V << CP_DMA_INLINK_START_S)
#define CP_DMA_INLINK_START_V 0x00000001
#define CP_DMA_INLINK_START_S 29
/** CP_DMA_INLINK_RESTART : R/W; bitpos: [30]; default: 0;
* Set this bit to restart new inlink descriptors.
*/
#define CP_DMA_INLINK_RESTART (BIT(30))
#define CP_DMA_INLINK_RESTART_M (CP_DMA_INLINK_RESTART_V << CP_DMA_INLINK_RESTART_S)
#define CP_DMA_INLINK_RESTART_V 0x00000001
#define CP_DMA_INLINK_RESTART_S 30
/** CP_DMA_INLINK_PARK : RO; bitpos: [31]; default: 0;
* 1: the inlink descriptor's FSM is in idle state.
* 0: the inlink descriptor's FSM is working.
*/
#define CP_DMA_INLINK_PARK (BIT(31))
#define CP_DMA_INLINK_PARK_M (CP_DMA_INLINK_PARK_V << CP_DMA_INLINK_PARK_S)
#define CP_DMA_INLINK_PARK_V 0x00000001
#define CP_DMA_INLINK_PARK_S 31
/** CP_DMA_OUT_EOF_DES_ADDR_REG register
* Outlink descriptor address when EOF occurs
*/
#define CP_DMA_OUT_EOF_DES_ADDR_REG (DR_REG_CP_BASE + 0x18)
/** CP_DMA_OUT_EOF_DES_ADDR : RO; bitpos: [31:0]; default: 0;
* This register stores the address of the outlink descriptor when the EOF bit in this
* descriptor is 1.
*/
#define CP_DMA_OUT_EOF_DES_ADDR 0xFFFFFFFF
#define CP_DMA_OUT_EOF_DES_ADDR_M (CP_DMA_OUT_EOF_DES_ADDR_V << CP_DMA_OUT_EOF_DES_ADDR_S)
#define CP_DMA_OUT_EOF_DES_ADDR_V 0xFFFFFFFF
#define CP_DMA_OUT_EOF_DES_ADDR_S 0
/** CP_DMA_IN_EOF_DES_ADDR_REG register
* Inlink descriptor address when EOF occurs
*/
#define CP_DMA_IN_EOF_DES_ADDR_REG (DR_REG_CP_BASE + 0x1c)
/** CP_DMA_IN_SUC_EOF_DES_ADDR : RO; bitpos: [31:0]; default: 0;
* This register stores the address of the inlink descriptor when received successful
* EOF.
*/
#define CP_DMA_IN_SUC_EOF_DES_ADDR 0xFFFFFFFF
#define CP_DMA_IN_SUC_EOF_DES_ADDR_M (CP_DMA_IN_SUC_EOF_DES_ADDR_V << CP_DMA_IN_SUC_EOF_DES_ADDR_S)
#define CP_DMA_IN_SUC_EOF_DES_ADDR_V 0xFFFFFFFF
#define CP_DMA_IN_SUC_EOF_DES_ADDR_S 0
/** CP_DMA_OUT_EOF_BFR_DES_ADDR_REG register
* Outlink descriptor address before the last outlink descriptor
*/
#define CP_DMA_OUT_EOF_BFR_DES_ADDR_REG (DR_REG_CP_BASE + 0x20)
/** CP_DMA_OUT_EOF_BFR_DES_ADDR : RO; bitpos: [31:0]; default: 0;
* This register stores the address of the outlink descriptor before the last outlink
* descriptor.
*/
#define CP_DMA_OUT_EOF_BFR_DES_ADDR 0xFFFFFFFF
#define CP_DMA_OUT_EOF_BFR_DES_ADDR_M (CP_DMA_OUT_EOF_BFR_DES_ADDR_V << CP_DMA_OUT_EOF_BFR_DES_ADDR_S)
#define CP_DMA_OUT_EOF_BFR_DES_ADDR_V 0xFFFFFFFF
#define CP_DMA_OUT_EOF_BFR_DES_ADDR_S 0
/** CP_DMA_INLINK_DSCR_REG register
* Address of current inlink descriptor
*/
#define CP_DMA_INLINK_DSCR_REG (DR_REG_CP_BASE + 0x24)
/** CP_DMA_INLINK_DSCR : RO; bitpos: [31:0]; default: 0;
* The address of the current inlink descriptor x.
*/
#define CP_DMA_INLINK_DSCR 0xFFFFFFFF
#define CP_DMA_INLINK_DSCR_M (CP_DMA_INLINK_DSCR_V << CP_DMA_INLINK_DSCR_S)
#define CP_DMA_INLINK_DSCR_V 0xFFFFFFFF
#define CP_DMA_INLINK_DSCR_S 0
/** CP_DMA_INLINK_DSCR_BF0_REG register
* Address of last inlink descriptor
*/
#define CP_DMA_INLINK_DSCR_BF0_REG (DR_REG_CP_BASE + 0x28)
/** CP_DMA_INLINK_DSCR_BF0 : RO; bitpos: [31:0]; default: 0;
* The address of the last inlink descriptor x-1.
*/
#define CP_DMA_INLINK_DSCR_BF0 0xFFFFFFFF
#define CP_DMA_INLINK_DSCR_BF0_M (CP_DMA_INLINK_DSCR_BF0_V << CP_DMA_INLINK_DSCR_BF0_S)
#define CP_DMA_INLINK_DSCR_BF0_V 0xFFFFFFFF
#define CP_DMA_INLINK_DSCR_BF0_S 0
/** CP_DMA_INLINK_DSCR_BF1_REG register
* Address of the second-to-last inlink descriptor
*/
#define CP_DMA_INLINK_DSCR_BF1_REG (DR_REG_CP_BASE + 0x2c)
/** CP_DMA_INLINK_DSCR_BF1 : RO; bitpos: [31:0]; default: 0;
* The address of the second-to-last inlink descriptor x-2.
*/
#define CP_DMA_INLINK_DSCR_BF1 0xFFFFFFFF
#define CP_DMA_INLINK_DSCR_BF1_M (CP_DMA_INLINK_DSCR_BF1_V << CP_DMA_INLINK_DSCR_BF1_S)
#define CP_DMA_INLINK_DSCR_BF1_V 0xFFFFFFFF
#define CP_DMA_INLINK_DSCR_BF1_S 0
/** CP_DMA_OUTLINK_DSCR_REG register
* Address of current outlink descriptor
*/
#define CP_DMA_OUTLINK_DSCR_REG (DR_REG_CP_BASE + 0x30)
/** CP_DMA_OUTLINK_DSCR : RO; bitpos: [31:0]; default: 0;
* The address of the current outlink descriptor y.
*/
#define CP_DMA_OUTLINK_DSCR 0xFFFFFFFF
#define CP_DMA_OUTLINK_DSCR_M (CP_DMA_OUTLINK_DSCR_V << CP_DMA_OUTLINK_DSCR_S)
#define CP_DMA_OUTLINK_DSCR_V 0xFFFFFFFF
#define CP_DMA_OUTLINK_DSCR_S 0
/** CP_DMA_OUTLINK_DSCR_BF0_REG register
* Address of last outlink descriptor
*/
#define CP_DMA_OUTLINK_DSCR_BF0_REG (DR_REG_CP_BASE + 0x34)
/** CP_DMA_OUTLINK_DSCR_BF0 : RO; bitpos: [31:0]; default: 0;
* The address of the last outlink descriptor y-1.
*/
#define CP_DMA_OUTLINK_DSCR_BF0 0xFFFFFFFF
#define CP_DMA_OUTLINK_DSCR_BF0_M (CP_DMA_OUTLINK_DSCR_BF0_V << CP_DMA_OUTLINK_DSCR_BF0_S)
#define CP_DMA_OUTLINK_DSCR_BF0_V 0xFFFFFFFF
#define CP_DMA_OUTLINK_DSCR_BF0_S 0
/** CP_DMA_OUTLINK_DSCR_BF1_REG register
* Address of the second-to-last outlink descriptor
*/
#define CP_DMA_OUTLINK_DSCR_BF1_REG (DR_REG_CP_BASE + 0x38)
/** CP_DMA_OUTLINK_DSCR_BF1 : RO; bitpos: [31:0]; default: 0;
* The address of the second-to-last outlink descriptor y-2.
*/
#define CP_DMA_OUTLINK_DSCR_BF1 0xFFFFFFFF
#define CP_DMA_OUTLINK_DSCR_BF1_M (CP_DMA_OUTLINK_DSCR_BF1_V << CP_DMA_OUTLINK_DSCR_BF1_S)
#define CP_DMA_OUTLINK_DSCR_BF1_V 0xFFFFFFFF
#define CP_DMA_OUTLINK_DSCR_BF1_S 0
/** CP_DMA_CONF_REG register
* Copy DMA configuration register
*/
#define CP_DMA_CONF_REG (DR_REG_CP_BASE + 0x3c)
/** CP_DMA_IN_RST : R/W; bitpos: [0]; default: 0;
* Set this bit to reset in_inf state machine.
*/
#define CP_DMA_IN_RST (BIT(0))
#define CP_DMA_IN_RST_M (CP_DMA_IN_RST_V << CP_DMA_IN_RST_S)
#define CP_DMA_IN_RST_V 0x00000001
#define CP_DMA_IN_RST_S 0
/** CP_DMA_OUT_RST : R/W; bitpos: [1]; default: 0;
* Set this bit to reset out_inf state machine.
*/
#define CP_DMA_OUT_RST (BIT(1))
#define CP_DMA_OUT_RST_M (CP_DMA_OUT_RST_V << CP_DMA_OUT_RST_S)
#define CP_DMA_OUT_RST_V 0x00000001
#define CP_DMA_OUT_RST_S 1
/** CP_DMA_CMDFIFO_RST : R/W; bitpos: [2]; default: 0;
* Set this bit to reset in_cmd fifo and out_cmd fifo.
*/
#define CP_DMA_CMDFIFO_RST (BIT(2))
#define CP_DMA_CMDFIFO_RST_M (CP_DMA_CMDFIFO_RST_V << CP_DMA_CMDFIFO_RST_S)
#define CP_DMA_CMDFIFO_RST_V 0x00000001
#define CP_DMA_CMDFIFO_RST_S 2
/** CP_DMA_FIFO_RST : R/W; bitpos: [3]; default: 0;
* Set this bit to reset data in receive FIFO.
*/
#define CP_DMA_FIFO_RST (BIT(3))
#define CP_DMA_FIFO_RST_M (CP_DMA_FIFO_RST_V << CP_DMA_FIFO_RST_S)
#define CP_DMA_FIFO_RST_V 0x00000001
#define CP_DMA_FIFO_RST_S 3
/** CP_DMA_OUT_OWNER : R/W; bitpos: [4]; default: 0;
* This is used to configure the owner bit in OUT descriptor. This is effective only
* when you set reg_out_auto_wrback.
*/
#define CP_DMA_OUT_OWNER (BIT(4))
#define CP_DMA_OUT_OWNER_M (CP_DMA_OUT_OWNER_V << CP_DMA_OUT_OWNER_S)
#define CP_DMA_OUT_OWNER_V 0x00000001
#define CP_DMA_OUT_OWNER_S 4
/** CP_DMA_IN_OWNER : R/W; bitpos: [5]; default: 0;
* This is used to configure the owner bit in IN descriptor.
*/
#define CP_DMA_IN_OWNER (BIT(5))
#define CP_DMA_IN_OWNER_M (CP_DMA_IN_OWNER_V << CP_DMA_IN_OWNER_S)
#define CP_DMA_IN_OWNER_V 0x00000001
#define CP_DMA_IN_OWNER_S 5
/** CP_DMA_OUT_AUTO_WRBACK : R/W; bitpos: [6]; default: 0;
* This bit is used to write back out descriptor when hardware has already used this
* descriptor.
*/
#define CP_DMA_OUT_AUTO_WRBACK (BIT(6))
#define CP_DMA_OUT_AUTO_WRBACK_M (CP_DMA_OUT_AUTO_WRBACK_V << CP_DMA_OUT_AUTO_WRBACK_S)
#define CP_DMA_OUT_AUTO_WRBACK_V 0x00000001
#define CP_DMA_OUT_AUTO_WRBACK_S 6
/** CP_DMA_CHECK_OWNER : R/W; bitpos: [7]; default: 0;
* Set this bit to enable owner bit check in descriptor.
*/
#define CP_DMA_CHECK_OWNER (BIT(7))
#define CP_DMA_CHECK_OWNER_M (CP_DMA_CHECK_OWNER_V << CP_DMA_CHECK_OWNER_S)
#define CP_DMA_CHECK_OWNER_V 0x00000001
#define CP_DMA_CHECK_OWNER_S 7
/** CP_DMA_CRC_CAL_RESET : R/W; bitpos: [8]; default: 0;
* Set this bit to reset crc calculation.
*/
#define CP_DMA_CRC_CAL_RESET (BIT(8))
#define CP_DMA_CRC_CAL_RESET_M (CP_DMA_CRC_CAL_RESET_V << CP_DMA_CRC_CAL_RESET_S)
#define CP_DMA_CRC_CAL_RESET_V 0x00000001
#define CP_DMA_CRC_CAL_RESET_S 8
/** CP_DMA_CRC_CAL_EN : R/W; bitpos: [9]; default: 0;
* Set this bit enable crc calculation function.
*/
#define CP_DMA_CRC_CAL_EN (BIT(9))
#define CP_DMA_CRC_CAL_EN_M (CP_DMA_CRC_CAL_EN_V << CP_DMA_CRC_CAL_EN_S)
#define CP_DMA_CRC_CAL_EN_V 0x00000001
#define CP_DMA_CRC_CAL_EN_S 9
/** CP_DMA_CRC_BIG_ENDIAN_EN : R/W; bitpos: [10]; default: 0;
* Set this bit to reorder the bit of data which will be send to excute crc.
*/
#define CP_DMA_CRC_BIG_ENDIAN_EN (BIT(10))
#define CP_DMA_CRC_BIG_ENDIAN_EN_M (CP_DMA_CRC_BIG_ENDIAN_EN_V << CP_DMA_CRC_BIG_ENDIAN_EN_S)
#define CP_DMA_CRC_BIG_ENDIAN_EN_V 0x00000001
#define CP_DMA_CRC_BIG_ENDIAN_EN_S 10
/** CP_DMA_CRC_OUT_REVERSE_EN : R/W; bitpos: [11]; default: 0;
* Set this bit to reverse the crc calculation result.
*/
#define CP_DMA_CRC_OUT_REVERSE_EN (BIT(11))
#define CP_DMA_CRC_OUT_REVERSE_EN_M (CP_DMA_CRC_OUT_REVERSE_EN_V << CP_DMA_CRC_OUT_REVERSE_EN_S)
#define CP_DMA_CRC_OUT_REVERSE_EN_V 0x00000001
#define CP_DMA_CRC_OUT_REVERSE_EN_S 11
/** CP_DMA_CLK_EN : R/W; bitpos: [31]; default: 0;
* 1'b1: Force clock on for register. 1'b0: Support clock only when application writes
* registers.
*/
#define CP_DMA_CLK_EN (BIT(31))
#define CP_DMA_CLK_EN_M (CP_DMA_CLK_EN_V << CP_DMA_CLK_EN_S)
#define CP_DMA_CLK_EN_V 0x00000001
#define CP_DMA_CLK_EN_S 31
/** CP_DMA_IN_ST_REG register
* Status register of receiving data
*/
#define CP_DMA_IN_ST_REG (DR_REG_CP_BASE + 0x40)
/** CP_DMA_INLINK_DSCR_ADDR : RO; bitpos: [17:0]; default: 0;
* This register stores the current inlink descriptor's address.
*/
#define CP_DMA_INLINK_DSCR_ADDR 0x0003FFFF
#define CP_DMA_INLINK_DSCR_ADDR_M (CP_DMA_INLINK_DSCR_ADDR_V << CP_DMA_INLINK_DSCR_ADDR_S)
#define CP_DMA_INLINK_DSCR_ADDR_V 0x0003FFFF
#define CP_DMA_INLINK_DSCR_ADDR_S 0
/** CP_DMA_IN_DSCR_STATE : RO; bitpos: [19:18]; default: 0;
* Reserved.
*/
#define CP_DMA_IN_DSCR_STATE 0x00000003
#define CP_DMA_IN_DSCR_STATE_M (CP_DMA_IN_DSCR_STATE_V << CP_DMA_IN_DSCR_STATE_S)
#define CP_DMA_IN_DSCR_STATE_V 0x00000003
#define CP_DMA_IN_DSCR_STATE_S 18
/** CP_DMA_IN_STATE : RO; bitpos: [22:20]; default: 0;
* Reserved.
*/
#define CP_DMA_IN_STATE 0x00000007
#define CP_DMA_IN_STATE_M (CP_DMA_IN_STATE_V << CP_DMA_IN_STATE_S)
#define CP_DMA_IN_STATE_V 0x00000007
#define CP_DMA_IN_STATE_S 20
/** CP_DMA_FIFO_EMPTY : RO; bitpos: [23]; default: 0;
* Copy DMA FIFO empty signal.
*/
#define CP_DMA_FIFO_EMPTY (BIT(23))
#define CP_DMA_FIFO_EMPTY_M (CP_DMA_FIFO_EMPTY_V << CP_DMA_FIFO_EMPTY_S)
#define CP_DMA_FIFO_EMPTY_V 0x00000001
#define CP_DMA_FIFO_EMPTY_S 23
/** CP_DMA_OUT_ST_REG register
* Status register of trasmitting data
*/
#define CP_DMA_OUT_ST_REG (DR_REG_CP_BASE + 0x44)
/** CP_DMA_OUTLINK_DSCR_ADDR : RO; bitpos: [17:0]; default: 0;
* This register stores the current outlink descriptor's address.
*/
#define CP_DMA_OUTLINK_DSCR_ADDR 0x0003FFFF
#define CP_DMA_OUTLINK_DSCR_ADDR_M (CP_DMA_OUTLINK_DSCR_ADDR_V << CP_DMA_OUTLINK_DSCR_ADDR_S)
#define CP_DMA_OUTLINK_DSCR_ADDR_V 0x0003FFFF
#define CP_DMA_OUTLINK_DSCR_ADDR_S 0
/** CP_DMA_OUT_DSCR_STATE : RO; bitpos: [19:18]; default: 0;
* Reserved.
*/
#define CP_DMA_OUT_DSCR_STATE 0x00000003
#define CP_DMA_OUT_DSCR_STATE_M (CP_DMA_OUT_DSCR_STATE_V << CP_DMA_OUT_DSCR_STATE_S)
#define CP_DMA_OUT_DSCR_STATE_V 0x00000003
#define CP_DMA_OUT_DSCR_STATE_S 18
/** CP_DMA_OUT_STATE : RO; bitpos: [22:20]; default: 0;
* Reserved.
*/
#define CP_DMA_OUT_STATE 0x00000007
#define CP_DMA_OUT_STATE_M (CP_DMA_OUT_STATE_V << CP_DMA_OUT_STATE_S)
#define CP_DMA_OUT_STATE_V 0x00000007
#define CP_DMA_OUT_STATE_S 20
/** CP_DMA_FIFO_FULL : RO; bitpos: [23]; default: 0;
* Copy DMA FIFO full signal.
*/
#define CP_DMA_FIFO_FULL (BIT(23))
#define CP_DMA_FIFO_FULL_M (CP_DMA_FIFO_FULL_V << CP_DMA_FIFO_FULL_S)
#define CP_DMA_FIFO_FULL_V 0x00000001
#define CP_DMA_FIFO_FULL_S 23
/** CP_DMA_CRC_OUT_REG register
* CRC result register
*/
#define CP_DMA_CRC_OUT_REG (DR_REG_CP_BASE + 0x48)
/** CP_DMA_CRC_RESULT : RO; bitpos: [31:0]; default: 0;
* This register stores the result of CRC.
*/
#define CP_DMA_CRC_RESULT 0xFFFFFFFF
#define CP_DMA_CRC_RESULT_M (CP_DMA_CRC_RESULT_V << CP_DMA_CRC_RESULT_S)
#define CP_DMA_CRC_RESULT_V 0xFFFFFFFF
#define CP_DMA_CRC_RESULT_S 0
/** CP_DMA_DATE_REG register
* Copy DMA version register
*/
#define CP_DMA_DATE_REG (DR_REG_CP_BASE + 0xfc)
/** CP_DMA_DMA_DATE : R/W; bitpos: [31:0]; default: 403185664;
* This is the version register.
*/
#define CP_DMA_DMA_DATE 0xFFFFFFFF
#define CP_DMA_DMA_DATE_M (CP_DMA_DMA_DATE_V << CP_DMA_DMA_DATE_S)
#define CP_DMA_DMA_DATE_V 0xFFFFFFFF
#define CP_DMA_DMA_DATE_S 0
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,623 @@
/** 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 <stdint.h>
#ifdef __cplusplus
extern "C" {
#endif
/** Interrupt Registers */
/** Type of dma_int_raw register
* Raw interrupt status
*/
typedef union {
struct {
/** dma_in_done_int_raw : RO; bitpos: [0]; default: 0;
* This is the interrupt raw bit. Triggered when the last data of frame is received or
* the receive buffer is full indicated by inlink descriptor.
*/
uint32_t dma_in_done_int_raw: 1;
/** dma_in_suc_eof_int_raw : RO; bitpos: [1]; default: 0;
* This is the interrupt raw bit. Triggered when the last data of one frame is
* received.
*/
uint32_t dma_in_suc_eof_int_raw: 1;
/** dma_out_done_int_raw : RO; bitpos: [2]; default: 0;
* This is the interrupt raw bit. Triggered when all data indicated by one outlink
* descriptor has been pushed into Tx FIFO.
*/
uint32_t dma_out_done_int_raw: 1;
/** dma_out_eof_int_raw : RO; bitpos: [3]; default: 0;
* This is the interrupt raw bit. Triggered when the last data with EOF flag has been
* pushed into Tx FIFO.
*/
uint32_t dma_out_eof_int_raw: 1;
/** dma_in_dscr_err_int_raw : RO; bitpos: [4]; default: 0;
* This is the interrupt raw bit. Triggered when detecting inlink descriptor error,
* including owner error, the second and third word error of inlink descriptor.
*/
uint32_t dma_in_dscr_err_int_raw: 1;
/** dma_out_dscr_err_int_raw : RO; bitpos: [5]; default: 0;
* This is the interrupt raw bit. Triggered when detecting outlink descriptor error,
* including owner error, the second and third word error of outlink descriptor.
*/
uint32_t dma_out_dscr_err_int_raw: 1;
/** dma_in_dscr_empty_int_raw : RO; bitpos: [6]; default: 0;
* This is the interrupt raw bit. Triggered when receiving data is completed and no
* more inlink descriptor.
*/
uint32_t dma_in_dscr_empty_int_raw: 1;
/** dma_out_total_eof_int_raw : RO; bitpos: [7]; default: 0;
* This is the interrupt raw bit. Triggered when data corresponding to all outlink
* descriptor and the last descriptor with valid EOF is transmitted out.
*/
uint32_t dma_out_total_eof_int_raw: 1;
/** dma_crc_done_int_raw : RO; bitpos: [8]; default: 0;
* This is the interrupt raw bit. Triggered when crc calculation is done.
*/
uint32_t dma_crc_done_int_raw: 1;
};
uint32_t val;
} cp_dma_int_raw_reg_t;
/** Type of dma_int_st register
* Masked interrupt status
*/
typedef union {
struct {
/** dma_in_done_int_st : RO; bitpos: [0]; default: 0;
* This is the masked interrupt bit for cp_in_done_int interrupt when
* cp_in_done_int_ena is set to 1.
*/
uint32_t dma_in_done_int_st: 1;
/** dma_in_suc_eof_int_st : RO; bitpos: [1]; default: 0;
* This is the masked interrupt bit for cp_in_suc_eof_int interrupt when
* cp_in_suc_eof_int_ena is set to 1.
*/
uint32_t dma_in_suc_eof_int_st: 1;
/** dma_out_done_int_st : RO; bitpos: [2]; default: 0;
* This is the masked interrupt bit for cp_out_done_int interrupt when
* cp_out_done_int_ena is set to 1.
*/
uint32_t dma_out_done_int_st: 1;
/** dma_out_eof_int_st : RO; bitpos: [3]; default: 0;
* This is the masked interrupt bit for cp_out_eof_int interrupt when
* cp_out_eof_int_ena is set to 1.
*/
uint32_t dma_out_eof_int_st: 1;
/** dma_in_dscr_err_int_st : RO; bitpos: [4]; default: 0;
* This is the masked interrupt bit for cp_in_dscr_err_int interrupt when
* cp_in_dscr_err_int_ena is set to 1.
*/
uint32_t dma_in_dscr_err_int_st: 1;
/** dma_out_dscr_err_int_st : RO; bitpos: [5]; default: 0;
* This is the masked interrupt bit for cp_out_dscr_err_int interrupt when
* cp_out_dscr_err_int_ena is set to 1.
*/
uint32_t dma_out_dscr_err_int_st: 1;
/** dma_in_dscr_empty_int_st : RO; bitpos: [6]; default: 0;
* This is the masked interrupt bit for cp_in_dscr_empty_int interrupt when
* cp_in_dscr_empty_int_ena is set to 1.
*/
uint32_t dma_in_dscr_empty_int_st: 1;
/** dma_out_total_eof_int_st : RO; bitpos: [7]; default: 0;
* This is the masked interrupt bit for cp_out_total_eof_int interrupt when
* cp_out_total_eof_int_ena is set to 1.
*/
uint32_t dma_out_total_eof_int_st: 1;
/** dma_crc_done_int_st : RO; bitpos: [8]; default: 0;
* This is the masked interrupt bit for cp_crc_done_int interrupt when
* cp_crc_done_int_ena is set to 1.
*/
uint32_t dma_crc_done_int_st: 1;
};
uint32_t val;
} cp_dma_int_st_reg_t;
/** Type of dma_int_ena register
* Interrupt enable bits
*/
typedef union {
struct {
/** dma_in_done_int_ena : R/W; bitpos: [0]; default: 0;
* This is the interrupt enable bit for cp_in_done_int interrupt.
*/
uint32_t dma_in_done_int_ena: 1;
/** dma_in_suc_eof_int_ena : R/W; bitpos: [1]; default: 0;
* This is the interrupt enable bit for cp_in_suc_eof_int interrupt.
*/
uint32_t dma_in_suc_eof_int_ena: 1;
/** dma_out_done_int_ena : R/W; bitpos: [2]; default: 0;
* This is the interrupt enable bit for cp_out_done_int interrupt.
*/
uint32_t dma_out_done_int_ena: 1;
/** dma_out_eof_int_ena : R/W; bitpos: [3]; default: 0;
* This is the interrupt enable bit for cp_out_eof_int interrupt.
*/
uint32_t dma_out_eof_int_ena: 1;
/** dma_in_dscr_err_int_ena : R/W; bitpos: [4]; default: 0;
* This is the interrupt enable bit for cp_in_dscr_err_int interrupt.
*/
uint32_t dma_in_dscr_err_int_ena: 1;
/** dma_out_dscr_err_int_ena : R/W; bitpos: [5]; default: 0;
* This is the interrupt enable bit for cp_out_dscr_err_int interrupt.
*/
uint32_t dma_out_dscr_err_int_ena: 1;
/** dma_in_dscr_empty_int_ena : R/W; bitpos: [6]; default: 0;
* This is the interrupt enable bit for cp_in_dscr_empty_int interrupt.
*/
uint32_t dma_in_dscr_empty_int_ena: 1;
/** dma_out_total_eof_int_ena : R/W; bitpos: [7]; default: 0;
* This is the interrupt enable bit for cp_out_total_eof_int interrupt.
*/
uint32_t dma_out_total_eof_int_ena: 1;
/** dma_crc_done_int_ena : R/W; bitpos: [8]; default: 0;
* This is the interrupt enable bit for cp_crc_done_int interrupt.
*/
uint32_t dma_crc_done_int_ena: 1;
};
uint32_t val;
} cp_dma_int_ena_reg_t;
/** Type of dma_int_clr register
* Interrupt clear bits
*/
typedef union {
struct {
/** dma_in_done_int_clr : WO; bitpos: [0]; default: 0;
* Set this bit to clear cp_in_done_int interrupt.
*/
uint32_t dma_in_done_int_clr: 1;
/** dma_in_suc_eof_int_clr : WO; bitpos: [1]; default: 0;
* Set this bit to clear cp_in_suc_eof_int interrupt.
*/
uint32_t dma_in_suc_eof_int_clr: 1;
/** dma_out_done_int_clr : WO; bitpos: [2]; default: 0;
* Set this bit to clear cp_out_done_int interrupt.
*/
uint32_t dma_out_done_int_clr: 1;
/** dma_out_eof_int_clr : WO; bitpos: [3]; default: 0;
* Set this bit to clear cp_out_eof_int interrupt.
*/
uint32_t dma_out_eof_int_clr: 1;
/** dma_in_dscr_err_int_clr : WO; bitpos: [4]; default: 0;
* Set this bit to clear cp_in_dscr_err_int interrupt.
*/
uint32_t dma_in_dscr_err_int_clr: 1;
/** dma_out_dscr_err_int_clr : WO; bitpos: [5]; default: 0;
* Set this bit to clear cp_out_dscr_err_int interrupt.
*/
uint32_t dma_out_dscr_err_int_clr: 1;
/** dma_in_dscr_empty_int_clr : WO; bitpos: [6]; default: 0;
* Set this bit to clear cp_in_dscr_empty_int interrupt.
*/
uint32_t dma_in_dscr_empty_int_clr: 1;
/** dma_out_total_eof_int_clr : WO; bitpos: [7]; default: 0;
* Set this bit to clear cp_out_total_eof_int interrupt.
*/
uint32_t dma_out_total_eof_int_clr: 1;
/** dma_crc_done_int_clr : WO; bitpos: [8]; default: 0;
* Set this bit to clear cp_crc_done_int interrupt.
*/
uint32_t dma_crc_done_int_clr: 1;
};
uint32_t val;
} cp_dma_int_clr_reg_t;
/** Configuration Registers */
/** Type of dma_out_link register
* Link descriptor address and control
*/
typedef union {
struct {
/** dma_outlink_addr : R/W; bitpos: [19:0]; default: 0;
* This register is used to specify the least significant 20 bits of the first outlink
* descriptor's address.
*/
uint32_t dma_outlink_addr: 20;
uint32_t reserved_20: 8;
/** dma_outlink_stop : R/W; bitpos: [28]; default: 0;
* Set this bit to stop dealing with the outlink descriptor.
*/
uint32_t dma_outlink_stop: 1;
/** dma_outlink_start : R/W; bitpos: [29]; default: 0;
* Set this bit to start a new outlink descriptor.
*/
uint32_t dma_outlink_start: 1;
/** dma_outlink_restart : R/W; bitpos: [30]; default: 0;
* Set this bit to restart the outlink descriptpr from the last address.
*/
uint32_t dma_outlink_restart: 1;
/** dma_outlink_park : RO; bitpos: [31]; default: 0;
* 1: the outlink descriptor's FSM is in idle state.
* 0: the outlink descriptor's FSM is working.
*/
uint32_t dma_outlink_park: 1;
};
uint32_t val;
} cp_dma_out_link_reg_t;
/** Type of dma_in_link register
* Link descriptor address and control
*/
typedef union {
struct {
/** dma_inlink_addr : R/W; bitpos: [19:0]; default: 0;
* This register is used to specify the least significant 20 bits of the first inlink
* descriptor's address.
*/
uint32_t dma_inlink_addr: 20;
uint32_t reserved_20: 8;
/** dma_inlink_stop : R/W; bitpos: [28]; default: 0;
* Set this bit to stop dealing with the inlink descriptors.
*/
uint32_t dma_inlink_stop: 1;
/** dma_inlink_start : R/W; bitpos: [29]; default: 0;
* Set this bit to start dealing with the inlink descriptors.
*/
uint32_t dma_inlink_start: 1;
/** dma_inlink_restart : R/W; bitpos: [30]; default: 0;
* Set this bit to restart new inlink descriptors.
*/
uint32_t dma_inlink_restart: 1;
/** dma_inlink_park : RO; bitpos: [31]; default: 0;
* 1: the inlink descriptor's FSM is in idle state.
* 0: the inlink descriptor's FSM is working.
*/
uint32_t dma_inlink_park: 1;
};
uint32_t val;
} cp_dma_in_link_reg_t;
/** Type of dma_conf register
* Copy DMA configuration register
*/
typedef union {
struct {
/** dma_in_rst : R/W; bitpos: [0]; default: 0;
* Set this bit to reset in_inf state machine.
*/
uint32_t dma_in_rst: 1;
/** dma_out_rst : R/W; bitpos: [1]; default: 0;
* Set this bit to reset out_inf state machine.
*/
uint32_t dma_out_rst: 1;
/** dma_cmdfifo_rst : R/W; bitpos: [2]; default: 0;
* Set this bit to reset in_cmd fifo and out_cmd fifo.
*/
uint32_t dma_cmdfifo_rst: 1;
/** dma_fifo_rst : R/W; bitpos: [3]; default: 0;
* Set this bit to reset data in receive FIFO.
*/
uint32_t dma_fifo_rst: 1;
/** dma_out_owner : R/W; bitpos: [4]; default: 0;
* This is used to configure the owner bit in OUT descriptor. This is effective only
* when you set reg_out_auto_wrback.
*/
uint32_t dma_out_owner: 1;
/** dma_in_owner : R/W; bitpos: [5]; default: 0;
* This is used to configure the owner bit in IN descriptor.
*/
uint32_t dma_in_owner: 1;
/** dma_out_auto_wrback : R/W; bitpos: [6]; default: 0;
* This bit is used to write back out descriptor when hardware has already used this
* descriptor.
*/
uint32_t dma_out_auto_wrback: 1;
/** dma_check_owner : R/W; bitpos: [7]; default: 0;
* Set this bit to enable owner bit check in descriptor.
*/
uint32_t dma_check_owner: 1;
/** dma_crc_cal_reset : R/W; bitpos: [8]; default: 0;
* Set this bit to reset crc calculation.
*/
uint32_t dma_crc_cal_reset: 1;
/** dma_crc_cal_en : R/W; bitpos: [9]; default: 0;
* Set this bit enable crc calculation function.
*/
uint32_t dma_crc_cal_en: 1;
/** dma_crc_big_endian_en : R/W; bitpos: [10]; default: 0;
* Set this bit to reorder the bit of data which will be send to excute crc.
*/
uint32_t dma_crc_big_endian_en: 1;
/** dma_crc_out_reverse_en : R/W; bitpos: [11]; default: 0;
* Set this bit to reverse the crc calculation result.
*/
uint32_t dma_crc_out_reverse_en: 1;
uint32_t reserved_12: 19;
/** dma_clk_en : R/W; bitpos: [31]; default: 0;
* 1'b1: Force clock on for register. 1'b0: Support clock only when application writes
* registers.
*/
uint32_t dma_clk_en: 1;
};
uint32_t val;
} cp_dma_conf_reg_t;
/** Status Registers */
/** Type of dma_out_eof_des_addr register
* Outlink descriptor address when EOF occurs
*/
typedef union {
struct {
/** dma_out_eof_des_addr : RO; bitpos: [31:0]; default: 0;
* This register stores the address of the outlink descriptor when the EOF bit in this
* descriptor is 1.
*/
uint32_t dma_out_eof_des_addr: 32;
};
uint32_t val;
} cp_dma_out_eof_des_addr_reg_t;
/** Type of dma_in_eof_des_addr register
* Inlink descriptor address when EOF occurs
*/
typedef union {
struct {
/** dma_in_suc_eof_des_addr : RO; bitpos: [31:0]; default: 0;
* This register stores the address of the inlink descriptor when received successful
* EOF.
*/
uint32_t dma_in_suc_eof_des_addr: 32;
};
uint32_t val;
} cp_dma_in_eof_des_addr_reg_t;
/** Type of dma_out_eof_bfr_des_addr register
* Outlink descriptor address before the last outlink descriptor
*/
typedef union {
struct {
/** dma_out_eof_bfr_des_addr : RO; bitpos: [31:0]; default: 0;
* This register stores the address of the outlink descriptor before the last outlink
* descriptor.
*/
uint32_t dma_out_eof_bfr_des_addr: 32;
};
uint32_t val;
} cp_dma_out_eof_bfr_des_addr_reg_t;
/** Type of dma_inlink_dscr register
* Address of current inlink descriptor
*/
typedef union {
struct {
/** dma_inlink_dscr : RO; bitpos: [31:0]; default: 0;
* The address of the current inlink descriptor x.
*/
uint32_t dma_inlink_dscr: 32;
};
uint32_t val;
} cp_dma_inlink_dscr_reg_t;
/** Type of dma_inlink_dscr_bf0 register
* Address of last inlink descriptor
*/
typedef union {
struct {
/** dma_inlink_dscr_bf0 : RO; bitpos: [31:0]; default: 0;
* The address of the last inlink descriptor x-1.
*/
uint32_t dma_inlink_dscr_bf0: 32;
};
uint32_t val;
} cp_dma_inlink_dscr_bf0_reg_t;
/** Type of dma_inlink_dscr_bf1 register
* Address of the second-to-last inlink descriptor
*/
typedef union {
struct {
/** dma_inlink_dscr_bf1 : RO; bitpos: [31:0]; default: 0;
* The address of the second-to-last inlink descriptor x-2.
*/
uint32_t dma_inlink_dscr_bf1: 32;
};
uint32_t val;
} cp_dma_inlink_dscr_bf1_reg_t;
/** Type of dma_outlink_dscr register
* Address of current outlink descriptor
*/
typedef union {
struct {
/** dma_outlink_dscr : RO; bitpos: [31:0]; default: 0;
* The address of the current outlink descriptor y.
*/
uint32_t dma_outlink_dscr: 32;
};
uint32_t val;
} cp_dma_outlink_dscr_reg_t;
/** Type of dma_outlink_dscr_bf0 register
* Address of last outlink descriptor
*/
typedef union {
struct {
/** dma_outlink_dscr_bf0 : RO; bitpos: [31:0]; default: 0;
* The address of the last outlink descriptor y-1.
*/
uint32_t dma_outlink_dscr_bf0: 32;
};
uint32_t val;
} cp_dma_outlink_dscr_bf0_reg_t;
/** Type of dma_outlink_dscr_bf1 register
* Address of the second-to-last outlink descriptor
*/
typedef union {
struct {
/** dma_outlink_dscr_bf1 : RO; bitpos: [31:0]; default: 0;
* The address of the second-to-last outlink descriptor y-2.
*/
uint32_t dma_outlink_dscr_bf1: 32;
};
uint32_t val;
} cp_dma_outlink_dscr_bf1_reg_t;
/** Type of dma_in_st register
* Status register of receiving data
*/
typedef union {
struct {
/** dma_inlink_dscr_addr : RO; bitpos: [17:0]; default: 0;
* This register stores the current inlink descriptor's address.
*/
uint32_t dma_inlink_dscr_addr: 18;
/** dma_in_dscr_state : RO; bitpos: [19:18]; default: 0;
* Reserved.
*/
uint32_t dma_in_dscr_state: 2;
/** dma_in_state : RO; bitpos: [22:20]; default: 0;
* Reserved.
*/
uint32_t dma_in_state: 3;
/** dma_fifo_empty : RO; bitpos: [23]; default: 0;
* Copy DMA FIFO empty signal.
*/
uint32_t dma_fifo_empty: 1;
};
uint32_t val;
} cp_dma_in_st_reg_t;
/** Type of dma_out_st register
* Status register of transmitting data
*/
typedef union {
struct {
/** dma_outlink_dscr_addr : RO; bitpos: [17:0]; default: 0;
* This register stores the current outlink descriptor's address.
*/
uint32_t dma_outlink_dscr_addr: 18;
/** dma_out_dscr_state : RO; bitpos: [19:18]; default: 0;
* Reserved.
*/
uint32_t dma_out_dscr_state: 2;
/** dma_out_state : RO; bitpos: [22:20]; default: 0;
* Reserved.
*/
uint32_t dma_out_state: 3;
/** dma_fifo_full : RO; bitpos: [23]; default: 0;
* Copy DMA FIFO full signal.
*/
uint32_t dma_fifo_full: 1;
};
uint32_t val;
} cp_dma_out_st_reg_t;
/** Type of dma_crc_out register
* CRC result register
*/
typedef union {
struct {
/** dma_crc_result : RO; bitpos: [31:0]; default: 0;
* This register stores the result of CRC.
*/
uint32_t dma_crc_result: 32;
};
uint32_t val;
} cp_dma_crc_out_reg_t;
/** Type of dma_date register
* Copy DMA version register
*/
typedef union {
struct {
/** dma_dma_date : R/W; bitpos: [31:0]; default: 403185664;
* This is the version register.
*/
uint32_t dma_dma_date: 32;
};
uint32_t val;
} cp_dma_date_reg_t;
typedef struct {
volatile cp_dma_int_raw_reg_t dma_int_raw;
volatile cp_dma_int_st_reg_t dma_int_st;
volatile cp_dma_int_ena_reg_t dma_int_ena;
volatile cp_dma_int_clr_reg_t dma_int_clr;
volatile cp_dma_out_link_reg_t dma_out_link;
volatile cp_dma_in_link_reg_t dma_in_link;
volatile cp_dma_out_eof_des_addr_reg_t dma_out_eof_des_addr;
volatile cp_dma_in_eof_des_addr_reg_t dma_in_eof_des_addr;
volatile cp_dma_out_eof_bfr_des_addr_reg_t dma_out_eof_bfr_des_addr;
volatile cp_dma_inlink_dscr_reg_t dma_inlink_dscr;
volatile cp_dma_inlink_dscr_bf0_reg_t dma_inlink_dscr_bf0;
volatile cp_dma_inlink_dscr_bf1_reg_t dma_inlink_dscr_bf1;
volatile cp_dma_outlink_dscr_reg_t dma_outlink_dscr;
volatile cp_dma_outlink_dscr_bf0_reg_t dma_outlink_dscr_bf0;
volatile cp_dma_outlink_dscr_bf1_reg_t dma_outlink_dscr_bf1;
volatile cp_dma_conf_reg_t dma_conf;
volatile cp_dma_in_st_reg_t dma_in_st;
volatile cp_dma_out_st_reg_t dma_out_st;
volatile cp_dma_crc_out_reg_t dma_crc_out;
uint32_t reserved_04c;
uint32_t reserved_050;
uint32_t reserved_054;
uint32_t reserved_058;
uint32_t reserved_05c;
uint32_t reserved_060;
uint32_t reserved_064;
uint32_t reserved_068;
uint32_t reserved_06c;
uint32_t reserved_070;
uint32_t reserved_074;
uint32_t reserved_078;
uint32_t reserved_07c;
uint32_t reserved_080;
uint32_t reserved_084;
uint32_t reserved_088;
uint32_t reserved_08c;
uint32_t reserved_090;
uint32_t reserved_094;
uint32_t reserved_098;
uint32_t reserved_09c;
uint32_t reserved_0a0;
uint32_t reserved_0a4;
uint32_t reserved_0a8;
uint32_t reserved_0ac;
uint32_t reserved_0b0;
uint32_t reserved_0b4;
uint32_t reserved_0b8;
uint32_t reserved_0bc;
uint32_t reserved_0c0;
uint32_t reserved_0c4;
uint32_t reserved_0c8;
uint32_t reserved_0cc;
uint32_t reserved_0d0;
uint32_t reserved_0d4;
uint32_t reserved_0d8;
uint32_t reserved_0dc;
uint32_t reserved_0e0;
uint32_t reserved_0e4;
uint32_t reserved_0e8;
uint32_t reserved_0ec;
uint32_t reserved_0f0;
uint32_t reserved_0f4;
uint32_t reserved_0f8;
volatile cp_dma_date_reg_t dma_date;
} cp_dma_dev_t;
_Static_assert(sizeof(cp_dma_dev_t) == 0x100, "cp_dma_dev_t should occupy 0x100 bytes in memory");
extern cp_dma_dev_t CP_DMA;
#ifdef __cplusplus
}
#endif

View File

@ -40,6 +40,9 @@ extern "C" {
#define GPIO_IS_VALID_OUTPUT_GPIO(gpio_num) ((GPIO_IS_VALID_GPIO(gpio_num)) && (gpio_num < 46)) /*!< Check whether it can be a valid GPIO number of output mode */
#define GPIO_MASK_CONTAIN_INPUT_GPIO(gpio_mask) ((gpio_mask & (GPIO_SEL_46))) /*!< Check whether it contains input io */
#define GPIO_MATRIX_CONST_ONE_INPUT (0x38)
#define GPIO_MATRIX_CONST_ZERO_INPUT (0x3C)
#ifdef __cplusplus
}
#endif

View File

@ -188,10 +188,10 @@
#define FSPICS3_OUT_IDX 120
#define FSPICS4_OUT_IDX 121
#define FSPICS5_OUT_IDX 122
#define CAN_RX_IDX 123
#define CAN_TX_IDX 123
#define CAN_BUS_OFF_ON_IDX 124
#define CAN_CLKOUT_IDX 125
#define TWAI_RX_IDX 123
#define TWAI_TX_IDX 123
#define TWAI_BUS_OFF_ON_IDX 124
#define TWAI_CLKOUT_IDX 125
#define SUBSPICLK_OUT_MUX_IDX 126
#define SUBSPIQ_IN_IDX 127
#define SUBSPIQ_OUT_IDX 127

View File

@ -1,248 +0,0 @@
// Copyright 2015-2018 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.
#ifndef _SOC_HINF_REG_H_
#define _SOC_HINF_REG_H_
#include "soc.h"
#define HINF_CFG_DATA0_REG (DR_REG_HINF_BASE + 0x0)
/* HINF_DEVICE_ID_FN1 : R/W ;bitpos:[31:16] ;default: 16'h2222 ; */
/*description: */
#define HINF_DEVICE_ID_FN1 0x0000FFFF
#define HINF_DEVICE_ID_FN1_M ((HINF_DEVICE_ID_FN1_V)<<(HINF_DEVICE_ID_FN1_S))
#define HINF_DEVICE_ID_FN1_V 0xFFFF
#define HINF_DEVICE_ID_FN1_S 16
/* HINF_USER_ID_FN1 : R/W ;bitpos:[15:0] ;default: 16'h6666 ; */
/*description: */
#define HINF_USER_ID_FN1 0x0000FFFF
#define HINF_USER_ID_FN1_M ((HINF_USER_ID_FN1_V)<<(HINF_USER_ID_FN1_S))
#define HINF_USER_ID_FN1_V 0xFFFF
#define HINF_USER_ID_FN1_S 0
#define HINF_CFG_DATA1_REG (DR_REG_HINF_BASE + 0x4)
/* HINF_SDIO20_CONF1 : R/W ;bitpos:[31:29] ;default: 3'h0 ; */
/*description: */
#define HINF_SDIO20_CONF1 0x00000007
#define HINF_SDIO20_CONF1_M ((HINF_SDIO20_CONF1_V)<<(HINF_SDIO20_CONF1_S))
#define HINF_SDIO20_CONF1_V 0x7
#define HINF_SDIO20_CONF1_S 29
/* HINF_FUNC2_EPS : RO ;bitpos:[28] ;default: 1'b0 ; */
/*description: */
#define HINF_FUNC2_EPS (BIT(28))
#define HINF_FUNC2_EPS_M (BIT(28))
#define HINF_FUNC2_EPS_V 0x1
#define HINF_FUNC2_EPS_S 28
/* HINF_SDIO_VER : R/W ;bitpos:[27:16] ;default: 12'h111 ; */
/*description: */
#define HINF_SDIO_VER 0x00000FFF
#define HINF_SDIO_VER_M ((HINF_SDIO_VER_V)<<(HINF_SDIO_VER_S))
#define HINF_SDIO_VER_V 0xFFF
#define HINF_SDIO_VER_S 16
/* HINF_SDIO20_CONF0 : R/W ;bitpos:[15:12] ;default: 4'b0 ; */
/*description: */
#define HINF_SDIO20_CONF0 0x0000000F
#define HINF_SDIO20_CONF0_M ((HINF_SDIO20_CONF0_V)<<(HINF_SDIO20_CONF0_S))
#define HINF_SDIO20_CONF0_V 0xF
#define HINF_SDIO20_CONF0_S 12
/* HINF_IOENABLE1 : RO ;bitpos:[11] ;default: 1'b0 ; */
/*description: */
#define HINF_IOENABLE1 (BIT(11))
#define HINF_IOENABLE1_M (BIT(11))
#define HINF_IOENABLE1_V 0x1
#define HINF_IOENABLE1_S 11
/* HINF_EMP : RO ;bitpos:[10] ;default: 1'b0 ; */
/*description: */
#define HINF_EMP (BIT(10))
#define HINF_EMP_M (BIT(10))
#define HINF_EMP_V 0x1
#define HINF_EMP_S 10
/* HINF_FUNC1_EPS : RO ;bitpos:[9] ;default: 1'b0 ; */
/*description: */
#define HINF_FUNC1_EPS (BIT(9))
#define HINF_FUNC1_EPS_M (BIT(9))
#define HINF_FUNC1_EPS_V 0x1
#define HINF_FUNC1_EPS_S 9
/* HINF_CD_DISABLE : RO ;bitpos:[8] ;default: 1'b0 ; */
/*description: */
#define HINF_CD_DISABLE (BIT(8))
#define HINF_CD_DISABLE_M (BIT(8))
#define HINF_CD_DISABLE_V 0x1
#define HINF_CD_DISABLE_S 8
/* HINF_IOENABLE2 : RO ;bitpos:[7] ;default: 1'b0 ; */
/*description: */
#define HINF_IOENABLE2 (BIT(7))
#define HINF_IOENABLE2_M (BIT(7))
#define HINF_IOENABLE2_V 0x1
#define HINF_IOENABLE2_S 7
/* HINF_SDIO_INT_MASK : R/W ;bitpos:[6] ;default: 1'b0 ; */
/*description: */
#define HINF_SDIO_INT_MASK (BIT(6))
#define HINF_SDIO_INT_MASK_M (BIT(6))
#define HINF_SDIO_INT_MASK_V 0x1
#define HINF_SDIO_INT_MASK_S 6
/* HINF_SDIO_IOREADY2 : R/W ;bitpos:[5] ;default: 1'b0 ; */
/*description: */
#define HINF_SDIO_IOREADY2 (BIT(5))
#define HINF_SDIO_IOREADY2_M (BIT(5))
#define HINF_SDIO_IOREADY2_V 0x1
#define HINF_SDIO_IOREADY2_S 5
/* HINF_SDIO_CD_ENABLE : R/W ;bitpos:[4] ;default: 1'b1 ; */
/*description: */
#define HINF_SDIO_CD_ENABLE (BIT(4))
#define HINF_SDIO_CD_ENABLE_M (BIT(4))
#define HINF_SDIO_CD_ENABLE_V 0x1
#define HINF_SDIO_CD_ENABLE_S 4
/* HINF_HIGHSPEED_MODE : RO ;bitpos:[3] ;default: 1'b0 ; */
/*description: */
#define HINF_HIGHSPEED_MODE (BIT(3))
#define HINF_HIGHSPEED_MODE_M (BIT(3))
#define HINF_HIGHSPEED_MODE_V 0x1
#define HINF_HIGHSPEED_MODE_S 3
/* HINF_HIGHSPEED_ENABLE : R/W ;bitpos:[2] ;default: 1'b0 ; */
/*description: */
#define HINF_HIGHSPEED_ENABLE (BIT(2))
#define HINF_HIGHSPEED_ENABLE_M (BIT(2))
#define HINF_HIGHSPEED_ENABLE_V 0x1
#define HINF_HIGHSPEED_ENABLE_S 2
/* HINF_SDIO_IOREADY1 : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: */
#define HINF_SDIO_IOREADY1 (BIT(1))
#define HINF_SDIO_IOREADY1_M (BIT(1))
#define HINF_SDIO_IOREADY1_V 0x1
#define HINF_SDIO_IOREADY1_S 1
/* HINF_SDIO_ENABLE : R/W ;bitpos:[0] ;default: 1'b1 ; */
/*description: */
#define HINF_SDIO_ENABLE (BIT(0))
#define HINF_SDIO_ENABLE_M (BIT(0))
#define HINF_SDIO_ENABLE_V 0x1
#define HINF_SDIO_ENABLE_S 0
#define HINF_CFG_DATA7_REG (DR_REG_HINF_BASE + 0x1C)
/* HINF_SDIO_IOREADY0 : R/W ;bitpos:[17] ;default: 1'b1 ; */
/*description: */
#define HINF_SDIO_IOREADY0 (BIT(17))
#define HINF_SDIO_IOREADY0_M (BIT(17))
#define HINF_SDIO_IOREADY0_V 0x1
#define HINF_SDIO_IOREADY0_S 17
/* HINF_SDIO_RST : R/W ;bitpos:[16] ;default: 1'b0 ; */
/*description: */
#define HINF_SDIO_RST (BIT(16))
#define HINF_SDIO_RST_M (BIT(16))
#define HINF_SDIO_RST_V 0x1
#define HINF_SDIO_RST_S 16
/* HINF_CHIP_STATE : R/W ;bitpos:[15:8] ;default: 8'b0 ; */
/*description: */
#define HINF_CHIP_STATE 0x000000FF
#define HINF_CHIP_STATE_M ((HINF_CHIP_STATE_V)<<(HINF_CHIP_STATE_S))
#define HINF_CHIP_STATE_V 0xFF
#define HINF_CHIP_STATE_S 8
/* HINF_PIN_STATE : R/W ;bitpos:[7:0] ;default: 8'b0 ; */
/*description: */
#define HINF_PIN_STATE 0x000000FF
#define HINF_PIN_STATE_M ((HINF_PIN_STATE_V)<<(HINF_PIN_STATE_S))
#define HINF_PIN_STATE_V 0xFF
#define HINF_PIN_STATE_S 0
#define HINF_CIS_CONF0_REG (DR_REG_HINF_BASE + 0x20)
/* HINF_CIS_CONF_W0 : R/W ;bitpos:[31:0] ;default: 32'hffffffff ; */
/*description: */
#define HINF_CIS_CONF_W0 0xFFFFFFFF
#define HINF_CIS_CONF_W0_M ((HINF_CIS_CONF_W0_V)<<(HINF_CIS_CONF_W0_S))
#define HINF_CIS_CONF_W0_V 0xFFFFFFFF
#define HINF_CIS_CONF_W0_S 0
#define HINF_CIS_CONF1_REG (DR_REG_HINF_BASE + 0x24)
/* HINF_CIS_CONF_W1 : R/W ;bitpos:[31:0] ;default: 32'hffffffff ; */
/*description: */
#define HINF_CIS_CONF_W1 0xFFFFFFFF
#define HINF_CIS_CONF_W1_M ((HINF_CIS_CONF_W1_V)<<(HINF_CIS_CONF_W1_S))
#define HINF_CIS_CONF_W1_V 0xFFFFFFFF
#define HINF_CIS_CONF_W1_S 0
#define HINF_CIS_CONF2_REG (DR_REG_HINF_BASE + 0x28)
/* HINF_CIS_CONF_W2 : R/W ;bitpos:[31:0] ;default: 32'hffffffff ; */
/*description: */
#define HINF_CIS_CONF_W2 0xFFFFFFFF
#define HINF_CIS_CONF_W2_M ((HINF_CIS_CONF_W2_V)<<(HINF_CIS_CONF_W2_S))
#define HINF_CIS_CONF_W2_V 0xFFFFFFFF
#define HINF_CIS_CONF_W2_S 0
#define HINF_CIS_CONF3_REG (DR_REG_HINF_BASE + 0x2C)
/* HINF_CIS_CONF_W3 : R/W ;bitpos:[31:0] ;default: 32'hffffffff ; */
/*description: */
#define HINF_CIS_CONF_W3 0xFFFFFFFF
#define HINF_CIS_CONF_W3_M ((HINF_CIS_CONF_W3_V)<<(HINF_CIS_CONF_W3_S))
#define HINF_CIS_CONF_W3_V 0xFFFFFFFF
#define HINF_CIS_CONF_W3_S 0
#define HINF_CIS_CONF4_REG (DR_REG_HINF_BASE + 0x30)
/* HINF_CIS_CONF_W4 : R/W ;bitpos:[31:0] ;default: 32'hffffffff ; */
/*description: */
#define HINF_CIS_CONF_W4 0xFFFFFFFF
#define HINF_CIS_CONF_W4_M ((HINF_CIS_CONF_W4_V)<<(HINF_CIS_CONF_W4_S))
#define HINF_CIS_CONF_W4_V 0xFFFFFFFF
#define HINF_CIS_CONF_W4_S 0
#define HINF_CIS_CONF5_REG (DR_REG_HINF_BASE + 0x34)
/* HINF_CIS_CONF_W5 : R/W ;bitpos:[31:0] ;default: 32'hffffffff ; */
/*description: */
#define HINF_CIS_CONF_W5 0xFFFFFFFF
#define HINF_CIS_CONF_W5_M ((HINF_CIS_CONF_W5_V)<<(HINF_CIS_CONF_W5_S))
#define HINF_CIS_CONF_W5_V 0xFFFFFFFF
#define HINF_CIS_CONF_W5_S 0
#define HINF_CIS_CONF6_REG (DR_REG_HINF_BASE + 0x38)
/* HINF_CIS_CONF_W6 : R/W ;bitpos:[31:0] ;default: 32'hffffffff ; */
/*description: */
#define HINF_CIS_CONF_W6 0xFFFFFFFF
#define HINF_CIS_CONF_W6_M ((HINF_CIS_CONF_W6_V)<<(HINF_CIS_CONF_W6_S))
#define HINF_CIS_CONF_W6_V 0xFFFFFFFF
#define HINF_CIS_CONF_W6_S 0
#define HINF_CIS_CONF7_REG (DR_REG_HINF_BASE + 0x3C)
/* HINF_CIS_CONF_W7 : R/W ;bitpos:[31:0] ;default: 32'hffffffff ; */
/*description: */
#define HINF_CIS_CONF_W7 0xFFFFFFFF
#define HINF_CIS_CONF_W7_M ((HINF_CIS_CONF_W7_V)<<(HINF_CIS_CONF_W7_S))
#define HINF_CIS_CONF_W7_V 0xFFFFFFFF
#define HINF_CIS_CONF_W7_S 0
#define HINF_CFG_DATA16_REG (DR_REG_HINF_BASE + 0x40)
/* HINF_DEVICE_ID_FN2 : R/W ;bitpos:[31:16] ;default: 16'h3333 ; */
/*description: */
#define HINF_DEVICE_ID_FN2 0x0000FFFF
#define HINF_DEVICE_ID_FN2_M ((HINF_DEVICE_ID_FN2_V)<<(HINF_DEVICE_ID_FN2_S))
#define HINF_DEVICE_ID_FN2_V 0xFFFF
#define HINF_DEVICE_ID_FN2_S 16
/* HINF_USER_ID_FN2 : R/W ;bitpos:[15:0] ;default: 16'h6666 ; */
/*description: */
#define HINF_USER_ID_FN2 0x0000FFFF
#define HINF_USER_ID_FN2_M ((HINF_USER_ID_FN2_V)<<(HINF_USER_ID_FN2_S))
#define HINF_USER_ID_FN2_V 0xFFFF
#define HINF_USER_ID_FN2_S 0
#define HINF_DATE_REG (DR_REG_HINF_BASE + 0xFC)
/* HINF_SDIO_DATE : R/W ;bitpos:[31:0] ;default: 32'h15030200 ; */
/*description: */
#define HINF_SDIO_DATE 0xFFFFFFFF
#define HINF_SDIO_DATE_M ((HINF_SDIO_DATE_V)<<(HINF_SDIO_DATE_S))
#define HINF_SDIO_DATE_V 0xFFFFFFFF
#define HINF_SDIO_DATE_S 0
#endif /*_SOC_HINF_REG_H_ */

View File

@ -1,134 +0,0 @@
// Copyright 2015-2018 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.
#ifndef _SOC_HINF_STRUCT_H_
#define _SOC_HINF_STRUCT_H_
#ifdef __cplusplus
extern "C" {
#endif
typedef volatile struct {
union {
struct {
uint32_t user_id_fn1: 16;
uint32_t device_id_fn1:16;
};
uint32_t val;
} cfg_data0;
union {
struct {
uint32_t sdio_enable: 1;
uint32_t sdio_ioready1: 1;
uint32_t highspeed_enable: 1;
uint32_t highspeed_mode: 1;
uint32_t sdio_cd_enable: 1;
uint32_t sdio_ioready2: 1;
uint32_t sdio_int_mask: 1;
uint32_t ioenable2: 1;
uint32_t cd_disable: 1;
uint32_t func1_eps: 1;
uint32_t emp: 1;
uint32_t ioenable1: 1;
uint32_t sdio20_conf0: 4;
uint32_t sdio_ver: 12;
uint32_t func2_eps: 1;
uint32_t sdio20_conf1: 3;
};
uint32_t val;
} cfg_data1;
uint32_t reserved_8;
uint32_t reserved_c;
uint32_t reserved_10;
uint32_t reserved_14;
uint32_t reserved_18;
union {
struct {
uint32_t pin_state: 8;
uint32_t chip_state: 8;
uint32_t sdio_rst: 1;
uint32_t sdio_ioready0: 1;
uint32_t reserved18: 14;
};
uint32_t val;
} cfg_data7;
uint32_t cis_conf0; /**/
uint32_t cis_conf1; /**/
uint32_t cis_conf2; /**/
uint32_t cis_conf3; /**/
uint32_t cis_conf4; /**/
uint32_t cis_conf5; /**/
uint32_t cis_conf6; /**/
uint32_t cis_conf7; /**/
union {
struct {
uint32_t user_id_fn2: 16;
uint32_t device_id_fn2:16;
};
uint32_t val;
} cfg_data16;
uint32_t reserved_44;
uint32_t reserved_48;
uint32_t reserved_4c;
uint32_t reserved_50;
uint32_t reserved_54;
uint32_t reserved_58;
uint32_t reserved_5c;
uint32_t reserved_60;
uint32_t reserved_64;
uint32_t reserved_68;
uint32_t reserved_6c;
uint32_t reserved_70;
uint32_t reserved_74;
uint32_t reserved_78;
uint32_t reserved_7c;
uint32_t reserved_80;
uint32_t reserved_84;
uint32_t reserved_88;
uint32_t reserved_8c;
uint32_t reserved_90;
uint32_t reserved_94;
uint32_t reserved_98;
uint32_t reserved_9c;
uint32_t reserved_a0;
uint32_t reserved_a4;
uint32_t reserved_a8;
uint32_t reserved_ac;
uint32_t reserved_b0;
uint32_t reserved_b4;
uint32_t reserved_b8;
uint32_t reserved_bc;
uint32_t reserved_c0;
uint32_t reserved_c4;
uint32_t reserved_c8;
uint32_t reserved_cc;
uint32_t reserved_d0;
uint32_t reserved_d4;
uint32_t reserved_d8;
uint32_t reserved_dc;
uint32_t reserved_e0;
uint32_t reserved_e4;
uint32_t reserved_e8;
uint32_t reserved_ec;
uint32_t reserved_f0;
uint32_t reserved_f4;
uint32_t reserved_f8;
uint32_t date; /**/
} hinf_dev_t;
extern hinf_dev_t HINF;
#ifdef __cplusplus
}
#endif
#endif /* _SOC_HINF_STRUCT_H_ */

View File

@ -1,602 +0,0 @@
// Copyright 2017-2018 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.
#ifndef _SOC_HOST_STRUCT_H_
#define _SOC_HOST_STRUCT_H_
#ifdef __cplusplus
extern "C" {
#endif
typedef volatile struct {
uint32_t reserved_0;
uint32_t reserved_4;
uint32_t reserved_8;
uint32_t reserved_c;
uint32_t reserved_10;
uint32_t reserved_14;
uint32_t reserved_18;
uint32_t reserved_1c;
union {
struct {
uint32_t func1_mdstat: 1;
uint32_t reserved1: 31;
};
uint32_t val;
} func2_2;
uint32_t reserved_24;
uint32_t reserved_28;
uint32_t reserved_2c;
uint32_t reserved_30;
uint32_t gpio_status0; /**/
union {
struct {
uint32_t sdio_int1: 22;
uint32_t reserved22: 10;
};
uint32_t val;
} gpio_status1;
uint32_t gpio_in0; /**/
union {
struct {
uint32_t sdio_in1: 22;
uint32_t reserved22: 10;
};
uint32_t val;
} gpio_in1;
union {
struct {
uint32_t token0: 12;
uint32_t rx_pf_valid: 1;
uint32_t reserved13: 3;
uint32_t reg_token1: 12;
uint32_t rx_pf_eof: 4;
};
uint32_t val;
} slc0_token_rdata;
uint32_t slc0_pf; /**/
uint32_t reserved_4c;
union {
struct {
uint32_t tohost_bit0: 1;
uint32_t tohost_bit1: 1;
uint32_t tohost_bit2: 1;
uint32_t tohost_bit3: 1;
uint32_t tohost_bit4: 1;
uint32_t tohost_bit5: 1;
uint32_t tohost_bit6: 1;
uint32_t tohost_bit7: 1;
uint32_t token0_1to0: 1;
uint32_t token1_1to0: 1;
uint32_t token0_0to1: 1;
uint32_t token1_0to1: 1;
uint32_t rx_sof: 1;
uint32_t rx_eof: 1;
uint32_t rx_start: 1;
uint32_t tx_start: 1;
uint32_t rx_udf: 1;
uint32_t tx_ovf: 1;
uint32_t rx_pf_valid: 1;
uint32_t ext_bit0: 1;
uint32_t ext_bit1: 1;
uint32_t ext_bit2: 1;
uint32_t ext_bit3: 1;
uint32_t rx_new_packet: 1;
uint32_t rd_retry: 1;
uint32_t gpio_sdio: 1;
uint32_t reserved26: 6;
};
uint32_t val;
} slc0_int_raw;
uint32_t reserved_54;
union {
struct {
uint32_t tohost_bit0: 1;
uint32_t tohost_bit1: 1;
uint32_t tohost_bit2: 1;
uint32_t tohost_bit3: 1;
uint32_t tohost_bit4: 1;
uint32_t tohost_bit5: 1;
uint32_t tohost_bit6: 1;
uint32_t tohost_bit7: 1;
uint32_t token0_1to0: 1;
uint32_t token1_1to0: 1;
uint32_t token0_0to1: 1;
uint32_t token1_0to1: 1;
uint32_t rx_sof: 1;
uint32_t rx_eof: 1;
uint32_t rx_start: 1;
uint32_t tx_start: 1;
uint32_t rx_udf: 1;
uint32_t tx_ovf: 1;
uint32_t rx_pf_valid: 1;
uint32_t ext_bit0: 1;
uint32_t ext_bit1: 1;
uint32_t ext_bit2: 1;
uint32_t ext_bit3: 1;
uint32_t rx_new_packet: 1;
uint32_t rd_retry: 1;
uint32_t gpio_sdio: 1;
uint32_t reserved26: 6;
};
uint32_t val;
} slc0_int_st;
uint32_t reserved_5c;
union {
struct {
uint32_t reg_slc0_len: 20;
uint32_t reg_slc0_len_check:12;
};
uint32_t val;
} pkt_len;
union {
struct {
uint32_t state0: 8;
uint32_t state1: 8;
uint32_t state2: 8;
uint32_t state3: 8;
};
uint32_t val;
} state_w0;
union {
struct {
uint32_t state4: 8;
uint32_t state5: 8;
uint32_t state6: 8;
uint32_t state7: 8;
};
uint32_t val;
} state_w1;
union {
struct {
uint32_t conf0: 8;
uint32_t conf1: 8;
uint32_t conf2: 8;
uint32_t conf3: 8;
};
uint32_t val;
} conf_w0;
union {
struct {
uint32_t conf4: 8;
uint32_t conf5: 8;
uint32_t conf6: 8;
uint32_t conf7: 8;
};
uint32_t val;
} conf_w1;
union {
struct {
uint32_t conf8: 8;
uint32_t conf9: 8;
uint32_t conf10: 8;
uint32_t conf11: 8;
};
uint32_t val;
} conf_w2;
union {
struct {
uint32_t conf12: 8;
uint32_t conf13: 8;
uint32_t conf14: 8;
uint32_t conf15: 8;
};
uint32_t val;
} conf_w3;
union {
struct {
uint32_t conf16: 8; /*SLC timeout value*/
uint32_t conf17: 8; /*SLC timeout enable*/
uint32_t conf18: 8;
uint32_t conf19: 8; /*Interrupt to target CPU*/
};
uint32_t val;
} conf_w4;
union {
struct {
uint32_t conf20: 8;
uint32_t conf21: 8;
uint32_t conf22: 8;
uint32_t conf23: 8;
};
uint32_t val;
} conf_w5;
union {
struct {
uint32_t win_cmd: 16;
uint32_t reserved16: 16;
};
uint32_t val;
} win_cmd;
union {
struct {
uint32_t conf24: 8;
uint32_t conf25: 8;
uint32_t conf26: 8;
uint32_t conf27: 8;
};
uint32_t val;
} conf_w6;
union {
struct {
uint32_t conf28: 8;
uint32_t conf29: 8;
uint32_t conf30: 8;
uint32_t conf31: 8;
};
uint32_t val;
} conf_w7;
union {
struct {
uint32_t reg_slc0_len0: 20;
uint32_t reg_slc0_len0_check:12;
};
uint32_t val;
} pkt_len0;
union {
struct {
uint32_t reg_slc0_len1: 20;
uint32_t reg_slc0_len1_check:12;
};
uint32_t val;
} pkt_len1;
union {
struct {
uint32_t reg_slc0_len2: 20;
uint32_t reg_slc0_len2_check:12;
};
uint32_t val;
} pkt_len2;
union {
struct {
uint32_t conf32: 8;
uint32_t conf33: 8;
uint32_t conf34: 8;
uint32_t conf35: 8;
};
uint32_t val;
} conf_w8;
union {
struct {
uint32_t conf36: 8;
uint32_t conf37: 8;
uint32_t conf38: 8;
uint32_t conf39: 8;
};
uint32_t val;
} conf_w9;
union {
struct {
uint32_t conf40: 8;
uint32_t conf41: 8;
uint32_t conf42: 8;
uint32_t conf43: 8;
};
uint32_t val;
} conf_w10;
union {
struct {
uint32_t conf44: 8;
uint32_t conf45: 8;
uint32_t conf46: 8;
uint32_t conf47: 8;
};
uint32_t val;
} conf_w11;
union {
struct {
uint32_t conf48: 8;
uint32_t conf49: 8;
uint32_t conf50: 8;
uint32_t conf51: 8;
};
uint32_t val;
} conf_w12;
union {
struct {
uint32_t conf52: 8;
uint32_t conf53: 8;
uint32_t conf54: 8;
uint32_t conf55: 8;
};
uint32_t val;
} conf_w13;
union {
struct {
uint32_t conf56: 8;
uint32_t conf57: 8;
uint32_t conf58: 8;
uint32_t conf59: 8;
};
uint32_t val;
} conf_w14;
union {
struct {
uint32_t conf60: 8;
uint32_t conf61: 8;
uint32_t conf62: 8;
uint32_t conf63: 8;
};
uint32_t val;
} conf_w15;
uint32_t check_sum0; /**/
uint32_t check_sum1; /**/
uint32_t reserved_c4;
union {
struct {
uint32_t token0_wd: 12;
uint32_t reserved12: 4;
uint32_t token1_wd: 12;
uint32_t reserved28: 4;
};
uint32_t val;
} slc0_token_wdata;
uint32_t reserved_cc;
union {
struct {
uint32_t slc0_token0_dec: 1;
uint32_t slc0_token1_dec: 1;
uint32_t slc0_token0_wr: 1;
uint32_t slc0_token1_wr: 1;
uint32_t reserved4: 4;
uint32_t slc0_len_wr: 1;
uint32_t reserved9: 23;
};
uint32_t val;
} token_con;
union {
struct {
uint32_t tohost_bit0: 1;
uint32_t tohost_bit1: 1;
uint32_t tohost_bit2: 1;
uint32_t tohost_bit3: 1;
uint32_t tohost_bit4: 1;
uint32_t tohost_bit5: 1;
uint32_t tohost_bit6: 1;
uint32_t tohost_bit7: 1;
uint32_t token0_1to0: 1;
uint32_t token1_1to0: 1;
uint32_t token0_0to1: 1;
uint32_t token1_0to1: 1;
uint32_t rx_sof: 1;
uint32_t rx_eof: 1;
uint32_t rx_start: 1;
uint32_t tx_start: 1;
uint32_t rx_udf: 1;
uint32_t tx_ovf: 1;
uint32_t rx_pf_valid: 1;
uint32_t ext_bit0: 1;
uint32_t ext_bit1: 1;
uint32_t ext_bit2: 1;
uint32_t ext_bit3: 1;
uint32_t rx_new_packet: 1;
uint32_t rd_retry: 1;
uint32_t gpio_sdio: 1;
uint32_t reserved26: 6;
};
uint32_t val;
} slc0_int_clr;
uint32_t reserved_d8;
union {
struct {
uint32_t tohost_bit0: 1;
uint32_t tohost_bit1: 1;
uint32_t tohost_bit2: 1;
uint32_t tohost_bit3: 1;
uint32_t tohost_bit4: 1;
uint32_t tohost_bit5: 1;
uint32_t tohost_bit6: 1;
uint32_t tohost_bit7: 1;
uint32_t token0_1to0: 1;
uint32_t token1_1to0: 1;
uint32_t token0_0to1: 1;
uint32_t token1_0to1: 1;
uint32_t rx_sof: 1;
uint32_t rx_eof: 1;
uint32_t rx_start: 1;
uint32_t tx_start: 1;
uint32_t rx_udf: 1;
uint32_t tx_ovf: 1;
uint32_t rx_pf_valid: 1;
uint32_t ext_bit0: 1;
uint32_t ext_bit1: 1;
uint32_t ext_bit2: 1;
uint32_t ext_bit3: 1;
uint32_t rx_new_packet: 1;
uint32_t rd_retry: 1;
uint32_t gpio_sdio: 1;
uint32_t reserved26: 6;
};
uint32_t val;
} slc0_func1_int_ena;
uint32_t reserved_e0;
uint32_t reserved_e4;
uint32_t reserved_e8;
union {
struct {
uint32_t tohost_bit0: 1;
uint32_t tohost_bit1: 1;
uint32_t tohost_bit2: 1;
uint32_t tohost_bit3: 1;
uint32_t tohost_bit4: 1;
uint32_t tohost_bit5: 1;
uint32_t tohost_bit6: 1;
uint32_t tohost_bit7: 1;
uint32_t token0_1to0: 1;
uint32_t token1_1to0: 1;
uint32_t token0_0to1: 1;
uint32_t token1_0to1: 1;
uint32_t rx_sof: 1;
uint32_t rx_eof: 1;
uint32_t rx_start: 1;
uint32_t tx_start: 1;
uint32_t rx_udf: 1;
uint32_t tx_ovf: 1;
uint32_t rx_pf_valid: 1;
uint32_t ext_bit0: 1;
uint32_t ext_bit1: 1;
uint32_t ext_bit2: 1;
uint32_t ext_bit3: 1;
uint32_t rx_new_packet: 1;
uint32_t rd_retry: 1;
uint32_t gpio_sdio: 1;
uint32_t reserved26: 6;
};
uint32_t val;
} slc0_int_ena;
uint32_t reserved_f0;
union {
struct {
uint32_t infor: 20;
uint32_t reserved20: 12;
};
uint32_t val;
} slc0_rx_infor;
uint32_t reserved_f8;
uint32_t slc0_len_wd; /**/
uint32_t apbwin_wdata; /**/
union {
struct {
uint32_t addr: 28;
uint32_t wr: 1;
uint32_t start: 1;
uint32_t bus: 1;
uint32_t reserved31: 1;
};
uint32_t val;
} apbwin_conf;
uint32_t apbwin_rdata; /**/
union {
struct {
uint32_t bit7_clraddr: 9;
uint32_t bit6_clraddr: 9;
uint32_t reserved18: 14;
};
uint32_t val;
} slc0_rdclr;
uint32_t reserved_110;
union {
struct {
uint32_t tohost_bit01: 1;
uint32_t tohost_bit11: 1;
uint32_t tohost_bit21: 1;
uint32_t tohost_bit31: 1;
uint32_t tohost_bit41: 1;
uint32_t tohost_bit51: 1;
uint32_t tohost_bit61: 1;
uint32_t tohost_bit71: 1;
uint32_t token0_1to01: 1;
uint32_t token1_1to01: 1;
uint32_t token0_0to11: 1;
uint32_t token1_0to11: 1;
uint32_t rx_sof1: 1;
uint32_t rx_eof1: 1;
uint32_t rx_start1: 1;
uint32_t tx_start1: 1;
uint32_t rx_udf1: 1;
uint32_t tx_ovf1: 1;
uint32_t rx_pf_valid1: 1;
uint32_t ext_bit01: 1;
uint32_t ext_bit11: 1;
uint32_t ext_bit21: 1;
uint32_t ext_bit31: 1;
uint32_t rx_new_packet1: 1;
uint32_t rd_retry1: 1;
uint32_t gpio_sdio1: 1;
uint32_t reserved26: 6;
};
uint32_t val;
} slc0_int_ena1;
uint32_t reserved_118;
uint32_t reserved_11c;
uint32_t reserved_120;
uint32_t reserved_124;
uint32_t reserved_128;
uint32_t reserved_12c;
uint32_t reserved_130;
uint32_t reserved_134;
uint32_t reserved_138;
uint32_t reserved_13c;
uint32_t reserved_140;
uint32_t reserved_144;
uint32_t reserved_148;
uint32_t reserved_14c;
uint32_t reserved_150;
uint32_t reserved_154;
uint32_t reserved_158;
uint32_t reserved_15c;
uint32_t reserved_160;
uint32_t reserved_164;
uint32_t reserved_168;
uint32_t reserved_16c;
uint32_t reserved_170;
uint32_t reserved_174;
uint32_t date; /**/
uint32_t id; /**/
uint32_t reserved_180;
uint32_t reserved_184;
uint32_t reserved_188;
uint32_t reserved_18c;
uint32_t reserved_190;
uint32_t reserved_194;
uint32_t reserved_198;
uint32_t reserved_19c;
uint32_t reserved_1a0;
uint32_t reserved_1a4;
uint32_t reserved_1a8;
uint32_t reserved_1ac;
uint32_t reserved_1b0;
uint32_t reserved_1b4;
uint32_t reserved_1b8;
uint32_t reserved_1bc;
uint32_t reserved_1c0;
uint32_t reserved_1c4;
uint32_t reserved_1c8;
uint32_t reserved_1cc;
uint32_t reserved_1d0;
uint32_t reserved_1d4;
uint32_t reserved_1d8;
uint32_t reserved_1dc;
uint32_t reserved_1e0;
uint32_t reserved_1e4;
uint32_t reserved_1e8;
uint32_t reserved_1ec;
union {
struct {
uint32_t frc_sdio11: 5;
uint32_t frc_sdio20: 5;
uint32_t frc_neg_samp: 5;
uint32_t frc_pos_samp: 5;
uint32_t frc_quick_in: 5;
uint32_t sdio20_int_delay: 1;
uint32_t sdio_pad_pullup: 1;
uint32_t hspeed_con_en: 1;
uint32_t reserved28: 4;
};
uint32_t val;
} conf;
union {
struct {
uint32_t sdio20_mode: 5;
uint32_t sdio_neg_samp: 5;
uint32_t sdio_quick_in: 5;
uint32_t reserved15: 17;
};
uint32_t val;
} inf_st;
} host_dev_t;
extern host_dev_t HOST;
#ifdef __cplusplus
}
#endif
#endif /* _SOC_HOST_STRUCT_H_ */

View File

@ -1,540 +0,0 @@
// Copyright 2017-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.
#ifndef _SOC_MCP_REG_H_
#define _SOC_MCP_REG_H_
#ifdef __cplusplus
extern "C" {
#endif
#include "soc.h"
#define MCP_INT_RAW_REG (DR_REG_MCP_BASE + 0x0000)
/* MCP_CRC_DONE_INT_RAW : RO ;bitpos:[8] ;default: 1'b0 ; */
/*description: */
#define MCP_CRC_DONE_INT_RAW (BIT(8))
#define MCP_CRC_DONE_INT_RAW_M (BIT(8))
#define MCP_CRC_DONE_INT_RAW_V 0x1
#define MCP_CRC_DONE_INT_RAW_S 8
/* MCP_OUT_TOTAL_EOF_INT_RAW : RO ;bitpos:[7] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_TOTAL_EOF_INT_RAW (BIT(7))
#define MCP_OUT_TOTAL_EOF_INT_RAW_M (BIT(7))
#define MCP_OUT_TOTAL_EOF_INT_RAW_V 0x1
#define MCP_OUT_TOTAL_EOF_INT_RAW_S 7
/* MCP_IN_DSCR_EMPTY_INT_RAW : RO ;bitpos:[6] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_DSCR_EMPTY_INT_RAW (BIT(6))
#define MCP_IN_DSCR_EMPTY_INT_RAW_M (BIT(6))
#define MCP_IN_DSCR_EMPTY_INT_RAW_V 0x1
#define MCP_IN_DSCR_EMPTY_INT_RAW_S 6
/* MCP_OUT_DSCR_ERR_INT_RAW : RO ;bitpos:[5] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_DSCR_ERR_INT_RAW (BIT(5))
#define MCP_OUT_DSCR_ERR_INT_RAW_M (BIT(5))
#define MCP_OUT_DSCR_ERR_INT_RAW_V 0x1
#define MCP_OUT_DSCR_ERR_INT_RAW_S 5
/* MCP_IN_DSCR_ERR_INT_RAW : RO ;bitpos:[4] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_DSCR_ERR_INT_RAW (BIT(4))
#define MCP_IN_DSCR_ERR_INT_RAW_M (BIT(4))
#define MCP_IN_DSCR_ERR_INT_RAW_V 0x1
#define MCP_IN_DSCR_ERR_INT_RAW_S 4
/* MCP_OUT_EOF_INT_RAW : RO ;bitpos:[3] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_EOF_INT_RAW (BIT(3))
#define MCP_OUT_EOF_INT_RAW_M (BIT(3))
#define MCP_OUT_EOF_INT_RAW_V 0x1
#define MCP_OUT_EOF_INT_RAW_S 3
/* MCP_OUT_DONE_INT_RAW : RO ;bitpos:[2] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_DONE_INT_RAW (BIT(2))
#define MCP_OUT_DONE_INT_RAW_M (BIT(2))
#define MCP_OUT_DONE_INT_RAW_V 0x1
#define MCP_OUT_DONE_INT_RAW_S 2
/* MCP_IN_SUC_EOF_INT_RAW : RO ;bitpos:[1] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_SUC_EOF_INT_RAW (BIT(1))
#define MCP_IN_SUC_EOF_INT_RAW_M (BIT(1))
#define MCP_IN_SUC_EOF_INT_RAW_V 0x1
#define MCP_IN_SUC_EOF_INT_RAW_S 1
/* MCP_IN_DONE_INT_RAW : RO ;bitpos:[0] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_DONE_INT_RAW (BIT(0))
#define MCP_IN_DONE_INT_RAW_M (BIT(0))
#define MCP_IN_DONE_INT_RAW_V 0x1
#define MCP_IN_DONE_INT_RAW_S 0
#define MCP_INT_ST_REG (DR_REG_MCP_BASE + 0x0004)
/* MCP_CRC_DONE_INT_ST : RO ;bitpos:[8] ;default: 1'b0 ; */
/*description: */
#define MCP_CRC_DONE_INT_ST (BIT(8))
#define MCP_CRC_DONE_INT_ST_M (BIT(8))
#define MCP_CRC_DONE_INT_ST_V 0x1
#define MCP_CRC_DONE_INT_ST_S 8
/* MCP_OUT_TOTAL_EOF_INT_ST : RO ;bitpos:[7] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_TOTAL_EOF_INT_ST (BIT(7))
#define MCP_OUT_TOTAL_EOF_INT_ST_M (BIT(7))
#define MCP_OUT_TOTAL_EOF_INT_ST_V 0x1
#define MCP_OUT_TOTAL_EOF_INT_ST_S 7
/* MCP_IN_DSCR_EMPTY_INT_ST : RO ;bitpos:[6] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_DSCR_EMPTY_INT_ST (BIT(6))
#define MCP_IN_DSCR_EMPTY_INT_ST_M (BIT(6))
#define MCP_IN_DSCR_EMPTY_INT_ST_V 0x1
#define MCP_IN_DSCR_EMPTY_INT_ST_S 6
/* MCP_OUT_DSCR_ERR_INT_ST : RO ;bitpos:[5] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_DSCR_ERR_INT_ST (BIT(5))
#define MCP_OUT_DSCR_ERR_INT_ST_M (BIT(5))
#define MCP_OUT_DSCR_ERR_INT_ST_V 0x1
#define MCP_OUT_DSCR_ERR_INT_ST_S 5
/* MCP_IN_DSCR_ERR_INT_ST : RO ;bitpos:[4] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_DSCR_ERR_INT_ST (BIT(4))
#define MCP_IN_DSCR_ERR_INT_ST_M (BIT(4))
#define MCP_IN_DSCR_ERR_INT_ST_V 0x1
#define MCP_IN_DSCR_ERR_INT_ST_S 4
/* MCP_OUT_EOF_INT_ST : RO ;bitpos:[3] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_EOF_INT_ST (BIT(3))
#define MCP_OUT_EOF_INT_ST_M (BIT(3))
#define MCP_OUT_EOF_INT_ST_V 0x1
#define MCP_OUT_EOF_INT_ST_S 3
/* MCP_OUT_DONE_INT_ST : RO ;bitpos:[2] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_DONE_INT_ST (BIT(2))
#define MCP_OUT_DONE_INT_ST_M (BIT(2))
#define MCP_OUT_DONE_INT_ST_V 0x1
#define MCP_OUT_DONE_INT_ST_S 2
/* MCP_IN_SUC_EOF_INT_ST : RO ;bitpos:[1] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_SUC_EOF_INT_ST (BIT(1))
#define MCP_IN_SUC_EOF_INT_ST_M (BIT(1))
#define MCP_IN_SUC_EOF_INT_ST_V 0x1
#define MCP_IN_SUC_EOF_INT_ST_S 1
/* MCP_IN_DONE_INT_ST : RO ;bitpos:[0] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_DONE_INT_ST (BIT(0))
#define MCP_IN_DONE_INT_ST_M (BIT(0))
#define MCP_IN_DONE_INT_ST_V 0x1
#define MCP_IN_DONE_INT_ST_S 0
#define MCP_INT_ENA_REG (DR_REG_MCP_BASE + 0x008)
/* MCP_CRC_DONE_INT_ENA : R/W ;bitpos:[8] ;default: 1'b0 ; */
/*description: */
#define MCP_CRC_DONE_INT_ENA (BIT(8))
#define MCP_CRC_DONE_INT_ENA_M (BIT(8))
#define MCP_CRC_DONE_INT_ENA_V 0x1
#define MCP_CRC_DONE_INT_ENA_S 8
/* MCP_OUT_TOTAL_EOF_INT_ENA : R/W ;bitpos:[7] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_TOTAL_EOF_INT_ENA (BIT(7))
#define MCP_OUT_TOTAL_EOF_INT_ENA_M (BIT(7))
#define MCP_OUT_TOTAL_EOF_INT_ENA_V 0x1
#define MCP_OUT_TOTAL_EOF_INT_ENA_S 7
/* MCP_IN_DSCR_EMPTY_INT_ENA : R/W ;bitpos:[6] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_DSCR_EMPTY_INT_ENA (BIT(6))
#define MCP_IN_DSCR_EMPTY_INT_ENA_M (BIT(6))
#define MCP_IN_DSCR_EMPTY_INT_ENA_V 0x1
#define MCP_IN_DSCR_EMPTY_INT_ENA_S 6
/* MCP_OUT_DSCR_ERR_INT_ENA : R/W ;bitpos:[5] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_DSCR_ERR_INT_ENA (BIT(5))
#define MCP_OUT_DSCR_ERR_INT_ENA_M (BIT(5))
#define MCP_OUT_DSCR_ERR_INT_ENA_V 0x1
#define MCP_OUT_DSCR_ERR_INT_ENA_S 5
/* MCP_IN_DSCR_ERR_INT_ENA : R/W ;bitpos:[4] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_DSCR_ERR_INT_ENA (BIT(4))
#define MCP_IN_DSCR_ERR_INT_ENA_M (BIT(4))
#define MCP_IN_DSCR_ERR_INT_ENA_V 0x1
#define MCP_IN_DSCR_ERR_INT_ENA_S 4
/* MCP_OUT_EOF_INT_ENA : R/W ;bitpos:[3] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_EOF_INT_ENA (BIT(3))
#define MCP_OUT_EOF_INT_ENA_M (BIT(3))
#define MCP_OUT_EOF_INT_ENA_V 0x1
#define MCP_OUT_EOF_INT_ENA_S 3
/* MCP_OUT_DONE_INT_ENA : R/W ;bitpos:[2] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_DONE_INT_ENA (BIT(2))
#define MCP_OUT_DONE_INT_ENA_M (BIT(2))
#define MCP_OUT_DONE_INT_ENA_V 0x1
#define MCP_OUT_DONE_INT_ENA_S 2
/* MCP_IN_SUC_EOF_INT_ENA : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_SUC_EOF_INT_ENA (BIT(1))
#define MCP_IN_SUC_EOF_INT_ENA_M (BIT(1))
#define MCP_IN_SUC_EOF_INT_ENA_V 0x1
#define MCP_IN_SUC_EOF_INT_ENA_S 1
/* MCP_IN_DONE_INT_ENA : R/W ;bitpos:[0] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_DONE_INT_ENA (BIT(0))
#define MCP_IN_DONE_INT_ENA_M (BIT(0))
#define MCP_IN_DONE_INT_ENA_V 0x1
#define MCP_IN_DONE_INT_ENA_S 0
#define MCP_INT_CLR_REG (DR_REG_MCP_BASE + 0x000c)
/* MCP_CRC_DONE_INT_CLR : WO ;bitpos:[8] ;default: 1'b0 ; */
/*description: */
#define MCP_CRC_DONE_INT_CLR (BIT(8))
#define MCP_CRC_DONE_INT_CLR_M (BIT(8))
#define MCP_CRC_DONE_INT_CLR_V 0x1
#define MCP_CRC_DONE_INT_CLR_S 8
/* MCP_OUT_TOTAL_EOF_INT_CLR : WO ;bitpos:[7] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_TOTAL_EOF_INT_CLR (BIT(7))
#define MCP_OUT_TOTAL_EOF_INT_CLR_M (BIT(7))
#define MCP_OUT_TOTAL_EOF_INT_CLR_V 0x1
#define MCP_OUT_TOTAL_EOF_INT_CLR_S 7
/* MCP_IN_DSCR_EMPTY_INT_CLR : WO ;bitpos:[6] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_DSCR_EMPTY_INT_CLR (BIT(6))
#define MCP_IN_DSCR_EMPTY_INT_CLR_M (BIT(6))
#define MCP_IN_DSCR_EMPTY_INT_CLR_V 0x1
#define MCP_IN_DSCR_EMPTY_INT_CLR_S 6
/* MCP_OUT_DSCR_ERR_INT_CLR : WO ;bitpos:[5] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_DSCR_ERR_INT_CLR (BIT(5))
#define MCP_OUT_DSCR_ERR_INT_CLR_M (BIT(5))
#define MCP_OUT_DSCR_ERR_INT_CLR_V 0x1
#define MCP_OUT_DSCR_ERR_INT_CLR_S 5
/* MCP_IN_DSCR_ERR_INT_CLR : WO ;bitpos:[4] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_DSCR_ERR_INT_CLR (BIT(4))
#define MCP_IN_DSCR_ERR_INT_CLR_M (BIT(4))
#define MCP_IN_DSCR_ERR_INT_CLR_V 0x1
#define MCP_IN_DSCR_ERR_INT_CLR_S 4
/* MCP_OUT_EOF_INT_CLR : WO ;bitpos:[3] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_EOF_INT_CLR (BIT(3))
#define MCP_OUT_EOF_INT_CLR_M (BIT(3))
#define MCP_OUT_EOF_INT_CLR_V 0x1
#define MCP_OUT_EOF_INT_CLR_S 3
/* MCP_OUT_DONE_INT_CLR : WO ;bitpos:[2] ;default: 1'b0 ; */
/*description: */
#define MCP_OUT_DONE_INT_CLR (BIT(2))
#define MCP_OUT_DONE_INT_CLR_M (BIT(2))
#define MCP_OUT_DONE_INT_CLR_V 0x1
#define MCP_OUT_DONE_INT_CLR_S 2
/* MCP_IN_SUC_EOF_INT_CLR : WO ;bitpos:[1] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_SUC_EOF_INT_CLR (BIT(1))
#define MCP_IN_SUC_EOF_INT_CLR_M (BIT(1))
#define MCP_IN_SUC_EOF_INT_CLR_V 0x1
#define MCP_IN_SUC_EOF_INT_CLR_S 1
/* MCP_IN_DONE_INT_CLR : WO ;bitpos:[0] ;default: 1'b0 ; */
/*description: */
#define MCP_IN_DONE_INT_CLR (BIT(0))
#define MCP_IN_DONE_INT_CLR_M (BIT(0))
#define MCP_IN_DONE_INT_CLR_V 0x1
#define MCP_IN_DONE_INT_CLR_S 0
#define MCP_OUT_LINK_REG (DR_REG_MCP_BASE + 0x0010)
/* MCP_OUTLINK_PARK : RO ;bitpos:[31] ;default: 1'h0 ; */
/*description: */
#define MCP_OUTLINK_PARK (BIT(31))
#define MCP_OUTLINK_PARK_M (BIT(31))
#define MCP_OUTLINK_PARK_V 0x1
#define MCP_OUTLINK_PARK_S 31
/* MCP_OUTLINK_RESTART : R/W ;bitpos:[30] ;default: 1'b0 ; */
/*description: */
#define MCP_OUTLINK_RESTART (BIT(30))
#define MCP_OUTLINK_RESTART_M (BIT(30))
#define MCP_OUTLINK_RESTART_V 0x1
#define MCP_OUTLINK_RESTART_S 30
/* MCP_OUTLINK_START : R/W ;bitpos:[29] ;default: 1'b0 ; */
/*description: */
#define MCP_OUTLINK_START (BIT(29))
#define MCP_OUTLINK_START_M (BIT(29))
#define MCP_OUTLINK_START_V 0x1
#define MCP_OUTLINK_START_S 29
/* MCP_OUTLINK_STOP : R/W ;bitpos:[28] ;default: 1'b0 ; */
/*description: */
#define MCP_OUTLINK_STOP (BIT(28))
#define MCP_OUTLINK_STOP_M (BIT(28))
#define MCP_OUTLINK_STOP_V 0x1
#define MCP_OUTLINK_STOP_S 28
/* MCP_OUTLINK_ADDR : R/W ;bitpos:[19:0] ;default: 20'h0 ; */
/*description: */
#define MCP_OUTLINK_ADDR 0x000FFFFF
#define MCP_OUTLINK_ADDR_M ((MCP_OUTLINK_ADDR_V)<<(MCP_OUTLINK_ADDR_S))
#define MCP_OUTLINK_ADDR_V 0xFFFFF
#define MCP_OUTLINK_ADDR_S 0
#define MCP_IN_LINK_REG (DR_REG_MCP_BASE + 0x0014)
/* MCP_INLINK_PARK : RO ;bitpos:[31] ;default: 1'h0 ; */
/*description: */
#define MCP_INLINK_PARK (BIT(31))
#define MCP_INLINK_PARK_M (BIT(31))
#define MCP_INLINK_PARK_V 0x1
#define MCP_INLINK_PARK_S 31
/* MCP_INLINK_RESTART : R/W ;bitpos:[30] ;default: 1'b0 ; */
/*description: */
#define MCP_INLINK_RESTART (BIT(30))
#define MCP_INLINK_RESTART_M (BIT(30))
#define MCP_INLINK_RESTART_V 0x1
#define MCP_INLINK_RESTART_S 30
/* MCP_INLINK_START : R/W ;bitpos:[29] ;default: 1'b0 ; */
/*description: */
#define MCP_INLINK_START (BIT(29))
#define MCP_INLINK_START_M (BIT(29))
#define MCP_INLINK_START_V 0x1
#define MCP_INLINK_START_S 29
/* MCP_INLINK_STOP : R/W ;bitpos:[28] ;default: 1'b0 ; */
/*description: */
#define MCP_INLINK_STOP (BIT(28))
#define MCP_INLINK_STOP_M (BIT(28))
#define MCP_INLINK_STOP_V 0x1
#define MCP_INLINK_STOP_S 28
/* MCP_INLINK_ADDR : R/W ;bitpos:[19:0] ;default: 20'h0 ; */
/*description: */
#define MCP_INLINK_ADDR 0x000FFFFF
#define MCP_INLINK_ADDR_M ((MCP_INLINK_ADDR_V)<<(MCP_INLINK_ADDR_S))
#define MCP_INLINK_ADDR_V 0xFFFFF
#define MCP_INLINK_ADDR_S 0
#define MCP_OUT_EOF_DES_ADDR_REG (DR_REG_MCP_BASE + 0x0018)
/* MCP_OUT_EOF_DES_ADDR : RO ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: */
#define MCP_OUT_EOF_DES_ADDR 0xFFFFFFFF
#define MCP_OUT_EOF_DES_ADDR_M ((MCP_OUT_EOF_DES_ADDR_V)<<(MCP_OUT_EOF_DES_ADDR_S))
#define MCP_OUT_EOF_DES_ADDR_V 0xFFFFFFFF
#define MCP_OUT_EOF_DES_ADDR_S 0
#define MCP_IN_EOF_DES_ADDR_REG (DR_REG_MCP_BASE + 0x001c)
/* MCP_IN_SUC_EOF_DES_ADDR : RO ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: */
#define MCP_IN_SUC_EOF_DES_ADDR 0xFFFFFFFF
#define MCP_IN_SUC_EOF_DES_ADDR_M ((MCP_IN_SUC_EOF_DES_ADDR_V)<<(MCP_IN_SUC_EOF_DES_ADDR_S))
#define MCP_IN_SUC_EOF_DES_ADDR_V 0xFFFFFFFF
#define MCP_IN_SUC_EOF_DES_ADDR_S 0
#define MCP_OUT_EOF_BFR_DES_ADDR_REG (DR_REG_MCP_BASE + 0x0020)
/* MCP_OUT_EOF_BFR_DES_ADDR : RO ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: */
#define MCP_OUT_EOF_BFR_DES_ADDR 0xFFFFFFFF
#define MCP_OUT_EOF_BFR_DES_ADDR_M ((MCP_OUT_EOF_BFR_DES_ADDR_V)<<(MCP_OUT_EOF_BFR_DES_ADDR_S))
#define MCP_OUT_EOF_BFR_DES_ADDR_V 0xFFFFFFFF
#define MCP_OUT_EOF_BFR_DES_ADDR_S 0
#define MCP_INLINK_DSCR_REG (DR_REG_MCP_BASE + 0x0024)
/* MCP_INLINK_DSCR : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define MCP_INLINK_DSCR 0xFFFFFFFF
#define MCP_INLINK_DSCR_M ((MCP_INLINK_DSCR_V)<<(MCP_INLINK_DSCR_S))
#define MCP_INLINK_DSCR_V 0xFFFFFFFF
#define MCP_INLINK_DSCR_S 0
#define MCP_INLINK_DSCR_BF0_REG (DR_REG_MCP_BASE + 0x0028)
/* MCP_INLINK_DSCR_BF0 : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define MCP_INLINK_DSCR_BF0 0xFFFFFFFF
#define MCP_INLINK_DSCR_BF0_M ((MCP_INLINK_DSCR_BF0_V)<<(MCP_INLINK_DSCR_BF0_S))
#define MCP_INLINK_DSCR_BF0_V 0xFFFFFFFF
#define MCP_INLINK_DSCR_BF0_S 0
#define MCP_INLINK_DSCR_BF1_REG (DR_REG_MCP_BASE + 0x002c)
/* MCP_INLINK_DSCR_BF1 : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define MCP_INLINK_DSCR_BF1 0xFFFFFFFF
#define MCP_INLINK_DSCR_BF1_M ((MCP_INLINK_DSCR_BF1_V)<<(MCP_INLINK_DSCR_BF1_S))
#define MCP_INLINK_DSCR_BF1_V 0xFFFFFFFF
#define MCP_INLINK_DSCR_BF1_S 0
#define MCP_OUTLINK_DSCR_REG (DR_REG_MCP_BASE + 0x0030)
/* MCP_OUTLINK_DSCR : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define MCP_OUTLINK_DSCR 0xFFFFFFFF
#define MCP_OUTLINK_DSCR_M ((MCP_OUTLINK_DSCR_V)<<(MCP_OUTLINK_DSCR_S))
#define MCP_OUTLINK_DSCR_V 0xFFFFFFFF
#define MCP_OUTLINK_DSCR_S 0
#define MCP_OUTLINK_DSCR_BF0_REG (DR_REG_MCP_BASE + 0x0034)
/* MCP_OUTLINK_DSCR_BF0 : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define MCP_OUTLINK_DSCR_BF0 0xFFFFFFFF
#define MCP_OUTLINK_DSCR_BF0_M ((MCP_OUTLINK_DSCR_BF0_V)<<(MCP_OUTLINK_DSCR_BF0_S))
#define MCP_OUTLINK_DSCR_BF0_V 0xFFFFFFFF
#define MCP_OUTLINK_DSCR_BF0_S 0
#define MCP_OUTLINK_DSCR_BF1_REG (DR_REG_MCP_BASE + 0x0038)
/* MCP_OUTLINK_DSCR_BF1 : RO ;bitpos:[31:0] ;default: 32'b0 ; */
/*description: */
#define MCP_OUTLINK_DSCR_BF1 0xFFFFFFFF
#define MCP_OUTLINK_DSCR_BF1_M ((MCP_OUTLINK_DSCR_BF1_V)<<(MCP_OUTLINK_DSCR_BF1_S))
#define MCP_OUTLINK_DSCR_BF1_V 0xFFFFFFFF
#define MCP_OUTLINK_DSCR_BF1_S 0
#define MCP_CONF_REG (DR_REG_MCP_BASE + 0x003c)
/* MCP_CLK_EN : R/W ;bitpos:[31] ;default: 1'h0 ; */
/*description: */
#define MCP_CLK_EN (BIT(31))
#define MCP_CLK_EN_M (BIT(31))
#define MCP_CLK_EN_V 0x1
#define MCP_CLK_EN_S 31
/* MCP_CRC_OUT_REVERSE_EN : R/W ;bitpos:[11] ;default: 1'b0 ; */
/*description: */
#define MCP_CRC_OUT_REVERSE_EN (BIT(11))
#define MCP_CRC_OUT_REVERSE_EN_M (BIT(11))
#define MCP_CRC_OUT_REVERSE_EN_V 0x1
#define MCP_CRC_OUT_REVERSE_EN_S 11
/* MCP_CRC_BIG_ENDIAN_EN : R/W ;bitpos:[10] ;default: 1'b0 ; */
/*description: Set this bit to reorder the bit of data which will be send to excute crc.*/
#define MCP_CRC_BIG_ENDIAN_EN (BIT(10))
#define MCP_CRC_BIG_ENDIAN_EN_M (BIT(10))
#define MCP_CRC_BIG_ENDIAN_EN_V 0x1
#define MCP_CRC_BIG_ENDIAN_EN_S 10
/* MCP_CRC_CAL_EN : R/W ;bitpos:[9] ;default: 1'b0 ; */
/*description: Set this bit enable crc calculation function.*/
#define MCP_CRC_CAL_EN (BIT(9))
#define MCP_CRC_CAL_EN_M (BIT(9))
#define MCP_CRC_CAL_EN_V 0x1
#define MCP_CRC_CAL_EN_S 9
/* MCP_CRC_CAL_RESET : R/W ;bitpos:[8] ;default: 1'b0 ; */
/*description: Set this bit to reset crc calculation.*/
#define MCP_CRC_CAL_RESET (BIT(8))
#define MCP_CRC_CAL_RESET_M (BIT(8))
#define MCP_CRC_CAL_RESET_V 0x1
#define MCP_CRC_CAL_RESET_S 8
/* MCP_CHECK_OWNER : R/W ;bitpos:[7] ;default: 1'b0 ; */
/*description: Set this bit to enable owner bit check in descriptor.*/
#define MCP_CHECK_OWNER (BIT(7))
#define MCP_CHECK_OWNER_M (BIT(7))
#define MCP_CHECK_OWNER_V 0x1
#define MCP_CHECK_OWNER_S 7
/* MCP_OUT_AUTO_WRBACK : R/W ;bitpos:[6] ;default: 1'b0 ; */
/*description: this bit is used to write back out descriptor when hardware has
already used this descriptor.*/
#define MCP_OUT_AUTO_WRBACK (BIT(6))
#define MCP_OUT_AUTO_WRBACK_M (BIT(6))
#define MCP_OUT_AUTO_WRBACK_V 0x1
#define MCP_OUT_AUTO_WRBACK_S 6
/* MCP_IN_OWNER : R/W ;bitpos:[5] ;default: 1'b0 ; */
/*description: This is used to configure the owner bit in IN descriptor.*/
#define MCP_IN_OWNER (BIT(5))
#define MCP_IN_OWNER_M (BIT(5))
#define MCP_IN_OWNER_V 0x1
#define MCP_IN_OWNER_S 5
/* MCP_OUT_OWNER : R/W ;bitpos:[4] ;default: 1'b0 ; */
/*description: This is used to configure the owner bit in OUT descriptor. This
is effective only when you set reg_out_auto_wrback.*/
#define MCP_OUT_OWNER (BIT(4))
#define MCP_OUT_OWNER_M (BIT(4))
#define MCP_OUT_OWNER_V 0x1
#define MCP_OUT_OWNER_S 4
/* MCP_FIFO_RST : R/W ;bitpos:[3] ;default: 1'b0 ; */
/*description: */
#define MCP_FIFO_RST (BIT(3))
#define MCP_FIFO_RST_M (BIT(3))
#define MCP_FIFO_RST_V 0x1
#define MCP_FIFO_RST_S 3
/* MCP_CMDFIFO_RST : R/W ;bitpos:[2] ;default: 1'b0 ; */
/*description: set this bit to reset in_cmdfifo and out_cmdfifo.*/
#define MCP_CMDFIFO_RST (BIT(2))
#define MCP_CMDFIFO_RST_M (BIT(2))
#define MCP_CMDFIFO_RST_V 0x1
#define MCP_CMDFIFO_RST_S 2
/* MCP_OUT_RST : R/W ;bitpos:[1] ;default: 1'b0 ; */
/*description: set this bit to reset out_inf state machine.*/
#define MCP_OUT_RST (BIT(1))
#define MCP_OUT_RST_M (BIT(1))
#define MCP_OUT_RST_V 0x1
#define MCP_OUT_RST_S 1
/* MCP_IN_RST : R/W ;bitpos:[0] ;default: 1'h0 ; */
/*description: set this bit to reset in_inf state machine.*/
#define MCP_IN_RST (BIT(0))
#define MCP_IN_RST_M (BIT(0))
#define MCP_IN_RST_V 0x1
#define MCP_IN_RST_S 0
#define MCP_IN_ST_REG (DR_REG_MCP_BASE + 0x0040)
/* MCP_FIFO_EMPTY : RO ;bitpos:[23] ;default: 1'b0 ; */
/*description: */
#define MCP_FIFO_EMPTY (BIT(23))
#define MCP_FIFO_EMPTY_M (BIT(23))
#define MCP_FIFO_EMPTY_V 0x1
#define MCP_FIFO_EMPTY_S 23
/* MCP_IN_STATE : RO ;bitpos:[22:20] ;default: 3'b0 ; */
/*description: */
#define MCP_IN_STATE 0x00000007
#define MCP_IN_STATE_M ((MCP_IN_STATE_V)<<(MCP_IN_STATE_S))
#define MCP_IN_STATE_V 0x7
#define MCP_IN_STATE_S 20
/* MCP_IN_DSCR_STATE : RO ;bitpos:[19:18] ;default: 2'b0 ; */
/*description: */
#define MCP_IN_DSCR_STATE 0x00000003
#define MCP_IN_DSCR_STATE_M ((MCP_IN_DSCR_STATE_V)<<(MCP_IN_DSCR_STATE_S))
#define MCP_IN_DSCR_STATE_V 0x3
#define MCP_IN_DSCR_STATE_S 18
/* MCP_INLINK_DSCR_ADDR : RO ;bitpos:[17:0] ;default: 18'b0 ; */
/*description: */
#define MCP_INLINK_DSCR_ADDR 0x0003FFFF
#define MCP_INLINK_DSCR_ADDR_M ((MCP_INLINK_DSCR_ADDR_V)<<(MCP_INLINK_DSCR_ADDR_S))
#define MCP_INLINK_DSCR_ADDR_V 0x3FFFF
#define MCP_INLINK_DSCR_ADDR_S 0
#define MCP_OUT_ST_REG (DR_REG_MCP_BASE + 0x0044)
/* MCP_FIFO_FULL : RO ;bitpos:[23] ;default: 1'b0 ; */
/*description: */
#define MCP_FIFO_FULL (BIT(23))
#define MCP_FIFO_FULL_M (BIT(23))
#define MCP_FIFO_FULL_V 0x1
#define MCP_FIFO_FULL_S 23
/* MCP_OUT_STATE : RO ;bitpos:[22:20] ;default: 3'b0 ; */
/*description: */
#define MCP_OUT_STATE 0x00000007
#define MCP_OUT_STATE_M ((MCP_OUT_STATE_V)<<(MCP_OUT_STATE_S))
#define MCP_OUT_STATE_V 0x7
#define MCP_OUT_STATE_S 20
/* MCP_OUT_DSCR_STATE : RO ;bitpos:[19:18] ;default: 2'b0 ; */
/*description: */
#define MCP_OUT_DSCR_STATE 0x00000003
#define MCP_OUT_DSCR_STATE_M ((MCP_OUT_DSCR_STATE_V)<<(MCP_OUT_DSCR_STATE_S))
#define MCP_OUT_DSCR_STATE_V 0x3
#define MCP_OUT_DSCR_STATE_S 18
/* MCP_OUTLINK_DSCR_ADDR : RO ;bitpos:[17:0] ;default: 18'b0 ; */
/*description: */
#define MCP_OUTLINK_DSCR_ADDR 0x0003FFFF
#define MCP_OUTLINK_DSCR_ADDR_M ((MCP_OUTLINK_DSCR_ADDR_V)<<(MCP_OUTLINK_DSCR_ADDR_S))
#define MCP_OUTLINK_DSCR_ADDR_V 0x3FFFF
#define MCP_OUTLINK_DSCR_ADDR_S 0
#define MCP_CRC_OUT_REG (DR_REG_MCP_BASE + 0x0048)
/* MCP_CRC_RESULT : RO ;bitpos:[31:0] ;default: 32'h0 ; */
/*description: */
#define MCP_CRC_RESULT 0xFFFFFFFF
#define MCP_CRC_RESULT_M ((MCP_CRC_RESULT_V)<<(MCP_CRC_RESULT_S))
#define MCP_CRC_RESULT_V 0xFFFFFFFF
#define MCP_CRC_RESULT_S 0
#define MCP_DATE_REG (DR_REG_MCP_BASE + 0x00fc)
/* MCP_DMA_DATE : R/W ;bitpos:[31:0] ;default: 32'h18082000 ; */
/*description: */
#define MCP_DMA_DATE 0xFFFFFFFF
#define MCP_DMA_DATE_M ((MCP_DMA_DATE_V)<<(MCP_DMA_DATE_S))
#define MCP_DMA_DATE_V 0xFFFFFFFF
#define MCP_DMA_DATE_S 0
#ifdef __cplusplus
}
#endif
#endif /*_SOC_MCP_REG_H_ */

View File

@ -1,203 +0,0 @@
// Copyright 2017-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.
#ifndef _SOC_MCP_STRUCT_H_
#define _SOC_MCP_STRUCT_H_
#ifdef __cplusplus
extern "C" {
#endif
typedef volatile struct {
union {
struct {
uint32_t in_done: 1;
uint32_t in_suc_eof: 1;
uint32_t out_done: 1;
uint32_t out_eof: 1;
uint32_t in_dscr_err: 1;
uint32_t out_dscr_err: 1;
uint32_t in_dscr_empty: 1;
uint32_t out_total_eof: 1;
uint32_t crc_done: 1;
uint32_t reserved9: 23;
};
uint32_t val;
} int_raw;
union {
struct {
uint32_t in_done: 1;
uint32_t in_suc_eof: 1;
uint32_t out_done: 1;
uint32_t out_eof: 1;
uint32_t in_dscr_err: 1;
uint32_t out_dscr_err: 1;
uint32_t in_dscr_empty: 1;
uint32_t out_total_eof: 1;
uint32_t crc_done: 1;
uint32_t reserved9: 23;
};
uint32_t val;
} int_st;
union {
struct {
uint32_t in_done: 1;
uint32_t in_suc_eof: 1;
uint32_t out_done: 1;
uint32_t out_eof: 1;
uint32_t in_dscr_err: 1;
uint32_t out_dscr_err: 1;
uint32_t in_dscr_empty: 1;
uint32_t out_total_eof: 1;
uint32_t crc_done: 1;
uint32_t reserved9: 23;
};
uint32_t val;
} int_ena;
union {
struct {
uint32_t in_done: 1;
uint32_t in_suc_eof: 1;
uint32_t out_done: 1;
uint32_t out_eof: 1;
uint32_t in_dscr_err: 1;
uint32_t out_dscr_err: 1;
uint32_t in_dscr_empty: 1;
uint32_t out_total_eof: 1;
uint32_t crc_done: 1;
uint32_t reserved9: 23;
};
uint32_t val;
} int_clr;
union {
struct {
uint32_t addr: 20;
uint32_t reserved20: 8;
uint32_t stop: 1;
uint32_t start: 1;
uint32_t restart: 1;
uint32_t park: 1;
};
uint32_t val;
} out_link;
union {
struct {
uint32_t addr: 20;
uint32_t reserved20: 8;
uint32_t stop: 1;
uint32_t start: 1;
uint32_t restart: 1;
uint32_t park: 1;
};
uint32_t val;
} in_link;
uint32_t out_eof_des_addr; /**/
uint32_t in_eof_des_addr; /**/
uint32_t out_eof_bfr_des_addr; /**/
uint32_t inlink_dscr; /**/
uint32_t inlink_dscr_bf0; /**/
uint32_t inlink_dscr_bf1; /**/
uint32_t outlink_dscr; /**/
uint32_t outlink_dscr_bf0; /**/
uint32_t outlink_dscr_bf1; /**/
union {
struct {
uint32_t in_rst: 1; /*set this bit to reset in_inf state machine.*/
uint32_t out_rst: 1; /*set this bit to reset out_inf state machine.*/
uint32_t cmdfifo_rst: 1; /*set this bit to reset in_cmdfifo and out_cmdfifo.*/
uint32_t fifo_rst: 1;
uint32_t out_owner: 1; /*This is used to configure the owner bit in OUT descriptor. This is effective only when you set reg_out_auto_wrback.*/
uint32_t in_owner: 1; /*This is used to configure the owner bit in IN descriptor.*/
uint32_t out_auto_wrback: 1; /*this bit is used to write back out descriptor when hardware has already used this descriptor.*/
uint32_t check_owner: 1; /*Set this bit to enable owner bit check in descriptor.*/
uint32_t crc_cal_reset: 1; /*Set this bit to reset crc calculation.*/
uint32_t crc_cal_en: 1; /*Set this bit enable crc calculation function.*/
uint32_t crc_big_endian_en: 1; /*Set this bit to reorder the bit of data which will be send to excute crc.*/
uint32_t crc_out_reverse_en: 1;
uint32_t reserved12: 19;
uint32_t clk_en: 1;
};
uint32_t val;
} conf;
union {
struct {
uint32_t dscr_addr: 18;
uint32_t dscr_state: 2;
uint32_t state: 3;
uint32_t fifo_empty: 1;
uint32_t reserved24: 8;
};
uint32_t val;
} in_st;
union {
struct {
uint32_t dscr_addr: 18;
uint32_t dscr_state: 2;
uint32_t state: 3;
uint32_t fifo_full: 1;
uint32_t reserved24: 8;
};
uint32_t val;
} out_st;
uint32_t crc_out; /**/
uint32_t reserved_4c;
uint32_t reserved_50;
uint32_t reserved_54;
uint32_t reserved_58;
uint32_t reserved_5c;
uint32_t reserved_60;
uint32_t reserved_64;
uint32_t reserved_68;
uint32_t reserved_6c;
uint32_t reserved_70;
uint32_t reserved_74;
uint32_t reserved_78;
uint32_t reserved_7c;
uint32_t reserved_80;
uint32_t reserved_84;
uint32_t reserved_88;
uint32_t reserved_8c;
uint32_t reserved_90;
uint32_t reserved_94;
uint32_t reserved_98;
uint32_t reserved_9c;
uint32_t reserved_a0;
uint32_t reserved_a4;
uint32_t reserved_a8;
uint32_t reserved_ac;
uint32_t reserved_b0;
uint32_t reserved_b4;
uint32_t reserved_b8;
uint32_t reserved_bc;
uint32_t reserved_c0;
uint32_t reserved_c4;
uint32_t reserved_c8;
uint32_t reserved_cc;
uint32_t reserved_d0;
uint32_t reserved_d4;
uint32_t reserved_d8;
uint32_t reserved_dc;
uint32_t reserved_e0;
uint32_t reserved_e4;
uint32_t reserved_e8;
uint32_t reserved_ec;
uint32_t reserved_f0;
uint32_t reserved_f4;
uint32_t reserved_f8;
uint32_t date; /**/
} mcp_dev_t;
extern mcp_dev_t MCP;
#ifdef __cplusplus
}
#endif
#endif /* _SOC_MCP_STRUCT_H_ */

View File

@ -43,7 +43,7 @@ typedef enum {
PERIPH_HSPI_MODULE, //SPI3
PERIPH_SPI2_DMA_MODULE,
PERIPH_SPI3_DMA_MODULE,
PERIPH_CAN_MODULE,
PERIPH_TWAI_MODULE,
PERIPH_RNG_MODULE,
PERIPH_WIFI_MODULE,
PERIPH_WIFI_BT_COMMON_MODULE,
@ -107,7 +107,7 @@ typedef enum {
ETS_PWM3_INTR_SOURCE, /**< interruot of PWM3, level*/
ETS_LEDC_INTR_SOURCE, /**< interrupt of LED PWM, level*/
ETS_EFUSE_INTR_SOURCE, /**< interrupt of efuse, level, not likely to use*/
ETS_CAN_INTR_SOURCE , /**< interrupt of can, level*/
ETS_TWAI_INTR_SOURCE , /**< interrupt of twai, level*/
ETS_USB_INTR_SOURCE = 48, /**< interrupt of USB, level*/
ETS_RTC_CORE_INTR_SOURCE, /**< interrupt of rtc core, level, include rtc watchdog*/

View File

@ -687,14 +687,6 @@ typedef struct {
void rtc_sleep_init(rtc_sleep_config_t cfg);
/**
* @brief Set target value of RTC counter for RTC_TIMER_TRIG_EN wakeup source
* @param t value of RTC counter at which wakeup from sleep will happen;
* only the lower 48 bits are used
*/
void rtc_sleep_set_wakeup_time(uint64_t t);
#define RTC_EXT0_TRIG_EN BIT(0) //!< EXT0 GPIO wakeup
#define RTC_EXT1_TRIG_EN BIT(1) //!< EXT1 GPIO wakeup
#define RTC_GPIO_TRIG_EN BIT(2) //!< GPIO wakeup (light sleep only)
@ -809,6 +801,7 @@ rtc_vddsdio_config_t rtc_vddsdio_get_config(void);
*/
void rtc_vddsdio_set_config(rtc_vddsdio_config_t config);
#ifdef __cplusplus
}
#endif

View File

@ -3114,30 +3114,30 @@ extern "C" {
#define RTC_CNTL_TOUCH_DEBOUNCE_M ((RTC_CNTL_TOUCH_DEBOUNCE_V)<<(RTC_CNTL_TOUCH_DEBOUNCE_S))
#define RTC_CNTL_TOUCH_DEBOUNCE_V 0x7
#define RTC_CNTL_TOUCH_DEBOUNCE_S 25
/* RTC_CNTL_TOUCH_HYSTERESIS : R/W ;bitpos:[24:23] ;default: 2'd1 ; */
/* RTC_CNTL_TOUCH_CONFIG3 : R/W ;bitpos:[24:23] ;default: 2'd1 ; */
/*description: */
#define RTC_CNTL_TOUCH_HYSTERESIS 0x00000003
#define RTC_CNTL_TOUCH_HYSTERESIS_M ((RTC_CNTL_TOUCH_HYSTERESIS_V)<<(RTC_CNTL_TOUCH_HYSTERESIS_S))
#define RTC_CNTL_TOUCH_HYSTERESIS_V 0x3
#define RTC_CNTL_TOUCH_HYSTERESIS_S 23
#define RTC_CNTL_TOUCH_CONFIG3 0x00000003
#define RTC_CNTL_TOUCH_CONFIG3_M ((RTC_CNTL_TOUCH_CONFIG3_V)<<(RTC_CNTL_TOUCH_CONFIG3_S))
#define RTC_CNTL_TOUCH_CONFIG3_V 0x3
#define RTC_CNTL_TOUCH_CONFIG3_S 23
/* RTC_CNTL_TOUCH_NOISE_THRES : R/W ;bitpos:[22:21] ;default: 2'd1 ; */
/*description: */
#define RTC_CNTL_TOUCH_NOISE_THRES 0x00000003
#define RTC_CNTL_TOUCH_NOISE_THRES_M ((RTC_CNTL_TOUCH_NOISE_THRES_V)<<(RTC_CNTL_TOUCH_NOISE_THRES_S))
#define RTC_CNTL_TOUCH_NOISE_THRES_V 0x3
#define RTC_CNTL_TOUCH_NOISE_THRES_S 21
/* RTC_CNTL_TOUCH_NEG_NOISE_THRES : R/W ;bitpos:[20:19] ;default: 2'd1 ; */
/* RTC_CNTL_TOUCH_CONFIG2 : R/W ;bitpos:[20:19] ;default: 2'd1 ; */
/*description: */
#define RTC_CNTL_TOUCH_NEG_NOISE_THRES 0x00000003
#define RTC_CNTL_TOUCH_NEG_NOISE_THRES_M ((RTC_CNTL_TOUCH_NEG_NOISE_THRES_V)<<(RTC_CNTL_TOUCH_NEG_NOISE_THRES_S))
#define RTC_CNTL_TOUCH_NEG_NOISE_THRES_V 0x3
#define RTC_CNTL_TOUCH_NEG_NOISE_THRES_S 19
/* RTC_CNTL_TOUCH_NEG_NOISE_LIMIT : R/W ;bitpos:[18:15] ;default: 4'd5 ; */
/*description: negative threshold counter limit*/
#define RTC_CNTL_TOUCH_NEG_NOISE_LIMIT 0x0000000F
#define RTC_CNTL_TOUCH_NEG_NOISE_LIMIT_M ((RTC_CNTL_TOUCH_NEG_NOISE_LIMIT_V)<<(RTC_CNTL_TOUCH_NEG_NOISE_LIMIT_S))
#define RTC_CNTL_TOUCH_NEG_NOISE_LIMIT_V 0xF
#define RTC_CNTL_TOUCH_NEG_NOISE_LIMIT_S 15
#define RTC_CNTL_TOUCH_CONFIG2 0x00000003
#define RTC_CNTL_TOUCH_CONFIG2_M ((RTC_CNTL_TOUCH_CONFIG2_V)<<(RTC_CNTL_TOUCH_CONFIG2_S))
#define RTC_CNTL_TOUCH_CONFIG2_V 0x3
#define RTC_CNTL_TOUCH_CONFIG2_S 19
/* RTC_CNTL_TOUCH_CONFIG1 : R/W ;bitpos:[18:15] ;default: 4'd5 ; */
/*description: */
#define RTC_CNTL_TOUCH_CONFIG1 0x0000000F
#define RTC_CNTL_TOUCH_CONFIG1_M ((RTC_CNTL_TOUCH_CONFIG1_V)<<(RTC_CNTL_TOUCH_CONFIG1_S))
#define RTC_CNTL_TOUCH_CONFIG1_V 0xF
#define RTC_CNTL_TOUCH_CONFIG1_S 15
/* RTC_CNTL_TOUCH_JITTER_STEP : R/W ;bitpos:[14:11] ;default: 4'd1 ; */
/*description: touch jitter step*/
#define RTC_CNTL_TOUCH_JITTER_STEP 0x0000000F

View File

@ -800,10 +800,10 @@ typedef volatile struct {
uint32_t reserved0: 9;
uint32_t touch_smooth_lvl: 2;
uint32_t touch_jitter_step: 4; /*touch jitter step*/
uint32_t touch_neg_noise_limit: 4; /*negative threshold counter limit*/
uint32_t touch_neg_noise_thres: 2;
uint32_t config1: 4;
uint32_t config2: 2;
uint32_t touch_noise_thres: 2;
uint32_t touch_hysteresis: 2;
uint32_t config3: 2;
uint32_t touch_debounce: 3; /*debounce counter*/
uint32_t touch_filter_mode: 3; /*0: IIR ? 1: IIR ? 2: IIR 1/8 3: Jitter*/
uint32_t touch_filter_en: 1; /*touch filter enable*/

View File

@ -631,7 +631,7 @@ extern "C" {
#define SENS_TOUCH_DENOISE_END_V 0x1
#define SENS_TOUCH_DENOISE_END_S 18
/* SENS_TOUCH_DATA_SEL : R/W ;bitpos:[17:16] ;default: 2'd0 ; */
/*description: 3: smooth data 2: baseline 1 0: raw_data*/
/*description: 3: smooth data 2: benchmark 1 0: raw_data*/
#define SENS_TOUCH_DATA_SEL 0x00000003
#define SENS_TOUCH_DATA_SEL_M ((SENS_TOUCH_DATA_SEL_V)<<(SENS_TOUCH_DATA_SEL_S))
#define SENS_TOUCH_DATA_SEL_V 0x3

View File

@ -225,7 +225,7 @@ typedef volatile struct {
struct {
uint32_t touch_outen: 15; /*touch controller output enable*/
uint32_t touch_status_clr: 1; /*clear all touch active status*/
uint32_t touch_data_sel: 2; /*3: smooth data 2: baseline 1 0: raw_data*/
uint32_t touch_data_sel: 2; /*3: smooth data 2: benchmark 1 0: raw_data*/
uint32_t touch_denoise_end: 1; /*touch_denoise_done*/
uint32_t touch_unit_end: 1; /*touch_unit_done*/
uint32_t touch_approach_pad2: 4; /*indicate which pad is approach pad2*/

File diff suppressed because it is too large Load Diff

View File

@ -1,588 +0,0 @@
// Copyright 2017-2018 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.
#ifndef _SOC_SLC_STRUCT_H_
#define _SOC_SLC_STRUCT_H_
#ifdef __cplusplus
extern "C" {
#endif
typedef volatile struct {
union {
struct {
uint32_t slc0_tx_rst: 1;
uint32_t slc0_rx_rst: 1;
uint32_t ahbm_fifo_rst: 1;
uint32_t ahbm_rst: 1;
uint32_t slc0_tx_loop_test: 1;
uint32_t slc0_rx_loop_test: 1;
uint32_t slc0_rx_auto_wrback: 1;
uint32_t slc0_rx_no_restart_clr: 1;
uint32_t slc0_rxdscr_burst_en: 1;
uint32_t slc0_rxdata_burst_en: 1;
uint32_t slc0_rxlink_auto_ret: 1;
uint32_t slc0_txlink_auto_ret: 1;
uint32_t slc0_txdscr_burst_en: 1;
uint32_t slc0_txdata_burst_en: 1;
uint32_t slc0_token_auto_clr: 1;
uint32_t slc0_token_sel: 1;
uint32_t reserved16: 2;
uint32_t slc0_wr_retry_mask_en: 1;
uint32_t reserved19: 13;
};
uint32_t val;
} conf0;
union {
struct {
uint32_t frhost_bit0: 1;
uint32_t frhost_bit1: 1;
uint32_t frhost_bit2: 1;
uint32_t frhost_bit3: 1;
uint32_t frhost_bit4: 1;
uint32_t frhost_bit5: 1;
uint32_t frhost_bit6: 1;
uint32_t frhost_bit7: 1;
uint32_t rx_start: 1;
uint32_t tx_start: 1;
uint32_t rx_udf: 1;
uint32_t tx_ovf: 1;
uint32_t token0_1to0: 1;
uint32_t token1_1to0: 1;
uint32_t tx_done: 1;
uint32_t tx_suc_eof: 1;
uint32_t rx_done: 1;
uint32_t rx_eof: 1;
uint32_t tohost: 1;
uint32_t tx_dscr_err: 1;
uint32_t rx_dscr_err: 1;
uint32_t tx_dscr_empty: 1;
uint32_t host_rd_ack: 1;
uint32_t wr_retry_done: 1;
uint32_t tx_err_eof: 1;
uint32_t cmd_dtc: 1;
uint32_t rx_quick_eof: 1;
uint32_t host_pop_eof_err: 1;
uint32_t reserved28: 4;
};
uint32_t val;
} slc0_int_raw;
union {
struct {
uint32_t frhost_bit0: 1;
uint32_t frhost_bit1: 1;
uint32_t frhost_bit2: 1;
uint32_t frhost_bit3: 1;
uint32_t frhost_bit4: 1;
uint32_t frhost_bit5: 1;
uint32_t frhost_bit6: 1;
uint32_t frhost_bit7: 1;
uint32_t rx_start: 1;
uint32_t tx_start: 1;
uint32_t rx_udf: 1;
uint32_t tx_ovf: 1;
uint32_t token0_1to0: 1;
uint32_t token1_1to0: 1;
uint32_t tx_done: 1;
uint32_t tx_suc_eof: 1;
uint32_t rx_done: 1;
uint32_t rx_eof: 1;
uint32_t tohost: 1;
uint32_t tx_dscr_err: 1;
uint32_t rx_dscr_err: 1;
uint32_t tx_dscr_empty: 1;
uint32_t host_rd_ack: 1;
uint32_t wr_retry_done: 1;
uint32_t tx_err_eof: 1;
uint32_t cmd_dtc: 1;
uint32_t rx_quick_eof: 1;
uint32_t host_pop_eof_err: 1;
uint32_t reserved28: 4;
};
uint32_t val;
} slc0_int_st;
union {
struct {
uint32_t frhost_bit0: 1;
uint32_t frhost_bit1: 1;
uint32_t frhost_bit2: 1;
uint32_t frhost_bit3: 1;
uint32_t frhost_bit4: 1;
uint32_t frhost_bit5: 1;
uint32_t frhost_bit6: 1;
uint32_t frhost_bit7: 1;
uint32_t rx_start: 1;
uint32_t tx_start: 1;
uint32_t rx_udf: 1;
uint32_t tx_ovf: 1;
uint32_t token0_1to0: 1;
uint32_t token1_1to0: 1;
uint32_t tx_done: 1;
uint32_t tx_suc_eof: 1;
uint32_t rx_done: 1;
uint32_t rx_eof: 1;
uint32_t tohost: 1;
uint32_t tx_dscr_err: 1;
uint32_t rx_dscr_err: 1;
uint32_t tx_dscr_empty: 1;
uint32_t host_rd_ack: 1;
uint32_t wr_retry_done: 1;
uint32_t tx_err_eof: 1;
uint32_t cmd_dtc: 1;
uint32_t rx_quick_eof: 1;
uint32_t host_pop_eof_err: 1;
uint32_t reserved28: 4;
};
uint32_t val;
} slc0_int_ena;
union {
struct {
uint32_t frhost_bit0: 1;
uint32_t frhost_bit1: 1;
uint32_t frhost_bit2: 1;
uint32_t frhost_bit3: 1;
uint32_t frhost_bit4: 1;
uint32_t frhost_bit5: 1;
uint32_t frhost_bit6: 1;
uint32_t frhost_bit7: 1;
uint32_t rx_start: 1;
uint32_t tx_start: 1;
uint32_t rx_udf: 1;
uint32_t tx_ovf: 1;
uint32_t token0_1to0: 1;
uint32_t token1_1to0: 1;
uint32_t tx_done: 1;
uint32_t tx_suc_eof: 1;
uint32_t rx_done: 1;
uint32_t rx_eof: 1;
uint32_t tohost: 1;
uint32_t tx_dscr_err: 1;
uint32_t rx_dscr_err: 1;
uint32_t tx_dscr_empty: 1;
uint32_t host_rd_ack: 1;
uint32_t wr_retry_done: 1;
uint32_t tx_err_eof: 1;
uint32_t cmd_dtc: 1;
uint32_t rx_quick_eof: 1;
uint32_t host_pop_eof_err: 1;
uint32_t reserved28: 4;
};
uint32_t val;
} slc0_int_clr;
uint32_t reserved_14;
uint32_t reserved_18;
uint32_t reserved_1c;
uint32_t reserved_20;
union {
struct {
uint32_t slc0_rx_full: 1;
uint32_t slc0_rx_empty: 1;
uint32_t slc0_rx_buf_len:12;
uint32_t reserved14: 18;
};
uint32_t val;
} rx_status;
union {
struct {
uint32_t rxfifo_wdata: 9;
uint32_t reserved9: 7;
uint32_t rxfifo_push: 1;
uint32_t reserved17: 15;
};
uint32_t val;
} slc0_rxfifo_push;
uint32_t reserved_2c;
union {
struct {
uint32_t slc0_tx_full: 1;
uint32_t slc0_tx_empty: 1;
uint32_t reserved2: 30;
};
uint32_t val;
} tx_status;
union {
struct {
uint32_t txfifo_rdata: 11;
uint32_t reserved11: 5;
uint32_t txfifo_pop: 1;
uint32_t reserved17: 15;
};
uint32_t val;
} slc0_txfifo_pop;
uint32_t reserved_38;
union {
struct {
uint32_t addr: 20;
uint32_t reserved20: 8;
uint32_t stop: 1;
uint32_t start: 1;
uint32_t restart: 1;
uint32_t park: 1;
};
uint32_t val;
} slc0_rx_link;
union {
struct {
uint32_t addr: 20;
uint32_t reserved20: 8;
uint32_t stop: 1;
uint32_t start: 1;
uint32_t restart: 1;
uint32_t park: 1;
};
uint32_t val;
} slc0_tx_link;
uint32_t reserved_44;
uint32_t reserved_48;
union {
struct {
uint32_t slc0_intvec: 8;
uint32_t reserved8: 24;
};
uint32_t val;
} intvec_tohost;
union {
struct {
uint32_t wdata: 12;
uint32_t wr: 1;
uint32_t inc: 1;
uint32_t inc_more: 1;
uint32_t reserved15: 1;
uint32_t token0: 12;
uint32_t reserved28: 4;
};
uint32_t val;
} slc0_token0;
union {
struct {
uint32_t wdata: 12;
uint32_t wr: 1;
uint32_t inc: 1;
uint32_t inc_more: 1;
uint32_t reserved15: 1;
uint32_t token1: 12;
uint32_t reserved28: 4;
};
uint32_t val;
} slc0_token1;
uint32_t reserved_58;
uint32_t reserved_5c;
union {
struct {
uint32_t slc0_check_owner: 1;
uint32_t slc0_tx_check_sum_en: 1;
uint32_t slc0_rx_check_sum_en: 1;
uint32_t cmd_hold_en: 1;
uint32_t slc0_len_auto_clr: 1;
uint32_t slc0_tx_stitch_en: 1;
uint32_t slc0_rx_stitch_en: 1;
uint32_t reserved7: 12;
uint32_t host_int_level_sel: 1;
uint32_t reserved20: 2;
uint32_t clk_en: 1;
uint32_t reserved23: 9;
};
uint32_t val;
} conf1;
uint32_t slc0_state0; /**/
uint32_t slc0_state1; /**/
uint32_t reserved_6c;
uint32_t reserved_70;
union {
struct {
uint32_t txeof_ena: 6;
uint32_t reserved6: 2;
uint32_t fifo_map_ena: 4;
uint32_t slc0_tx_dummy_mode: 1;
uint32_t hda_map_128k: 1;
uint32_t reserved14: 2;
uint32_t tx_push_idle_num: 16;
};
uint32_t val;
} bridge_conf;
uint32_t slc0_to_eof_des_addr; /**/
uint32_t slc0_tx_eof_des_addr; /**/
uint32_t slc0_to_eof_bfr_des_addr; /**/
uint32_t reserved_84;
uint32_t reserved_88;
uint32_t reserved_8c;
union {
struct {
uint32_t mode: 3;
uint32_t reserved3: 1;
uint32_t addr: 2;
uint32_t reserved6: 26;
};
uint32_t val;
} ahb_test;
union {
struct {
uint32_t cmd_st: 3;
uint32_t reserved3: 1;
uint32_t func_st: 4;
uint32_t sdio_wakeup: 1;
uint32_t reserved9: 3;
uint32_t bus_st: 3;
uint32_t reserved15: 1;
uint32_t func1_acc_state: 5;
uint32_t reserved21: 11;
};
uint32_t val;
} sdio_st;
union {
struct {
uint32_t slc0_token_no_replace: 1;
uint32_t slc0_infor_no_replace: 1;
uint32_t slc0_rx_fill_mode: 1;
uint32_t slc0_rx_eof_mode: 1;
uint32_t slc0_rx_fill_en: 1;
uint32_t slc0_rd_retry_threshold:11;
uint32_t reserved16: 16;
};
uint32_t val;
} rx_dscr_conf;
uint32_t slc0_txlink_dscr; /**/
uint32_t slc0_txlink_dscr_bf0; /**/
uint32_t slc0_txlink_dscr_bf1; /**/
uint32_t slc0_rxlink_dscr; /**/
uint32_t slc0_rxlink_dscr_bf0; /**/
uint32_t slc0_rxlink_dscr_bf1; /**/
uint32_t reserved_b4;
uint32_t reserved_b8;
uint32_t reserved_bc;
uint32_t reserved_c0;
uint32_t reserved_c4;
uint32_t reserved_c8;
uint32_t slc0_tx_erreof_des_addr; /**/
uint32_t reserved_d0;
union {
struct {
uint32_t slc0_token:12;
uint32_t reserved12:20;
};
uint32_t val;
} token_lat;
union {
struct {
uint32_t wr_retry_threshold:11;
uint32_t reserved11: 21;
};
uint32_t val;
} tx_dscr_conf;
uint32_t cmd_infor0; /**/
uint32_t cmd_infor1; /**/
union {
struct {
uint32_t len_wdata: 20;
uint32_t len_wr: 1;
uint32_t len_inc: 1;
uint32_t len_inc_more: 1;
uint32_t rx_packet_load_en: 1;
uint32_t tx_packet_load_en: 1;
uint32_t rx_get_used_dscr: 1;
uint32_t tx_get_used_dscr: 1;
uint32_t rx_new_pkt_ind: 1;
uint32_t tx_new_pkt_ind: 1;
uint32_t reserved29: 3;
};
uint32_t val;
} slc0_len_conf;
union {
struct {
uint32_t len: 20;
uint32_t reserved20:12;
};
uint32_t val;
} slc0_length;
uint32_t slc0_txpkt_h_dscr; /**/
uint32_t slc0_txpkt_e_dscr; /**/
uint32_t slc0_rxpkt_h_dscr; /**/
uint32_t slc0_rxpkt_e_dscr; /**/
uint32_t slc0_txpktu_h_dscr; /**/
uint32_t slc0_txpktu_e_dscr; /**/
uint32_t slc0_rxpktu_h_dscr; /**/
uint32_t slc0_rxpktu_e_dscr; /**/
uint32_t reserved_10c;
uint32_t reserved_110;
union {
struct {
uint32_t slc0_position: 8;
uint32_t reserved8: 24;
};
uint32_t val;
} seq_position;
union {
struct {
uint32_t rx_dscr_rec_lim: 10;
uint32_t reserved10: 22;
};
uint32_t val;
} slc0_dscr_rec_conf;
union {
struct {
uint32_t dat0_crc_err_cnt: 8;
uint32_t dat1_crc_err_cnt: 8;
uint32_t dat2_crc_err_cnt: 8;
uint32_t dat3_crc_err_cnt: 8;
};
uint32_t val;
} sdio_crc_st0;
union {
struct {
uint32_t cmd_crc_err_cnt: 8;
uint32_t reserved8: 23;
uint32_t err_cnt_clr: 1;
};
uint32_t val;
} sdio_crc_st1;
uint32_t slc0_eof_start_des; /**/
uint32_t slc0_push_dscr_addr; /**/
uint32_t slc0_done_dscr_addr; /**/
uint32_t slc0_sub_start_des; /**/
union {
struct {
uint32_t rx_dscr_cnt_lat: 10;
uint32_t reserved10: 6;
uint32_t rx_get_eof_occ: 1;
uint32_t reserved17: 15;
};
uint32_t val;
} slc0_dscr_cnt;
union {
struct {
uint32_t len_lim: 20;
uint32_t reserved20: 12;
};
uint32_t val;
} slc0_len_lim_conf;
union {
struct {
uint32_t frhost_bit01: 1;
uint32_t frhost_bit11: 1;
uint32_t frhost_bit21: 1;
uint32_t frhost_bit31: 1;
uint32_t frhost_bit41: 1;
uint32_t frhost_bit51: 1;
uint32_t frhost_bit61: 1;
uint32_t frhost_bit71: 1;
uint32_t rx_start1: 1;
uint32_t tx_start1: 1;
uint32_t rx_udf1: 1;
uint32_t tx_ovf1: 1;
uint32_t token0_1to01: 1;
uint32_t token1_1to01: 1;
uint32_t tx_done1: 1;
uint32_t tx_suc_eof1: 1;
uint32_t rx_done1: 1;
uint32_t rx_eof1: 1;
uint32_t tohost1: 1;
uint32_t tx_dscr_err1: 1;
uint32_t rx_dscr_err1: 1;
uint32_t tx_dscr_empty1: 1;
uint32_t host_rd_ack1: 1;
uint32_t wr_retry_done1: 1;
uint32_t tx_err_eof1: 1;
uint32_t cmd_dtc1: 1;
uint32_t rx_quick_eof1: 1;
uint32_t host_pop_eof_err1: 1;
uint32_t reserved28: 4;
};
uint32_t val;
} slc0_int_st1;
union {
struct {
uint32_t frhost_bit01: 1;
uint32_t frhost_bit11: 1;
uint32_t frhost_bit21: 1;
uint32_t frhost_bit31: 1;
uint32_t frhost_bit41: 1;
uint32_t frhost_bit51: 1;
uint32_t frhost_bit61: 1;
uint32_t frhost_bit71: 1;
uint32_t rx_start1: 1;
uint32_t tx_start1: 1;
uint32_t rx_udf1: 1;
uint32_t tx_ovf1: 1;
uint32_t token0_1to01: 1;
uint32_t token1_1to01: 1;
uint32_t tx_done1: 1;
uint32_t tx_suc_eof1: 1;
uint32_t rx_done1: 1;
uint32_t rx_eof1: 1;
uint32_t tohost1: 1;
uint32_t tx_dscr_err1: 1;
uint32_t rx_dscr_err1: 1;
uint32_t tx_dscr_empty1: 1;
uint32_t host_rd_ack1: 1;
uint32_t wr_retry_done1: 1;
uint32_t tx_err_eof1: 1;
uint32_t cmd_dtc1: 1;
uint32_t rx_quick_eof1: 1;
uint32_t host_pop_eof_err1: 1;
uint32_t reserved28: 4;
};
uint32_t val;
} slc0_int_ena1;
uint32_t reserved_144;
uint32_t reserved_148;
uint32_t reserved_14c;
uint32_t reserved_150;
uint32_t reserved_154;
uint32_t reserved_158;
uint32_t reserved_15c;
uint32_t reserved_160;
uint32_t reserved_164;
uint32_t reserved_168;
uint32_t reserved_16c;
uint32_t reserved_170;
uint32_t reserved_174;
uint32_t reserved_178;
uint32_t reserved_17c;
uint32_t reserved_180;
uint32_t reserved_184;
uint32_t reserved_188;
uint32_t reserved_18c;
uint32_t reserved_190;
uint32_t reserved_194;
uint32_t reserved_198;
uint32_t reserved_19c;
uint32_t reserved_1a0;
uint32_t reserved_1a4;
uint32_t reserved_1a8;
uint32_t reserved_1ac;
uint32_t reserved_1b0;
uint32_t reserved_1b4;
uint32_t reserved_1b8;
uint32_t reserved_1bc;
uint32_t reserved_1c0;
uint32_t reserved_1c4;
uint32_t reserved_1c8;
uint32_t reserved_1cc;
uint32_t reserved_1d0;
uint32_t reserved_1d4;
uint32_t reserved_1d8;
uint32_t reserved_1dc;
uint32_t reserved_1e0;
uint32_t reserved_1e4;
uint32_t reserved_1e8;
uint32_t reserved_1ec;
uint32_t reserved_1f0;
uint32_t reserved_1f4;
uint32_t date; /**/
uint32_t id; /**/
} slc_dev_t;
extern slc_dev_t SLC;
#ifdef __cplusplus
}
#endif
#endif /* _SOC_SLC_STRUCT_H_ */

View File

@ -93,6 +93,10 @@
#define REG_SPI_MEM_BASE(i) (DR_REG_SPI0_BASE - (i) * 0x1000)
#define REG_I2C_BASE(i) (DR_REG_I2C_EXT_BASE + (i) * 0x14000 )
//Convenient way to replace the register ops when ulp riscv projects
//consume this file
#ifndef ULP_RISCV_REGISTER_OPS
//Registers Operation {{
#define ETS_UNCACHED_ADDR(addr) (addr)
#define ETS_CACHED_ADDR(addr) (addr)
@ -229,6 +233,7 @@
#endif /* !__ASSEMBLER__ */
//}}
#endif /* !ULP_RISCV_REGISTER_OPS */
//Periheral Clock {{
#define APB_CLK_FREQ_ROM ( 40*1000000 )

View File

@ -5,6 +5,7 @@
#pragma once
#define SOC_TWAI_SUPPORTED 1
#define SOC_CPU_CORES_NUM 1
#define SOC_SUPPORTS_SECURE_DL_MODE 1
#define SOC_RISCV_COPROC_SUPPORTED 1

View File

@ -16,7 +16,7 @@
#define SOC_SPI_PERIPH_NUM 3
#define SOC_SPI_DMA_CHAN_NUM 3
#define SOC_SPI_PERIPH_CS_NUM(i) 3
#define SOC_SPI_PERIPH_CS_NUM(i) (((i)==0)? 2: (((i)==1)? 6: 3))
#define SPI_FUNC_NUM 0
#define SPI_IOMUX_PIN_NUM_HD 27
@ -45,7 +45,8 @@
#define SOC_SPI_SLAVE_SUPPORT_SEG_TRANS 1
#define SOC_SPI_SUPPORT_CD_SIG 1
#define SOC_SPI_SUPPORT_CONTINUOUS_TRANS 1
/// The SPI Slave half duplex mode has been updated greatly in ESP32-S2
#define SOC_SPI_SUPPORT_SLAVE_HD_VER2 1
// Peripheral supports DIO, DOUT, QIO, or QOUT
// VSPI (SPI3) only support 1-bit mode
@ -55,3 +56,4 @@
// Only SPI1 supports this feature
#define SOC_SPI_PERIPH_SUPPORT_CONTROL_DUMMY_OUTPUT(host_id) ((host_id) == 0)
#define SOC_MEMSPI_IS_INDEPENDENT 1

View File

@ -262,12 +262,12 @@ extern "C" {
#define DPORT_PWM1_CLK_EN_M (BIT(20))
#define DPORT_PWM1_CLK_EN_V 0x1
#define DPORT_PWM1_CLK_EN_S 20
/* DPORT_CAN_CLK_EN : R/W ;bitpos:[19] ;default: 1'b0 ; */
/* DPORT_TWAI_CLK_EN : R/W ;bitpos:[19] ;default: 1'b0 ; */
/*description: */
#define DPORT_CAN_CLK_EN (BIT(19))
#define DPORT_CAN_CLK_EN_M (BIT(19))
#define DPORT_CAN_CLK_EN_V 0x1
#define DPORT_CAN_CLK_EN_S 19
#define DPORT_TWAI_CLK_EN (BIT(19))
#define DPORT_TWAI_CLK_EN_M (BIT(19))
#define DPORT_TWAI_CLK_EN_V 0x1
#define DPORT_TWAI_CLK_EN_S 19
/* DPORT_I2C_EXT1_CLK_EN : R/W ;bitpos:[18] ;default: 1'b0 ; */
/*description: */
#define DPORT_I2C_EXT1_CLK_EN (BIT(18))
@ -496,12 +496,12 @@ extern "C" {
#define DPORT_PWM1_RST_M (BIT(20))
#define DPORT_PWM1_RST_V 0x1
#define DPORT_PWM1_RST_S 20
/* DPORT_CAN_RST : R/W ;bitpos:[19] ;default: 1'b0 ; */
/* DPORT_TWAI_RST : R/W ;bitpos:[19] ;default: 1'b0 ; */
/*description: */
#define DPORT_CAN_RST (BIT(19))
#define DPORT_CAN_RST_M (BIT(19))
#define DPORT_CAN_RST_V 0x1
#define DPORT_CAN_RST_S 19
#define DPORT_TWAI_RST (BIT(19))
#define DPORT_TWAI_RST_M (BIT(19))
#define DPORT_TWAI_RST_V 0x1
#define DPORT_TWAI_RST_S 19
/* DPORT_I2C_EXT1_RST : R/W ;bitpos:[18] ;default: 1'b0 ; */
/*description: */
#define DPORT_I2C_EXT1_RST (BIT(18))

View File

@ -24,9 +24,7 @@ extern "C" {
#define SOC_TOUCH_PAD_MEASURE_WAIT (0xFF) /*!<The timer frequency is 8Mhz, the max value is 0xff */
#define SOC_TOUCH_PAD_THRESHOLD_MAX (0x1FFFFF) /*!<If set touch threshold max value, The touch sensor can't be in touched status */
#define SOC_TOUCH_SHIELD_CHANNEL (14) /*!< The waterproof function includes a shielded channel (TOUCH_PAD_NUM14)
The shielded channel outputs the same signal as the channel being measured.
It is generally designed as a grid and is placed around the touch buttons. */
#define SOC_TOUCH_SHIELD_CHANNEL (14) /*!< The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) */
#define SOC_TOUCH_DENOISE_CHANNEL (0) /*!< T0 is an internal channel that does not have a corresponding external GPIO.
T0 will work simultaneously with the measured channel Tn. Finally, the actual
measured value of Tn is the value after subtracting lower bits of T0. */

View File

@ -0,0 +1,26 @@
// 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 32768
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,208 @@
// 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 ms: 1; /* SR.8 Miss Status */
uint32_t reserved23: 23; /* 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 reserved2: 2; /* Internal Reserved (Data Overrun interrupt and Wake-up not supported) */
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: 14; /* BTR0[13:0] Baud Rate Prescaler */
uint32_t sjw: 2; /* BTR0[15:14] Synchronization Jump Width*/
uint32_t reserved16: 16; /* 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: 8; /* CDR[7:0] CLKOUT frequency selector based of fOSC */
uint32_t co: 1; /* CDR.8 CLKOUT enable/disable */
uint32_t reserved24: 23; /* 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

@ -20,10 +20,8 @@
extern "C" {
#endif
#if CONFIG_IDF_TARGET_ESP32
#include "soc/can_struct.h"
#include "soc/can_caps.h"
#endif
#include "soc/twai_struct.h"
#include "soc/twai_caps.h"
#ifdef __cplusplus
}

View File

@ -110,6 +110,19 @@ typedef enum {
#define ADC_LL_SAR1_SAMPLE_CYCLE_ADDR 0x2
#define ADC_LL_SAR1_SAMPLE_CYCLE_ADDR_MSB 0x2
#define ADC_LL_SAR1_SAMPLE_CYCLE_ADDR_LSB 0x0
#define ADC_LL_SARADC_DTEST_RTC_ADDR 0x7
#define ADC_LL_SARADC_DTEST_RTC_ADDR_MSB 1
#define ADC_LL_SARADC_DTEST_RTC_ADDR_LSB 0
#define ADC_LL_SARADC_ENT_TSENS_ADDR 0x7
#define ADC_LL_SARADC_ENT_TSENS_ADDR_MSB 2
#define ADC_LL_SARADC_ENT_TSENS_ADDR_LSB 2
#define ADC_LL_SARADC_ENT_RTC_ADDR 0x7
#define ADC_LL_SARADC_ENT_RTC_ADDR_MSB 3
#define ADC_LL_SARADC_ENT_RTC_ADDR_LSB 3
/* ADC calibration defines end. */
/*---------------------------------------------------------------
@ -1248,6 +1261,59 @@ static inline void adc_ll_set_calibration_param(adc_ll_num_t adc_n, uint32_t par
}
/* Temp code end. */
/**
* Output ADCn inter reference voltage to ADC2 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.
*
* @param[in] adc ADC unit select
* @param[in] channel ADC2 channel number
* @param[in] en Enable/disable the reference voltage output
*/
static inline void adc_ll_vref_output(adc_ll_num_t adc, adc_channel_t channel, bool en)
{
/* Should be called before writing I2C registers. */
void phy_get_romfunc_addr(void);
phy_get_romfunc_addr();
SET_PERI_REG_MASK(RTC_CNTL_ANA_CONF_REG, RTC_CNTL_SAR_I2C_FORCE_PU_M);
CLEAR_PERI_REG_MASK(ANA_CONFIG_REG, BIT(18));
SET_PERI_REG_MASK(ADC_LL_ANA_CONFIG2_REG, BIT(16));
if (en) {
if (adc == ADC_NUM_1) {
/* Config test mux to route v_ref to ADC1 Channels */
I2C_WRITEREG_MASK_RTC(ADC_LL_I2C_ADC, ADC_LL_SARADC_DTEST_RTC_ADDR, 1);
I2C_WRITEREG_MASK_RTC(ADC_LL_I2C_ADC, ADC_LL_SARADC_ENT_TSENS_ADDR, 0);
I2C_WRITEREG_MASK_RTC(ADC_LL_I2C_ADC, ADC_LL_SARADC_ENT_RTC_ADDR, 1);
} else {
/* Config test mux to route v_ref to ADC2 Channels */
I2C_WRITEREG_MASK_RTC(ADC_LL_I2C_ADC, ADC_LL_SARADC_DTEST_RTC_ADDR, 0);
I2C_WRITEREG_MASK_RTC(ADC_LL_I2C_ADC, ADC_LL_SARADC_ENT_TSENS_ADDR, 1);
I2C_WRITEREG_MASK_RTC(ADC_LL_I2C_ADC, ADC_LL_SARADC_ENT_RTC_ADDR, 0);
}
//in sleep force to use rtc to control ADC
SENS.sar_meas2_mux.sar2_rtc_force = 1;
//set sar2_en_test
SENS.sar_meas2_ctrl1.sar2_en_test = 1;
//set sar2 en force
SENS.sar_meas2_ctrl2.sar2_en_pad_force = 1; //Pad bitmap controlled by SW
//set en_pad for ADC2 channels (bits 0x380)
SENS.sar_meas2_ctrl2.sar2_en_pad = 1 << channel;
} else {
I2C_WRITEREG_MASK_RTC(ADC_LL_I2C_ADC, ADC_LL_SARADC_ENT_TSENS_ADDR, 0);
I2C_WRITEREG_MASK_RTC(ADC_LL_I2C_ADC, ADC_LL_SARADC_ENT_RTC_ADDR, 0);
SENS.sar_meas2_mux.sar2_rtc_force = 0;
//set sar2_en_test
SENS.sar_meas2_ctrl1.sar2_en_test = 0;
//set sar2 en force
SENS.sar_meas2_ctrl2.sar2_en_pad_force = 0; //Pad bitmap controlled by SW
//set en_pad for ADC2 channels (bits 0x380)
SENS.sar_meas2_ctrl2.sar2_en_pad = 0;
}
}
#ifdef __cplusplus
}
#endif

View File

@ -74,8 +74,8 @@ static inline uint32_t periph_ll_get_clk_en_mask(periph_module_t periph)
return DPORT_SPI2_DMA_CLK_EN;
case PERIPH_SPI3_DMA_MODULE:
return DPORT_SPI3_DMA_CLK_EN;
case PERIPH_CAN_MODULE:
return DPORT_CAN_CLK_EN;
case PERIPH_TWAI_MODULE:
return DPORT_TWAI_CLK_EN;
case PERIPH_RNG_MODULE:
return DPORT_WIFI_CLK_RNG_EN;
case PERIPH_WIFI_MODULE:
@ -152,8 +152,8 @@ static inline uint32_t periph_ll_get_rst_en_mask(periph_module_t periph, bool en
return DPORT_SPI2_DMA_RST;
case PERIPH_SPI3_DMA_MODULE:
return DPORT_SPI3_DMA_RST;
case PERIPH_CAN_MODULE:
return DPORT_CAN_RST;
case PERIPH_TWAI_MODULE:
return DPORT_TWAI_RST;
case PERIPH_SYSTIMER_MODULE:
return DPORT_SYSTIMER_RST;
case PERIPH_AES_MODULE:
@ -254,12 +254,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,155 @@
// 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.
/*******************************************************************************
* NOTICE
* The HAL is not public api, don't use in application code.
* See readme.md in soc/README.md
******************************************************************************/
// CP DMA HAL usages:
// 1. Initialize HAL layer by cp_dma_hal_init, pass in the allocated descriptors for TX and RX
// 2. Enable DMA and interrupt by cp_dma_hal_start
// 3. Prepare descriptors used for TX and RX
// 4. Restart the DMA engine in case it's not in working
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#include <stddef.h>
#include <stdbool.h>
#include "esp_attr.h"
#include "soc/cp_dma_struct.h"
typedef struct cp_dma_descriptor {
struct {
uint32_t size : 12; /*!< buffer size */
uint32_t length : 12; /*!< specify number of valid bytes in the buffer */
uint32_t reversed24_27 : 4; /*!< reserved */
uint32_t err : 1; /*!< specify whether a received buffer contains error */
uint32_t reserved29 : 1; /*!< reserved */
uint32_t eof : 1; /*!< if this dma link is the last one, you shoule set this bit 1 */
uint32_t owner : 1; /*!< specify the owner of buffer that this descriptor points to, 1=DMA, 0=CPU. DMA will clear it after use. */
} dw0; /*!< descriptor word 0 */
void *buffer; /*!< pointer to the buffer */
struct cp_dma_descriptor *next; /*!< pointer to the next descriptor or NULL if this descriptor is the last one */
} cp_dma_descriptor_t;
_Static_assert(sizeof(cp_dma_descriptor_t) == 12, "cp_dma_descriptor_t should occupy 12 bytes in memory");
/**
* @brief HAL context
*
* @note `tx_desc` and `rx_desc` are internal state of the HAL, will be modified during the operations.
* Upper layer of HAL should keep the buffer address themselves and make sure the buffers are freed when the HAL is no longer used.
*
*/
typedef struct {
cp_dma_dev_t *dev;
cp_dma_descriptor_t *tx_desc;
cp_dma_descriptor_t *rx_desc;
cp_dma_descriptor_t *next_rx_desc_to_check;
} cp_dma_hal_context_t;
/**
* @brief Initialize HAL layer context
*
* @param hal HAL layer context, memroy should be allocated at driver layer
* @param tx_descriptors out link descriptor pool
* @param tx_desc_num number of out link descriptors
* @param rx_descriptors in line descriptor pool
* @param rx_desc_num number of in link descriptors
*/
void cp_dma_hal_init(cp_dma_hal_context_t *hal, cp_dma_descriptor_t *tx_descriptors[], uint32_t tx_desc_num, cp_dma_descriptor_t *rx_descriptors[], uint32_t rx_desc_num);
/**
* @brief Deinitialize HAL layer context
*/
void cp_dma_hal_deinit(cp_dma_hal_context_t *hal);
/**
* @brief Start mem2mem DMA state machine
*/
void cp_dma_hal_start(cp_dma_hal_context_t *hal);
/**
* @brief Stop mem2mem DMA state machine
*/
void cp_dma_hal_stop(cp_dma_hal_context_t *hal);
/**
* @brief Get interrupt status word
*
* @return uint32_t Interrupt status
*/
uint32_t cp_dma_hal_get_intr_status(cp_dma_hal_context_t *hal) IRAM_ATTR;
/**
* @brief Clear interrupt mask
*
* @param mask interrupt mask
*/
void cp_dma_hal_clear_intr_status(cp_dma_hal_context_t *hal, uint32_t mask) IRAM_ATTR;
/**
* @brief Get next RX descriptor that needs recycling
*
* @param eof_desc EOF descriptor for this iteration
* @param[out] next_desc Next descriptor needs to check
* @return Whether to continue
*/
bool cp_dma_hal_get_next_rx_descriptor(cp_dma_hal_context_t *hal, cp_dma_descriptor_t *eof_desc, cp_dma_descriptor_t **next_desc);
/**
* @brief Prepare buffer to be transmitted
*
* @param hal HAL layer context
* @param buffer buffer address
* @param len buffer size
* @param[out] start_desc The first descriptor that carry the TX transaction
* @param[out] end_desc The last descriptor that carry the TX transaction
* @return Number of bytes has been parepared to transmit
*/
int cp_dma_hal_prepare_transmit(cp_dma_hal_context_t *hal, void *buffer, size_t len, cp_dma_descriptor_t **start_desc, cp_dma_descriptor_t **end_desc);
/**
* @brief Prepare buffer to receive
*
* @param hal HAL layer context
* @param buffer buffer address
* @param size buffer size
* @param[out] start_desc The first descriptor that carries the RX transaction
* @param[out] end_desc The last descriptor that carries the RX transaction
* @return Number of bytes has been parepared to receive
*/
int cp_dma_hal_prepare_receive(cp_dma_hal_context_t *hal, void *buffer, size_t size, cp_dma_descriptor_t **start_desc, cp_dma_descriptor_t **end_desc);
/**@{*/
/**
* @brief Give the owner of descriptors between [start_desc, end_desc] to DMA, and restart DMA HW engine
*
* @param hal HAL layer context
* @param start_desc The first descriptor that carries one transaction
* @param end_desc The last descriptor that carries one transaction
*/
void cp_dma_hal_restart_tx(cp_dma_hal_context_t *hal, cp_dma_descriptor_t *start_desc, cp_dma_descriptor_t *end_desc);
void cp_dma_hal_restart_rx(cp_dma_hal_context_t *hal, cp_dma_descriptor_t *start_desc, cp_dma_descriptor_t *end_desc);
/**@}*/
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,159 @@
// 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
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
#include <stdbool.h>
#include "soc/cp_dma_struct.h"
#define CP_DMA_LL_EVENT_RX_DONE (1 << 0)
#define CP_DMA_LL_EVENT_RX_EOF (1 << 1)
#define CP_DMA_LL_EVENT_TX_DONE (1 << 2)
#define CP_DMA_LL_EVENT_TX_EOF (1 << 3)
#define CP_DMA_LL_EVENT_RX_DESC_ERR (1 << 4)
#define CP_DMA_LL_EVENT_TX_DESC_ERR (1 << 5)
#define CP_DMA_LL_EVENT_RX_DESC_EMPTY (1 << 6)
#define CP_DMA_LL_EVENT_TX_TOTAL_EOF (1 << 7)
#define CP_DMA_LL_EVENT_ALL (0xFF)
/**
* Copy DMA firstly reads data to be transferred from internal RAM,
* stores the data into DMA FIFO via an outlink,
* and then writes the data to the destination internal RAM via an inlink.
*/
static inline void cp_dma_ll_reset_in_link(cp_dma_dev_t *dev)
{
dev->dma_conf.dma_in_rst = 1;
dev->dma_conf.dma_in_rst = 0;
}
static inline void cp_dma_ll_reset_out_link(cp_dma_dev_t *dev)
{
dev->dma_conf.dma_out_rst = 1;
dev->dma_conf.dma_out_rst = 0;
}
static inline void cp_dma_ll_reset_fifo(cp_dma_dev_t *dev)
{
dev->dma_conf.dma_fifo_rst = 1;
dev->dma_conf.dma_fifo_rst = 0;
}
static inline void cp_dma_ll_reset_cmd_fifo(cp_dma_dev_t *dev)
{
dev->dma_conf.dma_cmdfifo_rst = 1;
dev->dma_conf.dma_cmdfifo_rst = 0;
}
static inline void cp_dma_ll_enable_owner_check(cp_dma_dev_t *dev, bool enable)
{
dev->dma_conf.dma_check_owner = enable;
dev->dma_conf.dma_out_auto_wrback = 1;
dev->dma_conf.dma_out_owner = 0;
dev->dma_conf.dma_in_owner = 0;
}
static inline void cp_dma_ll_enable_clock(cp_dma_dev_t *dev, bool enable)
{
dev->dma_conf.dma_clk_en = enable;
}
static inline void cp_dma_ll_enable_intr(cp_dma_dev_t *dev, uint32_t mask, bool enable)
{
if (enable) {
dev->dma_int_ena.val |= mask;
} else {
dev->dma_int_ena.val &= ~mask;
}
}
static inline __attribute__((always_inline)) uint32_t cp_dma_ll_get_intr_status(cp_dma_dev_t *dev)
{
return dev->dma_int_st.val;
}
static inline __attribute__((always_inline)) void cp_dma_ll_clear_intr_status(cp_dma_dev_t *dev, uint32_t mask)
{
dev->dma_int_clr.val = mask;
}
static inline void cp_dma_ll_tx_set_descriptor_base_addr(cp_dma_dev_t *dev, uint32_t address)
{
dev->dma_out_link.dma_outlink_addr = address;
}
static inline void cp_dma_ll_rx_set_descriptor_base_addr(cp_dma_dev_t *dev, uint32_t address)
{
dev->dma_in_link.dma_inlink_addr = address;
}
static inline void cp_dma_ll_start_tx(cp_dma_dev_t *dev, bool enable)
{
if (enable) {
dev->dma_out_link.dma_outlink_start = 1; // cleared automatically by HW
} else {
dev->dma_out_link.dma_outlink_stop = 1; // cleared automatically by HW
}
}
static inline void cp_dma_ll_start_rx(cp_dma_dev_t *dev, bool enable)
{
if (enable) {
dev->dma_in_link.dma_inlink_start = 1; // cleared automatically by HW
} else {
dev->dma_in_link.dma_inlink_stop = 1; // cleared automatically by HW
}
}
static inline void cp_dma_ll_restart_tx(cp_dma_dev_t *dev)
{
dev->dma_out_link.dma_outlink_restart = 1; // cleared automatically by HW
}
static inline void cp_dma_ll_restart_rx(cp_dma_dev_t *dev)
{
dev->dma_in_link.dma_inlink_restart = 1; // cleared automatically by HW
}
// get the address of last rx descriptor
static inline uint32_t cp_dma_ll_get_rx_eof_descriptor_address(cp_dma_dev_t *dev)
{
return dev->dma_in_eof_des_addr.dma_in_suc_eof_des_addr;
}
// get the address of last tx descriptor
static inline uint32_t cp_dma_ll_get_tx_eof_descriptor_address(cp_dma_dev_t *dev)
{
return dev->dma_out_eof_des_addr.dma_out_eof_des_addr;
}
static inline uint32_t cp_dma_ll_get_tx_status(cp_dma_dev_t *dev)
{
return dev->dma_out_st.val;
}
static inline uint32_t cp_dma_ll_get_rx_status(cp_dma_dev_t *dev)
{
return dev->dma_in_st.val;
}
#ifdef __cplusplus
}
#endif

View File

@ -18,7 +18,7 @@
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
// The LL layer for ESP32 GPIO register operations
// The LL layer for ESP32-S2 GPIO register operations
#pragma once

View File

@ -185,8 +185,12 @@ static inline void gpspi_flash_ll_read_phase(spi_dev_t *dev)
*/
static inline void gpspi_flash_ll_set_cs_pin(spi_dev_t *dev, int pin)
{
dev->misc.cs0_dis = (pin == 0) ? 0 : 1;
dev->misc.cs1_dis = (pin == 1) ? 0 : 1;
dev->misc.cs0_dis = (pin != 0);
dev->misc.cs1_dis = (pin != 1);
dev->misc.cs2_dis = (pin != 2);
dev->misc.cs3_dis = (pin != 3);
dev->misc.cs4_dis = (pin != 4);
dev->misc.cs5_dis = (pin != 5);
}
/**
@ -203,10 +207,10 @@ static inline void gpspi_flash_ll_set_read_mode(spi_dev_t *dev, esp_flash_io_mod
ctrl.val &= ~(SPI_FCMD_QUAD_M | SPI_FADDR_QUAD_M | SPI_FREAD_QUAD_M | SPI_FCMD_DUAL_M | SPI_FADDR_DUAL_M | SPI_FREAD_DUAL_M);
user.val &= ~(SPI_FWRITE_QUAD_M | SPI_FWRITE_DUAL_M);
// ctrl.val |= SPI_FAST_RD_MODE_M;
switch (read_mode) {
case SPI_FLASH_FASTRD:
//the default option
case SPI_FLASH_SLOWRD:
break;
case SPI_FLASH_QIO:
ctrl.fread_quad = 1;
@ -226,9 +230,6 @@ static inline void gpspi_flash_ll_set_read_mode(spi_dev_t *dev, esp_flash_io_mod
ctrl.fread_dual = 1;
user.fwrite_dual = 1;
break;
// case SPI_FLASH_SLOWRD:
// ctrl.fast_rd_mode = 0;
// break;
default:
abort();
}

View File

@ -0,0 +1,58 @@
// 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"
#include "soc/rtc_cntl_reg.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);
SET_PERI_REG_MASK(RTC_CNTL_INT_CLR_REG, RTC_CNTL_MAIN_TIMER_INT_CLR_M);
SET_PERI_REG_MASK(RTC_CNTL_SLP_TIMER1_REG, RTC_CNTL_MAIN_TIMER_ALARM_EN_M);
}
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_ext1_clear_wakeup_pins(void)
{
REG_SET_BIT(RTC_CNTL_EXT_WAKEUP1_REG, RTC_CNTL_EXT_WAKEUP1_STATUS_CLR);
}
static inline void rtc_cntl_ll_ulp_wakeup_enable(void)
{
SET_PERI_REG_BITS(RTC_CNTL_STATE0_REG, RTC_CNTL_WAKEUP_ENA_V, 0x800, RTC_CNTL_WAKEUP_ENA_S);
}
#ifdef __cplusplus
}
#endif

View File

@ -354,6 +354,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

@ -28,6 +28,7 @@
#include "esp_types.h"
#include "soc/spi_periph.h"
#include "esp32s2/rom/lldesc.h"
#include "esp_attr.h"
#ifdef __cplusplus
extern "C" {
@ -64,6 +65,34 @@ typedef enum {
SPI_LL_INT_TYPE_SEG = 1, ///< Wait for DMA signals
} spi_ll_slave_intr_type;
/// Type definition of all supported interrupts
typedef enum {
SPI_LL_INTR_TRANS_DONE = BIT(0), ///< A transaction has done
SPI_LL_INTR_IN_SUC_EOF = BIT(1), ///< DMA in_suc_eof triggered
SPI_LL_INTR_OUT_EOF = BIT(2), ///< DMA out_eof triggered
SPI_LL_INTR_OUT_TOTAL_EOF = BIT(3), ///< DMA out_total_eof triggered
SPI_LL_INTR_IN_FULL = BIT(4), ///< DMA in_full error happened
SPI_LL_INTR_OUT_EMPTY = BIT(5), ///< DMA out_empty error happened
SPI_LL_INTR_RDBUF = BIT(6), ///< Has received RDBUF command. Only available in slave HD.
SPI_LL_INTR_WRBUF = BIT(7), ///< Has received WRBUF command. Only available in slave HD.
SPI_LL_INTR_RDDMA = BIT(8), ///< Has received RDDMA command. Only available in slave HD.
SPI_LL_INTR_WRDMA = BIT(9), ///< Has received WRDMA command. Only available in slave HD.
SPI_LL_INTR_WR_DONE = BIT(10), ///< Has received WR_DONE command. Only available in slave HD.
SPI_LL_INTR_CMD8 = BIT(11), ///< Has received CMD8 command. Only available in slave HD.
SPI_LL_INTR_CMD9 = BIT(12), ///< Has received CMD9 command. Only available in slave HD.
SPI_LL_INTR_CMDA = BIT(13), ///< Has received CMDA command. Only available in slave HD.
SPI_LL_INTR_SEG_DONE = BIT(14),
} spi_ll_intr_t;
FLAG_ATTR(spi_ll_intr_t)
///< Flags for conditions under which the transaction length should be recorded
typedef enum {
SPI_LL_TRANS_LEN_COND_WRBUF = BIT(0), ///< WRBUF length will be recorded
SPI_LL_TRANS_LEN_COND_RDBUF = BIT(1), ///< RDBUF length will be recorded
SPI_LL_TRANS_LEN_COND_WRDMA = BIT(2), ///< WRDMA length will be recorded
SPI_LL_TRANS_LEN_COND_RDDMA = BIT(3), ///< RDDMA length will be recorded
} spi_ll_trans_len_cond_t;
FLAG_ATTR(spi_ll_trans_len_cond_t)
/*------------------------------------------------------------------------------
* Control
@ -125,6 +154,76 @@ static inline void spi_ll_slave_init(spi_dev_t *hw)
hw->dma_int_ena.val = 0;
}
static inline void spi_ll_slave_hd_init(spi_dev_t* hw)
{
hw->clock.val = 0;
hw->user.val = 0;
hw->ctrl.val = 0;
hw->user.sio = 0;
//hw->user.tx_start_bit = 7;
hw->slave.soft_reset = 1;
hw->slave.soft_reset = 0;
//Reset DMA
hw->dma_conf.val |= SPI_OUT_RST | SPI_IN_RST | SPI_AHBM_RST | SPI_AHBM_FIFO_RST;
hw->dma_out_link.start = 0;
hw->dma_in_link.start = 0;
hw->dma_conf.val &= ~(SPI_OUT_RST | SPI_IN_RST | SPI_AHBM_RST | SPI_AHBM_FIFO_RST);
if (hw == &GPSPI2) {
hw->dma_conf.out_data_burst_en = 1;
} else {
hw->dma_conf.out_data_burst_en = 0;
}
hw->dma_conf.outdscr_burst_en = 1;
hw->dma_conf.indscr_burst_en = 1;
hw->dma_conf.rx_eof_en = 0;
hw->dma_conf.out_eof_mode = 1;
hw->dma_conf.out_auto_wrback = 1;
hw->user.doutdin = 0; //we only support full duplex
hw->slave.slave_mode = 1;
}
/**
* Check whether user-defined transaction is done.
*
* @param hw Beginning address of the peripheral registers.
*
* @return true if transaction is done, otherwise false.
*/
static inline bool spi_ll_usr_is_done(spi_dev_t *hw)
{
return hw->slave.trans_done;
}
/**
* Trigger start of user-defined transaction.
*
* @param hw Beginning address of the peripheral registers.
*/
static inline void spi_ll_user_start(spi_dev_t *hw)
{
hw->cmd.usr = 1;
}
/**
* Get current running command bit-mask. (Preview)
*
* @param hw Beginning address of the peripheral registers.
*
* @return Bitmask of running command, see ``SPI_CMD_REG``. 0 if no in-flight command.
*/
static inline uint32_t spi_ll_get_running_cmd(spi_dev_t *hw)
{
return hw->cmd.val;
}
/*------------------------------------------------------------------------------
* DMA
*----------------------------------------------------------------------------*/
/**
* Reset TX and RX DMAs.
*
@ -168,6 +267,62 @@ static inline void spi_ll_txdma_start(spi_dev_t *hw, lldesc_t *addr)
hw->dma_out_link.start = 1;
}
static inline void spi_ll_rxdma_reset(spi_dev_t* hw)
{
hw->dma_conf.in_rst = 1;
hw->dma_conf.in_rst = 0;
hw->dma_conf.infifo_full_clr = 1;
hw->dma_conf.infifo_full_clr = 0;
}
static inline void spi_ll_txdma_reset(spi_dev_t* hw)
{
hw->dma_conf.out_rst = 1;
hw->dma_conf.out_rst = 0;
hw->dma_conf.outfifo_empty_clr = 1;
hw->dma_conf.outfifo_empty_clr = 0;
}
static inline void spi_ll_rxdma_restart(spi_dev_t* hw)
{
hw->dma_in_link.restart = 1;
}
static inline void spi_ll_txdma_restart(spi_dev_t* hw)
{
hw->dma_out_link.restart = 1;
}
static inline void spi_ll_rxdma_disable(spi_dev_t* hw)
{
hw->dma_in_link.dma_rx_ena = 0;
}
static inline void spi_ll_txdma_disable(spi_dev_t* hw)
{
hw->dma_out_link.dma_tx_ena = 0;
hw->dma_out_link.stop = 1;
}
static inline void spi_ll_rxdma_clr_err(spi_dev_t* hw)
{
hw->dma_conf.infifo_full_clr = 1;
hw->dma_conf.infifo_full_clr = 0;
}
static inline void spi_ll_txdma_clr_err(spi_dev_t* hw)
{
hw->dma_int_clr.outfifo_empty_err= 1;
}
static inline bool spi_ll_txdma_get_empty_err(spi_dev_t* hw)
{
return hw->dma_int_raw.outfifo_empty_err;
}
/*------------------------------------------------------------------------------
* Buffer
*----------------------------------------------------------------------------*/
/**
* Write to SPI buffer.
*
@ -205,99 +360,43 @@ static inline void spi_ll_read_buffer(spi_dev_t *hw, uint8_t *buffer_to_rcv, siz
}
}
/**
* Check whether user-defined transaction is done.
*
* @param hw Beginning address of the peripheral registers.
*
* @return true if transaction is done, otherwise false.
*/
static inline bool spi_ll_usr_is_done(spi_dev_t *hw)
static inline void spi_ll_read_buffer_byte(spi_dev_t *hw, int byte_addr, uint8_t *out_data, int len)
{
return hw->slave.trans_done;
while (len>0) {
uint32_t word = hw->data_buf[byte_addr/4];
int offset = byte_addr % 4;
int copy_len = 4 - offset;
if (copy_len > len) copy_len = len;
memcpy(out_data, ((uint8_t*)&word)+offset, copy_len);
byte_addr += copy_len;
out_data += copy_len;
len -= copy_len;
}
}
/**
* Trigger start of user-defined transaction.
*
* @param hw Beginning address of the peripheral registers.
*/
static inline void spi_ll_user_start(spi_dev_t *hw)
static inline void spi_ll_write_buffer_byte(spi_dev_t *hw, int byte_addr, uint8_t *data, int len)
{
hw->cmd.usr = 1;
}
assert( byte_addr + len <= 72);
assert(len > 0);
assert(byte_addr >= 0);
/**
* Get current running command bit-mask. (Preview)
*
* @param hw Beginning address of the peripheral registers.
*
* @return Bitmask of running command, see ``SPI_CMD_REG``. 0 if no in-flight command.
*/
static inline uint32_t spi_ll_get_running_cmd(spi_dev_t *hw)
{
return hw->cmd.val;
}
while (len > 0) {
uint32_t word;
int offset = byte_addr % 4;
/**
* Disable the trans_done interrupt.
*
* @param hw Beginning address of the peripheral registers.
*/
static inline void spi_ll_disable_int(spi_dev_t *hw)
{
hw->slave.int_trans_done_en = 0;
}
int copy_len = 4 - offset;
if (copy_len > len) copy_len = len;
/**
* Clear the trans_done interrupt.
*
* @param hw Beginning address of the peripheral registers.
*/
static inline void spi_ll_clear_int_stat(spi_dev_t *hw)
{
hw->slave.trans_done = 0;
hw->dma_int_clr.val = UINT32_MAX;
}
//read-modify-write
if (copy_len != 4) word = hw->data_buf[byte_addr / 4];
/**
* Set the trans_done interrupt.
*
* @param hw Beginning address of the peripheral registers.
*/
static inline void spi_ll_set_int_stat(spi_dev_t *hw)
{
hw->slave.trans_done = 1;
}
/**
* Enable the trans_done interrupt.
*
* @param hw Beginning address of the peripheral registers.
*/
static inline void spi_ll_enable_int(spi_dev_t *hw)
{
hw->slave.int_trans_done_en = 1;
}
/**
* Set different interrupt types for the slave.
*
* @param hw Beginning address of the peripheral registers.
* @param int_type Interrupt type
*/
static inline void spi_ll_slave_set_int_type(spi_dev_t *hw, spi_ll_slave_intr_type int_type)
{
switch (int_type) {
case SPI_LL_INT_TYPE_SEG:
hw->dma_int_ena.in_suc_eof = 1;
hw->dma_int_ena.out_total_eof = 1;
hw->slave.int_trans_done_en = 0;
break;
default:
hw->dma_int_ena.in_suc_eof = 0;
hw->dma_int_ena.out_total_eof = 0;
hw->slave.int_trans_done_en = 1;
memcpy(((uint8_t *)&word) + offset, data, copy_len);
hw->data_buf[byte_addr / 4] = word;
data += copy_len;
byte_addr += copy_len;
len -= copy_len;
}
}
@ -460,6 +559,12 @@ static inline void spi_ll_master_set_io_mode(spi_dev_t *hw, spi_ll_io_mode_t io_
}
}
static inline void spi_ll_slave_set_seg_mode(spi_dev_t* hw, bool seg_trans)
{
hw->dma_conf.dma_seg_trans_en = seg_trans;
hw->dma_conf.rx_eof_en = seg_trans;
}
/**
* Select one of the CS to use in current transaction.
*
@ -471,6 +576,9 @@ static inline void spi_ll_master_select_cs(spi_dev_t *hw, int cs_id)
hw->misc.cs0_dis = (cs_id == 0) ? 0 : 1;
hw->misc.cs1_dis = (cs_id == 1) ? 0 : 1;
hw->misc.cs2_dis = (cs_id == 2) ? 0 : 1;
hw->misc.cs3_dis = (cs_id == 3) ? 0 : 1;
hw->misc.cs4_dis = (cs_id == 4) ? 0 : 1;
hw->misc.cs5_dis = (cs_id == 5) ? 0 : 1;
}
/*------------------------------------------------------------------------------
@ -859,7 +967,150 @@ static inline uint32_t spi_ll_slave_get_rcv_bitlen(spi_dev_t *hw)
return hw->slv_rd_byte.data_bytelen * 8;
}
/*------------------------------------------------------------------------------
* Interrupts
*----------------------------------------------------------------------------*/
//helper macros to generate code for each interrupts
#define FOR_EACH_ITEM(op, list) do { list(op) } while(0)
#define INTR_LIST(item) \
item(SPI_LL_INTR_TRANS_DONE, slave.int_trans_done_en, slave.trans_done, slave.trans_done=0) \
item(SPI_LL_INTR_RDBUF, slave.int_rd_buf_done_en, slv_rdbuf_dlen.rd_buf_done, slv_rdbuf_dlen.rd_buf_done=0) \
item(SPI_LL_INTR_WRBUF, slave.int_wr_buf_done_en, slv_wrbuf_dlen.wr_buf_done, slv_wrbuf_dlen.wr_buf_done=0) \
item(SPI_LL_INTR_RDDMA, slave.int_rd_dma_done_en, slv_rd_byte.rd_dma_done, slv_rd_byte.rd_dma_done=0) \
item(SPI_LL_INTR_WRDMA, slave.int_wr_dma_done_en, slave1.wr_dma_done, slave1.wr_dma_done=0) \
item(SPI_LL_INTR_IN_SUC_EOF, dma_int_ena.in_suc_eof, dma_int_raw.in_suc_eof, dma_int_clr.in_suc_eof=1) \
item(SPI_LL_INTR_OUT_EOF, dma_int_ena.out_eof, dma_int_raw.out_eof, dma_int_clr.out_eof=1) \
item(SPI_LL_INTR_OUT_TOTAL_EOF, dma_int_ena.out_total_eof, dma_int_raw.out_total_eof, dma_int_clr.out_total_eof=1) \
item(SPI_LL_INTR_SEG_DONE, slave.int_dma_seg_trans_en, hold.dma_seg_trans_done, hold.dma_seg_trans_done=0) \
item(SPI_LL_INTR_IN_FULL, dma_int_ena.infifo_full_err, dma_int_raw.infifo_full_err, dma_int_clr.infifo_full_err=1) \
item(SPI_LL_INTR_OUT_EMPTY, dma_int_ena.outfifo_empty_err, dma_int_raw.outfifo_empty_err, dma_int_clr.outfifo_empty_err=1) \
item(SPI_LL_INTR_WR_DONE, dma_int_ena.cmd7, dma_int_raw.cmd7, dma_int_clr.cmd7=1) \
item(SPI_LL_INTR_CMD8, dma_int_ena.cmd8, dma_int_raw.cmd8, dma_int_clr.cmd8=1) \
item(SPI_LL_INTR_CMD9, dma_int_ena.cmd9, dma_int_raw.cmd9, dma_int_clr.cmd9=1) \
item(SPI_LL_INTR_CMDA, dma_int_ena.cmda, dma_int_raw.cmda, dma_int_clr.cmda=1)
static inline void spi_ll_enable_intr(spi_dev_t* hw, spi_ll_intr_t intr_mask)
{
#define ENA_INTR(intr_bit, en_reg, ...) if (intr_mask & (intr_bit)) hw->en_reg = 1;
FOR_EACH_ITEM(ENA_INTR, INTR_LIST);
#undef ENA_INTR
}
static inline void spi_ll_disable_intr(spi_dev_t* hw, spi_ll_intr_t intr_mask)
{
#define DIS_INTR(intr_bit, en_reg, ...) if (intr_mask & (intr_bit)) hw->en_reg = 0;
FOR_EACH_ITEM(DIS_INTR, INTR_LIST);
#undef DIS_INTR
}
static inline void spi_ll_set_intr(spi_dev_t* hw, spi_ll_intr_t intr_mask)
{
#define SET_INTR(intr_bit, _, st_reg, ...) if (intr_mask & (intr_bit)) hw->st_reg = 1;
FOR_EACH_ITEM(SET_INTR, INTR_LIST);
#undef SET_INTR
}
static inline void spi_ll_clear_intr(spi_dev_t* hw, spi_ll_intr_t intr_mask)
{
#define CLR_INTR(intr_bit, _, __, clr_op) if (intr_mask & (intr_bit)) hw->clr_op;
FOR_EACH_ITEM(CLR_INTR, INTR_LIST);
#undef CLR_INTR
}
static inline bool spi_ll_get_intr(spi_dev_t* hw, spi_ll_intr_t intr_mask)
{
#define GET_INTR(intr_bit, _, st_reg, ...) if (intr_mask & (intr_bit) && hw->st_reg) return true;
FOR_EACH_ITEM(GET_INTR, INTR_LIST);
return false;
#undef GET_INTR
}
#undef FOR_EACH_ITEM
#undef INTR_LIST
/**
* Disable the trans_done interrupt.
*
* @param hw Beginning address of the peripheral registers.
*/
static inline void spi_ll_disable_int(spi_dev_t *hw)
{
hw->slave.int_trans_done_en = 0;
}
/**
* Clear the trans_done interrupt.
*
* @param hw Beginning address of the peripheral registers.
*/
static inline void spi_ll_clear_int_stat(spi_dev_t *hw)
{
hw->slave.trans_done = 0;
hw->dma_int_clr.val = UINT32_MAX;
}
/**
* Set the trans_done interrupt.
*
* @param hw Beginning address of the peripheral registers.
*/
static inline void spi_ll_set_int_stat(spi_dev_t *hw)
{
hw->slave.trans_done = 1;
}
/**
* Enable the trans_done interrupt.
*
* @param hw Beginning address of the peripheral registers.
*/
static inline void spi_ll_enable_int(spi_dev_t *hw)
{
hw->slave.int_trans_done_en = 1;
}
/**
* Set different interrupt types for the slave.
*
* @param hw Beginning address of the peripheral registers.
* @param int_type Interrupt type
*/
static inline void spi_ll_slave_set_int_type(spi_dev_t *hw, spi_ll_slave_intr_type int_type)
{
switch (int_type) {
case SPI_LL_INT_TYPE_SEG:
hw->dma_int_ena.in_suc_eof = 1;
hw->dma_int_ena.out_total_eof = 1;
hw->slave.int_trans_done_en = 0;
break;
default:
hw->dma_int_ena.in_suc_eof = 0;
hw->dma_int_ena.out_total_eof = 0;
hw->slave.int_trans_done_en = 1;
}
}
/*------------------------------------------------------------------------------
* Slave HD
*----------------------------------------------------------------------------*/
static inline void spi_ll_slave_hd_set_len_cond(spi_dev_t* hw, spi_ll_trans_len_cond_t cond_mask)
{
hw->slv_rd_byte.rdbuf_bytelen_en = (cond_mask & SPI_LL_TRANS_LEN_COND_RDBUF) ? 1 : 0;
hw->slv_rd_byte.wrbuf_bytelen_en = (cond_mask & SPI_LL_TRANS_LEN_COND_WRBUF) ? 1 : 0;
hw->slv_rd_byte.rddma_bytelen_en = (cond_mask & SPI_LL_TRANS_LEN_COND_RDDMA) ? 1 : 0;
hw->slv_rd_byte.wrdma_bytelen_en = (cond_mask & SPI_LL_TRANS_LEN_COND_WRDMA) ? 1 : 0;
}
static inline int spi_ll_slave_get_rx_byte_len(spi_dev_t* hw)
{
return hw->slv_rd_byte.data_bytelen;
}
static inline uint32_t spi_ll_slave_hd_get_last_addr(spi_dev_t* hw)
{
return hw->slave1.last_addr;
}
#undef SPI_LL_RST_MASK
#undef SPI_LL_UNUSED_INT_MASK

View File

@ -227,12 +227,12 @@ static inline void spimem_flash_ll_read_phase(spi_mem_dev_t *dev)
* Select which pin to use for the flash
*
* @param dev Beginning address of the peripheral registers.
* @param pin Pin ID to use, 0-2. Set to other values to disable all the CS pins.
* @param pin Pin ID to use, 0-1. Set to other values to disable all the CS pins.
*/
static inline void spimem_flash_ll_set_cs_pin(spi_mem_dev_t *dev, int pin)
{
dev->misc.cs0_dis = (pin == 0) ? 0 : 1;
dev->misc.cs1_dis = (pin == 1) ? 0 : 1;
dev->misc.cs0_dis = (pin != 0);
dev->misc.cs1_dis = (pin != 1);
}
/**

View File

@ -182,32 +182,33 @@ void touch_hal_filter_get_config(touch_filter_config_t *filter_info);
#define touch_hal_filter_read_smooth(touch_num, smooth_data) touch_ll_filter_read_smooth(touch_num, smooth_data)
/**
* Get baseline value of touch sensor.
* Get benchmark value of touch sensor.
*
* @note After initialization, the baseline value is the maximum during the first measurement period.
* @note After initialization, the benchmark value is the maximum during the first measurement period.
* @param touch_num touch pad index
* @param touch_value pointer to accept touch sensor value
*/
#define touch_hal_filter_read_baseline(touch_num, basedata) touch_ll_filter_read_baseline(touch_num, basedata)
#define touch_hal_read_benchmark(touch_num, benchmark) touch_ll_read_benchmark(touch_num, benchmark)
/**
* Force reset baseline to raw data of touch sensor.
* Force reset benchmark to raw data of touch sensor.
*
* @param touch_num touch pad index
* - TOUCH_PAD_MAX Reset basaline of all channels.
*/
#define touch_hal_filter_reset_baseline(touch_num) touch_ll_filter_reset_baseline(touch_num)
#define touch_hal_reset_benchmark(touch_num) touch_ll_reset_benchmark(touch_num)
/**
* 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.
* 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.
*
* @param mode Filter mode type. Refer to ``touch_filter_mode_t``.
*/
#define touch_hal_filter_set_filter_mode(mode) touch_ll_filter_set_filter_mode(mode)
/**
* Get filter mode. The input to the filter is raw data and the output is the baseline value.
* Get 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.
*
* @param mode Filter mode type. Refer to ``touch_filter_mode_t``.
*/
@ -229,89 +230,47 @@ void touch_hal_filter_get_config(touch_filter_config_t *filter_info);
#define touch_hal_filter_get_debounce(dbc_cnt) touch_ll_filter_get_debounce(dbc_cnt)
/**
* Set hysteresis threshold coefficient. hysteresis = hysteresis_thr * 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: 1/8; 1: 3/32; 2: 1/16; 3: 1/32
*
* @param hys_thr hysteresis coefficient.
*/
#define touch_hal_filter_set_hysteresis(hys_thr) touch_ll_filter_set_hysteresis(hys_thr)
/**
* Get hysteresis threshold coefficient. hysteresis = hysteresis_thr * 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: 1/8; 1: 3/32; 2: 1/16; 3: 1/32
*
* @param hys_thr hysteresis coefficient.
*/
#define touch_hal_filter_get_hysteresis(hys_thr) touch_ll_filter_get_hysteresis(hys_thr)
/**
* Set noise threshold coefficient. noise = noise_thr * touch threshold.
* If (raw data - baseline) > (noise), the baseline stop updating.
* If (raw data - baseline) < (noise), the baseline start updating.
* Range: 0 ~ 3. The coefficient is 0: 1/2; 1: 3/8; 2: 1/4; 3: 1/8;
* Set 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;
*
* @param hys_thr Noise threshold coefficient.
*/
#define touch_hal_filter_set_noise_thres(noise_thr) touch_ll_filter_set_noise_thres(noise_thr)
/**
* Get noise threshold coefficient. noise = noise_thr * touch threshold.
* If (raw data - baseline) > (noise), the baseline stop updating.
* If (raw data - baseline) < (noise), the baseline start updating.
* Range: 0 ~ 3. The coefficient is 0: 1/2; 1: 3/8; 2: 1/4; 3: 1/8;
* Get 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;
*
* @param noise_thr Noise threshold coefficient.
*/
#define touch_hal_filter_get_noise_thres(noise_thr) touch_ll_filter_get_noise_thres(noise_thr)
/**
* Set negative noise threshold coefficient. negative noise = noise_neg_thr * 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: 1/2; 1: 3/8; 2: 1/4; 3: 1/8;
*
* @param noise_thr Negative threshold coefficient.
*/
#define touch_hal_filter_set_neg_noise_thres(noise_thr) touch_ll_filter_set_neg_noise_thres(noise_thr)
/**
* Get negative noise threshold coefficient. negative noise = noise_neg_thr * 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: 1/2; 1: 3/8; 2: 1/4; 3: 1/8;
*
* @param noise_thr Negative noise threshold coefficient.
*/
#define touch_hal_filter_get_neg_noise_thres(noise_thr) touch_ll_filter_get_neg_noise_thres(noise_thr)
/**
* Set the cumulative number of baseline reset processes. such as `n`. If the measured values continue to exceed
* the negative noise threshold for `n` times, the baseline reset to raw data.
* Set the cumulative number of benchmark reset processes. such as `n`. If the measured values continue to exceed
* the negative noise threshold for `n` times, the benchmark reset to raw data.
* Range: 0 ~ 15
*
* @param reset_cnt The cumulative number of baseline reset processes.
* @param reset_cnt The cumulative number of benchmark reset processes.
*/
#define touch_hal_filter_set_baseline_reset(reset_cnt) touch_ll_filter_set_baseline_reset(reset_cnt)
#define touch_hal_filter_set_benchmark_reset(reset_cnt) touch_ll_filter_set_benchmark_reset(reset_cnt)
/**
* Get the cumulative number of baseline reset processes. such as `n`. If the measured values continue to exceed
* the negative noise threshold for `n` times, the baseline reset to raw data.
* Get the cumulative number of benchmark reset processes. such as `n`. If the measured values continue to exceed
* the negative noise threshold for `n` times, the benchmark reset to raw data.
* Range: 0 ~ 15
*
* @param reset_cnt The cumulative number of baseline reset processes.
* @param reset_cnt The cumulative number of benchmark reset processes.
*/
#define touch_hal_filter_get_baseline_reset(reset_cnt) touch_ll_filter_get_baseline_reset(reset_cnt)
#define touch_hal_filter_get_benchmark_reset(reset_cnt) touch_ll_filter_get_benchmark_reset(reset_cnt)
/**
* Set jitter filter step size.
* If filter mode is jitter, should set filter step for jitter.
* Range: 0 ~ 15
*
* @param step The step size of the data change when the baseline is updated.
* @param step The step size of the data change.
*/
#define touch_hal_filter_set_jitter_step(step) touch_ll_filter_set_jitter_step(step)
@ -320,7 +279,7 @@ void touch_hal_filter_get_config(touch_filter_config_t *filter_info);
* If filter mode is jitter, should set filter step for jitter.
* Range: 0 ~ 15
*
* @param step The step size of the data change when the baseline is updated.
* @param step The step size of the data change.
*/
#define touch_hal_filter_get_jitter_step(step) touch_ll_filter_get_jitter_step(step)
@ -453,11 +412,11 @@ void touch_hal_denoise_enable(void);
/**
* Set parameter of waterproof function.
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
*
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* Guard pad is used to detect the large area of water covering the touch panel.
* Shield pad is used to shield the influence of water droplets covering the touch panel.
* It is generally designed as a grid and is placed around the touch buttons.
*
* @param waterproof parameter of waterproof
*/
@ -472,21 +431,12 @@ void touch_hal_waterproof_get_config(touch_pad_waterproof_t *waterproof);
/**
* Enable parameter of waterproof function.
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
* Should be called after function ``touch_hal_waterproof_set_config``.
*/
void touch_hal_waterproof_enable(void);
/**
* Disable parameter of waterproof function.
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
*/
#define touch_hal_waterproof_disable() touch_ll_waterproof_disable()
@ -591,7 +541,7 @@ void touch_hal_sleep_channel_enable(touch_pad_t pad_num, bool enable);
/**
* Set the trigger threshold of touch sensor in deep sleep.
* The threshold determines the sensitivity of the touch sensor.
* The threshold is the original value of the trigger state minus the baseline value.
* The threshold is the original value of the trigger state minus the benchmark value.
*
* @note The threshold at sleep is the same as the threshold before sleep.
*/
@ -600,7 +550,7 @@ void touch_hal_sleep_channel_enable(touch_pad_t pad_num, bool enable);
/**
* Get the trigger threshold of touch sensor in deep sleep.
* The threshold determines the sensitivity of the touch sensor.
* The threshold is the original value of the trigger state minus the baseline value.
* The threshold is the original value of the trigger state minus the benchmark value.
*
* @note The threshold at sleep is the same as the threshold before sleep.
*/
@ -617,11 +567,11 @@ void touch_hal_sleep_channel_enable(touch_pad_t pad_num, bool enable);
#define touch_hal_sleep_disable_approach() touch_ll_sleep_disable_approach()
/**
* Read baseline of touch sensor for sleep pad.
* Read benchmark of touch sensor for sleep pad.
*
* @param baseline Pointer to accept touch sensor baseline value.
* @param benchmark Pointer to accept touch sensor benchmark value.
*/
#define touch_hal_sleep_read_baseline(baseline) touch_ll_sleep_read_baseline(baseline)
#define touch_hal_sleep_read_benchmark(benchmark) touch_ll_sleep_read_benchmark(benchmark)
/**
* Read smooth data of touch sensor for sleep pad.
@ -634,9 +584,9 @@ void touch_hal_sleep_channel_enable(touch_pad_t pad_num, bool enable);
#define touch_hal_sleep_read_data(raw_data) touch_ll_sleep_read_data(raw_data)
/**
* Reset baseline of touch sensor for sleep pad.
* Reset benchmark of touch sensor for sleep pad.
*/
#define touch_hal_sleep_reset_baseline() touch_ll_sleep_reset_baseline()
#define touch_hal_sleep_reset_benchmark() touch_ll_sleep_reset_benchmark()
/**
* Read debounce of touch sensor for sleep pad.

View File

@ -32,7 +32,7 @@ extern "C" {
#endif
#define TOUCH_LL_READ_RAW 0x0
#define TOUCH_LL_READ_BASELINE 0x2
#define TOUCH_LL_READ_BENCHMARK 0x2
#define TOUCH_LL_READ_SMOOTH 0x3
#define TOUCH_LL_TIMER_FORCE_DONE 0x3
#define TOUCH_LL_TIMER_DONE 0x0
@ -307,7 +307,7 @@ static inline void touch_ll_start_sw_meas(void)
/**
* Set the trigger threshold of touch sensor.
* The threshold determines the sensitivity of the touch sensor.
* The threshold is the original value of the trigger state minus the baseline value.
* The threshold is the original value of the trigger state minus the benchmark value.
*
* @note If set "TOUCH_PAD_THRESHOLD_MAX", the touch is never be trigered.
* @param touch_num touch pad index
@ -321,7 +321,7 @@ static inline void touch_ll_set_threshold(touch_pad_t touch_num, uint32_t thresh
/**
* Get the trigger threshold of touch sensor.
* The threshold determines the sensitivity of the touch sensor.
* The threshold is the original value of the trigger state minus the baseline value.
* The threshold is the original value of the trigger state minus the benchmark value.
*
* @param touch_num touch pad index.
* @param threshold pointer to accept threshold.
@ -635,28 +635,28 @@ static inline void IRAM_ATTR touch_ll_filter_read_smooth(touch_pad_t touch_num,
}
/**
* Get baseline value of touch sensor.
* Get benchmark value of touch sensor.
*
* @note After initialization, the baseline value is the maximum during the first measurement period.
* @note After initialization, the benchmark value is the maximum during the first measurement period.
* @param touch_num touch pad index
* @param touch_value pointer to accept touch sensor value
*/
static inline void IRAM_ATTR touch_ll_filter_read_baseline(touch_pad_t touch_num, uint32_t *basedata)
static inline void IRAM_ATTR touch_ll_read_benchmark(touch_pad_t touch_num, uint32_t *benchmark)
{
SENS.sar_touch_conf.touch_data_sel = TOUCH_LL_READ_BASELINE;
*basedata = SENS.sar_touch_status[touch_num - 1].touch_pad_data;
SENS.sar_touch_conf.touch_data_sel = TOUCH_LL_READ_BENCHMARK;
*benchmark = SENS.sar_touch_status[touch_num - 1].touch_pad_data;
}
/**
* Force reset baseline to raw data of touch sensor.
* Force reset benchmark to raw data of touch sensor.
*
* @note If call this API, make sure enable clock gate(`touch_ll_clkgate`) first.
* @param touch_num touch pad index
* - TOUCH_PAD_MAX Reset basaline of all channels.
*/
static inline void touch_ll_filter_reset_baseline(touch_pad_t touch_num)
static inline void touch_ll_reset_benchmark(touch_pad_t touch_num)
{
/* Clear touch channels to initialize the channel value (baseline, raw_data).
/* Clear touch channels to initialize the channel value (benchmark, raw_data).
*/
if (touch_num == TOUCH_PAD_MAX) {
SENS.sar_touch_chn_st.touch_channel_clr = SOC_TOUCH_SENSOR_BIT_MASK_MAX;
@ -666,8 +666,8 @@ static inline void touch_ll_filter_reset_baseline(touch_pad_t touch_num)
}
/**
* 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.
* 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.
*
* @param mode Filter mode type. Refer to ``touch_filter_mode_t``.
*/
@ -677,7 +677,8 @@ static inline void touch_ll_filter_set_filter_mode(touch_filter_mode_t mode)
}
/**
* Get filter mode. The input to the filter is raw data and the output is the baseline value.
* Get 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.
*
* @param mode Filter mode type. Refer to ``touch_filter_mode_t``.
*/
@ -729,35 +730,8 @@ static inline void touch_ll_filter_get_debounce(uint32_t *dbc_cnt)
}
/**
* Set hysteresis threshold coefficient. hysteresis = hysteresis_thr * 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: 2/32; 3: OFF.
*
* @param hys_thr hysteresis coefficient.
*/
static inline void touch_ll_filter_set_hysteresis(uint32_t hys_thr)
{
RTCCNTL.touch_filter_ctrl.touch_hysteresis = hys_thr;
}
/**
* Get hysteresis threshold coefficient. hysteresis = hysteresis_thr * 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: 2/32; 3: OFF.
*
* @param hys_thr hysteresis coefficient.
*/
static inline void touch_ll_filter_get_hysteresis(uint32_t *hys_thr)
{
*hys_thr = RTCCNTL.touch_filter_ctrl.touch_hysteresis;
}
/**
* Set noise threshold coefficient. noise = noise_thr * touch threshold.
* If (raw data - baseline) > (noise), the baseline stop updating.
* If (raw data - baseline) < (noise), the baseline start updating.
* Set 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;
*
* @param hys_thr Noise threshold coefficient.
@ -765,12 +739,14 @@ static inline void touch_ll_filter_get_hysteresis(uint32_t *hys_thr)
static inline void touch_ll_filter_set_noise_thres(uint32_t noise_thr)
{
RTCCNTL.touch_filter_ctrl.touch_noise_thres = noise_thr;
RTCCNTL.touch_filter_ctrl.config2 = noise_thr;
RTCCNTL.touch_filter_ctrl.config1 = 0xF;
RTCCNTL.touch_filter_ctrl.config3 = 2;
}
/**
* Get noise threshold coefficient. noise = noise_thr * touch threshold.
* If (raw data - baseline) > (noise), the baseline stop updating.
* If (raw data - baseline) < (noise), the baseline start updating.
* Get 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;
*
* @param noise_thr Noise threshold coefficient.
@ -780,62 +756,12 @@ static inline void touch_ll_filter_get_noise_thres(uint32_t *noise_thr)
*noise_thr = RTCCNTL.touch_filter_ctrl.touch_noise_thres;
}
/**
* Set negative noise threshold coefficient. negative noise = noise_neg_thr * 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: 1/2; 1: 3/8; 2: 1/4; 3: 1/8;
*
* @param noise_thr Negative threshold coefficient.
*/
static inline void touch_ll_filter_set_neg_noise_thres(uint32_t noise_thr)
{
RTCCNTL.touch_filter_ctrl.touch_neg_noise_thres = noise_thr;
}
/**
* Get negative noise threshold coefficient. negative noise = noise_neg_thr * 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: 1/2; 1: 3/8; 2: 1/4; 3: 1/8;
*
* @param noise_thr Negative noise threshold coefficient.
*/
static inline void touch_ll_filter_get_neg_noise_thres(uint32_t *noise_thr)
{
*noise_thr = RTCCNTL.touch_filter_ctrl.touch_neg_noise_thres;
}
/**
* 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
*
* @param reset_cnt The cumulative number of baseline reset processes.
*/
static inline void touch_ll_filter_set_baseline_reset(uint32_t reset_cnt)
{
RTCCNTL.touch_filter_ctrl.touch_neg_noise_limit = reset_cnt;
}
/**
* Get 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
*
* @param reset_cnt The cumulative number of baseline reset processes.
*/
static inline void touch_ll_filter_get_baseline_reset(uint32_t *reset_cnt)
{
*reset_cnt = RTCCNTL.touch_filter_ctrl.touch_neg_noise_limit;
}
/**
* Set jitter filter step size.
* If filter mode is jitter, should set filter step for jitter.
* Range: 0 ~ 15
*
* @param step The step size of the data change when the baseline is updated.
* @param step The step size of the data change.
*/
static inline void touch_ll_filter_set_jitter_step(uint32_t step)
{
@ -847,7 +773,7 @@ static inline void touch_ll_filter_set_jitter_step(uint32_t step)
* If filter mode is jitter, should set filter step for jitter.
* Range: 0 ~ 15
*
* @param step The step size of the data change when the baseline is updated.
* @param step The step size of the data change.
*/
static inline void touch_ll_filter_get_jitter_step(uint32_t *step)
{
@ -1004,11 +930,11 @@ static inline void touch_ll_waterproof_get_sheild_driver(touch_pad_shield_driver
/**
* Enable parameter of waterproof function.
*
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* Guard pad is used to detect the large area of water covering the touch panel.
* Shield pad is used to shield the influence of water droplets covering the touch panel.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
*/
static inline void touch_ll_waterproof_enable(void)
{
@ -1017,11 +943,6 @@ static inline void touch_ll_waterproof_enable(void)
/**
* Disable parameter of waterproof function.
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
*/
static inline void touch_ll_waterproof_disable(void)
{
@ -1135,7 +1056,7 @@ static inline void touch_ll_sleep_get_channel_num(touch_pad_t *touch_num)
/**
* Set the trigger threshold of touch sensor in deep sleep.
* The threshold determines the sensitivity of the touch sensor.
* The threshold is the original value of the trigger state minus the baseline value.
* The threshold is the original value of the trigger state minus the benchmark value.
*
* @note In general, the touch threshold during sleep can use the threshold parameter parameters before sleep.
*/
@ -1147,7 +1068,7 @@ static inline void touch_ll_sleep_set_threshold(uint32_t touch_thres)
/**
* Get the trigger threshold of touch sensor in deep sleep.
* The threshold determines the sensitivity of the touch sensor.
* The threshold is the original value of the trigger state minus the baseline value.
* The threshold is the original value of the trigger state minus the benchmark value.
*
* @note In general, the touch threshold during sleep can use the threshold parameter parameters before sleep.
*/
@ -1181,14 +1102,14 @@ static inline bool touch_ll_sleep_get_approach_status(void)
}
/**
* Read baseline of touch sensor for sleep pad.
* Read benchmark of touch sensor for sleep pad.
*
* @param baseline Pointer to accept touch sensor baseline value.
* @param benchmark Pointer to accept touch sensor benchmark value.
*/
static inline void touch_ll_sleep_read_baseline(uint32_t *baseline)
static inline void touch_ll_sleep_read_benchmark(uint32_t *benchmark)
{
SENS.sar_touch_conf.touch_data_sel = TOUCH_LL_READ_BASELINE;
*baseline = SENS.sar_touch_slp_status.touch_slp_data;
SENS.sar_touch_conf.touch_data_sel = TOUCH_LL_READ_BENCHMARK;
*benchmark = SENS.sar_touch_slp_status.touch_slp_data;
}
static inline void touch_ll_sleep_read_smooth(uint32_t *smooth_data)
@ -1205,7 +1126,7 @@ static inline void touch_ll_sleep_read_data(uint32_t *raw_data)
*raw_data = SENS.sar_touch_status[touch_num - 1].touch_pad_data;
}
static inline void touch_ll_sleep_reset_baseline(void)
static inline void touch_ll_sleep_reset_benchmark(void)
{
RTCCNTL.touch_approach.touch_slp_channel_clr = 1;
}

View File

@ -0,0 +1,675 @@
// 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 "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)
//Todo: Add Miss status support
#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; //Set command_reg.tr and command_reg.at simultaneously for single shot transmittion request
}
/**
* @brief Aborts TX
*
* Frames awaiting TX will be aborted. Frames already being TX are not aborted.
* Transmission Complete Status bit is automatically set to 1.
* Similar to setting TX command, but the TWAI controller will not automatically
* retry transmission upon an error (e.g., due to acknowledge error).
*
* @param hw Start address of the TWAI registers
*
* @note Transmit commands should be called last (i.e., after handling buffer
* release and clear data overrun) in order to prevent the other commands
* overwriting this latched TX bit with 0.
*/
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; //Set command_reg.srr and command_reg.at simultaneously for single shot self reception request
}
/* --------------------------- Status Register ------------------------------ */
/**
* @brief Get all status bits
*
* @param hw Start address of the TWAI registers
* @return Status bits
*/
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)
{
hw->interrupt_enable_reg.val = intr_mask;
}
/* ------------------------ 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 ESP32S2 brp can be any even number between 2 to 32768
*/
static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t sjw, uint32_t tseg1, uint32_t tseg2, bool triple_sampling)
{
hw->bus_timing_0_reg.brp = (brp / 2) - 1;
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 a remote frame)
for (int i = 0; (i < dlc) && (i < TWAI_FRAME_MAX_DLC); i++) {
data_buffer[i] = data[i];
}
}
}
/**
* @brief Parse formatted TWAI frame (RX Buffer Layout) into its constituent contents
*
* @param[in] rx_frame Pointer to formatted frame
* @param[out] id 11 or 29bit ID
* @param[out] dlc Data length code
* @param[out] data Data. Left over bytes set to 0.
* @param[out] format Type of TWAI frame
*/
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 490. Set the divider to 0 to disable CLKOUT.
*
* @param hw Start address of the TWAI registers
* @param divider Divider for CLKOUT (any even number from 2 to 490). Set to 0 to disable CLKOUT
*/
static inline void twai_ll_set_clkout(twai_dev_t *hw, uint32_t divider)
{
if (divider >= 2 && divider <= 490) {
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 (255) means a divider of 1
hw->clock_divider_reg.co = 0;
hw->clock_divider_reg.cd = 255;
} else {
hw->clock_divider_reg.co = 1;
hw->clock_divider_reg.cd = 0;
}
}
#ifdef __cplusplus
}
#endif