Merge branch 'feat/soc_combination_esp32_s2' into 'master'

soc: combine xxx_caps.h into soc_caps.h

See merge request espressif/esp-idf!10384
This commit is contained in:
Michael (XIAO Xufeng)
2020-10-18 00:28:29 +08:00
198 changed files with 1085 additions and 1432 deletions

View File

@ -23,7 +23,8 @@
#include "soc/gpio_periph.h"
#include "soc/efuse_reg.h"
#include "soc/spi_reg.h"
#include "soc/spi_caps.h"
#include "soc/soc_caps.h"
#include "soc/soc_pins.h"
#include "flash_qio_mode.h"
#include "bootloader_common.h"
#include "bootloader_flash_config.h"

View File

@ -21,7 +21,7 @@
#include "soc/efuse_reg.h"
#include "soc/spi_reg.h"
#include "soc/spi_mem_reg.h"
#include "soc/spi_caps.h"
#include "soc/soc_caps.h"
#include "flash_qio_mode.h"
#include "bootloader_flash_config.h"
#include "bootloader_common.h"

View File

@ -21,7 +21,7 @@
#include "soc/efuse_reg.h"
#include "soc/spi_reg.h"
#include "soc/spi_mem_reg.h"
#include "soc/spi_caps.h"
#include "soc/soc_caps.h"
#include "flash_qio_mode.h"
#include "bootloader_flash_config.h"
#include "bootloader_common.h"

View File

@ -18,7 +18,7 @@
#include "hal/cpu_hal.h"
#include "hal/mpu_hal.h"
#include "hal/mpu_types.h"
#include "soc/mpu_caps.h"
#include "soc/soc_caps.h"
#include "bootloader_mem.h"
#include "xt_instr_macros.h"
#include "xtensa/config/specreg.h"
@ -28,7 +28,7 @@ static inline void cpu_configure_region_protection(void)
/* Currently, the only supported chips esp32 and esp32s2
* have the same configuration. Move this to the port layer once
* more chips with different configurations are supported.
*
*
* Both chips have the address space divided into 8 regions, 512MB each.
*/
const int illegal_regions[] = {0, 4, 5, 6, 7}; // 0x00000000, 0x80000000, 0xa0000000, 0xc0000000, 0xe0000000

View File

