feat(adc): support ADC continuous mode on ESP32P4

This commit is contained in:
gaoxu 2024-05-21 19:47:55 +08:00
parent db6e53fd44
commit 795f3fe377
28 changed files with 553 additions and 218 deletions

View File

@ -57,7 +57,7 @@ extern portMUX_TYPE rtc_spinlock; //TODO: Will be placed in the appropriate posi
#define INTERNAL_BUF_NUM 5
#if SOC_AHB_GDMA_VERSION == 1
#if SOC_AHB_GDMA_SUPPORTED
#define ADC_GDMA_HOST 0
#define ADC_DMA_INTR_MASK GDMA_LL_EVENT_RX_SUC_EOF
#define ADC_DMA_INTR_MASK GDMA_LL_EVENT_RX_SUC_EOF

View File

@ -571,7 +571,7 @@ esp_err_t adc2_get_raw(adc2_channel_t channel, adc_bits_width_t width_bit, int *
#endif
adc_oneshot_ll_set_output_bits(ADC_UNIT_2, bitwidth);
#if CONFIG_IDF_TARGET_ESP32
#if CONFIG_IDF_TARGET_ESP32 || CONFIG_IDF_TARGET_ESP32P4
adc_ll_set_controller(ADC_UNIT_2, ADC_LL_CTRL_RTC);// set controller
#else
adc_ll_set_controller(ADC_UNIT_2, ADC_LL_CTRL_ARB);// set controller

View File

@ -17,6 +17,10 @@ components/driver/test_apps/i2s_test_apps/legacy_i2s_driver:
components/driver/test_apps/legacy_adc_driver:
disable:
- if: SOC_ADC_SUPPORTED != 1
disable_test:
- if: IDF_TARGET == "esp32p4"
temporary: true
reason: lack of runners, TODO IDF-9573
depends_components:
- efuse
- esp_driver_i2s

View File

@ -1,5 +1,6 @@
# SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD
# SPDX-License-Identifier: CC0-1.0
import pytest
from pytest_embedded import Dut
@ -10,7 +11,6 @@ from pytest_embedded import Dut
@pytest.mark.esp32c3
@pytest.mark.esp32c6
@pytest.mark.esp32h2
@pytest.mark.esp32p4
@pytest.mark.adc
@pytest.mark.parametrize(
'config',

View File

@ -53,5 +53,5 @@ endif()
idf_component_register(SRCS ${srcs}
INCLUDE_DIRS ${includes}
PRIV_REQUIRES driver esp_driver_gpio efuse esp_pm esp_ringbuf
PRIV_REQUIRES driver esp_driver_gpio efuse esp_pm esp_ringbuf esp_mm
LDFRAGMENTS linker.lf)

View File

@ -37,6 +37,11 @@
#include "adc_continuous_internal.h"
#include "esp_private/adc_dma.h"
#include "adc_dma_internal.h"
#include "esp_dma_utils.h"
#if SOC_CACHE_INTERNAL_MEM_VIA_L1CACHE
#include "esp_cache.h"
#include "esp_private/esp_cache_private.h"
#endif
static const char *ADC_TAG = "adc_continuous";
@ -66,6 +71,12 @@ static IRAM_ATTR bool adc_dma_intr(adc_continuous_ctx_t *adc_digi_ctx)
if (status != ADC_HAL_DMA_DESC_VALID) {
break;
}
#if SOC_CACHE_INTERNAL_MEM_VIA_L1CACHE
else {
esp_err_t msync_ret = esp_cache_msync((void *)finished_buffer, finished_size, ESP_CACHE_MSYNC_FLAG_DIR_M2C);
assert(msync_ret == ESP_OK);
}
#endif
ret = xRingbufferSendFromISR(adc_digi_ctx->ringbuf_hdl, finished_buffer, finished_size, &taskAwoken);
need_yield |= (taskAwoken == pdTRUE);
@ -108,7 +119,10 @@ static IRAM_ATTR bool adc_dma_intr(adc_continuous_ctx_t *adc_digi_ctx)
}
}
}
#if SOC_CACHE_INTERNAL_MEM_VIA_L1CACHE
esp_err_t msync_ret = esp_cache_msync((void *)(adc_digi_ctx->hal.rx_desc), adc_digi_ctx->adc_desc_size, ESP_CACHE_MSYNC_FLAG_DIR_M2C);
assert(msync_ret == ESP_OK);
#endif
return need_yield;
}
@ -178,7 +192,11 @@ esp_err_t adc_continuous_new_handle(const adc_continuous_handle_cfg_t *hdl_confi
}
//malloc internal buffer used by DMA
adc_ctx->rx_dma_buf = heap_caps_calloc(1, hdl_config->conv_frame_size * INTERNAL_BUF_NUM, MALLOC_CAP_INTERNAL | MALLOC_CAP_DMA);
esp_dma_mem_info_t dma_mem_info = {
.extra_heap_caps = (MALLOC_CAP_INTERNAL | MALLOC_CAP_DMA),
.dma_alignment_bytes = 4,
};
esp_dma_capable_calloc(1, hdl_config->conv_frame_size * INTERNAL_BUF_NUM, &dma_mem_info, (void **)&adc_ctx->rx_dma_buf, NULL);
if (!adc_ctx->rx_dma_buf) {
ret = ESP_ERR_NO_MEM;
goto cleanup;
@ -187,7 +205,7 @@ esp_err_t adc_continuous_new_handle(const adc_continuous_handle_cfg_t *hdl_confi
//malloc dma descriptor
uint32_t dma_desc_num_per_frame = (hdl_config->conv_frame_size + DMA_DESCRIPTOR_BUFFER_MAX_SIZE_4B_ALIGNED - 1) / DMA_DESCRIPTOR_BUFFER_MAX_SIZE_4B_ALIGNED;
uint32_t dma_desc_max_num = dma_desc_num_per_frame * INTERNAL_BUF_NUM;
adc_ctx->hal.rx_desc = heap_caps_calloc(1, (sizeof(dma_descriptor_t)) * dma_desc_max_num, MALLOC_CAP_INTERNAL | MALLOC_CAP_DMA);
esp_dma_capable_calloc(1, (sizeof(dma_descriptor_t)) * dma_desc_max_num, &dma_mem_info, (void **)&adc_ctx->hal.rx_desc, &adc_ctx->adc_desc_size);
if (!adc_ctx->hal.rx_desc) {
ret = ESP_ERR_NO_MEM;
goto cleanup;
@ -297,6 +315,10 @@ esp_err_t adc_continuous_start(adc_continuous_handle_t handle)
adc_dma_reset(handle->adc_dma);
adc_hal_digi_reset();
adc_hal_digi_dma_link(&handle->hal, handle->rx_dma_buf);
#if SOC_CACHE_INTERNAL_MEM_VIA_L1CACHE
esp_err_t ret = esp_cache_msync(handle->hal.rx_desc, handle->adc_desc_size, ESP_CACHE_MSYNC_FLAG_DIR_C2M);
assert(ret == ESP_OK);
#endif
adc_dma_start(handle->adc_dma, handle->hal.rx_desc);
adc_hal_digi_connect(true);

View File

@ -99,6 +99,7 @@ struct adc_continuous_ctx_t {
#if SOC_ADC_MONITOR_SUPPORTED
adc_monitor_t *adc_monitor[SOC_ADC_DIGI_MONITOR_NUM]; // adc monitor context
#endif
size_t adc_desc_size;
adc_dma_t adc_dma;
adc_dma_intr_func_t adc_intr_func;
};

View File

@ -4,6 +4,10 @@ components/esp_adc/test_apps/adc:
disable:
- if: SOC_ADC_SUPPORTED != 1
- if: CONFIG_NAME == "gdma_iram_safe" and IDF_TARGET in ["esp32", "esp32s2", "esp32c2"]
disable_test:
- if: IDF_TARGET == "esp32p4"
temporary: true
reason: not runners for ESP32P4 ADC # TODO: IDF-9573
depends_components:
- esp_adc
- esp_driver_gpio

View File

@ -28,7 +28,6 @@ __attribute__((unused)) static const char *TAG = "TEST_ADC";
#define TEST_STD_ADC1_CHANNEL0 ADC_CHANNEL_2
#endif
#if !CONFIG_IDF_TARGET_ESP32P4 // TODO: IDF-6497
static int s_adc_count_size;
static int *s_p_adc_count;
static int s_adc_offset = -1;
@ -132,8 +131,6 @@ static float s_print_summary(bool figure)
return sqrt(variation_square / count);
}
#endif
#if SOC_ADC_DMA_SUPPORTED
/*---------------------------------------------------------------
ADC Continuous Average / STD_Deviation Test

View File

@ -36,6 +36,8 @@ entries:
sleep_system_peripheral:peripheral_domain_pd_allowed (noflash)
sleep_modem:modem_domain_pd_allowed (noflash)
sleep_modem:periph_inform_out_light_sleep_overhead (noflash)
if IDF_TARGET_ESP32P4 = n: # TODO: IDF-6496
sar_periph_ctrl:sar_periph_ctrl_power_disable (noflash)
[mapping:esp_system_pm]
archive: libesp_system.a

View File

@ -74,6 +74,10 @@ void adc_hal_digi_init(adc_hal_dma_ctx_t *hal)
void adc_hal_digi_deinit()
{
#if ADC_LL_POWER_MANAGE_SUPPORTED
adc_ll_set_power_manage(ADC_UNIT_1, ADC_LL_POWER_SW_OFF);
adc_ll_set_power_manage(ADC_UNIT_2, ADC_LL_POWER_SW_OFF);
#endif
adc_ll_digi_trigger_disable();
adc_ll_digi_dma_disable();
adc_ll_digi_clear_pattern_table(ADC_UNIT_1);
@ -144,6 +148,9 @@ void adc_hal_digi_controller_config(adc_hal_dma_ctx_t *hal, const adc_hal_digi_c
for (int i = 0; i < cfg->adc_pattern_len; i++) {
adc_ll_digi_set_pattern_table(pattern_both, i, cfg->adc_pattern[i]);
}
#if ADC_LL_POWER_MANAGE_SUPPORTED
adc_ll_set_power_manage(0, ADC_LL_POWER_SW_ON);
#endif
#elif (SOC_ADC_DIGI_CONTROLLER_NUM >= 2)
uint32_t adc1_pattern_idx = 0;
@ -154,9 +161,15 @@ void adc_hal_digi_controller_config(adc_hal_dma_ctx_t *hal, const adc_hal_digi_c
for (int i = 0; i < cfg->adc_pattern_len; i++) {
if (cfg->adc_pattern[i].unit == ADC_UNIT_1) {
#if ADC_LL_POWER_MANAGE_SUPPORTED
adc_ll_set_power_manage(ADC_UNIT_1, ADC_LL_POWER_SW_ON);
#endif
adc_ll_digi_set_pattern_table(ADC_UNIT_1, adc1_pattern_idx, cfg->adc_pattern[i]);
adc1_pattern_idx++;
} else if (cfg->adc_pattern[i].unit == ADC_UNIT_2) {
#if ADC_LL_POWER_MANAGE_SUPPORTED
adc_ll_set_power_manage(ADC_UNIT_2, ADC_LL_POWER_SW_ON);
#endif
adc_ll_digi_set_pattern_table(ADC_UNIT_2, adc2_pattern_idx, cfg->adc_pattern[i]);
adc2_pattern_idx++;
} else {

View File

@ -142,7 +142,7 @@ bool adc_oneshot_hal_convert(adc_oneshot_hal_ctx_t *hal, int *out_raw)
}
esp_rom_delay_us(read_delay_us);
*out_raw = adc_oneshot_ll_get_raw_result(hal->unit);
#if (SOC_ADC_PERIPH_NUM == 2)
#if SOC_ADC_ARBITER_SUPPORTED
if (hal->unit == ADC_UNIT_2) {
valid = adc_oneshot_ll_raw_check_valid(ADC_UNIT_2, *out_raw);
if (!valid) {

View File

@ -17,7 +17,6 @@
#include "soc/syscon_struct.h"
#include "soc/rtc_cntl_struct.h"
#include "soc/clk_tree_defs.h"
#include "soc/dport_reg.h"
#ifdef __cplusplus
extern "C" {

View File

@ -59,6 +59,7 @@ extern "C" {
#define ADC_LL_DEFAULT_CONV_LIMIT_EN 0
#define ADC_LL_DEFAULT_CONV_LIMIT_NUM 10
#define ADC_LL_POWER_MANAGE_SUPPORTED 1 //ESP32C6 supported to manage power mode
/*---------------------------------------------------------------
PWDET (Power Detect)
---------------------------------------------------------------*/
@ -578,8 +579,9 @@ static inline void adc_ll_reset_register(void)
*
* @param manage Set ADC power status.
*/
static inline void adc_ll_set_power_manage(adc_ll_power_t manage)
static inline void adc_ll_set_power_manage(adc_unit_t adc_n, adc_ll_power_t manage)
{
(void) adc_n;
/* Bit1 0:Fsm 1: SW mode
Bit0 0:SW mode power down 1: SW mode power on */
if (manage == ADC_LL_POWER_SW_ON) {

View File

@ -60,6 +60,7 @@ extern "C" {
#define ADC_LL_DEFAULT_CONV_LIMIT_EN 0
#define ADC_LL_DEFAULT_CONV_LIMIT_NUM 10
#define ADC_LL_POWER_MANAGE_SUPPORTED 1 //ESP32H2 supported to manage power mode
/*---------------------------------------------------------------
PWDET (Power Detect)
---------------------------------------------------------------*/
@ -578,8 +579,9 @@ static inline void adc_ll_reset_register(void)
*
* @param manage Set ADC power status.
*/
static inline void adc_ll_set_power_manage(adc_ll_power_t manage)
static inline void adc_ll_set_power_manage(adc_unit_t adc_n, adc_ll_power_t manage)
{
(void) adc_n;
/* Bit1 0:Fsm 1: SW mode
Bit0 0:SW mode power down 1: SW mode power on */
if (manage == ADC_LL_POWER_SW_ON) {

View File

@ -10,24 +10,18 @@
#include "esp_attr.h"
#include "soc/adc_periph.h"
// #include "soc/ADC_struct.h"
// #include "soc/ADC_reg.h"
#include "soc/pmu_reg.h"
#include "soc/adc_struct.h"
#include "soc/clk_tree_defs.h"
// #include "soc/pcr_struct.h"
#include "soc/hp_sys_clkrst_struct.h"
#include "soc/lpperi_struct.h"
#include "soc/regi2c_saradc.h"
#include "hal/misc.h"
#include "hal/assert.h"
#include "hal/adc_types.h"
#include "hal/adc_types_private.h"
#include "hal/regi2c_ctrl.h"
#include "hal/sar_ctrl_ll.h"
#include "soc/regi2c_saradc.h"
#include "soc/hp_sys_clkrst_struct.h"
#include "soc/adc_struct.h"
#include "soc/lp_adc_struct.h"
#include "soc/lpperi_struct.h"
#ifdef __cplusplus
extern "C" {
@ -36,6 +30,10 @@ extern "C" {
#define ADC_LL_EVENT_ADC1_ONESHOT_DONE BIT(31)
#define ADC_LL_EVENT_ADC2_ONESHOT_DONE BIT(30)
#define LP_ADC_FORCE_XPD_SAR_FSM 0 // Use FSM to control power down
#define LP_ADC_FORCE_XPD_SAR_PD 2 // Force power down
#define LP_ADC_FORCE_XPD_SAR_PU 3 // Force power up
/*---------------------------------------------------------------
Oneshot
---------------------------------------------------------------*/
@ -46,7 +44,20 @@ extern "C" {
/*---------------------------------------------------------------
DMA
---------------------------------------------------------------*/
#define ADC_LL_DIGI_DATA_INVERT_DEFAULT(PERIPH_NUM) (0)
#define ADC_LL_FSM_RSTB_WAIT_DEFAULT (8)
#define ADC_LL_FSM_START_WAIT_DEFAULT (5)
#define ADC_LL_FSM_STANDBY_WAIT_DEFAULT (100)
#define ADC_LL_SAMPLE_CYCLE_DEFAULT (2)
#define ADC_LL_DIGI_SAR_CLK_DIV_DEFAULT (1)
#define ADC_LL_CLKM_DIV_NUM_DEFAULT 15
#define ADC_LL_CLKM_DIV_B_DEFAULT 1
#define ADC_LL_CLKM_DIV_A_DEFAULT 0
#define ADC_LL_DEFAULT_CONV_LIMIT_EN 0
#define ADC_LL_DEFAULT_CONV_LIMIT_NUM 10
#define ADC_LL_POWER_MANAGE_SUPPORTED 1 //ESP32P4 supported to manage power mode
/*---------------------------------------------------------------
PWDET (Power Detect)
---------------------------------------------------------------*/
@ -56,8 +67,7 @@ typedef enum {
ADC_LL_CTRL_RTC = 0, ///< For ADC1 and ADC2. Select RTC controller.
ADC_LL_CTRL_ULP = 1, ///< For ADC1 and ADC2. Select ULP controller.
ADC_LL_CTRL_DIG = 2, ///< For ADC1 and ADC2. Select DIG controller.
ADC_LL_CTRL_PWDET = 3, ///< ???
ADC_LL_CTRL_ARB = 4, ///< ???
ADC_LL_CTRL_PWDET = 3, ///< For ADC2. Select PWDET controller.
} adc_ll_controller_t;
typedef enum {
@ -94,28 +104,40 @@ typedef struct {
};
} __attribute__((packed)) adc_ll_digi_pattern_table_t;
/**
* @brief Analyze whether the obtained raw data is correct.
* ADC2 use arbiter by default. The arbitration result can be judged by the flag bit in the original data.
*
*/
typedef struct {
union {
struct {
uint16_t data: 13; /*!<ADC real output data info. Resolution: 13 bit. */
uint16_t reserved: 1; /*!<reserved */
uint16_t flag: 2; /*!<ADC data flag info.
If (flag == 0), The data is valid.
If (flag > 0), The data is invalid. */
};
uint16_t val;
};
} adc_ll_rtc_output_data_t;
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
/**
* Set adc fsm interval parameter for digital controller. These values are fixed for same platforms.
*
* @param rst_wait cycles between DIG ADC controller reset ADC sensor and start ADC sensor.
* @param start_wait Delay time after open xpd.
* @param standby_wait Delay time to close xpd.
*/
static inline void adc_ll_digi_set_fsm_time(uint32_t rst_wait, uint32_t start_wait, uint32_t standby_wait)
{
// Internal FSM reset wait time
HAL_FORCE_MODIFY_U32_REG_FIELD(ADC.fsm_wait, rstb_wait, rst_wait);
// Internal FSM start wait time
HAL_FORCE_MODIFY_U32_REG_FIELD(ADC.fsm_wait, xpd_wait, start_wait);
// Internal FSM standby wait time
HAL_FORCE_MODIFY_U32_REG_FIELD(ADC.fsm_wait, standby_wait, standby_wait);
}
/**
* Set adc sample cycle for digital controller.
*
* @note Normally, please use default value.
* @param sample_cycle Cycles between DIG ADC controller start ADC sensor and beginning to receive data from sensor.
* Range: 2 ~ 0xFF.
*/
static inline void adc_ll_set_sample_cycle(uint32_t sample_cycle)
{
/* Peripheral reg i2c has powered up in rtc_init, write directly */
REGI2C_WRITE_MASK(I2C_SAR_ADC, ADC_SAR1_SAMPLE_CYCLE_ADDR, sample_cycle);
}
/**
* Set SAR ADC module clock division factor.
* SAR ADC clock divided from digital controller clock.
@ -128,6 +150,49 @@ static inline void adc_ll_digi_set_clk_div(uint32_t div)
HAL_FORCE_MODIFY_U32_REG_FIELD(ADC.ctrl_reg, sar_clk_div, div);
}
/**
* Set adc max conversion number for digital controller.
* If the number of ADC conversion is equal to the maximum, the conversion is stopped.
*
* @param meas_num Max conversion number. Range: 0 ~ 255.
*/
static inline void adc_ll_digi_set_convert_limit_num(uint32_t meas_num)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(ADC.ctrl2, max_meas_num, meas_num);
}
/**
* Enable max conversion number detection for digital controller.
* If the number of ADC conversion is equal to the maximum, the conversion is stopped.
*
* @param enable true: enable; false: disable
*/
static inline void adc_ll_digi_convert_limit_enable(bool enable)
{
ADC.ctrl2.meas_num_limit = enable;
}
/**
* Set adc conversion mode for digital controller.
*
* @param mode Conversion mode select.
*/
static inline void adc_ll_digi_set_convert_mode(adc_ll_digi_convert_mode_t mode)
{
if (mode == ADC_LL_DIGI_CONV_ONLY_ADC1) {
ADC.ctrl_reg.work_mode = 0;
ADC.ctrl_reg.sar_sel = 0;
} else if (mode == ADC_LL_DIGI_CONV_ONLY_ADC2) {
ADC.ctrl_reg.work_mode = 0;
ADC.ctrl_reg.sar_sel = 1;
} else if (mode == ADC_LL_DIGI_CONV_BOTH_UNIT) {
ADC.ctrl_reg.work_mode = 1;
} else if (mode == ADC_LL_DIGI_CONV_ALTER_UNIT) {
ADC.ctrl_reg.work_mode = 2;
}
ADC.ctrl_reg.data_sar_sel = 1;
}
/**
* Set ADC digital controller clock division factor. The clock divided from `APLL` or `APB` clock.
* Expression: controller_clk = (APLL or APB) / (div_num + div_a / div_b + 1).
@ -139,8 +204,8 @@ static inline void adc_ll_digi_set_clk_div(uint32_t div)
static inline void adc_ll_digi_controller_clk_div(uint32_t div_num, uint32_t div_b, uint32_t div_a)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(HP_SYS_CLKRST.peri_clk_ctrl23, reg_adc_clk_div_num, div_num);
HP_SYS_CLKRST.root_clk_ctrl0.reg_cpu_clk_div_numerator = div_b;
HP_SYS_CLKRST.root_clk_ctrl0.reg_cpu_clk_div_denominator = div_a;
HP_SYS_CLKRST.peri_clk_ctrl23.reg_adc_clk_div_numerator = div_a;
HP_SYS_CLKRST.peri_clk_ctrl23.reg_adc_clk_div_denominator = div_b;
}
/**
@ -167,6 +232,235 @@ static inline void adc_ll_digi_clk_sel(adc_continuous_clk_src_t clk_src)
ADC.ctrl_reg.sar_clk_gated = 1;
}
/**
* Disable clock for ADC digital controller.
*/
static inline void adc_ll_digi_controller_clk_disable(void)
{
ADC.ctrl_reg.sar_clk_gated = 0;
}
/**
* Reset adc digital controller filter.
*
* @param idx Filter index
* @param adc_n ADC unit.
*/
static inline void adc_ll_digi_filter_reset(adc_digi_iir_filter_t idx, adc_unit_t adc_n)
{
(void)adc_n;
ADC.filter_ctrl0.filter_reset = 1;
ADC.filter_ctrl0.filter_reset = 0;
}
/**
* Set adc digital controller filter coeff.
*
* @param idx filter index
* @param adc_n adc unit
* @param channel adc channel
* @param coeff filter coeff
*/
static inline void adc_ll_digi_filter_set_factor(adc_digi_iir_filter_t idx, adc_unit_t adc_n, adc_channel_t channel, adc_digi_iir_filter_coeff_t coeff)
{
uint32_t factor_reg_val = 0;
switch (coeff) {
case ADC_DIGI_IIR_FILTER_COEFF_2:
factor_reg_val = 1;
break;
case ADC_DIGI_IIR_FILTER_COEFF_4:
factor_reg_val = 2;
break;
case ADC_DIGI_IIR_FILTER_COEFF_8:
factor_reg_val = 3;
break;
case ADC_DIGI_IIR_FILTER_COEFF_16:
factor_reg_val = 4;
break;
case ADC_DIGI_IIR_FILTER_COEFF_64:
factor_reg_val = 6;
break;
default:
HAL_ASSERT(false);
}
if (idx == ADC_DIGI_IIR_FILTER_0) {
ADC.filter_ctrl0.filter_channel0 = ((adc_n + 1) << 3) | (channel & 0x7);
ADC.filter_ctrl1.filter_factor0 = factor_reg_val;
} else if (idx == ADC_DIGI_IIR_FILTER_1) {
ADC.filter_ctrl0.filter_channel1 = ((adc_n + 1) << 3) | (channel & 0x7);
ADC.filter_ctrl1.filter_factor1 = factor_reg_val;
}
}
/**
* Enable adc digital controller filter.
* Filtering the ADC data to obtain smooth data at higher sampling rates.
*
* @param idx filter index
* @param adc_n ADC unit
* @param enable Enable / Disable
*/
static inline void adc_ll_digi_filter_enable(adc_digi_iir_filter_t idx, adc_unit_t adc_n, bool enable)
{
(void)adc_n;
if (!enable) {
if (idx == ADC_DIGI_IIR_FILTER_0) {
ADC.filter_ctrl0.filter_channel0 = 0xF;
ADC.filter_ctrl1.filter_factor0 = 0;
} else if (idx == ADC_DIGI_IIR_FILTER_1) {
ADC.filter_ctrl0.filter_channel1 = 0xF;
ADC.filter_ctrl1.filter_factor1 = 0;
}
}
//nothing to do to enable, after adc_ll_digi_filter_set_factor, it's enabled.
}
/**
* Set pattern table length for digital controller.
* The pattern table that defines the conversion rules for each SAR ADC. Each table has 16 items, in which channel selection,
* resolution and attenuation are stored. When the conversion is started, the controller reads conversion rules from the
* pattern table one by one. For each controller the scan sequence has at most 16 different rules before repeating itself.
*
* @param adc_n ADC unit.
* @param patt_len Items range: 1 ~ 16.
*/
static inline void adc_ll_digi_set_pattern_table_len(adc_unit_t adc_n, uint32_t patt_len)
{
if (adc_n == ADC_UNIT_1) {
ADC.ctrl_reg.sar1_patt_len = patt_len - 1;
} else { // adc_n == ADC_UNIT_2
ADC.ctrl_reg.sar2_patt_len = patt_len - 1;
}
}
/**
* Set pattern table for digital controller.
* The pattern table that defines the conversion rules for each SAR ADC. Each table has 12 items, in which channel selection,
* resolution and attenuation are stored. When the conversion is started, the controller reads conversion rules from the
* pattern table one by one. For each controller the scan sequence has at most 12 different rules before repeating itself.
*
* @param adc_n ADC unit.
* @param pattern_index Items index. Range: 0 ~ 11.
* @param pattern Stored conversion rules.
*/
static inline void adc_ll_digi_set_pattern_table(adc_unit_t adc_n, uint32_t pattern_index, adc_digi_pattern_config_t table)
{
uint32_t tab;
uint8_t index = pattern_index / 4;
uint8_t offset = (pattern_index % 4) * 6;
adc_ll_digi_pattern_table_t pattern = {0};
pattern.val = (table.atten & 0x3) | ((table.channel & 0xF) << 2);
if (table.unit == ADC_UNIT_1){
tab = ADC.sar1_patt_tab[index].sar1_patt_tab; //Read old register value
tab &= (~(0xFC0000 >> offset)); //Clear old data
tab |= ((uint32_t)(pattern.val & 0x3F) << 18) >> offset; //Fill in the new data
ADC.sar1_patt_tab[index].sar1_patt_tab = tab; //Write back
} else {
tab = ADC.sar2_patt_tab[index].sar2_patt_tab; //Read old register value
tab &= (~(0xFC0000 >> offset)); //clear old data
tab |= ((uint32_t)(pattern.val & 0x3F) << 18) >> offset; //Fill in the new data
ADC.sar2_patt_tab[index].sar2_patt_tab = tab; //Write back
}
}
/**
* Reset the pattern table pointer, then take the measurement rule from table header in next measurement.
*
* @param adc_n ADC unit.
*/
static inline void adc_ll_digi_clear_pattern_table(adc_unit_t adc_n)
{
if (adc_n == ADC_UNIT_1) {
ADC.ctrl_reg.sar1_patt_p_clear = 1;
ADC.ctrl_reg.sar1_patt_p_clear = 0;
} else { // adc_n == ADC_UNIT_2
ADC.ctrl_reg.sar2_patt_p_clear = 1;
ADC.ctrl_reg.sar2_patt_p_clear = 0;
}
}
/**
* ADC Digital controller output data invert or not.
*
* @param adc_n ADC unit.
* @param inv_en data invert or not.
*/
static inline void adc_ll_digi_output_invert(adc_unit_t adc_n, bool inv_en)
{
if (adc_n == ADC_UNIT_1) {
ADC.ctrl2.sar1_inv = inv_en; // Enable / Disable ADC data invert
} else { // adc_n == ADC_UNIT_2
ADC.ctrl2.sar2_inv = inv_en; // Enable / Disable ADC data invert
}
}
/**
* Set the interval clock cycle for the digital controller to trigger the measurement.
* Expression: `trigger_meas_freq` = `controller_clk` / 2 / interval.
*
* @note The trigger interval should not be smaller than the sampling time of the SAR ADC.
* @param cycle The clock cycle (trigger interval) of the measurement. Range: 30 ~ 4095.
*/
static inline void adc_ll_digi_set_trigger_interval(uint32_t cycle)
{
ADC.ctrl2.timer_target = cycle;
}
/**
* Set DMA eof num of adc digital controller.
* If the number of measurements reaches `dma_eof_num`, then `dma_in_suc_eof` signal is generated.
*
* @param num eof num of DMA.
*/
static inline void adc_ll_digi_dma_set_eof_num(uint32_t num)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(ADC.dma_conf, apb_adc_eof_num, num);
}
/**
* Enable output data to DMA from adc digital controller.
*/
static inline void adc_ll_digi_dma_enable(void)
{
ADC.dma_conf.apb_adc_trans = 1;
}
/**
* Disable output data to DMA from adc digital controller.
*/
static inline void adc_ll_digi_dma_disable(void)
{
ADC.dma_conf.apb_adc_trans = 0;
}
/**
* Reset adc digital controller.
*/
static inline void adc_ll_digi_reset(void)
{
ADC.dma_conf.apb_adc_reset_fsm = 1;
ADC.dma_conf.apb_adc_reset_fsm = 0;
}
/**
* Enable digital controller timer to trigger the measurement.
*/
static inline void adc_ll_digi_trigger_enable(void)
{
ADC.ctrl2.timer_sel = 1;
ADC.ctrl2.timer_en = 1;
}
/**
* Disable digital controller timer to trigger the measurement.
*/
static inline void adc_ll_digi_trigger_disable(void)
{
ADC.ctrl2.timer_en = 0;
}
/*---------------------------------------------------------------
PWDET(Power detect) controller setting
---------------------------------------------------------------*/
@ -206,6 +500,7 @@ static inline uint32_t adc_ll_pwdet_get_cct(void)
static inline void adc_ll_enable_bus_clock(bool enable)
{
HP_SYS_CLKRST.soc_clk_ctrl2.reg_adc_apb_clk_en = enable;
HP_SYS_CLKRST.peri_clk_ctrl23.reg_adc_clk_en = enable;
}
// HP_SYS_CLKRST.soc_clk_ctrl2 are shared registers, so this function must be used in an atomic way
#define adc_ll_enable_bus_clock(...) (void)__DECLARE_RCC_ATOMIC_ENV; adc_ll_enable_bus_clock(__VA_ARGS__)
@ -221,6 +516,84 @@ static inline void adc_ll_reset_register(void)
// HP_SYS_CLKRST.hp_rst_en2 is a shared register, so this function must be used in an atomic way
#define adc_ll_reset_register(...) (void)__DECLARE_RCC_ATOMIC_ENV; adc_ll_reset_register(__VA_ARGS__)
/**
* Set ADC digital controller power management.
*
* @param adc_n ADC unit.
* @param manage Set ADC power status.
*/
static inline void adc_ll_digi_set_power_manage(adc_unit_t adc_n, adc_ll_power_t manage)
{
if (adc_n == ADC_UNIT_1) {
/* Bit1 0:Fsm 1: SW mode
Bit0 0:SW mode power down 1: SW mode power on */
if (manage == ADC_LL_POWER_SW_ON) {
ADC.ctrl_reg.sar_clk_gated = 1;
ADC.ctrl_reg.xpd_sar1_force = LP_ADC_FORCE_XPD_SAR_PU;
} else if (manage == ADC_LL_POWER_BY_FSM) {
ADC.ctrl_reg.sar_clk_gated = 1;
ADC.ctrl_reg.xpd_sar1_force = LP_ADC_FORCE_XPD_SAR_FSM;
} else if (manage == ADC_LL_POWER_SW_OFF) {
ADC.ctrl_reg.sar_clk_gated = 0;
ADC.ctrl_reg.xpd_sar1_force = LP_ADC_FORCE_XPD_SAR_PD;
}
} else {
/* Bit1 0:Fsm 1: SW mode
Bit0 0:SW mode power down 1: SW mode power on */
if (manage == ADC_LL_POWER_SW_ON) {
ADC.ctrl_reg.sar_clk_gated = 1;
ADC.ctrl_reg.xpd_sar2_force = LP_ADC_FORCE_XPD_SAR_PU;
} else if (manage == ADC_LL_POWER_BY_FSM) {
ADC.ctrl_reg.sar_clk_gated = 1;
ADC.ctrl_reg.xpd_sar2_force = LP_ADC_FORCE_XPD_SAR_FSM;
} else if (manage == ADC_LL_POWER_SW_OFF) {
ADC.ctrl_reg.sar_clk_gated = 0;
ADC.ctrl_reg.xpd_sar2_force = LP_ADC_FORCE_XPD_SAR_PD;
}
}
}
/**
* Set ADC module power management.
*
* @param adc_n ADC unit.
* @param manage Set ADC power status.
*/
static inline void adc_ll_set_power_manage(adc_unit_t adc_n, adc_ll_power_t manage)
{
adc_ll_digi_set_power_manage(adc_n, manage);
if (adc_n == ADC_UNIT_1) {
/* Bit1 0:Fsm 1: SW mode
Bit0 0:SW mode power down 1: SW mode power on */
if (manage == ADC_LL_POWER_SW_ON) {
LPPERI.clk_en.ck_en_lp_adc = 1;
LP_ADC.force_wpd_sar.force_xpd_sar1 = LP_ADC_FORCE_XPD_SAR_PU;
} else if (manage == ADC_LL_POWER_BY_FSM) {
LPPERI.clk_en.ck_en_lp_adc = 1;
LP_ADC.force_wpd_sar.force_xpd_sar1 = LP_ADC_FORCE_XPD_SAR_FSM;
} else if (manage == ADC_LL_POWER_SW_OFF) {
LP_ADC.force_wpd_sar.force_xpd_sar1 = LP_ADC_FORCE_XPD_SAR_PD;
LPPERI.clk_en.ck_en_lp_adc = 0;
}
} else {
/* Bit1 0:Fsm 1: SW mode
Bit0 0:SW mode power down 1: SW mode power on */
if (manage == ADC_LL_POWER_SW_ON) {
LPPERI.clk_en.ck_en_lp_adc = 1;
LP_ADC.force_wpd_sar.force_xpd_sar2 = LP_ADC_FORCE_XPD_SAR_PU;
} else if (manage == ADC_LL_POWER_BY_FSM) {
LPPERI.clk_en.ck_en_lp_adc = 1;
LP_ADC.force_wpd_sar.force_xpd_sar2 = LP_ADC_FORCE_XPD_SAR_FSM;
} else if (manage == ADC_LL_POWER_SW_OFF) {
LP_ADC.force_wpd_sar.force_xpd_sar2 = LP_ADC_FORCE_XPD_SAR_PD;
LPPERI.clk_en.ck_en_lp_adc = 0;
}
}
}
/**
* Set ADC module controller.
* There are five SAR ADC controllers:
@ -277,39 +650,6 @@ static inline void adc_ll_set_controller(adc_unit_t adc_n, adc_ll_controller_t c
}
}
/**
* Set ADC2 module controller priority in arbiter.
* The arbiter is to improve the use efficiency of ADC2. After the control right is robbed by the high priority,
* the low priority controller will read the invalid ADC data, and the validity of the data can be judged by the flag bit in the data.
*
* @note Only ADC2 support arbiter.
* @note The arbiter's working clock is APB_CLK. When the APB_CLK clock drops below 8 MHz, the arbiter must be in shield mode.
* @note Default priority: Wi-Fi(2) > RTC(1) > Digital(0);
*
* @param pri_rtc RTC controller priority. Range: 0 ~ 2.
* @param pri_dig Digital controller priority. Range: 0 ~ 2.
* @param pri_pwdet Wi-Fi controller priority. Range: 0 ~ 2.
*/
__attribute__((always_inline))
static inline void adc_ll_set_arbiter_priority(uint8_t pri_rtc, uint8_t pri_dig, uint8_t pri_pwdet)
{
if (pri_rtc != pri_dig && pri_rtc != pri_pwdet && pri_dig != pri_pwdet) {
ADC.arb_ctrl.arb_rtc_priority = pri_rtc;
ADC.arb_ctrl.arb_apb_priority = pri_dig;
ADC.arb_ctrl.arb_wifi_priority = pri_pwdet;
}
/* Should select highest priority controller. */
if (pri_rtc > pri_dig) {
ADC.arb_ctrl.arb_apb_force = 0;
ADC.arb_ctrl.arb_rtc_force = 1;
ADC.arb_ctrl.arb_wifi_force = 0;
} else {
ADC.arb_ctrl.arb_apb_force = 1;
ADC.arb_ctrl.arb_rtc_force = 0;
ADC.arb_ctrl.arb_wifi_force = 0;
}
}
/*---------------------------------------------------------------
Oneshot Read
---------------------------------------------------------------*/
@ -436,26 +776,16 @@ static inline uint32_t adc_oneshot_ll_get_raw_result(adc_unit_t adc_n)
/**
* Analyze whether the obtained raw data is correct.
* ADC2 can use arbiter. The arbitration result can be judged by the flag bit in the original data.
*
* @param adc_n ADC unit.
* @param raw ADC raw data input (convert value).
* @return
* - true: raw data is valid
* - false: raw data is invalid
*/
static inline bool adc_oneshot_ll_raw_check_valid(adc_unit_t adc_n, uint32_t raw)
{
if (adc_n == ADC_UNIT_1) {
return true;
}
adc_ll_rtc_output_data_t *temp = (adc_ll_rtc_output_data_t *)&raw;
if (temp->flag == 0) {
return true;
} else {
//Could be ADC_LL_RTC_CTRL_UNSELECTED, ADC_LL_RTC_CTRL_BREAK or ADC_LL_RTC_DATA_FAIL
return false;
}
/* No arbiter, don't need check data */
return true;
}
/**
@ -481,8 +811,7 @@ static inline void adc_oneshot_ll_output_invert(adc_unit_t adc_n, bool inv_en)
static inline void adc_oneshot_ll_enable(adc_unit_t adc_n)
{
(void)adc_n;
HP_SYS_CLKRST.soc_clk_ctrl2.reg_adc_apb_clk_en = 1;
HP_SYS_CLKRST.peri_clk_ctrl23.reg_adc_clk_en = 1;
//For compatibility
}
/**
@ -490,8 +819,7 @@ static inline void adc_oneshot_ll_enable(adc_unit_t adc_n)
*/
static inline void adc_oneshot_ll_disable_all_unit(void)
{
HP_SYS_CLKRST.soc_clk_ctrl2.reg_adc_apb_clk_en = 0;
HP_SYS_CLKRST.peri_clk_ctrl23.reg_adc_clk_en = 0;
//For compatibility
}
/*---------------------------------------------------------------

View File

@ -50,15 +50,12 @@ __attribute__((always_inline))
static inline void sar_ctrl_ll_set_power_mode(sar_ctrl_ll_power_t mode)
{
if (mode == SAR_CTRL_LL_POWER_FSM) {
// LP_ADC.sar_peri_clk_gate_conf.saradc_clk_en = 1;
LP_ADC.force_wpd_sar.force_xpd_sar1 = 0x0;
LP_ADC.force_wpd_sar.force_xpd_sar2 = 0x0;
} else if (mode == SAR_CTRL_LL_POWER_ON) {
// LP_ADC.sar_peri_clk_gate_conf.saradc_clk_en = 1;
LP_ADC.force_wpd_sar.force_xpd_sar1 = 0x3;
LP_ADC.force_wpd_sar.force_xpd_sar2 = 0x3;
} else {
// LP_ADC.sar_peri_clk_gate_conf.saradc_clk_en = 0;
LP_ADC.force_wpd_sar.force_xpd_sar1 = 0x2;
LP_ADC.force_wpd_sar.force_xpd_sar2 = 0x2;
}

View File

@ -940,8 +940,8 @@ static inline void adc_ll_enable_bus_clock(bool enable)
*/
static inline void adc_ll_reset_register(void)
{
DPORT_SET_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_APB_SARADC_RST);
DPORT_CLEAR_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_APB_SARADC_RST);
SET_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_APB_SARADC_RST);
CLEAR_PERI_REG_MASK(DPORT_PERIP_RST_EN_REG, DPORT_APB_SARADC_RST);
}
// SYSTEM.perip_rst_en0 is a shared register, so this function must be used in an atomic way
#define adc_ll_reset_register(...) (void)__DECLARE_RCC_ATOMIC_ENV; adc_ll_reset_register(__VA_ARGS__)

View File

@ -19,6 +19,7 @@
#include "soc/io_mux_reg.h"
#include "soc/usb_serial_jtag_reg.h"
#include "soc/usb_serial_jtag_struct.h"
#include "soc/sens_struct.h"
#ifdef __cplusplus
extern "C" {
@ -27,7 +28,7 @@ extern "C" {
#define RTCIO_LL_PIN_FUNC 0
typedef enum {
RTCIO_LL_FUNC_RTC = 0x0, /*!< The pin controled by RTC module. */
RTCIO_LL_FUNC_RTC = 0x0, /*!< The pin controlled by RTC module. */
RTCIO_LL_FUNC_DIGITAL = 0x1, /*!< The pin controlled by DIGITAL module. */
} rtcio_ll_func_t;

View File

@ -10,3 +10,11 @@
/* Solicited yields (portYIELD() or taskYIELD()) take longer on esp32p4. TODO: IDF-2809 */
#define IDF_PERFORMANCE_MAX_SCHEDULING_TIME 3200
#define IDF_PERFORMANCE_MAX_ADC_CONTINUOUS_STD_ATTEN3_NO_FILTER 10
#define IDF_PERFORMANCE_MAX_ADC_CONTINUOUS_STD_ATTEN3_FILTER_2 10
#define IDF_PERFORMANCE_MAX_ADC_CONTINUOUS_STD_ATTEN3_FILTER_4 10
#define IDF_PERFORMANCE_MAX_ADC_CONTINUOUS_STD_ATTEN3_FILTER_8 10
#define IDF_PERFORMANCE_MAX_ADC_CONTINUOUS_STD_ATTEN3_FILTER_16 10
#define IDF_PERFORMANCE_MAX_ADC_CONTINUOUS_STD_ATTEN3_FILTER_64 10
#define IDF_PERFORMANCE_MAX_ADC_ONESHOT_STD_ATTEN3 10

View File

@ -315,6 +315,10 @@ config SOC_ADC_DIG_CTRL_SUPPORTED
bool
default y
config SOC_ADC_DMA_SUPPORTED
bool
default y
config SOC_ADC_PERIPH_NUM
int
default 2
@ -333,7 +337,7 @@ config SOC_ADC_DIGI_CONTROLLER_NUM
config SOC_ADC_PATT_LEN_MAX
int
default 8
default 16
config SOC_ADC_DIGI_MAX_BITWIDTH
int
@ -379,6 +383,10 @@ config SOC_ADC_CALIBRATION_V1_SUPPORTED
bool
default n
config SOC_ADC_SHARED_POWER
bool
default y
config SOC_APB_BACKUP_DMA
bool
default n

View File

@ -1,5 +1,5 @@
/**
* SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -195,6 +195,26 @@ extern "C" {
#define ADC_FILTER_FACTOR0_V 0x00000007U
#define ADC_FILTER_FACTOR0_S 29
#define ADC_FSM_WAIT_REG (DR_REG_ADC_BASE + 0xC)
/* ADC_STANDBY_WAIT : R/W ;bitpos:[23:16] ;default: 8'd255 ; */
/*description: need_des.*/
#define ADC_STANDBY_WAIT 0x000000FF
#define ADC_STANDBY_WAIT_M ((ADC_STANDBY_WAIT_V)<<(ADC_STANDBY_WAIT_S))
#define ADC_STANDBY_WAIT_V 0xFF
#define ADC_STANDBY_WAIT_S 16
/* ADC_RSTB_WAIT : R/W ;bitpos:[15:8] ;default: 8'd8 ; */
/*description: need_des.*/
#define ADC_RSTB_WAIT 0x000000FF
#define ADC_RSTB_WAIT_M ((ADC_RSTB_WAIT_V)<<(ADC_RSTB_WAIT_S))
#define ADC_RSTB_WAIT_V 0xFF
#define ADC_RSTB_WAIT_S 8
/* ADC_XPD_WAIT : R/W ;bitpos:[7:0] ;default: 8'd8 ; */
/*description: need_des.*/
#define ADC_XPD_WAIT 0x000000FF
#define ADC_XPD_WAIT_M ((ADC_XPD_WAIT_V)<<(ADC_XPD_WAIT_S))
#define ADC_XPD_WAIT_V 0xFF
#define ADC_XPD_WAIT_S 0
/** ADC_SAR1_PATT_TAB1_REG register
* Register
*/

View File

@ -1,5 +1,5 @@
/**
* SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -137,117 +137,46 @@ typedef union {
uint32_t val;
} adc_filter_ctrl1_reg_t;
/** Type of sar1_patt_tab1 register
/** Type of filter_ctrl1 register
* Register
*/
typedef union {
struct {
/** sar1_patt_tab1 : R/W; bitpos: [23:0]; default: 0;
uint32_t xpd_wait:8;
uint32_t rstb_wait:8;
uint32_t standby_wait:8;
uint32_t reserved24:8;
};
uint32_t val;
} adc_fsm_wait_reg_t;
/** Type of sar1_patt_tab register
* Register
*/
typedef union {
struct {
/** sar1_patt_tab : R/W; bitpos: [23:0]; default: 0;
* item 0 ~ 3 for pattern table 1 (each item one byte)
*/
uint32_t sar1_patt_tab1:24;
uint32_t sar1_patt_tab:24;
uint32_t reserved_24:8;
};
uint32_t val;
} adc_sar1_patt_tab1_reg_t;
/** Type of sar1_patt_tab2 register
* Register
*/
typedef union {
struct {
/** sar1_patt_tab2 : R/W; bitpos: [23:0]; default: 0;
* Item 4 ~ 7 for pattern table 1 (each item one byte)
*/
uint32_t sar1_patt_tab2:24;
uint32_t reserved_24:8;
};
uint32_t val;
} adc_sar1_patt_tab2_reg_t;
/** Type of sar1_patt_tab3 register
* Register
*/
typedef union {
struct {
/** sar1_patt_tab3 : R/W; bitpos: [23:0]; default: 0;
* Item 8 ~ 11 for pattern table 1 (each item one byte)
*/
uint32_t sar1_patt_tab3:24;
uint32_t reserved_24:8;
};
uint32_t val;
} adc_sar1_patt_tab3_reg_t;
/** Type of sar1_patt_tab4 register
* Register
*/
typedef union {
struct {
/** sar1_patt_tab4 : R/W; bitpos: [23:0]; default: 0;
* Item 12 ~ 15 for pattern table 1 (each item one byte)
*/
uint32_t sar1_patt_tab4:24;
uint32_t reserved_24:8;
};
uint32_t val;
} adc_sar1_patt_tab4_reg_t;
} adc_sar1_patt_tab_reg_t;
/** Type of sar2_patt_tab1 register
* Register
*/
typedef union {
struct {
/** sar2_patt_tab1 : R/W; bitpos: [23:0]; default: 0;
/** sar2_patt_tab : R/W; bitpos: [23:0]; default: 0;
* item 0 ~ 3 for pattern table 2 (each item one byte)
*/
uint32_t sar2_patt_tab1:24;
uint32_t sar2_patt_tab:24;
uint32_t reserved_24:8;
};
uint32_t val;
} adc_sar2_patt_tab1_reg_t;
/** Type of sar2_patt_tab2 register
* Register
*/
typedef union {
struct {
/** sar2_patt_tab2 : R/W; bitpos: [23:0]; default: 0;
* Item 4 ~ 7 for pattern table 2 (each item one byte)
*/
uint32_t sar2_patt_tab2:24;
uint32_t reserved_24:8;
};
uint32_t val;
} adc_sar2_patt_tab2_reg_t;
/** Type of sar2_patt_tab3 register
* Register
*/
typedef union {
struct {
/** sar2_patt_tab3 : R/W; bitpos: [23:0]; default: 0;
* Item 8 ~ 11 for pattern table 2 (each item one byte)
*/
uint32_t sar2_patt_tab3:24;
uint32_t reserved_24:8;
};
uint32_t val;
} adc_sar2_patt_tab3_reg_t;
/** Type of sar2_patt_tab4 register
* Register
*/
typedef union {
struct {
/** sar2_patt_tab4 : R/W; bitpos: [23:0]; default: 0;
* Item 12 ~ 15 for pattern table 2 (each item one byte)
*/
uint32_t sar2_patt_tab4:24;
uint32_t reserved_24:8;
};
uint32_t val;
} adc_sar2_patt_tab4_reg_t;
} adc_sar2_patt_tab_reg_t;
/** Type of arb_ctrl register
* Register
@ -655,15 +584,10 @@ typedef struct {
volatile adc_ctrl_reg_reg_t ctrl_reg;
volatile adc_ctrl2_reg_t ctrl2;
volatile adc_filter_ctrl1_reg_t filter_ctrl1;
uint32_t reserved_00c[3];
volatile adc_sar1_patt_tab1_reg_t sar1_patt_tab1;
volatile adc_sar1_patt_tab2_reg_t sar1_patt_tab2;
volatile adc_sar1_patt_tab3_reg_t sar1_patt_tab3;
volatile adc_sar1_patt_tab4_reg_t sar1_patt_tab4;
volatile adc_sar2_patt_tab1_reg_t sar2_patt_tab1;
volatile adc_sar2_patt_tab2_reg_t sar2_patt_tab2;
volatile adc_sar2_patt_tab3_reg_t sar2_patt_tab3;
volatile adc_sar2_patt_tab4_reg_t sar2_patt_tab4;
volatile adc_fsm_wait_reg_t fsm_wait;
uint32_t reserved_00c[2];
volatile adc_sar1_patt_tab_reg_t sar1_patt_tab[4];
volatile adc_sar2_patt_tab_reg_t sar2_patt_tab[4];
volatile adc_arb_ctrl_reg_t arb_ctrl;
volatile adc_filter_ctrl0_reg_t filter_ctrl0;
volatile adc_sar1_data_status_reg_t sar1_data_status;

View File

@ -601,7 +601,6 @@ typedef enum {
ADC_DIGI_CLK_SRC_XTAL = SOC_MOD_CLK_XTAL, /*!< Select XTAL as the source clock */
ADC_DIGI_CLK_SRC_RC_FAST = SOC_MOD_CLK_RC_FAST, /*!< Select RC_FAST as the source clock */
ADC_DIGI_CLK_SRC_PLL_F80M = SOC_MOD_CLK_PLL_F80M, /*!< Select PLL_F80M as the source clock */
ADC_DIGI_CLK_SRC_DEFAULT = SOC_MOD_CLK_PLL_F80M, /*!< Select PLL_F80M as the default clock choice */
} soc_periph_adc_digi_clk_src_t;
@ -615,7 +614,6 @@ typedef enum {
*/
typedef enum {
ADC_RTC_CLK_SRC_RC_FAST = SOC_MOD_CLK_RC_FAST, /*!< Select RC_FAST as the source clock */
ADC_RTC_CLK_SRC_DEFAULT = SOC_MOD_CLK_RC_FAST, /*!< Select RC_FAST as the default clock choice */
} soc_periph_adc_rtc_clk_src_t;

View File

@ -110,19 +110,18 @@
/*!< SAR ADC Module*/
#define SOC_ADC_RTC_CTRL_SUPPORTED 1
#define SOC_ADC_DIG_CTRL_SUPPORTED 1
// #define SOC_ADC_ARBITER_SUPPORTED 1
// #define SOC_ADC_DIG_IIR_FILTER_SUPPORTED 1
// #define SOC_ADC_MONITOR_SUPPORTED 1
#define SOC_ADC_DIG_SUPPORTED_UNIT(UNIT) 1 //Digital controller supported ADC unit
// #define SOC_ADC_DMA_SUPPORTED 1
#define SOC_ADC_DMA_SUPPORTED 1
#define SOC_ADC_PERIPH_NUM (2)
#define SOC_ADC_CHANNEL_NUM(PERIPH_NUM) (14)
#define SOC_ADC_CHANNEL_NUM(PERIPH_NUM) ((PERIPH_NUM==0)? 6: 8)
#define SOC_ADC_MAX_CHANNEL_NUM (8)
#define SOC_ADC_ATTEN_NUM (4)
/*!< Digital */
#define SOC_ADC_DIGI_CONTROLLER_NUM (2)
#define SOC_ADC_PATT_LEN_MAX (8) /*!< Two pattern tables, each contains 4 items. Each item takes 1 byte */
#define SOC_ADC_PATT_LEN_MAX (16) /*!< Four pattern tables, each contains 4 items. Each item takes 1 byte */
#define SOC_ADC_DIGI_MAX_BITWIDTH (12)
#define SOC_ADC_DIGI_MIN_BITWIDTH (12)
#define SOC_ADC_DIGI_IIR_FILTER_NUM (2)
@ -140,6 +139,9 @@
/*!< Calibration */
#define SOC_ADC_CALIBRATION_V1_SUPPORTED (0) /*!< support HW offset calibration version 1*/
/*!< ADC power control is shared by PWDET, TempSensor */
#define SOC_ADC_SHARED_POWER 1
// ESP32P4-TODO: Copy from esp32c6, need check
/*-------------------------- APB BACKUP DMA CAPS -------------------------------*/
#define SOC_APB_BACKUP_DMA (0)

View File

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2019-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2019-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -9,16 +9,11 @@
#include <stdint.h>
//include soc related (generated) definitions
#include "soc/soc_caps.h"
#include "sdkconfig.h"
#if SOC_RTCIO_PIN_COUNT > 0
#include "soc/rtc_io_channel.h"
#endif
#if SOC_ADC_RTC_CTRL_SUPPORTED && !CONFIG_IDF_TARGET_ESP32P4
#include "soc/sens_struct.h"
#endif
#ifdef __cplusplus
extern "C"
{

View File

@ -10,11 +10,19 @@
examples/peripherals/adc/continuous_read:
disable:
- if: SOC_ADC_DMA_SUPPORTED != 1
disable_test:
- if: IDF_TARGET == "esp32p4"
temporary: true
reason: lack of runners, TODO IDF-9573
<<: *adc_dependencies
examples/peripherals/adc/oneshot_read:
disable:
- if: SOC_ADC_SUPPORTED != 1
disable_test:
- if: IDF_TARGET == "esp32p4"
temporary: true
reason: lack of runner, TODO IDF-9573
<<: *adc_dependencies
examples/peripherals/analog_comparator:

View File

@ -1,5 +1,5 @@
| Supported Targets | ESP32 | ESP32-C3 | ESP32-C6 | ESP32-H2 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- | -------- | -------- |
| Supported Targets | ESP32 | ESP32-C3 | ESP32-C6 | ESP32-H2 | ESP32-P4 | ESP32-S2 | ESP32-S3 |
| ----------------- | ----- | -------- | -------- | -------- | -------- | -------- | -------- |
# ADC DMA Example