@ -32,6 +32,7 @@
#include "hal/adc_types.h"
#include "hal/adc_hal.h"
#include "hal/dac_hal.h"
#include "hal/adc_hal_conf.h"
#define ADC_CHECK_RET(fun_ret) ({ \
if (fun_ret != ESP_OK) { \

View File

@ -187,9 +187,9 @@ esp_err_t touch_pad_get_trigger_source(touch_trigger_src_t *src)
esp_err_t touch_pad_set_group_mask(uint16_t set1_mask, uint16_t set2_mask, uint16_t en_mask)
{
TOUCH_CHECK((set1_mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch set1 bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((set2_mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch set2 bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((en_mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch work_en bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((set1_mask <= TOUCH_PAD_BIT_MASK_ALL), "touch set1 bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((set2_mask <= TOUCH_PAD_BIT_MASK_ALL), "touch set2 bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((en_mask <= TOUCH_PAD_BIT_MASK_ALL), "touch work_en bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_set_group_mask(set1_mask, set2_mask);
@ -211,9 +211,9 @@ esp_err_t touch_pad_get_group_mask(uint16_t *set1_mask, uint16_t *set2_mask, uin
esp_err_t touch_pad_clear_group_mask(uint16_t set1_mask, uint16_t set2_mask, uint16_t en_mask)
{
TOUCH_CHECK((set1_mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch set1 bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((set2_mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch set2 bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((en_mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch work_en bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((set1_mask <= TOUCH_PAD_BIT_MASK_ALL), "touch set1 bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((set2_mask <= TOUCH_PAD_BIT_MASK_ALL), "touch set2 bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((en_mask <= TOUCH_PAD_BIT_MASK_ALL), "touch work_en bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_clear_channel_mask(en_mask);

View File

@ -17,6 +17,7 @@
#include <ctype.h>
#include "esp_log.h"
#include "sys/lock.h"
#include "soc/soc_pins.h"
#include "freertos/FreeRTOS.h"
#include "freertos/xtensa_api.h"
#include "freertos/semphr.h"
@ -53,7 +54,7 @@ static const char *TOUCH_TAG = "TOUCH_SENSOR";
TOUCH_CHECK(channel < SOC_TOUCH_SENSOR_NUM && channel >= 0, "Touch channel error", ESP_ERR_INVALID_ARG); \
TOUCH_CHECK(channel != SOC_TOUCH_DENOISE_CHANNEL, "TOUCH0 is internal denoise channel", ESP_ERR_INVALID_ARG); \
} while (0);
#define TOUCH_CH_MASK_CHECK(mask) TOUCH_CHECK((mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch channel bitmask error", ESP_ERR_INVALID_ARG)
#define TOUCH_CH_MASK_CHECK(mask) TOUCH_CHECK((mask <= TOUCH_PAD_BIT_MASK_ALL), "touch channel bitmask error", ESP_ERR_INVALID_ARG)
#define TOUCH_INTR_MASK_CHECK(mask) TOUCH_CHECK(mask & TOUCH_PAD_INTR_MASK_ALL, "intr mask error", ESP_ERR_INVALID_ARG)
#define TOUCH_PARAM_CHECK_STR(s) ""s" parameter error"

View File

@ -24,7 +24,7 @@
#include "esp_ipc.h"
#endif
#include "soc/gpio_caps.h"
#include "soc/soc_caps.h"
#include "soc/gpio_periph.h"
#include "esp_log.h"
#include "hal/gpio_hal.h"
@ -36,8 +36,14 @@ static const char *GPIO_TAG = "gpio";
ESP_LOGE(GPIO_TAG,"%s(%d): %s", __FUNCTION__, __LINE__, str); \
return (ret_val); \
}
#define GPIO_ISR_CORE_ID_UNINIT (3)
//default value for SOC_GPIO_SUPPORT_RTC_INDEPENDENT is 0
#ifndef SOC_GPIO_SUPPORT_RTC_INDEPENDENT
#define SOC_GPIO_SUPPORT_RTC_INDEPENDENT 0
#endif
typedef struct {
gpio_isr_t fn; /*!< isr function */
void *args; /*!< isr function args */
@ -76,7 +82,7 @@ esp_err_t gpio_pullup_en(gpio_num_t gpio_num)
{
GPIO_CHECK(GPIO_IS_VALID_GPIO(gpio_num), "GPIO number error", ESP_ERR_INVALID_ARG);
if (!rtc_gpio_is_valid_gpio(gpio_num) || GPIO_SUPPORTS_RTC_INDEPENDENT) {
if (!rtc_gpio_is_valid_gpio(gpio_num) || SOC_GPIO_SUPPORT_RTC_INDEPENDENT) {
portENTER_CRITICAL(&gpio_context.gpio_spinlock);
gpio_hal_pullup_en(gpio_context.gpio_hal, gpio_num);
portEXIT_CRITICAL(&gpio_context.gpio_spinlock);
@ -91,7 +97,7 @@ esp_err_t gpio_pullup_dis(gpio_num_t gpio_num)
{
GPIO_CHECK(GPIO_IS_VALID_GPIO(gpio_num), "GPIO number error", ESP_ERR_INVALID_ARG);
if (!rtc_gpio_is_valid_gpio(gpio_num) || GPIO_SUPPORTS_RTC_INDEPENDENT) {
if (!rtc_gpio_is_valid_gpio(gpio_num) || SOC_GPIO_SUPPORT_RTC_INDEPENDENT) {
portENTER_CRITICAL(&gpio_context.gpio_spinlock);
gpio_hal_pullup_dis(gpio_context.gpio_hal, gpio_num);
portEXIT_CRITICAL(&gpio_context.gpio_spinlock);
@ -106,7 +112,7 @@ esp_err_t gpio_pulldown_en(gpio_num_t gpio_num)
{
GPIO_CHECK(GPIO_IS_VALID_GPIO(gpio_num), "GPIO number error", ESP_ERR_INVALID_ARG);
if (!rtc_gpio_is_valid_gpio(gpio_num) || GPIO_SUPPORTS_RTC_INDEPENDENT) {
if (!rtc_gpio_is_valid_gpio(gpio_num) || SOC_GPIO_SUPPORT_RTC_INDEPENDENT) {
portENTER_CRITICAL(&gpio_context.gpio_spinlock);
gpio_hal_pulldown_en(gpio_context.gpio_hal, gpio_num);
portEXIT_CRITICAL(&gpio_context.gpio_spinlock);
@ -121,7 +127,7 @@ esp_err_t gpio_pulldown_dis(gpio_num_t gpio_num)
{
GPIO_CHECK(GPIO_IS_VALID_GPIO(gpio_num), "GPIO number error", ESP_ERR_INVALID_ARG);
if (!rtc_gpio_is_valid_gpio(gpio_num) || GPIO_SUPPORTS_RTC_INDEPENDENT) {
if (!rtc_gpio_is_valid_gpio(gpio_num) || SOC_GPIO_SUPPORT_RTC_INDEPENDENT) {
portENTER_CRITICAL(&gpio_context.gpio_spinlock);
gpio_hal_pulldown_dis(gpio_context.gpio_hal, gpio_num);
portEXIT_CRITICAL(&gpio_context.gpio_spinlock);
@ -302,26 +308,23 @@ esp_err_t gpio_config(const gpio_config_t *pGPIOConfig)
uint8_t pu_en = 0;
uint8_t pd_en = 0;
if (pGPIOConfig->pin_bit_mask == 0 || pGPIOConfig->pin_bit_mask >= (((uint64_t) 1) << GPIO_PIN_COUNT)) {
if (pGPIOConfig->pin_bit_mask == 0 ||
pGPIOConfig->pin_bit_mask & ~SOC_GPIO_VALID_GPIO_MASK) {
ESP_LOGE(GPIO_TAG, "GPIO_PIN mask error ");
return ESP_ERR_INVALID_ARG;
}
if ((pGPIOConfig->mode) & (GPIO_MODE_DEF_OUTPUT)) {
if(GPIO_MASK_CONTAIN_INPUT_GPIO(gpio_pin_mask)) {
ESP_LOGE(GPIO_TAG, "GPIO can only be used as input mode");
return ESP_ERR_INVALID_ARG;
}
if (pGPIOConfig->mode & GPIO_MODE_DEF_OUTPUT &&
pGPIOConfig->pin_bit_mask & ~SOC_GPIO_VALID_OUTPUT_GPIO_MASK) {
ESP_LOGE(GPIO_TAG, "GPIO can only be used as input mode");
return ESP_ERR_INVALID_ARG;
}
do {
io_reg = GPIO_PIN_MUX_REG[io_num];
if (((gpio_pin_mask >> io_num) & BIT(0))) {
if (!io_reg) {
ESP_LOGE(GPIO_TAG, "IO%d is not a valid GPIO", io_num);
return ESP_ERR_INVALID_ARG;
}
assert(io_reg != (intptr_t)NULL);
if (rtc_gpio_is_valid_gpio(io_num)) {
rtc_gpio_deinit(io_num);
@ -568,7 +571,7 @@ esp_err_t gpio_set_drive_capability(gpio_num_t gpio_num, gpio_drive_cap_t streng
GPIO_CHECK(strength < GPIO_DRIVE_CAP_MAX, "GPIO drive capability error", ESP_ERR_INVALID_ARG);
esp_err_t ret = ESP_OK;
if (!rtc_gpio_is_valid_gpio(gpio_num) || GPIO_SUPPORTS_RTC_INDEPENDENT) {
if (!rtc_gpio_is_valid_gpio(gpio_num) || SOC_GPIO_SUPPORT_RTC_INDEPENDENT) {
portENTER_CRITICAL(&gpio_context.gpio_spinlock);
gpio_hal_set_drive_capability(gpio_context.gpio_hal, gpio_num, strength);
portEXIT_CRITICAL(&gpio_context.gpio_spinlock);
@ -585,7 +588,7 @@ esp_err_t gpio_get_drive_capability(gpio_num_t gpio_num, gpio_drive_cap_t *stren
GPIO_CHECK(strength != NULL, "GPIO drive capability pointer error", ESP_ERR_INVALID_ARG);
esp_err_t ret = ESP_OK;
if (!rtc_gpio_is_valid_gpio(gpio_num) || GPIO_SUPPORTS_RTC_INDEPENDENT) {
if (!rtc_gpio_is_valid_gpio(gpio_num) || SOC_GPIO_SUPPORT_RTC_INDEPENDENT) {
portENTER_CRITICAL(&gpio_context.gpio_spinlock);
gpio_hal_get_drive_capability(gpio_context.gpio_hal, gpio_num, strength);
portEXIT_CRITICAL(&gpio_context.gpio_spinlock);
@ -646,7 +649,7 @@ void gpio_deep_sleep_hold_dis(void)
portEXIT_CRITICAL(&gpio_context.gpio_spinlock);
}
#if GPIO_SUPPORTS_FORCE_HOLD
#if SOC_GPIO_SUPPORT_FORCE_HOLD
esp_err_t gpio_force_hold_all()
{

View File

@ -155,7 +155,7 @@ typedef struct {
i2c_hal_context_t hal; /*!< I2C hal context */
portMUX_TYPE spinlock;
bool hw_enabled;
#if !I2C_SUPPORT_HW_CLR_BUS
#if !SOC_I2C_SUPPORT_HW_CLR_BUS
int scl_io_num;
int sda_io_num;
#endif
@ -304,8 +304,8 @@ esp_err_t i2c_driver_install(i2c_port_t i2c_num, i2c_mode_t mode, size_t slv_rx_
}
i2c_hw_enable(i2c_num);
//Disable I2C interrupt.
i2c_hal_disable_intr_mask(&(i2c_context[i2c_num].hal), I2C_INTR_MASK);
i2c_hal_clr_intsts_mask(&(i2c_context[i2c_num].hal), I2C_INTR_MASK);
i2c_hal_disable_intr_mask(&(i2c_context[i2c_num].hal), I2C_LL_INTR_MASK);
i2c_hal_clr_intsts_mask(&(i2c_context[i2c_num].hal), I2C_LL_INTR_MASK);
//hook isr handler
i2c_isr_register(i2c_num, i2c_isr_handler_default, p_i2c_obj[i2c_num], intr_alloc_flags, &p_i2c_obj[i2c_num]->intr_handle);
//Enable I2C slave rx interrupt
@ -364,7 +364,7 @@ esp_err_t i2c_driver_delete(i2c_port_t i2c_num)
I2C_CHECK(p_i2c_obj[i2c_num] != NULL, I2C_DRIVER_ERR_STR, ESP_FAIL);
i2c_obj_t *p_i2c = p_i2c_obj[i2c_num];
i2c_hal_disable_intr_mask(&(i2c_context[i2c_num].hal), I2C_INTR_MASK);
i2c_hal_disable_intr_mask(&(i2c_context[i2c_num].hal), I2C_LL_INTR_MASK);
esp_intr_free(p_i2c->intr_handle);
p_i2c->intr_handle = NULL;
@ -516,7 +516,7 @@ esp_err_t i2c_get_data_mode(i2c_port_t i2c_num, i2c_trans_mode_t *tx_trans_mode,
**/
static esp_err_t i2c_master_clear_bus(i2c_port_t i2c_num)
{
#if !I2C_SUPPORT_HW_CLR_BUS
#if !SOC_I2C_SUPPORT_HW_CLR_BUS
const int scl_half_period = I2C_CLR_BUS_HALF_PERIOD_US; // use standard 100kHz data rate
int i = 0;
int scl_io = i2c_context[i2c_num].scl_io_num;
@ -554,7 +554,7 @@ static esp_err_t i2c_master_clear_bus(i2c_port_t i2c_num)
**/
static esp_err_t i2c_hw_fsm_reset(i2c_port_t i2c_num)
{
#if !I2C_SUPPORT_HW_FSM_RST
#if !SOC_I2C_SUPPORT_HW_FSM_RST
int scl_low_period, scl_high_period;
int scl_start_hold, scl_rstart_setup;
int scl_stop_hold, scl_stop_setup;
@ -575,8 +575,8 @@ static esp_err_t i2c_hw_fsm_reset(i2c_port_t i2c_num)
i2c_hw_enable(i2c_num);
i2c_hal_master_init(&(i2c_context[i2c_num].hal), i2c_num);
i2c_hal_disable_intr_mask(&(i2c_context[i2c_num].hal), I2C_INTR_MASK);
i2c_hal_clr_intsts_mask(&(i2c_context[i2c_num].hal), I2C_INTR_MASK);
i2c_hal_disable_intr_mask(&(i2c_context[i2c_num].hal), I2C_LL_INTR_MASK);
i2c_hal_clr_intsts_mask(&(i2c_context[i2c_num].hal), I2C_LL_INTR_MASK);
i2c_hal_set_scl_timing(&(i2c_context[i2c_num].hal), scl_high_period, scl_low_period);
i2c_hal_set_start_timing(&(i2c_context[i2c_num].hal), scl_rstart_setup, scl_start_hold);
i2c_hal_set_stop_timing(&(i2c_context[i2c_num].hal), scl_stop_setup, scl_stop_hold);
@ -603,8 +603,8 @@ esp_err_t i2c_param_config(i2c_port_t i2c_num, const i2c_config_t *i2c_conf)
}
i2c_hw_enable(i2c_num);
I2C_ENTER_CRITICAL(&(i2c_context[i2c_num].spinlock));
i2c_hal_disable_intr_mask(&(i2c_context[i2c_num].hal), I2C_INTR_MASK);
i2c_hal_clr_intsts_mask(&(i2c_context[i2c_num].hal), I2C_INTR_MASK);
i2c_hal_disable_intr_mask(&(i2c_context[i2c_num].hal), I2C_LL_INTR_MASK);
i2c_hal_clr_intsts_mask(&(i2c_context[i2c_num].hal), I2C_LL_INTR_MASK);
if (i2c_conf->mode == I2C_MODE_SLAVE) { //slave mode
i2c_hal_slave_init(&(i2c_context[i2c_num].hal), i2c_num);
i2c_hal_set_slave_addr(&(i2c_context[i2c_num].hal), i2c_conf->slave.slave_addr, i2c_conf->slave.addr_10bit_en);
@ -805,7 +805,7 @@ esp_err_t i2c_set_pin(i2c_port_t i2c_num, int sda_io_num, int scl_io_num, bool s
gpio_set_pull_mode(scl_io_num, GPIO_FLOATING);
}
}
#if !I2C_SUPPORT_HW_CLR_BUS
#if !SOC_I2C_SUPPORT_HW_CLR_BUS
i2c_context[i2c_num].scl_io_num = scl_io_num;
i2c_context[i2c_num].sda_io_num = sda_io_num;
#endif
@ -1155,8 +1155,8 @@ esp_err_t i2c_master_cmd_begin(i2c_port_t i2c_num, i2c_cmd_handle_t cmd_handle,
i2c_reset_rx_fifo(i2c_num);
// These two interrupts some times can not be cleared when the FSM gets stuck.
// so we disable them when these two interrupt occurs and re-enable them here.
i2c_hal_disable_intr_mask(&(i2c_context[i2c_num].hal), I2C_INTR_MASK);
i2c_hal_clr_intsts_mask(&(i2c_context[i2c_num].hal), I2C_INTR_MASK);
i2c_hal_disable_intr_mask(&(i2c_context[i2c_num].hal), I2C_LL_INTR_MASK);
i2c_hal_clr_intsts_mask(&(i2c_context[i2c_num].hal), I2C_LL_INTR_MASK);
//start send commands, at most 32 bytes one time, isr handler will process the remaining commands.
i2c_master_cmd_begin_static(i2c_num);

View File

@ -54,6 +54,11 @@ static const char* I2S_TAG = "I2S";
#define I2S_FULL_DUPLEX_SLAVE_MODE_MASK (I2S_MODE_TX | I2S_MODE_RX | I2S_MODE_SLAVE)
#define I2S_FULL_DUPLEX_MASTER_MODE_MASK (I2S_MODE_TX | I2S_MODE_RX | I2S_MODE_MASTER)
//TODO: Refactor to put this logic into LL
#define I2S_AD_BCK_FACTOR (2)
#define I2S_PDM_BCK_FACTOR (64)
#define I2S_BASE_CLK (2*APB_CLK_FREQ)
/**
* @brief DMA buffer object
*
@ -112,7 +117,7 @@ static inline void gpio_matrix_out_check(uint32_t gpio, uint32_t signal_idx, boo
//if pin = -1, do not need to configure
if (gpio != -1) {
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[gpio], PIN_FUNC_GPIO);
gpio_set_direction(gpio, GPIO_MODE_DEF_OUTPUT);
gpio_set_direction(gpio, GPIO_MODE_OUTPUT);
esp_rom_gpio_connect_out_signal(gpio, signal_idx, out_inv, oen_inv);
}
}
@ -122,7 +127,7 @@ static inline void gpio_matrix_in_check(uint32_t gpio, uint32_t signal_idx, bool
if (gpio != -1) {
PIN_FUNC_SELECT(GPIO_PIN_MUX_REG[gpio], PIN_FUNC_GPIO);
//Set direction, for some GPIOs, the input function are not enabled as default.
gpio_set_direction(gpio, GPIO_MODE_DEF_INPUT);
gpio_set_direction(gpio, GPIO_MODE_INPUT);
esp_rom_gpio_connect_in_signal(gpio, signal_idx, inv);
}
}
@ -190,8 +195,8 @@ static float i2s_apll_get_fi2s(int bits_per_sample, int sdm0, int sdm1, int sdm2
}
#endif
float fout = f_xtal * (sdm2 + sdm1 / 256.0f + sdm0 / 65536.0f + 4);
if (fout < APLL_MIN_FREQ || fout > APLL_MAX_FREQ) {
return APLL_MAX_FREQ;
if (fout < SOC_I2S_APLL_MIN_FREQ || fout > SOC_I2S_APLL_MAX_FREQ) {
return SOC_I2S_APLL_MAX_FREQ;
}
float fpll = fout / (2 * (odir+2)); //== fi2s (N=1, b=0, a=1)
return fpll/2;
@ -236,7 +241,7 @@ static esp_err_t i2s_apll_calculate_fi2s(int rate, int bits_per_sample, int *sdm
int _odir, _sdm0, _sdm1, _sdm2;
float avg;
float min_rate, max_rate, min_diff;
if (rate/bits_per_sample/2/8 < APLL_I2S_MIN_RATE) {
if (rate/bits_per_sample/2/8 < SOC_I2S_APLL_MIN_RATE) {
return ESP_ERR_INVALID_ARG;
}
@ -244,7 +249,7 @@ static esp_err_t i2s_apll_calculate_fi2s(int rate, int bits_per_sample, int *sdm
*sdm1 = 0;
*sdm2 = 0;
*odir = 0;
min_diff = APLL_MAX_FREQ;
min_diff = SOC_I2S_APLL_MAX_FREQ;
for (_sdm2 = 4; _sdm2 < 9; _sdm2 ++) {
max_rate = i2s_apll_get_fi2s(bits_per_sample, 255, 255, _sdm2, 0);
@ -255,7 +260,7 @@ static esp_err_t i2s_apll_calculate_fi2s(int rate, int bits_per_sample, int *sdm
*sdm2 = _sdm2;
}
}
min_diff = APLL_MAX_FREQ;
min_diff = SOC_I2S_APLL_MAX_FREQ;
for (_odir = 0; _odir < 32; _odir ++) {
max_rate = i2s_apll_get_fi2s(bits_per_sample, 255, 255, *sdm2, _odir);
min_rate = i2s_apll_get_fi2s(bits_per_sample, 0, 0, *sdm2, _odir);
@ -265,7 +270,7 @@ static esp_err_t i2s_apll_calculate_fi2s(int rate, int bits_per_sample, int *sdm
*odir = _odir;
}
}
min_diff = APLL_MAX_FREQ;
min_diff = SOC_I2S_APLL_MAX_FREQ;
for (_sdm2 = 4; _sdm2 < 9; _sdm2 ++) {
max_rate = i2s_apll_get_fi2s(bits_per_sample, 255, 255, _sdm2, *odir);
min_rate = i2s_apll_get_fi2s(bits_per_sample, 0, 0, _sdm2, *odir);
@ -276,7 +281,7 @@ static esp_err_t i2s_apll_calculate_fi2s(int rate, int bits_per_sample, int *sdm
}
}
min_diff = APLL_MAX_FREQ;
min_diff = SOC_I2S_APLL_MAX_FREQ;
for (_sdm1 = 0; _sdm1 < 256; _sdm1 ++) {
max_rate = i2s_apll_get_fi2s(bits_per_sample, 255, _sdm1, *sdm2, *odir);
min_rate = i2s_apll_get_fi2s(bits_per_sample, 0, _sdm1, *sdm2, *odir);
@ -287,7 +292,7 @@ static esp_err_t i2s_apll_calculate_fi2s(int rate, int bits_per_sample, int *sdm
}
}
min_diff = APLL_MAX_FREQ;
min_diff = SOC_I2S_APLL_MAX_FREQ;
for (_sdm0 = 0; _sdm0 < 256; _sdm0 ++) {
avg = i2s_apll_get_fi2s(bits_per_sample, _sdm0, *sdm1, *sdm2, *odir);
if (abs(avg - rate) < min_diff) {
@ -501,7 +506,7 @@ static void IRAM_ATTR i2s_intr_handler_default(void *arg)
//Avoid spurious interrupt
return;
}
i2s_event_t i2s_event;
int dummy;
@ -922,7 +927,7 @@ esp_err_t i2s_driver_install(i2s_port_t i2s_num, const i2s_config_t *i2s_config,
}
memset(p_i2s_obj[i2s_num], 0, sizeof(i2s_obj_t));
portMUX_TYPE i2s_spinlock_unlocked[1] = {portMUX_INITIALIZER_UNLOCKED};
portMUX_TYPE i2s_spinlock_unlocked[1] = {portMUX_INITIALIZER_UNLOCKED};
for (int x = 0; x < I2S_NUM_MAX; x++) {
i2s_spinlock[x] = i2s_spinlock_unlocked[0];
}
@ -1036,7 +1041,7 @@ esp_err_t i2s_write(i2s_port_t i2s_num, const void *src, size_t size, size_t *by
int bytes_can_write;
*bytes_written = 0;
I2S_CHECK((i2s_num < I2S_NUM_MAX), "i2s_num error", ESP_ERR_INVALID_ARG);
I2S_CHECK((size < I2S_MAX_BUFFER_SIZE), "size is too large", ESP_ERR_INVALID_ARG);
I2S_CHECK((size < SOC_I2S_MAX_BUFFER_SIZE), "size is too large", ESP_ERR_INVALID_ARG);
I2S_CHECK((p_i2s_obj[i2s_num]->tx), "tx NULL", ESP_ERR_INVALID_ARG);
xSemaphoreTake(p_i2s_obj[i2s_num]->tx->mux, (portTickType)portMAX_DELAY);
#ifdef CONFIG_PM_ENABLE
@ -1105,7 +1110,7 @@ esp_err_t i2s_write_expand(i2s_port_t i2s_num, const void *src, size_t size, siz
*bytes_written = 0;
I2S_CHECK((i2s_num < I2S_NUM_MAX), "i2s_num error", ESP_ERR_INVALID_ARG);
I2S_CHECK((size > 0), "size must greater than zero", ESP_ERR_INVALID_ARG);
I2S_CHECK((aim_bits * size < I2S_MAX_BUFFER_SIZE), "size is too large", ESP_ERR_INVALID_ARG);
I2S_CHECK((aim_bits * size < SOC_I2S_MAX_BUFFER_SIZE), "size is too large", ESP_ERR_INVALID_ARG);
I2S_CHECK((aim_bits >= src_bits), "aim_bits mustn't be less than src_bits", ESP_ERR_INVALID_ARG);
I2S_CHECK((p_i2s_obj[i2s_num]->tx), "tx NULL", ESP_ERR_INVALID_ARG);
if (src_bits < I2S_BITS_PER_SAMPLE_8BIT || aim_bits < I2S_BITS_PER_SAMPLE_8BIT) {
@ -1167,7 +1172,7 @@ esp_err_t i2s_read(i2s_port_t i2s_num, void *dest, size_t size, size_t *bytes_re
*bytes_read = 0;
dest_byte = (char *)dest;
I2S_CHECK((i2s_num < I2S_NUM_MAX), "i2s_num error", ESP_ERR_INVALID_ARG);
I2S_CHECK((size < I2S_MAX_BUFFER_SIZE), "size is too large", ESP_ERR_INVALID_ARG);
I2S_CHECK((size < SOC_I2S_MAX_BUFFER_SIZE), "size is too large", ESP_ERR_INVALID_ARG);
I2S_CHECK((p_i2s_obj[i2s_num]->rx), "rx NULL", ESP_ERR_INVALID_ARG);
xSemaphoreTake(p_i2s_obj[i2s_num]->rx->mux, (portTickType)portMAX_DELAY);
#ifdef CONFIG_PM_ENABLE

View File

@ -19,6 +19,7 @@
#include <esp_bit_defs.h>
#include "esp_attr.h"
#include "esp_intr_alloc.h"
#include "soc/soc_caps.h"
#include "soc/gpio_periph.h"
#include "hal/gpio_types.h"
@ -40,6 +41,13 @@
extern "C" {
#endif
#define GPIO_PIN_COUNT (SOC_GPIO_PIN_COUNT)
/// Check whether it is a valid GPIO number
#define GPIO_IS_VALID_GPIO(gpio_num) (((1ULL << (gpio_num)) & SOC_GPIO_VALID_GPIO_MASK) != 0)
/// Check whether it can be a valid GPIO number of output mode
#define GPIO_IS_VALID_OUTPUT_GPIO(gpio_num) (((1ULL << (gpio_num)) & SOC_GPIO_VALID_OUTPUT_GPIO_MASK) != 0)
typedef intr_handle_t gpio_isr_handle_t;
/**
@ -419,7 +427,7 @@ void gpio_iomux_in(uint32_t gpio_num, uint32_t signal_idx);
*/
void gpio_iomux_out(uint8_t gpio_num, int func, bool oen_inv);
#if GPIO_SUPPORTS_FORCE_HOLD
#if SOC_GPIO_SUPPORT_FORCE_HOLD
/**
* @brief Force hold digital and rtc gpio pad.
* @note GPIO force hold, whether the chip in sleep mode or wakeup mode.

View File

@ -29,8 +29,8 @@ extern "C" {
#include "freertos/queue.h"
#include "freertos/ringbuf.h"
#include "driver/gpio.h"
#include "soc/soc_caps.h"
#include "hal/i2c_types.h"
#include "soc/i2c_caps.h"
#define I2C_APB_CLK_FREQ APB_CLK_FREQ /*!< I2C source clock is APB clock, 80MHz */

View File

@ -20,7 +20,7 @@
#include "freertos/semphr.h"
#include "soc/i2s_periph.h"
#include "soc/rtc_periph.h"
#include "soc/i2s_caps.h"
#include "soc/soc_caps.h"
#include "hal/i2s_hal.h"
#include "hal/i2s_types.h"
#include "driver/periph_ctrl.h"

View File

@ -12,13 +12,10 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef _DRIVER_MCPWM_H_
#define _DRIVER_MCPWM_H_
#pragma once
#include "soc/soc_caps.h"
#ifndef SOC_MCPWM_SUPPORTED
#error MCPWM is not supported in this chip target
#endif
#if SOC_MCPWM_SUPPORTED
#include "esp_err.h"
#include "soc/soc.h"
@ -26,7 +23,6 @@
#include "driver/periph_ctrl.h"
#include "esp_intr_alloc.h"
#include "hal/mcpwm_types.h"
#include "soc/mcpwm_caps.h"
#ifdef __cplusplus
extern "C" {
@ -665,4 +661,5 @@ esp_err_t mcpwm_isr_register(mcpwm_unit_t mcpwm_num, void (*fn)(void *), void *a
}
#endif
#endif /*_DRIVER_MCPWM_H_*/
#endif //SOC_MCPWM_SUPPORTED

View File

@ -21,10 +21,10 @@ extern "C" {
#include <stdbool.h>
#include <stdint.h>
#include "esp_err.h"
#include "soc/soc_caps.h"
#include "driver/gpio.h"
#include "freertos/FreeRTOS.h"
#include "freertos/ringbuf.h"
#include "soc/rmt_caps.h"
#include "soc/rmt_struct.h"
#include "hal/rmt_types.h"

View File

@ -15,9 +15,7 @@
#pragma once
#include "soc/soc_caps.h"
#ifndef SOC_SDMMC_HOST_SUPPORTED
#error SDMMC host is not supported in this chip target
#endif
#if SOC_SDMMC_HOST_SUPPORTED
#include <stdint.h>
#include <stddef.h>
@ -245,3 +243,5 @@ esp_err_t sdmmc_host_pullup_en(int slot, int width);
#ifdef __cplusplus
}
#endif
#endif //SOC_SDMMC_HOST_SUPPORTED

View File

@ -14,8 +14,8 @@
#pragma once
#include <esp_types.h>
#include "soc/soc_caps.h"
#include "soc/sigmadelta_periph.h"
#include "soc/sigmadelta_caps.h"
#include "driver/gpio.h"
#include "hal/sigmadelta_types.h"

View File

@ -15,7 +15,7 @@
#pragma once
#include "esp_types.h"
#include "soc/spi_caps.h"
#include "soc/soc_caps.h"
#include "freertos/FreeRTOS.h"
#include "hal/spi_types.h"

View File

@ -19,16 +19,13 @@ extern "C" {
#endif
#include "soc/soc_caps.h"
#ifndef SOC_TWAI_SUPPORTED
#error TWAI is not supported in this chip target
#endif
#if SOC_TWAI_SUPPORTED
#include "freertos/FreeRTOS.h"
#include "esp_types.h"
#include "esp_intr_alloc.h"
#include "esp_err.h"
#include "gpio.h"
#include "soc/twai_caps.h"
#include "hal/twai_types.h"
/* -------------------- Default initializers and flags ---------------------- */
@ -347,3 +344,5 @@ esp_err_t twai_clear_receive_queue(void);
#ifdef __cplusplus
}
#endif
#endif //SOC_TWAI_SUPPORTED

View File

@ -20,6 +20,7 @@ extern "C" {
#include "esp_err.h"
#include "esp_intr_alloc.h"
#include "soc/soc_caps.h"
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "freertos/xtensa_api.h"
@ -27,7 +28,6 @@ extern "C" {
#include "freertos/queue.h"
#include "freertos/ringbuf.h"
#include "hal/uart_types.h"
#include "soc/uart_caps.h"
// Valid UART port number
#define UART_NUM_0 (0) /*!< UART port 0 */
@ -39,6 +39,9 @@ extern "C" {
#define UART_PIN_NO_CHANGE (-1) /*!< Constant for uart_set_pin function which indicates that UART pin should not be changed */
#define UART_FIFO_LEN SOC_UART_FIFO_LEN ///< Length of the UART HW FIFO
#define UART_BITRATE_MAX SOC_UART_BITRATE_MAX ///< Maximum configurable bitrate
/**
* @brief UART interrupt configuration parameters for uart_intr_config function
*/
@ -224,7 +227,7 @@ esp_err_t uart_get_baudrate(uart_port_t uart_num, uint32_t* baudrate);
* @brief Set UART line inverse mode
*
* @param uart_num UART port number, the max port number is (UART_NUM_MAX -1).
* @param inverse_mask Choose the wires that need to be inverted. Using the ORred mask of `uart_signal_inv_t`
* @param inverse_mask Choose the wires that need to be inverted. Using the ORred mask of `uart_signal_inv_t`
*
* @return
* - ESP_OK Success

View File

@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#include "soc/soc_caps.h"
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "freertos/xtensa_api.h"
@ -19,7 +20,6 @@
#include "driver/pcnt.h"
#include "driver/periph_ctrl.h"
#include "hal/pcnt_hal.h"
#include "soc/pcnt_caps.h"
#include "esp_rom_gpio.h"
#define PCNT_CHANNEL_ERR_STR "PCNT CHANNEL ERROR"
@ -287,7 +287,7 @@ static void IRAM_ATTR pcnt_intr_service(void *arg)
uint32_t status;
pcnt_port_t pcnt_port = (pcnt_port_t)arg;
pcnt_hal_get_intr_status(&(p_pcnt_obj[pcnt_port]->hal), &status);
while (status) {
int unit = __builtin_ffs(status) - 1;
status &= ~(1 << unit);

View File

@ -17,8 +17,9 @@
#include <sys/param.h>
#include "esp_log.h"
#include "esp_intr_alloc.h"
#include "soc/soc_caps.h"
#include "soc/soc_pins.h"
#include "soc/gpio_periph.h"
#include "soc/gpio_caps.h"
#include "esp_rom_gpio.h"
#include "esp_rom_sys.h"
#include "driver/gpio.h"

View File

@ -18,7 +18,7 @@
#include "sdkconfig.h"
#include "spi_common_internal.h"
#include "esp_intr_alloc.h"
#include "soc/spi_caps.h"
#include "soc/soc_caps.h"
#include "stdatomic.h"
#include "esp_log.h"
#include <strings.h>

View File

@ -410,7 +410,7 @@ esp_err_t spi_bus_add_device(spi_host_device_t host_id, const spi_device_interfa
hal_dev->tx_lsbfirst = dev_config->flags & SPI_DEVICE_TXBIT_LSBFIRST ? 1 : 0;
hal_dev->rx_lsbfirst = dev_config->flags & SPI_DEVICE_RXBIT_LSBFIRST ? 1 : 0;
hal_dev->no_compensate = dev_config->flags & SPI_DEVICE_NO_DUMMY ? 1 : 0;
#ifdef SOC_SPI_SUPPORT_AS_CS
#if SOC_SPI_SUPPORT_AS_CS
hal_dev->as_cs = dev_config->flags& SPI_DEVICE_CLK_AS_CS ? 1 : 0;
#endif
hal_dev->positive_cs = dev_config->flags & SPI_DEVICE_POSITIVE_CS ? 1 : 0;

View File

@ -13,29 +13,30 @@
// limitations under the License.
#include <string.h>
#include "sdkconfig.h"
#include <hal/spi_ll.h>
#include <hal/spi_slave_hal.h>
#include <soc/lldesc.h>
#include "driver/spi_common_internal.h"
#include "driver/spi_slave.h"
#include "soc/spi_periph.h"
#include "soc/gpio_caps.h"
#include "esp_types.h"
#include "esp_attr.h"
#include "esp_intr_alloc.h"
#include "esp_log.h"
#include "esp_err.h"
#include "esp_pm.h"
#include "esp_heap_caps.h"
#include "esp_rom_gpio.h"
#include "esp_rom_sys.h"
#include "soc/lldesc.h"
#include "soc/soc_caps.h"
#include "soc/spi_periph.h"
#include "soc/soc_memory_layout.h"
#include "hal/spi_ll.h"
#include "hal/spi_slave_hal.h"
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "freertos/xtensa_api.h"
#include "freertos/task.h"
#include "soc/soc_memory_layout.h"
#include "sdkconfig.h"
#include "driver/gpio.h"
#include "esp_heap_caps.h"
#include "esp_rom_gpio.h"
#include "esp_rom_sys.h"
#include "driver/spi_common_internal.h"
#include "driver/spi_slave.h"
#include "hal/spi_slave_hal.h"
static const char *SPI_TAG = "spi_slave";

View File

@ -21,7 +21,7 @@
#include "esp_attr.h"
#include "esp_log.h"
#include "soc/gpio_periph.h"
#include "soc/gpio_caps.h"
#include "soc/soc_caps.h"
#include "unity.h"
#include "esp_rom_gpio.h"
@ -606,7 +606,7 @@ TEST_CASE("PCNT interrupt method test(control IO is low)", "[pcnt][timeout=120]"
TEST_ESP_OK(pcnt_counter_clear(PCNT_UNIT_0));
pcnt_evt_queue = xQueueCreate(10, sizeof(uint32_t));
pcnt_isr_handle_t pcnt_isr_service;
TEST_ESP_OK(pcnt_isr_register(pcnt_intr_handler, NULL, 0, &pcnt_isr_service));
TEST_ESP_OK(pcnt_intr_enable(PCNT_UNIT_0));

View File

@ -27,7 +27,7 @@
#if !TEMPORARY_DISABLED_FOR_TARGETS(ESP32S3)
#ifdef SOC_MCPWM_SUPPORTED
#if SOC_MCPWM_SUPPORTED
#include "soc/mcpwm_periph.h"
#include "driver/mcpwm.h"

View File

@ -24,7 +24,7 @@
#if !TEMPORARY_DISABLED_FOR_TARGETS(ESP32S3)
#if defined(SOC_SDMMC_HOST_SUPPORTED) && defined(SOC_SDIO_SLAVE_SUPPORTED)
#if SOC_SDMMC_HOST_SUPPORTED && SOC_SDIO_SLAVE_SUPPORTED
#include "driver/sdio_slave.h"
#include "driver/sdmmc_host.h"
@ -807,6 +807,6 @@ ptest_func_t tohost_slave = {
TEST_MASTER_SLAVE(SDIO_TOHOST, test_cfg_array, "[sdio][timeout=180][test_env=UT_SDIO]", &tohost_master, &tohost_slave);
#endif
#endif //SOC_SDMMC_HOST_SUPPORTED && SOC_SDIO_SLAVE_SUPPORTED
#endif

View File

@ -18,6 +18,7 @@
#include "esp_types.h"
#include "esp_log.h"
#include "sys/lock.h"
#include "soc/soc_pins.h"
#include "freertos/FreeRTOS.h"
#include "freertos/xtensa_api.h"
#include "freertos/semphr.h"

View File

@ -373,9 +373,9 @@ esp_err_t twai_driver_install(const twai_general_config_t *g_config, const twai_
TWAI_CHECK(g_config->tx_io >= 0 && g_config->tx_io < GPIO_NUM_MAX, ESP_ERR_INVALID_ARG);
TWAI_CHECK(g_config->rx_io >= 0 && g_config->rx_io < GPIO_NUM_MAX, ESP_ERR_INVALID_ARG);
#if (CONFIG_ESP32_REV_MIN >= 2)
TWAI_CHECK(t_config->brp >= TWAI_BRP_MIN && t_config->brp <= TWAI_BRP_MAX_ECO, ESP_ERR_INVALID_ARG);
TWAI_CHECK(t_config->brp >= SOC_TWAI_BRP_MIN && t_config->brp <= SOC_TWAI_BRP_MAX_ECO, ESP_ERR_INVALID_ARG);
#else
TWAI_CHECK(t_config->brp >= TWAI_BRP_MIN && t_config->brp <= TWAI_BRP_MAX, ESP_ERR_INVALID_ARG);
TWAI_CHECK(t_config->brp >= SOC_TWAI_BRP_MIN && t_config->brp <= SOC_TWAI_BRP_MAX, ESP_ERR_INVALID_ARG);
#endif
#ifndef CONFIG_TWAI_ISR_IN_IRAM
TWAI_CHECK(!(g_config->intr_flags & ESP_INTR_FLAG_IRAM), ESP_ERR_INVALID_ARG);

View File

@ -61,7 +61,7 @@ static const char* UART_TAG = "uart";
#define UART_CLKDIV_FRAG_BIT_WIDTH (3)
#define UART_TX_IDLE_NUM_DEFAULT (0)
#define UART_PATTERN_DET_QLEN_DEFAULT (10)
#define UART_MIN_WAKEUP_THRESH (SOC_UART_MIN_WAKEUP_THRESH)
#define UART_MIN_WAKEUP_THRESH (UART_LL_MIN_WAKEUP_THRESH)
#define UART_INTR_CONFIG_FLAG ((UART_INTR_RXFIFO_FULL) \
| (UART_INTR_RXFIFO_TOUT) \
@ -118,7 +118,7 @@ typedef struct {
int rx_cur_remain; /*!< Data number that waiting to be read out in ring buffer item*/
uint8_t* rx_ptr; /*!< pointer to the current data in ring buffer*/
uint8_t* rx_head_ptr; /*!< pointer to the head of RX item*/
uint8_t rx_data_buf[UART_FIFO_LEN]; /*!< Data buffer to stash FIFO data*/
uint8_t rx_data_buf[SOC_UART_FIFO_LEN]; /*!< Data buffer to stash FIFO data*/
uint8_t rx_stash_len; /*!< stashed data length.(When using flow control, after reading out FIFO data, if we fail to push to buffer, we can just stash them.) */
uart_pat_rb_t rx_pattern_pos;
@ -265,8 +265,8 @@ esp_err_t uart_set_line_inverse(uart_port_t uart_num, uint32_t inverse_mask)
esp_err_t uart_set_sw_flow_ctrl(uart_port_t uart_num, bool enable, uint8_t rx_thresh_xon, uint8_t rx_thresh_xoff)
{
UART_CHECK((uart_num < UART_NUM_MAX), "uart_num error", ESP_FAIL);
UART_CHECK((rx_thresh_xon < UART_FIFO_LEN), "rx flow xon thresh error", ESP_FAIL);
UART_CHECK((rx_thresh_xoff < UART_FIFO_LEN), "rx flow xon thresh error", ESP_FAIL);
UART_CHECK((rx_thresh_xon < SOC_UART_FIFO_LEN), "rx flow xon thresh error", ESP_FAIL);
UART_CHECK((rx_thresh_xoff < SOC_UART_FIFO_LEN), "rx flow xon thresh error", ESP_FAIL);
uart_sw_flowctrl_t sw_flow_ctl = {
.xon_char = XON,
.xoff_char = XOFF,
@ -282,7 +282,7 @@ esp_err_t uart_set_sw_flow_ctrl(uart_port_t uart_num, bool enable, uint8_t rx_t
esp_err_t uart_set_hw_flow_ctrl(uart_port_t uart_num, uart_hw_flowcontrol_t flow_ctrl, uint8_t rx_thresh)
{
UART_CHECK((uart_num < UART_NUM_MAX), "uart_num error", ESP_FAIL);
UART_CHECK((rx_thresh < UART_FIFO_LEN), "rx flow thresh error", ESP_FAIL);
UART_CHECK((rx_thresh < SOC_UART_FIFO_LEN), "rx flow thresh error", ESP_FAIL);
UART_CHECK((flow_ctrl < UART_HW_FLOWCTRL_MAX), "hw_flowctrl mode error", ESP_FAIL);
UART_ENTER_CRITICAL(&(uart_context[uart_num].spinlock));
uart_hal_set_hw_flow_ctrl(&(uart_context[uart_num].hal), flow_ctrl, rx_thresh);
@ -522,7 +522,7 @@ esp_err_t uart_disable_tx_intr(uart_port_t uart_num)
esp_err_t uart_enable_tx_intr(uart_port_t uart_num, int enable, int thresh)
{
UART_CHECK((uart_num < UART_NUM_MAX), "uart_num error", ESP_FAIL);
UART_CHECK((thresh < UART_FIFO_LEN), "empty intr threshold error", ESP_FAIL);
UART_CHECK((thresh < SOC_UART_FIFO_LEN), "empty intr threshold error", ESP_FAIL);
uart_hal_clr_intsts_mask(&(uart_context[uart_num].hal), UART_INTR_TXFIFO_EMPTY);
UART_ENTER_CRITICAL(&(uart_context[uart_num].spinlock));
uart_hal_set_txfifo_empty_thr(&(uart_context[uart_num].hal), thresh);
@ -622,7 +622,7 @@ esp_err_t uart_param_config(uart_port_t uart_num, const uart_config_t *uart_conf
{
UART_CHECK((uart_num < UART_NUM_MAX), "uart_num error", ESP_FAIL);
UART_CHECK((uart_config), "param null", ESP_FAIL);
UART_CHECK((uart_config->rx_flow_ctrl_thresh < UART_FIFO_LEN), "rx flow thresh error", ESP_FAIL);
UART_CHECK((uart_config->rx_flow_ctrl_thresh < SOC_UART_FIFO_LEN), "rx flow thresh error", ESP_FAIL);
UART_CHECK((uart_config->flow_ctrl < UART_HW_FLOWCTRL_MAX), "hw_flowctrl mode error", ESP_FAIL);
UART_CHECK((uart_config->data_bits < UART_DATA_BITS_MAX), "data bit error", ESP_FAIL);
uart_module_enable(uart_num);
@ -644,7 +644,7 @@ esp_err_t uart_intr_config(uart_port_t uart_num, const uart_intr_config_t *intr_
{
UART_CHECK((uart_num < UART_NUM_MAX), "uart_num error", ESP_FAIL);
UART_CHECK((intr_conf), "param null", ESP_FAIL);
uart_hal_clr_intsts_mask(&(uart_context[uart_num].hal), UART_INTR_MASK);
uart_hal_clr_intsts_mask(&(uart_context[uart_num].hal), UART_LL_INTR_MASK);
UART_ENTER_CRITICAL(&(uart_context[uart_num].spinlock));
if(intr_conf->intr_enable_mask & UART_INTR_RXFIFO_TOUT) {
uart_hal_set_rx_timeout(&(uart_context[uart_num].hal), intr_conf->rx_timeout_thresh);
@ -962,7 +962,7 @@ static void UART_ISR_ATTR uart_rx_intr_handler_default(void *param)
// then postpone interrupt processing for next interrupt
uart_event.type = UART_EVENT_MAX;
} else {
// Workaround for RS485: If the RS485 half duplex mode is active
// Workaround for RS485: If the RS485 half duplex mode is active
// and transmitter is in idle state then reset received buffer and reset RTS pin
// skip this behavior for other UART modes
UART_ENTER_CRITICAL_ISR(&(uart_context[uart_num].spinlock));
@ -1281,8 +1281,8 @@ esp_err_t uart_driver_install(uart_port_t uart_num, int rx_buffer_size, int tx_b
{
esp_err_t r;
UART_CHECK((uart_num < UART_NUM_MAX), "uart_num error", ESP_FAIL);
UART_CHECK((rx_buffer_size > UART_FIFO_LEN), "uart rx buffer length error", ESP_FAIL);
UART_CHECK((tx_buffer_size > UART_FIFO_LEN) || (tx_buffer_size == 0), "uart tx buffer length error", ESP_FAIL);
UART_CHECK((rx_buffer_size > SOC_UART_FIFO_LEN), "uart rx buffer length error", ESP_FAIL);
UART_CHECK((tx_buffer_size > SOC_UART_FIFO_LEN) || (tx_buffer_size == 0), "uart tx buffer length error", ESP_FAIL);
#if CONFIG_UART_ISR_IN_IRAM
if ((intr_alloc_flags & ESP_INTR_FLAG_IRAM) == 0) {
ESP_LOGI(UART_TAG, "ESP_INTR_FLAG_IRAM flag not set while CONFIG_UART_ISR_IN_IRAM is enabled, flag updated");
@ -1354,8 +1354,8 @@ esp_err_t uart_driver_install(uart_port_t uart_num, int rx_buffer_size, int tx_b
.txfifo_empty_intr_thresh = UART_EMPTY_THRESH_DEFAULT,
};
uart_module_enable(uart_num);
uart_hal_disable_intr_mask(&(uart_context[uart_num].hal), UART_INTR_MASK);
uart_hal_clr_intsts_mask(&(uart_context[uart_num].hal), UART_INTR_MASK);
uart_hal_disable_intr_mask(&(uart_context[uart_num].hal), UART_LL_INTR_MASK);
uart_hal_clr_intsts_mask(&(uart_context[uart_num].hal), UART_LL_INTR_MASK);
r=uart_isr_register(uart_num, uart_rx_intr_handler_default, p_uart_obj[uart_num], intr_alloc_flags, &p_uart_obj[uart_num]->intr_handle);
if (r!=ESP_OK) goto err;
r=uart_intr_config(uart_num, &uart_intr);

View File

@ -31,7 +31,7 @@
#include "esp_rom_efuse.h"
#include "soc/dport_reg.h"
#include "soc/efuse_periph.h"
#include "soc/spi_caps.h"
#include "soc/soc_caps.h"
#include "driver/gpio.h"
#include "driver/spi_common_internal.h"
#include "driver/periph_ctrl.h"
@ -972,7 +972,7 @@ esp_err_t IRAM_ATTR psram_enable(psram_cache_mode_t mode, psram_vaddr_mode_t vad
ESP_EARLY_LOGE(TAG, "PSRAM 2T mode and SPIRAM bank switching can not enabled meanwhile. Please read the help text for SPIRAM_2T_MODE in the project configuration menu.");
abort();
#endif
/* Note: 2T mode command should not be sent twice,
/* Note: 2T mode command should not be sent twice,
otherwise psram would get back to normal mode. */
if (psram_2t_mode_check(PSRAM_SPI_1) != ESP_OK) {
psram_2t_mode_enable(PSRAM_SPI_1);

View File

@ -31,7 +31,7 @@
#include "esp_rom_efuse.h"
#include "soc/dport_reg.h"
#include "soc/efuse_periph.h"
#include "soc/spi_caps.h"
#include "soc/soc_caps.h"
#include "soc/io_mux_reg.h"
#include "soc/apb_ctrl_reg.h"
#include "soc/efuse_reg.h"
@ -61,7 +61,7 @@ static const char* TAG = "psram";
#define PSRAM_RESET 0x99
#define PSRAM_SET_BURST_LEN 0xC0
#define PSRAM_DEVICE_ID 0x9F
// ID
// ID
#define PSRAM_ID_KGD_M 0xff
#define PSRAM_ID_KGD_S 8
#define PSRAM_ID_KGD 0x5d
@ -215,7 +215,7 @@ void psram_exec_cmd(int spi_num, psram_cmd_mode_t mode,
_psram_exec_cmd(spi_num, cmd, cmd_bit_len, addr, addr_bit_len,
dummy_bits, mosi_data, mosi_bit_len, miso_data, miso_bit_len);
esp_rom_spi_cmd_start(spi_num, miso_data, miso_bit_len / 8, cs_mask, is_write_erase_operation);
WRITE_PERI_REG(SPI_MEM_USER_REG(spi_num), backup_usr);
WRITE_PERI_REG(SPI_MEM_USER1_REG(spi_num), backup_usr1);
WRITE_PERI_REG(SPI_MEM_USER2_REG(spi_num), backup_usr2);

View File

@ -32,7 +32,7 @@
#include "esp_rom_efuse.h"
#include "soc/dport_reg.h"
#include "soc/efuse_periph.h"
#include "soc/spi_caps.h"
#include "soc/soc_caps.h"
#include "soc/io_mux_reg.h"
#include "soc/apb_ctrl_reg.h"
#include "soc/efuse_reg.h"

View File

@ -49,6 +49,39 @@
#define BIT0 0x00000001
//}}
#define BIT63 (0x80000000ULL << 32)
#define BIT62 (0x40000000ULL << 32)
#define BIT61 (0x20000000ULL << 32)
#define BIT60 (0x10000000ULL << 32)
#define BIT59 (0x08000000ULL << 32)
#define BIT58 (0x04000000ULL << 32)
#define BIT57 (0x02000000ULL << 32)
#define BIT56 (0x01000000ULL << 32)
#define BIT55 (0x00800000ULL << 32)
#define BIT54 (0x00400000ULL << 32)
#define BIT53 (0x00200000ULL << 32)
#define BIT52 (0x00100000ULL << 32)
#define BIT51 (0x00080000ULL << 32)
#define BIT50 (0x00040000ULL << 32)
#define BIT49 (0x00020000ULL << 32)
#define BIT48 (0x00010000ULL << 32)
#define BIT47 (0x00008000ULL << 32)
#define BIT46 (0x00004000ULL << 32)
#define BIT45 (0x00002000ULL << 32)
#define BIT44 (0x00001000ULL << 32)
#define BIT43 (0x00000800ULL << 32)
#define BIT42 (0x00000400ULL << 32)
#define BIT41 (0x00000200ULL << 32)
#define BIT40 (0x00000100ULL << 32)
#define BIT39 (0x00000080ULL << 32)
#define BIT38 (0x00000040ULL << 32)
#define BIT37 (0x00000020ULL << 32)
#define BIT36 (0x00000010ULL << 32)
#define BIT35 (0x00000008ULL << 32)
#define BIT34 (0x00000004ULL << 32)
#define BIT33 (0x00000002ULL << 32)
#define BIT32 (0x00000001ULL << 32)
#ifndef __ASSEMBLER__
#ifndef BIT
#define BIT(nr) (1UL << (nr))

View File

@ -35,7 +35,7 @@
#define BROWNOUT_DET_LVL 0
#endif
#ifdef SOC_BROWNOUT_RESET_SUPPORTED
#if SOC_BROWNOUT_RESET_SUPPORTED
#define BROWNOUT_RESET_EN true
#else
#define BROWNOUT_RESET_EN false

View File

@ -24,7 +24,7 @@
#ifdef CONFIG_LEGACY_INCLUDE_COMMON_HEADERS
#include "soc/gpio_reg.h"
#include "soc/gpio_caps.h"
#include "soc/soc_caps.h"
#endif
#ifdef __cplusplus

View File

@ -20,6 +20,7 @@ extern "C" {
#include <stdint.h>
#include <stdbool.h>
#include "soc/gpio_pins.h" //for GPIO_MATRIX_CONST_ONE_INPUT, GPIO_MATRIX_CONST_ZERO_INPUT
/**
* @brief Configure IO Pad as General Purpose IO,

View File

@ -32,7 +32,7 @@
#include "soc/cpu.h"
#include "soc/rtc.h"
#include "soc/dport_reg.h"
#include "soc/uart_caps.h"
#include "soc/soc_caps.h"
#include "hal/wdt_hal.h"
#include "hal/rtc_io_hal.h"
@ -587,7 +587,7 @@ static void touch_wakeup_prepare(void)
{
touch_pad_sleep_channel_t slp_config;
touch_pad_fsm_stop();
touch_pad_clear_channel_mask(SOC_TOUCH_SENSOR_BIT_MASK_MAX);
touch_pad_clear_channel_mask(TOUCH_PAD_BIT_MASK_ALL);
touch_pad_sleep_channel_get_info(&slp_config);
touch_pad_set_channel_mask(BIT(slp_config.touch_num));
touch_pad_fsm_start();

View File

@ -103,7 +103,7 @@ void esp_timer_impl_advance(int64_t time_us)
esp_err_t esp_timer_impl_init(intr_handler_t alarm_handler)
{
s_alarm_handler = alarm_handler;
#ifdef SOC_SYSTIMER_INT_LEVEL
#if SOC_SYSTIMER_INT_LEVEL
int int_type = 0;
#else
int int_type = ESP_INTR_FLAG_EDGE;

View File

@ -16,14 +16,14 @@
#if !TEMPORARY_DISABLED_FOR_TARGETS(ESP32S2)
//Function just extern, need not test
#ifdef SOC_BT_SUPPORTED
#if SOC_BT_SUPPORTED
extern void bt_bb_init_cmplx(void);
#endif
extern void IRAM_ATTR spi_flash_disable_interrupts_caches_and_other_cpu(void);
extern void IRAM_ATTR spi_flash_enable_interrupts_caches_and_other_cpu(void);
//Functions in librtc.a called by WIFI or Blutooth directly in ISR
#ifdef SOC_BT_SUPPORTED
#if SOC_BT_SUPPORTED
extern void bt_bb_init_cmplx_reg(void);
extern void bt_track_pll_cap(void);
#endif
@ -68,7 +68,7 @@ static IRAM_ATTR void test_phy_rtc_cache_task(void *arg)
spi_flash_enable_interrupts_caches_and_other_cpu();
}
#ifdef SOC_BT_SUPPORTED
#if SOC_BT_SUPPORTED
ESP_LOGI(TAG, "Test bt_bb_init_cmplx_reg()...");
spi_flash_disable_interrupts_caches_and_other_cpu();
bt_bb_init_cmplx_reg();

View File

@ -38,7 +38,7 @@
#define SDSPI_HOST_ID HSPI_HOST
#ifdef SOC_SDMMC_HOST_SUPPORTED
#if SOC_SDMMC_HOST_SUPPORTED
#include "driver/sdmmc_host.h"

View File

@ -25,7 +25,7 @@
#include "soc/soc_caps.h"
#include "driver/sdmmc_defs.h"
#ifdef SOC_SDMMC_HOST_SUPPORTED
#if SOC_SDMMC_HOST_SUPPORTED
#include "driver/sdmmc_host.h"
#endif

View File

@ -13,6 +13,7 @@
// limitations under the License.
#include "hal/adc_hal.h"
#include "hal/adc_hal_conf.h"
void adc_hal_init(void)
{

View File

@ -21,7 +21,7 @@
#include "hal/cpu_hal.h"
#include "hal/cpu_types.h"
#include "soc/cpu_caps.h"
#include "soc/soc_caps.h"
#if SOC_CPU_BREAKPOINTS_NUM > 0

View File

@ -15,6 +15,7 @@
// The HAL layer for ADC (common part)
#include "hal/adc_hal.h"
#include "hal/adc_hal_conf.h"
#include "hal/adc_types.h"
void adc_hal_digi_init(void)

View File

@ -0,0 +1,31 @@
// 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
#define SOC_ADC1_DATA_INVERT_DEFAULT (1)
#define SOC_ADC2_DATA_INVERT_DEFAULT (1)
#define SOC_ADC_DIGI_DATA_INVERT_DEFAULT(PERIPH_NUM) (1)
#define SOC_ADC_FSM_RSTB_WAIT_DEFAULT (8)
#define SOC_ADC_FSM_START_WAIT_DEFAULT (SOC_ADC_DIGI_SAR_CLK_DIV_DEFAULT)
#define SOC_ADC_FSM_STANDBY_WAIT_DEFAULT (100)
#define ADC_FSM_SAMPLE_CYCLE_DEFAULT (2)
#define SOC_ADC_PWDET_CCT_DEFAULT (4)
#define SOC_ADC_SAR_CLK_DIV_DEFAULT(PERIPH_NUM) (2)
#define SOC_ADC_DIGI_SAR_CLK_DIV_DEFAULT (16)

View File

@ -38,7 +38,7 @@ extern "C" {
#define CAN_MSG_FLAG_SELF TWAI_MSG_FLAG_SELF
#define CAN_MSG_FLAG_DLC_NON_COMP TWAI_MSG_FLAG_DLC_NON_COMP
#if (TWAI_BRP_MAX > 128) || (CONFIG_ESP32_REV_MIN >= 2)
#if (SOC_TWAI_BRP_MAX > 128) || (CONFIG_ESP32_REV_MIN >= 2)
#define CAN_TIMING_CONFIG_12_5KBITS() TWAI_TIMING_CONFIG_12_5KBITS()
#define CAN_TIMING_CONFIG_16KBITS() TWAI_TIMING_CONFIG_16KBITS()
#define CAN_TIMING_CONFIG_20KBITS() TWAI_TIMING_CONFIG_20KBITS()

View File

@ -17,7 +17,7 @@
#include "esp_attr.h"
#include "soc/cpu_caps.h"
#include "soc/soc_caps.h"
#include "xt_instr_macros.h"
#include "xtensa/config/specreg.h"

View File

@ -35,6 +35,12 @@ extern "C" {
// Get GPIO hardware instance with giving gpio num
#define GPIO_LL_GET_HW(num) (((num) == 0) ? (&GPIO) : NULL)
#define GPIO_LL_APP_CPU_INTR_ENA (BIT(0))
#define GPIO_LL_APP_CPU_NMI_INTR_ENA (BIT(1))
#define GPIO_LL_PRO_CPU_INTR_ENA (BIT(2))
#define GPIO_LL_PRO_CPU_NMI_INTR_ENA (BIT(3))
#define GPIO_LL_SDIO_EXT_INTR_ENA (BIT(4))
/**
* @brief Enable pull-up on GPIO.
*
@ -147,9 +153,9 @@ static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id, gpio_num_t gpio_num)
{
if (core_id == 0) {
hw->pin[gpio_num].int_ena = GPIO_PRO_CPU_INTR_ENA; //enable pro cpu intr
hw->pin[gpio_num].int_ena = GPIO_LL_PRO_CPU_INTR_ENA; //enable pro cpu intr
} else {
hw->pin[gpio_num].int_ena = GPIO_APP_CPU_INTR_ENA; //enable pro cpu intr
hw->pin[gpio_num].int_ena = GPIO_LL_APP_CPU_INTR_ENA; //enable pro cpu intr
}
}

View File

@ -22,6 +22,8 @@
extern "C" {
#endif
#define I2C_LL_INTR_MASK (0x3fff) /*!< I2C all interrupt bitmap */
/**
* @brief I2C hardware cmd register filed.
*/
@ -42,7 +44,7 @@ typedef union {
* @brief I2C interrupt event
*/
typedef enum {
I2C_INTR_EVENT_ERR,
I2C_INTR_EVENT_ERR,
I2C_INTR_EVENT_ARBIT_LOST, /*!< I2C arbition lost event */
I2C_INTR_EVENT_NACK, /*!< I2C NACK event */
I2C_INTR_EVENT_TOUT, /*!< I2C time out event */
@ -329,7 +331,7 @@ static inline void i2c_ll_set_sda_timing(i2c_dev_t *hw, int sda_sample, int sda_
*/
static inline void i2c_ll_set_txfifo_empty_thr(i2c_dev_t *hw, uint8_t empty_thr)
{
hw->fifo_conf.tx_fifo_empty_thrhd = empty_thr;
hw->fifo_conf.tx_fifo_empty_thrhd = empty_thr;
}
/**
@ -342,7 +344,7 @@ static inline void i2c_ll_set_txfifo_empty_thr(i2c_dev_t *hw, uint8_t empty_thr)
*/
static inline void i2c_ll_set_rxfifo_full_thr(i2c_dev_t *hw, uint8_t full_thr)
{
hw->fifo_conf.rx_fifo_full_thrhd = full_thr;
hw->fifo_conf.rx_fifo_full_thrhd = full_thr;
}
/**
@ -533,7 +535,7 @@ static inline void i2c_ll_write_txfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
uint32_t fifo_addr = (hw == &I2C0) ? 0x6001301c : 0x6002701c;
for(int i = 0; i < len; i++) {
WRITE_PERI_REG(fifo_addr, ptr[i]);
}
}
}
/**
@ -549,7 +551,7 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
{
for(int i = 0; i < len; i++) {
ptr[i] = hw->fifo_data.data;
}
}
}
/**

View File

@ -22,10 +22,10 @@
#pragma once
#include "soc/soc_caps.h"
#include <soc/mcpwm_periph.h>
#include "soc/mcpwm_periph.h"
#include "hal/mcpwm_types.h"
#include "soc/mcpwm_caps.h"
#include "hal/hal_defs.h"
#include "esp_types.h"

View File

@ -14,7 +14,7 @@
#include <stdint.h>
#include "soc/mpu_caps.h"
#include "soc/soc_caps.h"
#include "xt_instr_macros.h"

View File

@ -19,7 +19,7 @@ extern "C" {
#include <stdbool.h>
#include "soc/rmt_struct.h"
#include "soc/rmt_caps.h"
#include "soc/soc_caps.h"
#define RMT_LL_HW_BASE (&RMT)
#define RMT_LL_MEM_BASE (&RMTMEM)

View File

@ -25,6 +25,8 @@
#include "hal/rtc_io_types.h"
#include "hal/gpio_types.h"
#define RTCIO_LL_PIN_FUNC 0
#ifdef __cplusplus
extern "C" {
#endif
@ -58,7 +60,7 @@ static inline void rtcio_ll_function_select(int rtcio_num, rtcio_ll_func_t func)
// 0: GPIO connected to digital GPIO module. 1: GPIO connected to analog RTC module.
SET_PERI_REG_MASK(rtc_io_desc[rtcio_num].reg, (rtc_io_desc[rtcio_num].mux));
//0:RTC FUNCTION 1,2,3:Reserved
SET_PERI_REG_BITS(rtc_io_desc[rtcio_num].reg, RTC_IO_TOUCH_PAD1_FUN_SEL_V, SOC_PIN_FUNC_RTC_IO, rtc_io_desc[rtcio_num].func);
SET_PERI_REG_BITS(rtc_io_desc[rtcio_num].reg, RTC_IO_TOUCH_PAD1_FUN_SEL_V, RTCIO_LL_PIN_FUNC, rtc_io_desc[rtcio_num].func);
} else if (func == RTCIO_FUNC_DIGITAL) {
CLEAR_PERI_REG_MASK(rtc_io_desc[rtcio_num].reg, (rtc_io_desc[rtcio_num].mux));
}

View File

@ -62,7 +62,7 @@ static inline void touch_ll_set_meas_time(uint16_t meas_time)
//touch sensor measure time= meas_cycle / 8Mhz
SENS.sar_touch_ctrl1.touch_meas_delay = meas_time;
//the waiting cycles (in 8MHz) between TOUCH_START and TOUCH_XPD
SENS.sar_touch_ctrl1.touch_xpd_wait = SOC_TOUCH_PAD_MEASURE_WAIT;
SENS.sar_touch_ctrl1.touch_xpd_wait = SOC_TOUCH_PAD_MEASURE_WAIT_MAX;
}
/**

View File

@ -331,7 +331,7 @@ static inline uint32_t twai_ll_get_and_clear_intrs(twai_dev_t *hw)
*/
static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
{
#if (CONFIG_ESP32_REV_MIN >= 2)
#if TWAI_BRP_DIV_SUPPORTED
//ESP32 Rev 2 or later has brp div field. Need to mask it out
hw->interrupt_enable_reg.val = (hw->interrupt_enable_reg.val & 0x10) | intr_mask;
#else
@ -357,8 +357,8 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
*/
static inline void twai_ll_set_bus_timing(twai_dev_t *hw, uint32_t brp, uint32_t sjw, uint32_t tseg1, uint32_t tseg2, bool triple_sampling)
{
#if (CONFIG_ESP32_REV_MIN >= 2)
if (brp > TWAI_BRP_DIV_THRESH) {
#if TWAI_BRP_DIV_SUPPORTED
if (brp > SOC_TWAI_BRP_DIV_THRESH) {
//Need to set brp_div bit
hw->interrupt_enable_reg.brp_div = 1;
brp /= 2;

View File

@ -17,21 +17,24 @@
#pragma once
#include "hal/uart_types.h"
#include "soc/uart_periph.h"
#include "hal/uart_types.h"
#ifdef __cplusplus
extern "C" {
#endif
// The default fifo depth
#define UART_LL_FIFO_DEF_LEN (UART_FIFO_LEN)
#define UART_LL_FIFO_DEF_LEN (SOC_UART_FIFO_LEN)
// Get UART hardware instance with giving uart num
#define UART_LL_GET_HW(num) (((num) == 0) ? (&UART0) : (((num) == 1) ? (&UART1) : (&UART2)))
// The timeout calibration factor when using ref_tick
#define UART_LL_TOUT_REF_FACTOR_DEFAULT (8)
#define UART_LL_MIN_WAKEUP_THRESH (2)
#define UART_LL_INTR_MASK (0x7ffff) //All interrupt mask
// Define UART interrupts
typedef enum {
UART_INTR_RXFIFO_FULL = (0x1<<0),
@ -250,8 +253,8 @@ static inline uint32_t uart_ll_get_rxfifo_len(uart_dev_t *hw)
uint32_t fifo_cnt = hw->status.rxfifo_cnt;
typeof(hw->mem_rx_status) rx_status = hw->mem_rx_status;
uint32_t len = 0;
// When using DPort to read fifo, fifo_cnt is not credible, we need to calculate the real cnt based on the fifo read and write pointer.
// When using DPort to read fifo, fifo_cnt is not credible, we need to calculate the real cnt based on the fifo read and write pointer.
// When using AHB to read FIFO, we can use fifo_cnt to indicate the data length in fifo.
if (rx_status.wr_addr > rx_status.rd_addr) {
len = rx_status.wr_addr - rx_status.rd_addr;
@ -286,12 +289,12 @@ static inline uint32_t uart_ll_get_txfifo_len(uart_dev_t *hw)
*/
static inline void uart_ll_set_stop_bits(uart_dev_t *hw, uart_stop_bits_t stop_bit)
{
//workaround for hardware issue, when UART stop bit set as 2-bit mode.
//workaround for hardware issue, when UART stop bit set as 2-bit mode.
if(stop_bit == UART_STOP_BITS_2) {
hw->rs485_conf.dl1_en = 1;
hw->conf0.stop_bit_num = 0x1;
} else {
hw->rs485_conf.dl1_en = 0;
hw->rs485_conf.dl1_en = 0;
hw->conf0.stop_bit_num = stop_bit;
}
}
@ -306,7 +309,7 @@ static inline void uart_ll_set_stop_bits(uart_dev_t *hw, uart_stop_bits_t stop_b
*/
static inline void uart_ll_get_stop_bits(uart_dev_t *hw, uart_stop_bits_t *stop_bit)
{
//workaround for hardware issue, when UART stop bit set as 2-bit mode.
//workaround for hardware issue, when UART stop bit set as 2-bit mode.
if(hw->rs485_conf.dl1_en == 1 && hw->conf0.stop_bit_num == 0x1) {
*stop_bit = UART_STOP_BITS_2;
} else {
@ -573,7 +576,7 @@ static inline void uart_ll_set_dtr_active_level(uart_dev_t *hw, int level)
*/
static inline void uart_ll_set_wakeup_thrd(uart_dev_t *hw, uint32_t wakeup_thrd)
{
hw->sleep_conf.active_threshold = wakeup_thrd - SOC_UART_MIN_WAKEUP_THRESH;
hw->sleep_conf.active_threshold = wakeup_thrd - UART_LL_MIN_WAKEUP_THRESH;
}
/**
@ -715,7 +718,7 @@ static inline void uart_ll_get_at_cmd_char(uart_dev_t *hw, uint8_t *cmd_char, ui
*/
static inline uint32_t uart_ll_get_wakeup_thrd(uart_dev_t *hw)
{
return hw->sleep_conf.active_threshold + SOC_UART_MIN_WAKEUP_THRESH;
return hw->sleep_conf.active_threshold + UART_LL_MIN_WAKEUP_THRESH;
}
/**

View File

@ -20,8 +20,8 @@
void touch_hal_init(void)
{
touch_ll_intr_disable();
touch_ll_clear_channel_mask(SOC_TOUCH_SENSOR_BIT_MASK_MAX);
touch_ll_clear_group_mask(SOC_TOUCH_SENSOR_BIT_MASK_MAX, SOC_TOUCH_SENSOR_BIT_MASK_MAX);
touch_ll_clear_channel_mask(TOUCH_PAD_BIT_MASK_ALL);
touch_ll_clear_group_mask(TOUCH_PAD_BIT_MASK_ALL, TOUCH_PAD_BIT_MASK_ALL);
touch_ll_set_trigger_mode(TOUCH_TRIGGER_MODE_DEFAULT);
touch_ll_set_trigger_source(TOUCH_TRIGGER_SOURCE_DEFAULT);
touch_ll_clear_trigger_status_mask();

View File

@ -16,6 +16,7 @@
#include "hal/adc_hal.h"
#include "hal/adc_types.h"
#include "hal/adc_hal_conf.h"
/*---------------------------------------------------------------
Digital controller setting

View File

@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
#include "soc/soc_caps.h"
#include "hal/cp_dma_hal.h"
#include "hal/cp_dma_ll.h"

View File

@ -14,7 +14,18 @@
#pragma once
#define SOC_CPU_BREAKPOINTS_NUM 2
#define SOC_CPU_WATCHPOINTS_NUM 2
#define SOC_ADC1_DATA_INVERT_DEFAULT (0)
#define SOC_ADC2_DATA_INVERT_DEFAULT (0)
#define SOC_CPU_WATCHPOINT_SIZE 64 // bytes
#define SOC_ADC_DIGI_DATA_INVERT_DEFAULT(PERIPH_NUM) (0)
#define SOC_ADC_FSM_RSTB_WAIT_DEFAULT (8)
#define SOC_ADC_FSM_START_WAIT_DEFAULT (5)
#define SOC_ADC_FSM_STANDBY_WAIT_DEFAULT (100)
#define ADC_FSM_SAMPLE_CYCLE_DEFAULT (3)
#define SOC_ADC_PWDET_CCT_DEFAULT (4)
#define SOC_ADC_SAR_CLK_DIV_DEFAULT(PERIPH_NUM) ((PERIPH_NUM==0)? 2 : 1)
#define SOC_ADC_DIGI_SAR_CLK_DIV_DEFAULT (2)

View File

@ -16,7 +16,7 @@
#include "esp_attr.h"
#include "soc/cpu_caps.h"
#include "soc/soc_caps.h"
#include "xt_instr_macros.h"
#include "xtensa/config/specreg.h"

View File

@ -35,6 +35,9 @@ extern "C" {
// Get GPIO hardware instance with giving gpio num
#define GPIO_LL_GET_HW(num) (((num) == 0) ? (&GPIO) : NULL)
#define GPIO_LL_PRO_CPU_INTR_ENA (BIT(0))
#define GPIO_LL_PRO_CPU_NMI_INTR_ENA (BIT(1))
/**
* @brief Enable pull-up on GPIO.
*
@ -147,7 +150,7 @@ static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id, gpio_num_t gpio_num)
{
if (core_id == 0) {
GPIO.pin[gpio_num].int_ena = GPIO_PRO_CPU_INTR_ENA; //enable pro cpu intr
GPIO.pin[gpio_num].int_ena = GPIO_LL_PRO_CPU_INTR_ENA; //enable pro cpu intr
}
}

View File

@ -22,6 +22,8 @@
extern "C" {
#endif
#define I2C_LL_INTR_MASK (0x1ffff) /*!< I2C all interrupt bitmap */
/**
* @brief I2C hardware cmd register filed.
*/
@ -42,7 +44,7 @@ typedef union {
* @brief I2C interrupt event
*/
typedef enum {
I2C_INTR_EVENT_ERR,
I2C_INTR_EVENT_ERR,
I2C_INTR_EVENT_ARBIT_LOST, /*!< I2C arbition lost event */
I2C_INTR_EVENT_NACK, /*!< I2C NACK event */
I2C_INTR_EVENT_TOUT, /*!< I2C time out event */
@ -540,7 +542,7 @@ static inline void i2c_ll_write_txfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
uint32_t fifo_addr = (hw == &I2C0) ? 0x6001301c : 0x6002701c;
for(int i = 0; i < len; i++) {
WRITE_PERI_REG(fifo_addr, ptr[i]);
}
}
}
/**
@ -557,7 +559,7 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
uint32_t fifo_addr = (hw == &I2C0) ? 0x6001301c : 0x6002701c;
for(int i = 0; i < len; i++) {
ptr[i] = READ_PERI_REG(fifo_addr);
}
}
}
/**

View File

@ -14,7 +14,7 @@
#include <stdint.h>
#include "soc/mpu_caps.h"
#include "soc/soc_caps.h"
#include "xt_instr_macros.h"

View File

@ -18,8 +18,8 @@ extern "C" {
#endif
#include <stdbool.h>
#include "soc/soc_caps.h"
#include "soc/rmt_struct.h"
#include "soc/rmt_caps.h"
#define RMT_LL_HW_BASE (&RMT)
#define RMT_LL_MEM_BASE (&RMTMEM)

View File

@ -25,6 +25,8 @@
#include "hal/rtc_io_types.h"
#include "hal/gpio_types.h"
#define RTCIO_LL_PIN_FUNC 0
#ifdef __cplusplus
extern "C" {
#endif
@ -59,7 +61,7 @@ static inline void rtcio_ll_function_select(int rtcio_num, rtcio_ll_func_t func)
// 0: GPIO connected to digital GPIO module. 1: GPIO connected to analog RTC module.
SET_PERI_REG_MASK(rtc_io_desc[rtcio_num].reg, (rtc_io_desc[rtcio_num].mux));
//0:RTC FUNCTION 1,2,3:Reserved
SET_PERI_REG_BITS(rtc_io_desc[rtcio_num].reg, RTC_IO_TOUCH_PAD1_FUN_SEL_V, SOC_PIN_FUNC_RTC_IO, rtc_io_desc[rtcio_num].func);
SET_PERI_REG_BITS(rtc_io_desc[rtcio_num].reg, RTC_IO_TOUCH_PAD1_FUN_SEL_V, RTCIO_LL_PIN_FUNC, rtc_io_desc[rtcio_num].func);
} else if (func == RTCIO_FUNC_DIGITAL) {
CLEAR_PERI_REG_MASK(rtc_io_desc[rtcio_num].reg, (rtc_io_desc[rtcio_num].mux));
SENS.sar_io_mux_conf.iomux_clk_gate_en = 0;

View File

@ -48,7 +48,7 @@ static inline void touch_ll_set_meas_times(uint16_t meas_time)
//The times of charge and discharge in each measure process of touch channels.
RTCCNTL.touch_ctrl1.touch_meas_num = meas_time;
//the waiting cycles (in 8MHz) between TOUCH_START and TOUCH_XPD
RTCCNTL.touch_ctrl2.touch_xpd_wait = SOC_TOUCH_PAD_MEASURE_WAIT; //wait volt stable
RTCCNTL.touch_ctrl2.touch_xpd_wait = SOC_TOUCH_PAD_MEASURE_WAIT_MAX; //wait volt stable
}
/**
@ -345,8 +345,8 @@ static inline void touch_ll_get_threshold(touch_pad_t touch_num, uint32_t *thres
*/
static inline void touch_ll_set_channel_mask(uint16_t enable_mask)
{
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map |= (enable_mask & SOC_TOUCH_SENSOR_BIT_MASK_MAX);
SENS.sar_touch_conf.touch_outen |= (enable_mask & SOC_TOUCH_SENSOR_BIT_MASK_MAX);
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map |= (enable_mask & TOUCH_PAD_BIT_MASK_ALL);
SENS.sar_touch_conf.touch_outen |= (enable_mask & TOUCH_PAD_BIT_MASK_ALL);
}
/**
@ -359,7 +359,7 @@ static inline void touch_ll_get_channel_mask(uint16_t *enable_mask)
{
*enable_mask = SENS.sar_touch_conf.touch_outen \
& RTCCNTL.touch_scan_ctrl.touch_scan_pad_map \
& SOC_TOUCH_SENSOR_BIT_MASK_MAX;
& TOUCH_PAD_BIT_MASK_ALL;
}
/**
@ -370,8 +370,8 @@ static inline void touch_ll_get_channel_mask(uint16_t *enable_mask)
*/
static inline void touch_ll_clear_channel_mask(uint16_t disable_mask)
{
SENS.sar_touch_conf.touch_outen &= ~(disable_mask & SOC_TOUCH_SENSOR_BIT_MASK_MAX);
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map &= ~(disable_mask & SOC_TOUCH_SENSOR_BIT_MASK_MAX);
SENS.sar_touch_conf.touch_outen &= ~(disable_mask & TOUCH_PAD_BIT_MASK_ALL);
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map &= ~(disable_mask & TOUCH_PAD_BIT_MASK_ALL);
}
/**
@ -659,7 +659,7 @@ static inline void touch_ll_reset_benchmark(touch_pad_t touch_num)
/* 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;
SENS.sar_touch_chn_st.touch_channel_clr = TOUCH_PAD_BIT_MASK_ALL;
} else {
SENS.sar_touch_chn_st.touch_channel_clr = (1U << touch_num);
}

View File

@ -25,10 +25,13 @@ extern "C" {
#endif
// The default fifo depth
#define UART_LL_FIFO_DEF_LEN (UART_FIFO_LEN)
#define UART_LL_FIFO_DEF_LEN (SOC_UART_FIFO_LEN)
// Get UART hardware instance with giving uart num
#define UART_LL_GET_HW(num) (((num) == 0) ? (&UART0) : (&UART1))
#define UART_LL_MIN_WAKEUP_THRESH (2)
#define UART_LL_INTR_MASK (0x7ffff) //All interrupt mask
// Define UART interrupts
typedef enum {
UART_INTR_RXFIFO_FULL = (0x1<<0),
@ -247,7 +250,7 @@ static inline uint32_t uart_ll_get_txfifo_len(uart_dev_t *hw)
* @return None.
*/
static inline void uart_ll_set_stop_bits(uart_dev_t *hw, uart_stop_bits_t stop_bit)
{
{
hw->conf0.stop_bit_num = stop_bit;
}
@ -523,7 +526,7 @@ static inline void uart_ll_set_dtr_active_level(uart_dev_t *hw, int level)
*/
static inline void uart_ll_set_wakeup_thrd(uart_dev_t *hw, uint32_t wakeup_thrd)
{
hw->sleep_conf.active_threshold = wakeup_thrd - SOC_UART_MIN_WAKEUP_THRESH;
hw->sleep_conf.active_threshold = wakeup_thrd - UART_LL_MIN_WAKEUP_THRESH;
}
/**
@ -665,7 +668,7 @@ static inline void uart_ll_get_at_cmd_char(uart_dev_t *hw, uint8_t *cmd_char, ui
*/
static inline uint32_t uart_ll_get_wakeup_thrd(uart_dev_t *hw)
{
return hw->sleep_conf.active_threshold + SOC_UART_MIN_WAKEUP_THRESH;
return hw->sleep_conf.active_threshold + UART_LL_MIN_WAKEUP_THRESH;
}
/**

View File

@ -14,10 +14,10 @@
#include <sys/param.h>
#include <assert.h>
#include "soc/soc_caps.h"
#include "hal/systimer_hal.h"
#include "hal/systimer_ll.h"
#include "hal/systimer_types.h"
#include "soc/systimer_caps.h"
#include "soc/rtc.h"
#define SYSTIMER_TICKS_PER_US (80) // Number of timer ticks per microsecond

View File

@ -14,13 +14,14 @@
// The HAL layer for Touch Sensor (common part)
#include "soc/soc_pins.h"
#include "hal/touch_sensor_hal.h"
#include "hal/touch_sensor_types.h"
void touch_hal_init(void)
{
touch_ll_intr_disable(TOUCH_PAD_INTR_MASK_ALL);
touch_ll_clear_channel_mask(SOC_TOUCH_SENSOR_BIT_MASK_MAX);
touch_ll_clear_channel_mask(TOUCH_PAD_BIT_MASK_ALL);
touch_ll_clear_trigger_status_mask();
touch_ll_set_meas_times(TOUCH_PAD_MEASURE_CYCLE_DEFAULT);
touch_ll_set_sleep_time(TOUCH_PAD_SLEEP_CYCLE_DEFAULT);
@ -41,7 +42,7 @@ void touch_hal_deinit(void)
touch_ll_sleep_reset_benchmark();
touch_ll_stop_fsm();
touch_ll_clkgate(false);
touch_ll_clear_channel_mask(SOC_TOUCH_SENSOR_BIT_MASK_MAX);
touch_ll_clear_channel_mask(TOUCH_PAD_BIT_MASK_ALL);
touch_ll_clear_trigger_status_mask();
touch_ll_intr_disable(TOUCH_PAD_INTR_MASK_ALL);
touch_ll_timeout_disable();

View File

@ -0,0 +1,31 @@
// 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
#define SOC_ADC1_DATA_INVERT_DEFAULT (0)
#define SOC_ADC2_DATA_INVERT_DEFAULT (0)
#define SOC_ADC_DIGI_DATA_INVERT_DEFAULT(PERIPH_NUM) (0)
#define SOC_ADC_FSM_RSTB_WAIT_DEFAULT (8)
#define SOC_ADC_FSM_START_WAIT_DEFAULT (5)
#define SOC_ADC_FSM_STANDBY_WAIT_DEFAULT (100)
#define ADC_FSM_SAMPLE_CYCLE_DEFAULT (2)
#define SOC_ADC_PWDET_CCT_DEFAULT (4)
#define SOC_ADC_SAR_CLK_DIV_DEFAULT(PERIPH_NUM) ((PERIPH_NUM==0)? 2 : 1)
#define SOC_ADC_DIGI_SAR_CLK_DIV_DEFAULT (1)

View File

@ -15,7 +15,7 @@
#include <stdint.h>
#include "soc/cpu_caps.h"
#include "soc/soc_caps.h"
#include "xt_instr_macros.h"
#include "xtensa/config/specreg.h"

View File

@ -19,9 +19,9 @@ extern "C" {
#include <stdint.h>
#include <stdbool.h>
#include "soc/soc_caps.h"
#include "soc/gdma_struct.h"
#include "soc/gdma_reg.h"
#include "soc/gdma_caps.h"
#define GDMA_LL_EVENT_TX_L3_FIFO_UDF (1<<17)
#define GDMA_LL_EVENT_TX_L3_FIFO_OVF (1<<16)

View File

@ -35,6 +35,9 @@ extern "C" {
// Get GPIO hardware instance with giving gpio num
#define GPIO_LL_GET_HW(num) (((num) == 0) ? (&GPIO) : NULL)
#define GPIO_LL_PRO_CPU_INTR_ENA (BIT(0))
#define GPIO_LL_PRO_CPU_NMI_INTR_ENA (BIT(1))
/**
* @brief Enable pull-up on GPIO.
*
@ -147,7 +150,7 @@ static inline void gpio_ll_clear_intr_status_high(gpio_dev_t *hw, uint32_t mask)
static inline void gpio_ll_intr_enable_on_core(gpio_dev_t *hw, uint32_t core_id, gpio_num_t gpio_num)
{
if (core_id == 0) {
GPIO.pin[gpio_num].int_ena = GPIO_PRO_CPU_INTR_ENA; //enable pro cpu intr
GPIO.pin[gpio_num].int_ena = GPIO_LL_PRO_CPU_INTR_ENA; //enable pro cpu intr
}
}

View File

@ -22,6 +22,8 @@
extern "C" {
#endif
#define I2C_LL_INTR_MASK (0x3fff) /*!< I2C all interrupt bitmap */
/**
* @brief I2C hardware cmd register filed.
*/
@ -42,7 +44,7 @@ typedef union {
* @brief I2C interrupt event
*/
typedef enum {
I2C_INTR_EVENT_ERR,
I2C_INTR_EVENT_ERR,
I2C_INTR_EVENT_ARBIT_LOST, /*!< I2C arbition lost event */
I2C_INTR_EVENT_NACK, /*!< I2C NACK event */
I2C_INTR_EVENT_TOUT, /*!< I2C time out event */
@ -329,7 +331,7 @@ static inline void i2c_ll_set_sda_timing(i2c_dev_t *hw, int sda_sample, int sda_
*/
static inline void i2c_ll_set_txfifo_empty_thr(i2c_dev_t *hw, uint8_t empty_thr)
{
hw->fifo_conf.tx_fifo_empty_thrhd = empty_thr;
hw->fifo_conf.tx_fifo_empty_thrhd = empty_thr;
}
/**
@ -342,7 +344,7 @@ static inline void i2c_ll_set_txfifo_empty_thr(i2c_dev_t *hw, uint8_t empty_thr)
*/
static inline void i2c_ll_set_rxfifo_full_thr(i2c_dev_t *hw, uint8_t full_thr)
{
hw->fifo_conf.rx_fifo_full_thrhd = full_thr;
hw->fifo_conf.rx_fifo_full_thrhd = full_thr;
}
/**
@ -533,7 +535,7 @@ static inline void i2c_ll_write_txfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
uint32_t fifo_addr = (hw == &I2C0) ? 0x6001301c : 0x6002701c;
for(int i = 0; i < len; i++) {
WRITE_PERI_REG(fifo_addr, ptr[i]);
}
}
}
/**
@ -549,7 +551,7 @@ static inline void i2c_ll_read_rxfifo(i2c_dev_t *hw, uint8_t *ptr, uint8_t len)
{
for(int i = 0; i < len; i++) {
ptr[i] = hw->fifo_data.data;
}
}
}
/**

View File

@ -22,10 +22,10 @@
#pragma once
#include "soc/soc_caps.h"
#include <soc/mcpwm_periph.h>
#include "soc/mcpwm_periph.h"
#include "hal/mcpwm_types.h"
#include "soc/mcpwm_caps.h"
#include "hal/hal_defs.h"
#include "esp_types.h"

View File

@ -14,7 +14,7 @@
#include <stdint.h>
#include "soc/mpu_caps.h"
#include "soc/soc_caps.h"
#include "xt_instr_macros.h"

View File

@ -20,7 +20,7 @@ extern "C" {
#include <stdint.h>
#include <stdbool.h>
#include "soc/rmt_struct.h"
#include "soc/rmt_caps.h"
#include "soc/soc_caps.h"
#define RMT_LL_HW_BASE (&RMT)
#define RMT_LL_MEM_BASE (&RMTMEM)

View File

@ -59,7 +59,7 @@ static inline void rtcio_ll_function_select(int rtcio_num, rtcio_ll_func_t func)
// 0: GPIO connected to digital GPIO module. 1: GPIO connected to analog RTC module.
SET_PERI_REG_MASK(rtc_io_desc[rtcio_num].reg, (rtc_io_desc[rtcio_num].mux));
//0:RTC FUNCTION 1,2,3:Reserved
SET_PERI_REG_BITS(rtc_io_desc[rtcio_num].reg, RTC_IO_TOUCH_PAD1_FUN_SEL_V, SOC_PIN_FUNC_RTC_IO, rtc_io_desc[rtcio_num].func);
SET_PERI_REG_BITS(rtc_io_desc[rtcio_num].reg, RTC_IO_TOUCH_PAD1_FUN_SEL_V, RTCIO_LL_PIN_FUNC, rtc_io_desc[rtcio_num].func);
} else if (func == RTCIO_FUNC_DIGITAL) {
CLEAR_PERI_REG_MASK(rtc_io_desc[rtcio_num].reg, (rtc_io_desc[rtcio_num].mux));
// SENS.sar_io_mux_conf.iomux_clk_gate_en = 0;

View File

@ -48,7 +48,7 @@ static inline void touch_ll_set_meas_times(uint16_t meas_time)
//The times of charge and discharge in each measure process of touch channels.
RTCCNTL.touch_ctrl1.touch_meas_num = meas_time;
//the waiting cycles (in 8MHz) between TOUCH_START and TOUCH_XPD
RTCCNTL.touch_ctrl2.touch_xpd_wait = SOC_TOUCH_PAD_MEASURE_WAIT; //wait volt stable
RTCCNTL.touch_ctrl2.touch_xpd_wait = SOC_TOUCH_PAD_MEASURE_WAIT_MAX; //wait volt stable
}
/**
@ -345,8 +345,8 @@ static inline void touch_ll_get_threshold(touch_pad_t touch_num, uint32_t *thres
*/
static inline void touch_ll_set_channel_mask(uint16_t enable_mask)
{
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map |= (enable_mask & SOC_TOUCH_SENSOR_BIT_MASK_MAX);
SENS.sar_touch_conf.touch_outen |= (enable_mask & SOC_TOUCH_SENSOR_BIT_MASK_MAX);
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map |= (enable_mask & TOUCH_PAD_BIT_MASK_ALL);
SENS.sar_touch_conf.touch_outen |= (enable_mask & TOUCH_PAD_BIT_MASK_ALL);
}
/**
@ -359,7 +359,7 @@ static inline void touch_ll_get_channel_mask(uint16_t *enable_mask)
{
*enable_mask = SENS.sar_touch_conf.touch_outen \
& RTCCNTL.touch_scan_ctrl.touch_scan_pad_map \
& SOC_TOUCH_SENSOR_BIT_MASK_MAX;
& TOUCH_PAD_BIT_MASK_ALL;
}
/**
@ -370,8 +370,8 @@ static inline void touch_ll_get_channel_mask(uint16_t *enable_mask)
*/
static inline void touch_ll_clear_channel_mask(uint16_t disable_mask)
{
SENS.sar_touch_conf.touch_outen &= ~(disable_mask & SOC_TOUCH_SENSOR_BIT_MASK_MAX);
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map &= ~(disable_mask & SOC_TOUCH_SENSOR_BIT_MASK_MAX);
SENS.sar_touch_conf.touch_outen &= ~(disable_mask & TOUCH_PAD_BIT_MASK_ALL);
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map &= ~(disable_mask & TOUCH_PAD_BIT_MASK_ALL);
}
/**
@ -659,7 +659,7 @@ static inline void touch_ll_reset_benchmark(touch_pad_t touch_num)
/* 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;
SENS.sar_touch_chn_st.touch_channel_clr = TOUCH_PAD_BIT_MASK_ALL;
} else {
SENS.sar_touch_chn_st.touch_channel_clr = (1U << touch_num);
}

View File

@ -363,7 +363,7 @@ static inline void twai_ll_set_enabled_intrs(twai_dev_t *hw, uint32_t intr_mask)
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)
{
#ifdef TWAI_BRP_DIV_SUPPORTED
if (brp > TWAI_BRP_DIV_THRESH) {
if (brp > SOC_TWAI_BRP_DIV_THRESH) {
//Need to set brp_div bit
hw->interrupt_enable_reg.brp_div = 1;
brp /= 2;

View File

@ -25,10 +25,12 @@ extern "C" {
#endif
// The default fifo depth
#define UART_LL_FIFO_DEF_LEN (UART_FIFO_LEN)
#define UART_LL_FIFO_DEF_LEN (SOC_UART_FIFO_LEN)
// Get UART hardware instance with giving uart num
#define UART_LL_GET_HW(num) (((num) == 0) ? (&UART0) : (&UART1))
#define UART_LL_MIN_WAKEUP_THRESH (2)
#define UART_LL_INTR_MASK (0x7ffff) //All interrupt mask
// Define UART interrupts
typedef enum {
@ -521,7 +523,7 @@ static inline void uart_ll_set_dtr_active_level(uart_dev_t *hw, int level)
*/
static inline void uart_ll_set_wakeup_thrd(uart_dev_t *hw, uint32_t wakeup_thrd)
{
hw->sleep_conf.active_threshold = wakeup_thrd - SOC_UART_MIN_WAKEUP_THRESH;
hw->sleep_conf.active_threshold = wakeup_thrd - UART_LL_MIN_WAKEUP_THRESH;
}
/**
@ -663,7 +665,7 @@ static inline void uart_ll_get_at_cmd_char(uart_dev_t *hw, uint8_t *cmd_char, ui
*/
static inline uint32_t uart_ll_get_wakeup_thrd(uart_dev_t *hw)
{
return hw->sleep_conf.active_threshold + SOC_UART_MIN_WAKEUP_THRESH;
return hw->sleep_conf.active_threshold + UART_LL_MIN_WAKEUP_THRESH;
}
/**

View File

@ -13,10 +13,10 @@
// limitations under the License.
#include <sys/param.h>
#include "soc/soc_caps.h"
#include "hal/systimer_hal.h"
#include "hal/systimer_ll.h"
#include "hal/systimer_types.h"
#include "soc/systimer_caps.h"
#include "hal/clk_gate_ll.h"
#define SYSTIMER_TICKS_PER_US (16) // Systimer clock source is fixed to 16MHz

View File

@ -20,7 +20,7 @@
void touch_hal_init(void)
{
touch_ll_intr_disable(TOUCH_PAD_INTR_MASK_ALL);
touch_ll_clear_channel_mask(SOC_TOUCH_SENSOR_BIT_MASK_MAX);
touch_ll_clear_channel_mask(TOUCH_PAD_BIT_MASK_ALL);
touch_ll_clear_trigger_status_mask();
touch_ll_set_meas_times(TOUCH_PAD_MEASURE_CYCLE_DEFAULT);
touch_ll_set_sleep_time(TOUCH_PAD_SLEEP_CYCLE_DEFAULT);
@ -41,7 +41,7 @@ void touch_hal_deinit(void)
touch_ll_sleep_reset_benchmark();
touch_ll_stop_fsm();
touch_ll_clkgate(false);
touch_ll_clear_channel_mask(SOC_TOUCH_SENSOR_BIT_MASK_MAX);
touch_ll_clear_channel_mask(TOUCH_PAD_BIT_MASK_ALL);
touch_ll_clear_trigger_status_mask();
touch_ll_intr_disable(TOUCH_PAD_INTR_MASK_ALL);
touch_ll_timeout_disable();

View File

@ -16,7 +16,7 @@
#include <stdbool.h>
#include <stdint.h>
#include "sdkconfig.h"
#include "soc/adc_caps.h"
#include "soc/soc_caps.h"
/**
* @brief ADC unit enumeration.

View File

@ -27,7 +27,7 @@ extern "C" {
#include <stddef.h>
#include <stdbool.h>
#include <stdint.h>
#include "soc/brownout_caps.h"
#include "soc/soc_caps.h"
typedef struct {
uint8_t threshold;

View File

@ -19,9 +19,9 @@
#include "esp_err.h"
#include "soc/soc_caps.h"
#include "hal/cpu_types.h"
#include "hal/cpu_ll.h"
#include "soc/cpu_caps.h"
#ifdef __cplusplus
extern "C" {

View File

@ -1,6 +1,6 @@
#pragma once
#include "soc/dac_caps.h"
#include "soc/soc_caps.h"
#include "hal/adc_types.h"
#include "sdkconfig.h"

View File

@ -319,7 +319,7 @@ void gpio_hal_intr_disable(gpio_hal_context_t *hal, gpio_num_t gpio_num);
*/
#define gpio_hal_iomux_out(hal, gpio_num, func, oen_inv) gpio_ll_iomux_out((hal)->dev, gpio_num, func, oen_inv)
#if GPIO_SUPPORTS_FORCE_HOLD
#if SOC_GPIO_SUPPORT_FORCE_HOLD
/**
* @brief Force hold digital and rtc gpio pad.
* @note GPIO force hold, whether the chip in sleep mode or wakeup mode.

View File

@ -15,7 +15,7 @@
#pragma once
#include "soc/gpio_periph.h"
#include "soc/gpio_caps.h"
#include "soc/soc_caps.h"
#ifdef __cplusplus
extern "C" {
@ -70,7 +70,7 @@ typedef enum {
#define GPIO_SEL_37 ((uint64_t)(((uint64_t)1)<<37)) /*!< Pin 37 selected */
#define GPIO_SEL_38 ((uint64_t)(((uint64_t)1)<<38)) /*!< Pin 38 selected */
#define GPIO_SEL_39 ((uint64_t)(((uint64_t)1)<<39)) /*!< Pin 39 selected */
#if GPIO_PIN_COUNT > 40
#if SOC_GPIO_PIN_COUNT > 40
#define GPIO_SEL_40 ((uint64_t)(((uint64_t)1)<<40)) /*!< Pin 40 selected */
#define GPIO_SEL_41 ((uint64_t)(((uint64_t)1)<<41)) /*!< Pin 41 selected */
#define GPIO_SEL_42 ((uint64_t)(((uint64_t)1)<<42)) /*!< Pin 42 selected */
@ -122,7 +122,7 @@ typedef enum {
#define GPIO_PIN_REG_37 IO_MUX_GPIO37_REG
#define GPIO_PIN_REG_38 IO_MUX_GPIO38_REG
#define GPIO_PIN_REG_39 IO_MUX_GPIO39_REG
#if GPIO_PIN_COUNT > 40
#if SOC_GPIO_PIN_COUNT > 40
#define GPIO_PIN_REG_40 IO_MUX_GPIO40_REG
#define GPIO_PIN_REG_41 IO_MUX_GPIO41_REG
#define GPIO_PIN_REG_42 IO_MUX_GPIO42_REG
@ -179,7 +179,7 @@ typedef enum {
GPIO_NUM_37 = 37, /*!< GPIO37, input mode only(ESP32) / input and output(ESP32-S2) */
GPIO_NUM_38 = 38, /*!< GPIO38, input mode only(ESP32) / input and output(ESP32-S2) */
GPIO_NUM_39 = 39, /*!< GPIO39, input mode only(ESP32) / input and output(ESP32-S2) */
#if GPIO_PIN_COUNT > 40
#if SOC_GPIO_PIN_COUNT > 40
GPIO_NUM_40 = 40, /*!< GPIO40, input and output */
GPIO_NUM_41 = 41, /*!< GPIO41, input and output */
GPIO_NUM_42 = 42, /*!< GPIO42, input and output */
@ -202,6 +202,13 @@ typedef enum {
GPIO_INTR_MAX,
} gpio_int_type_t;
/** @cond */
#define GPIO_MODE_DEF_DISABLE (0)
#define GPIO_MODE_DEF_INPUT (BIT0) ///< bit mask for input
#define GPIO_MODE_DEF_OUTPUT (BIT1) ///< bit mask for output
#define GPIO_MODE_DEF_OD (BIT2) ///< bit mask for OD mode
/** @endcond */
typedef enum {
GPIO_MODE_DISABLE = GPIO_MODE_DEF_DISABLE, /*!< GPIO mode : disable input and output */
GPIO_MODE_INPUT = GPIO_MODE_DEF_INPUT, /*!< GPIO mode : input only */

View File

@ -20,7 +20,7 @@ extern "C" {
#include <stdint.h>
#include <stdbool.h>
#include "soc/i2c_caps.h"
#include "soc/soc_caps.h"
/**
* @brief I2C port number, can be I2C_NUM_0 ~ (I2C_NUM_MAX-1).

View File

@ -24,7 +24,7 @@
#pragma once
#include "soc/i2s_periph.h"
#include "soc/i2s_caps.h"
#include "soc/soc_caps.h"
#include "hal/i2s_ll.h"
#include "hal/i2s_types.h"

View File

@ -17,7 +17,7 @@
#include <stdint.h>
#include <stdlib.h>
#include <stddef.h>
#include "soc/i2s_caps.h"
#include "soc/soc_caps.h"
#ifdef __cplusplus
extern "C" {

View File

@ -20,10 +20,10 @@ extern "C" {
#include <stdint.h>
#include <stdbool.h>
#include "soc/ledc_caps.h"
#include "soc/soc_caps.h"
typedef enum {
#ifdef SOC_LEDC_SUPPORT_HS_MODE
#if SOC_LEDC_SUPPORT_HS_MODE
LEDC_HIGH_SPEED_MODE = 0, /*!< LEDC high speed speed_mode */
#endif
LEDC_LOW_SPEED_MODE, /*!< LEDC low speed speed_mode */
@ -45,7 +45,7 @@ typedef enum {
typedef enum {
LEDC_SLOW_CLK_RTC8M = 0, /*!< LEDC low speed timer clock source is 8MHz RTC clock*/
LEDC_SLOW_CLK_APB, /*!< LEDC low speed timer clock source is 80MHz APB clock*/
#ifdef SOC_LEDC_SUPPORT_XTAL_CLOCK
#if SOC_LEDC_SUPPORT_XTAL_CLOCK
LEDC_SLOW_CLK_XTAL, /*!< LEDC low speed timer clock source XTAL clock*/
#endif
} ledc_slow_clk_sel_t;
@ -55,7 +55,7 @@ typedef enum {
LEDC_USE_REF_TICK, /*!< LEDC timer select REF_TICK clock as source clock*/
LEDC_USE_APB_CLK, /*!< LEDC timer select APB clock as source clock*/
LEDC_USE_RTC8M_CLK, /*!< LEDC timer select RTC8M_CLK as source clock. Only for low speed channels and this parameter must be the same for all low speed channels*/
#ifdef SOC_LEDC_SUPPORT_XTAL_CLOCK
#if SOC_LEDC_SUPPORT_XTAL_CLOCK
LEDC_USE_XTAL_CLK, /*!< LEDC timer select XTAL clock as source clock*/
#endif
} ledc_clk_cfg_t;

View File

@ -18,8 +18,8 @@ extern "C" {
#endif
#include <stdint.h>
#include "soc/soc_caps.h"
#include "soc/rmt_struct.h"
#include "soc/rmt_caps.h"
/**
* @brief HAL context type of RMT driver

View File

@ -18,7 +18,7 @@
extern "C" {
#endif
#include "soc/rmt_caps.h"
#include "soc/soc_caps.h"
/**
* @brief RMT channel ID

View File

@ -33,7 +33,7 @@ extern "C" {
* Select the rtcio function.
*
* @note The RTC function must be selected before the pad analog function is enabled.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
* @param func Select pin function.
*/
#define rtcio_hal_function_select(rtcio_num, func) rtcio_ll_function_select(rtcio_num, func)
@ -41,21 +41,21 @@ extern "C" {
/**
* Enable rtcio output.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#define rtcio_hal_output_enable(rtcio_num) rtcio_ll_output_enable(rtcio_num)
/**
* Disable rtcio output.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#define rtcio_hal_output_disable(rtcio_num) rtcio_ll_output_disable(rtcio_num)
/**
* Set RTCIO output level.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
* @param level 0: output low; ~0: output high.
*/
#define rtcio_hal_set_level(rtcio_num, level) rtcio_ll_set_level(rtcio_num, level)
@ -63,21 +63,21 @@ extern "C" {
/**
* Enable rtcio input.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#define rtcio_hal_input_enable(rtcio_num) rtcio_ll_input_enable(rtcio_num)
/**
* Disable rtcio input.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#define rtcio_hal_input_disable(rtcio_num) rtcio_ll_input_disable(rtcio_num)
/**
* Get RTCIO input level.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
* @return 0: input low; ~0: input high.
*/
#define rtcio_hal_get_level(rtcio_num) rtcio_ll_get_level(rtcio_num)
@ -85,7 +85,7 @@ extern "C" {
/**
* @brief Set RTC GPIO pad drive capability.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
* @param strength Drive capability of the pad. Range: 0 ~ 3.
*/
#define rtcio_hal_set_drive_capability(rtcio_num, strength) rtcio_ll_set_drive_capability(rtcio_num, strength)
@ -93,7 +93,7 @@ extern "C" {
/**
* @brief Get RTC GPIO pad drive capability.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
* @return Drive capability of the pad. Range: 0 ~ 3.
*/
#define rtcio_hal_get_drive_capability(rtcio_num) rtcio_ll_get_drive_capability(rtcio_num)
@ -101,7 +101,7 @@ extern "C" {
/**
* Set RTCIO output level.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
* @param level 0: output low; ~0: output high.
*/
#define rtcio_hal_set_level(rtcio_num, level) rtcio_ll_set_level(rtcio_num, level)
@ -109,7 +109,7 @@ extern "C" {
/**
* Get RTCIO input level.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
* @return 0: input low; ~0: input high.
*/
#define rtcio_hal_get_level(rtcio_num) rtcio_ll_get_level(rtcio_num)
@ -120,7 +120,7 @@ extern "C" {
* Configure RTC IO direction, such as output only, input only,
* output and input.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
* @param mode IO direction.
*/
void rtcio_hal_set_direction(int rtcio_num, rtc_gpio_mode_t mode);
@ -131,7 +131,7 @@ void rtcio_hal_set_direction(int rtcio_num, rtc_gpio_mode_t mode);
* NOTE: ESP32 support INPUT_ONLY mode.
* ESP32S2 support INPUT_ONLY, OUTPUT_ONLY, INPUT_OUTPUT mode.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
* @param mode IO direction.
*/
void rtcio_hal_set_direction_in_sleep(int rtcio_num, rtc_gpio_mode_t mode);
@ -139,28 +139,28 @@ void rtcio_hal_set_direction_in_sleep(int rtcio_num, rtc_gpio_mode_t mode);
/**
* RTC GPIO pullup enable.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#define rtcio_hal_pullup_enable(rtcio_num) rtcio_ll_pullup_enable(rtcio_num)
/**
* RTC GPIO pullup disable.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#define rtcio_hal_pullup_disable(rtcio_num) rtcio_ll_pullup_disable(rtcio_num)
/**
* RTC GPIO pulldown enable.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#define rtcio_hal_pulldown_enable(rtcio_num) rtcio_ll_pulldown_enable(rtcio_num)
/**
* RTC GPIO pulldown disable.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#define rtcio_hal_pulldown_disable(rtcio_num) rtcio_ll_pulldown_disable(rtcio_num)
@ -172,7 +172,7 @@ void rtcio_hal_set_direction_in_sleep(int rtcio_num, rtc_gpio_mode_t mode);
* This function is useful when going into light or deep sleep mode to prevent
* the pin configuration from changing.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#define rtcio_hal_hold_enable(rtcio_num) rtcio_ll_force_hold_enable(rtcio_num)
@ -180,7 +180,7 @@ void rtcio_hal_set_direction_in_sleep(int rtcio_num, rtc_gpio_mode_t mode);
* Disable hold function on an RTC IO pad
*
* @note If disable the pad hold, the status of pad maybe changed in sleep mode.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#define rtcio_hal_hold_disable(rtcio_num) rtcio_ll_force_hold_disable(rtcio_num)
@ -192,7 +192,7 @@ void rtcio_hal_set_direction_in_sleep(int rtcio_num, rtc_gpio_mode_t mode);
* This function is useful when going into light or deep sleep mode to prevent
* the pin configuration from changing.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#define rtcio_hal_hold_all() rtcio_ll_force_hold_all()
@ -200,14 +200,14 @@ void rtcio_hal_set_direction_in_sleep(int rtcio_num, rtc_gpio_mode_t mode);
* Disable hold function on an RTC IO pads.
*
* @note If disable the pad hold, the status of pad maybe changed in sleep mode.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#define rtcio_hal_unhold_all() rtcio_ll_force_unhold_all()
/**
* Enable wakeup function and set wakeup type from light sleep status for rtcio.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
* @param type Wakeup on high level or low level.
*/
#define rtcio_hal_wakeup_enable(rtcio_num, type) rtcio_ll_wakeup_enable(rtcio_num, type)
@ -215,14 +215,14 @@ void rtcio_hal_set_direction_in_sleep(int rtcio_num, rtc_gpio_mode_t mode);
/**
* Disable wakeup function from light sleep status for rtcio.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#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.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
#define rtcio_hal_ext0_set_wakeup_pin(rtcio_num, level) rtcio_ll_ext0_set_wakeup_pin(rtcio_num, level)
@ -237,7 +237,7 @@ void rtcio_hal_set_direction_in_sleep(int rtcio_num, rtc_gpio_mode_t mode);
* rtc_gpio_isolate(GPIO_NUM_12) before entering deep sleep, to reduce
* deep sleep current.
*
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTC_IO_PIN_COUNT.
* @param rtcio_num The index of rtcio. 0 ~ SOC_RTCIO_PIN_COUNT.
*/
void rtcio_hal_isolate(int rtc_num);

View File

@ -14,7 +14,7 @@
#pragma once
#include "soc/sigmadelta_caps.h"
#include "soc/soc_caps.h"
#ifdef __cplusplus
extern "C" {
@ -23,12 +23,27 @@ extern "C" {
/**
* @brief SIGMADELTA port number, the max port number is (SIGMADELTA_NUM_MAX -1).
*/
typedef int sigmadelta_port_t;
typedef enum {
SIGMADELTA_PORT_0, /*!< SIGMADELTA port 0 */
SIGMADELTA_PORT_MAX, /*!< SIGMADELTA port max */
} sigmadelta_port_t;
_Static_assert(SIGMADELTA_PORT_MAX == SOC_SIGMADELTA_NUM, "Sigma-delta port num incorrect.");
/**
* @brief Sigma-delta channel list
*/
typedef int sigmadelta_channel_t;
typedef enum {
SIGMADELTA_CHANNEL_0, /*!< Sigma-delta channel 0 */
SIGMADELTA_CHANNEL_1, /*!< Sigma-delta channel 1 */
SIGMADELTA_CHANNEL_2, /*!< Sigma-delta channel 2 */
SIGMADELTA_CHANNEL_3, /*!< Sigma-delta channel 3 */
SIGMADELTA_CHANNEL_4, /*!< Sigma-delta channel 4 */
SIGMADELTA_CHANNEL_5, /*!< Sigma-delta channel 5 */
SIGMADELTA_CHANNEL_6, /*!< Sigma-delta channel 6 */
SIGMADELTA_CHANNEL_7, /*!< Sigma-delta channel 7 */
SIGMADELTA_CHANNEL_MAX, /*!< Sigma-delta channel max */
} sigmadelta_channel_t;
/**
* @brief Sigma-delta configure struct

Some files were not shown because too many files have changed in this diff Show More