Merge branch 'feature/esp32c3_adc_driver_cleanup' into 'master'

adc: esp32c3 adc driver cleanup

Closes IDF-2528, IDF-2695, and IDF-2765

See merge request espressif/esp-idf!12477
pull/6828/head
Michael (XIAO Xufeng) 2021-03-26 08:03:29 +00:00
commit 96e3ba881c
31 zmienionych plików z 553 dodań i 1041 usunięć

Wyświetl plik

@ -202,6 +202,33 @@ void adc_power_off(void)
ADC_POWER_EXIT();
}
esp_err_t adc1_pad_get_io_num(adc1_channel_t channel, gpio_num_t *gpio_num)
{
ADC_CHANNEL_CHECK(ADC_NUM_1, channel);
int io = ADC_GET_IO_NUM(ADC_NUM_1, channel);
if (io < 0) {
return ESP_ERR_INVALID_ARG;
} else {
*gpio_num = (gpio_num_t)io;
}
return ESP_OK;
}
esp_err_t adc2_pad_get_io_num(adc2_channel_t channel, gpio_num_t *gpio_num)
{
ADC_CHANNEL_CHECK(ADC_NUM_2, channel);
int io = ADC_GET_IO_NUM(ADC_NUM_2, channel);
if (io < 0) {
return ESP_ERR_INVALID_ARG;
} else {
*gpio_num = (gpio_num_t)io;
}
return ESP_OK;
}
#if CONFIG_IDF_TARGET_ESP32 || CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3
esp_err_t adc_set_clk_div(uint8_t clk_div)
@ -313,20 +340,6 @@ esp_err_t adc_rtc_reset(void)
/*-------------------------------------------------------------------------------------
* ADC1
*------------------------------------------------------------------------------------*/
esp_err_t adc1_pad_get_io_num(adc1_channel_t channel, gpio_num_t *gpio_num)
{
ADC_CHANNEL_CHECK(ADC_NUM_1, channel);
int io = ADC_GET_IO_NUM(ADC_NUM_1, channel);
if (io < 0) {
return ESP_ERR_INVALID_ARG;
} else {
*gpio_num = (gpio_num_t)io;
}
return ESP_OK;
}
esp_err_t adc1_config_channel_atten(adc1_channel_t channel, adc_atten_t atten)
{
ADC_CHANNEL_CHECK(ADC_NUM_1, channel);
@ -456,20 +469,6 @@ void adc1_ulp_enable(void)
/*---------------------------------------------------------------
ADC2
---------------------------------------------------------------*/
esp_err_t adc2_pad_get_io_num(adc2_channel_t channel, gpio_num_t *gpio_num)
{
ADC_CHANNEL_CHECK(ADC_NUM_2, channel);
int io = ADC_GET_IO_NUM(ADC_NUM_2, channel);
if (io < 0) {
return ESP_ERR_INVALID_ARG;
} else {
*gpio_num = (gpio_num_t)io;
}
return ESP_OK;
}
/** For ESP32S2 the ADC2 The right to use ADC2 is controlled by the arbiter, and there is no need to set a lock.*/
esp_err_t adc2_wifi_acquire(void)
{
@ -552,6 +551,7 @@ static inline void adc2_dac_disable( adc2_channel_t channel)
*/
esp_err_t adc2_get_raw(adc2_channel_t channel, adc_bits_width_t width_bit, int *raw_out)
{
esp_err_t ret = ESP_OK;
int adc_value = 0;
ADC_CHECK(raw_out != NULL, "ADC out value err", ESP_ERR_INVALID_ARG);
@ -591,7 +591,8 @@ esp_err_t adc2_get_raw(adc2_channel_t channel, adc_bits_width_t width_bit, int *
#endif //CONFIG_PM_ENABLE
#endif //CONFIG_IDF_TARGET_ESP32
if (adc_hal_convert(ADC_NUM_2, channel, &adc_value)) {
ret = adc_hal_convert(ADC_NUM_2, channel, &adc_value);
if (ret != ESP_OK) {
adc_value = -1;
}
@ -608,13 +609,8 @@ esp_err_t adc2_get_raw(adc2_channel_t channel, adc_bits_width_t width_bit, int *
adc_power_release();
SARADC2_RELEASE();
if (adc_value < 0) {
ESP_LOGD( ADC_TAG, "ADC2 ARB: Return data is invalid." );
return ESP_ERR_INVALID_STATE;
}
*raw_out = adc_value;
return ESP_OK;
return ret;
}
esp_err_t adc2_vref_to_gpio(gpio_num_t gpio)

Wyświetl plik

@ -19,6 +19,7 @@
#include "sdkconfig.h"
#include "esp_intr_alloc.h"
#include "esp_log.h"
#include "esp_pm.h"
#include "sys/lock.h"
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
@ -58,38 +59,34 @@ extern portMUX_TYPE rtc_spinlock; //TODO: Will be placed in the appropriate posi
#define ADC_ENTER_CRITICAL() portENTER_CRITICAL(&rtc_spinlock)
#define ADC_EXIT_CRITICAL() portEXIT_CRITICAL(&rtc_spinlock)
/*---------------------------------------------------------------
Digital Controller Context
---------------------------------------------------------------*/
/**
* 1. adc_digi_mutex: this mutex lock is used for ADC digital controller. On ESP32-C3, the ADC single read APIs (unit1 & unit2)
* and ADC DMA continuous read APIs share the ``apb_saradc_struct.h`` regs.
*
* 2. sar_adc_mutex: this mutex lock is used for SARADC2 module. On ESP32C-C3, the ADC single read APIs (unit2), ADC DMA
* continuous read APIs and WIFI share the SARADC2 analog IP.
*
* Sequence:
* Acquire: 1. sar_adc_mutex; 2. adc_digi_mutex;
* Release: 1. adc_digi_mutex; 2. sar_adc_mutex;
* 1. sar_adc1_lock: this mutex lock is to protect the SARADC1 module.
* 2. sar_adc2_lock: this mutex lock is to protect the SARADC2 module. On C3, it is controlled by the digital controller
* and PWDET controller.
* 3. adc_reg_lock: this spin lock is to protect the shared registers used by ADC1 / ADC2 single read mode.
*/
static _lock_t adc_digi_mutex;
#define ADC_DIGI_LOCK_ACQUIRE() _lock_acquire(&adc_digi_mutex)
#define ADC_DIGI_LOCK_RELEASE() _lock_release(&adc_digi_mutex)
static _lock_t sar_adc2_mutex;
#define SAC_ADC2_LOCK_ACQUIRE() _lock_acquire(&sar_adc2_mutex)
#define SAC_ADC2_LOCK_RELEASE() _lock_release(&sar_adc2_mutex)
static _lock_t sar_adc1_lock;
#define SAR_ADC1_LOCK_ACQUIRE() _lock_acquire(&sar_adc1_lock)
#define SAR_ADC1_LOCK_RELEASE() _lock_release(&sar_adc1_lock)
static _lock_t sar_adc2_lock;
#define SAR_ADC2_LOCK_ACQUIRE() _lock_acquire(&sar_adc2_lock)
#define SAR_ADC2_LOCK_RELEASE() _lock_release(&sar_adc2_lock)
portMUX_TYPE adc_reg_lock = portMUX_INITIALIZER_UNLOCKED;
#define ADC_REG_LOCK_ENTER() portENTER_CRITICAL(&adc_reg_lock)
#define ADC_REG_LOCK_EXIT() portEXIT_CRITICAL(&adc_reg_lock)
#define INTERNAL_BUF_NUM 5
#define IN_SUC_EOF_BIT GDMA_LL_EVENT_RX_SUC_EOF
/*---------------------------------------------------------------
Digital Controller Context
---------------------------------------------------------------*/
typedef struct adc_digi_context_t {
intr_handle_t dma_intr_hdl; //MD interrupt handle
uint32_t bytes_between_intr; //bytes between in suc eof intr
uint8_t *rx_dma_buf; //dma buffer
adc_dma_hal_context_t hal_dma; //dma context (hal)
adc_dma_hal_config_t hal_dma_config; //dma config (hal)
adc_hal_context_t hal; //hal context
gdma_channel_handle_t rx_dma_channel; //dma rx channel handle
RingbufHandle_t ringbuf_hdl; //RX ringbuffer handler
intptr_t rx_eof_desc_addr; //eof descriptor address of RX channel
bool ringbuf_overflow_flag; //1: ringbuffer overflow
bool driver_start_flag; //1: driver is started; 0: driver is stoped
bool use_adc1; //1: ADC unit1 will be used; 0: ADC unit1 won't be used.
@ -97,6 +94,7 @@ typedef struct adc_digi_context_t {
adc_atten_t adc1_atten; //Attenuation for ADC1. On this chip each ADC can only support one attenuation.
adc_atten_t adc2_atten; //Attenuation for ADC2. On this chip each ADC can only support one attenuation.
adc_digi_config_t digi_controller_config; //Digital Controller Configuration
esp_pm_lock_handle_t pm_lock; //For power management
} adc_digi_context_t;
static adc_digi_context_t *s_adc_digi_ctx = NULL;
@ -159,20 +157,18 @@ esp_err_t adc_digi_initialize(const adc_digi_init_config_t *init_config)
}
//malloc internal buffer used by DMA
s_adc_digi_ctx->bytes_between_intr = init_config->conv_num_each_intr;
s_adc_digi_ctx->rx_dma_buf = heap_caps_calloc(1, s_adc_digi_ctx->bytes_between_intr * INTERNAL_BUF_NUM, MALLOC_CAP_INTERNAL);
s_adc_digi_ctx->rx_dma_buf = heap_caps_calloc(1, init_config->conv_num_each_intr * INTERNAL_BUF_NUM, MALLOC_CAP_INTERNAL);
if (!s_adc_digi_ctx->rx_dma_buf) {
ret = ESP_ERR_NO_MEM;
goto cleanup;
}
//malloc dma descriptor
s_adc_digi_ctx->hal_dma_config.rx_desc = heap_caps_calloc(1, (sizeof(dma_descriptor_t)) * INTERNAL_BUF_NUM, MALLOC_CAP_DMA);
if (!s_adc_digi_ctx->hal_dma_config.rx_desc) {
s_adc_digi_ctx->hal.rx_desc = heap_caps_calloc(1, (sizeof(dma_descriptor_t)) * INTERNAL_BUF_NUM, MALLOC_CAP_DMA);
if (!s_adc_digi_ctx->hal.rx_desc) {
ret = ESP_ERR_NO_MEM;
goto cleanup;
}
s_adc_digi_ctx->hal_dma_config.desc_max_num = INTERNAL_BUF_NUM;
//malloc pattern table
s_adc_digi_ctx->digi_controller_config.adc_pattern = calloc(1, SOC_ADC_PATT_LEN_MAX * sizeof(adc_digi_pattern_table_t));
@ -181,6 +177,13 @@ esp_err_t adc_digi_initialize(const adc_digi_init_config_t *init_config)
goto cleanup;
}
#if CONFIG_PM_ENABLE
ret = esp_pm_lock_create(ESP_PM_APB_FREQ_MAX, 0, "adc_dma", &s_adc_digi_ctx->pm_lock);
if (ret != ESP_OK) {
goto cleanup;
}
#endif //CONFIG_PM_ENABLE
//init gpio pins
if (init_config->adc1_chan_mask) {
ret = adc_digi_gpio_init(ADC_NUM_1, init_config->adc1_chan_mask);
@ -218,7 +221,13 @@ esp_err_t adc_digi_initialize(const adc_digi_init_config_t *init_config)
int dma_chan;
gdma_get_channel_id(s_adc_digi_ctx->rx_dma_channel, &dma_chan);
s_adc_digi_ctx->hal_dma_config.dma_chan = dma_chan;
adc_hal_config_t config = {
.desc_max_num = INTERNAL_BUF_NUM,
.dma_chan = dma_chan,
.eof_num = init_config->conv_num_each_intr / ADC_HAL_DATA_LEN_PER_CONV
};
adc_hal_context_config(&s_adc_digi_ctx->hal, &config);
//enable SARADC module clock
periph_module_enable(PERIPH_SARADC_MODULE);
@ -238,7 +247,9 @@ static IRAM_ATTR bool adc_dma_intr(adc_digi_context_t *adc_digi_ctx);
static IRAM_ATTR bool adc_dma_in_suc_eof_callback(gdma_channel_handle_t dma_chan, gdma_event_data_t *event_data, void *user_data)
{
assert(event_data);
adc_digi_context_t *adc_digi_ctx = (adc_digi_context_t *)user_data;
adc_digi_ctx->rx_eof_desc_addr = event_data->rx_eof_desc_addr;
return adc_dma_intr(adc_digi_ctx);
}
@ -246,40 +257,28 @@ static IRAM_ATTR bool adc_dma_intr(adc_digi_context_t *adc_digi_ctx)
{
portBASE_TYPE taskAwoken = 0;
BaseType_t ret;
adc_hal_dma_desc_status_t status = false;
dma_descriptor_t *current_desc = NULL;
while (1) {
status = adc_hal_get_reading_result(&adc_digi_ctx->hal, adc_digi_ctx->rx_eof_desc_addr, &current_desc);
if (status != ADC_HAL_DMA_DESC_VALID) {
break;
}
while (adc_digi_ctx->hal_dma_config.cur_desc_ptr->dw0.owner == 0) {
dma_descriptor_t *current_desc = adc_digi_ctx->hal_dma_config.cur_desc_ptr;
ret = xRingbufferSendFromISR(adc_digi_ctx->ringbuf_hdl, current_desc->buffer, current_desc->dw0.length, &taskAwoken);
if (ret == pdFALSE) {
//ringbuffer overflow
adc_digi_ctx->ringbuf_overflow_flag = 1;
}
adc_digi_ctx->hal_dma_config.desc_cnt += 1;
//cycle the dma descriptor and buffers
adc_digi_ctx->hal_dma_config.cur_desc_ptr = adc_digi_ctx->hal_dma_config.cur_desc_ptr->next;
if (!adc_digi_ctx->hal_dma_config.cur_desc_ptr) {
break;
}
}
if (!adc_digi_ctx->hal_dma_config.cur_desc_ptr) {
assert(adc_digi_ctx->hal_dma_config.desc_cnt == adc_digi_ctx->hal_dma_config.desc_max_num);
//reset the current descriptor status
adc_digi_ctx->hal_dma_config.cur_desc_ptr = adc_digi_ctx->hal_dma_config.rx_desc;
adc_digi_ctx->hal_dma_config.desc_cnt = 0;
if (status == ADC_HAL_DMA_DESC_NULL) {
//start next turns of dma operation
adc_hal_digi_dma_multi_descriptor(&adc_digi_ctx->hal_dma_config, adc_digi_ctx->rx_dma_buf, adc_digi_ctx->bytes_between_intr, adc_digi_ctx->hal_dma_config.desc_max_num);
adc_hal_digi_rxdma_start(&adc_digi_ctx->hal_dma, &adc_digi_ctx->hal_dma_config);
adc_hal_digi_rxdma_start(&adc_digi_ctx->hal, adc_digi_ctx->rx_dma_buf);
}
if(taskAwoken == pdTRUE) {
return true;
} else {
return false;
}
return (taskAwoken == pdTRUE);
}
esp_err_t adc_digi_start(void)
@ -291,12 +290,17 @@ esp_err_t adc_digi_start(void)
//reset flags
s_adc_digi_ctx->ringbuf_overflow_flag = 0;
s_adc_digi_ctx->driver_start_flag = 1;
//When using SARADC2 module, this task needs to be protected from WIFI
if (s_adc_digi_ctx->use_adc2) {
SAC_ADC2_LOCK_ACQUIRE();
if (s_adc_digi_ctx->use_adc1) {
SAR_ADC1_LOCK_ACQUIRE();
}
ADC_DIGI_LOCK_ACQUIRE();
if (s_adc_digi_ctx->use_adc2) {
SAR_ADC2_LOCK_ACQUIRE();
}
#if CONFIG_PM_ENABLE
// Lock APB frequency while ADC driver is in use
esp_pm_lock_acquire(s_adc_digi_ctx->pm_lock);
#endif
adc_arbiter_t config = ADC_ARBITER_CONFIG_DEFAULT();
if (s_adc_digi_ctx->use_adc1) {
@ -309,26 +313,16 @@ esp_err_t adc_digi_start(void)
}
adc_hal_init();
adc_hal_arbiter_config(&config);
adc_hal_digi_init(&s_adc_digi_ctx->hal_dma, &s_adc_digi_ctx->hal_dma_config);
adc_hal_digi_init(&s_adc_digi_ctx->hal);
adc_hal_digi_controller_config(&s_adc_digi_ctx->digi_controller_config);
//create dma descriptors
adc_hal_digi_dma_multi_descriptor(&s_adc_digi_ctx->hal_dma_config, s_adc_digi_ctx->rx_dma_buf, s_adc_digi_ctx->bytes_between_intr, s_adc_digi_ctx->hal_dma_config.desc_max_num);
adc_hal_digi_set_eof_num(&s_adc_digi_ctx->hal_dma, &s_adc_digi_ctx->hal_dma_config, (s_adc_digi_ctx->bytes_between_intr)/4);
//set the current descriptor pointer
s_adc_digi_ctx->hal_dma_config.cur_desc_ptr = s_adc_digi_ctx->hal_dma_config.rx_desc;
s_adc_digi_ctx->hal_dma_config.desc_cnt = 0;
//enable in suc eof intr
adc_hal_digi_ena_intr(&s_adc_digi_ctx->hal_dma, &s_adc_digi_ctx->hal_dma_config, IN_SUC_EOF_BIT);
//start ADC
adc_hal_digi_start(&s_adc_digi_ctx->hal_dma, &s_adc_digi_ctx->hal_dma_config);
//reset ADC and DMA
adc_hal_fifo_reset(&s_adc_digi_ctx->hal);
//start DMA
adc_hal_digi_rxdma_start(&s_adc_digi_ctx->hal_dma, &s_adc_digi_ctx->hal_dma_config);
adc_hal_digi_rxdma_start(&s_adc_digi_ctx->hal, s_adc_digi_ctx->rx_dma_buf);
//start ADC
adc_hal_digi_start(&s_adc_digi_ctx->hal);
return ESP_OK;
}
@ -342,19 +336,25 @@ esp_err_t adc_digi_stop(void)
s_adc_digi_ctx->driver_start_flag = 0;
//disable the in suc eof intrrupt
adc_hal_digi_dis_intr(&s_adc_digi_ctx->hal_dma, &s_adc_digi_ctx->hal_dma_config, IN_SUC_EOF_BIT);
adc_hal_digi_dis_intr(&s_adc_digi_ctx->hal, IN_SUC_EOF_BIT);
//clear the in suc eof interrupt
adc_hal_digi_clr_intr(&s_adc_digi_ctx->hal_dma, &s_adc_digi_ctx->hal_dma_config, IN_SUC_EOF_BIT);
//stop DMA
adc_hal_digi_rxdma_stop(&s_adc_digi_ctx->hal_dma, &s_adc_digi_ctx->hal_dma_config);
adc_hal_digi_clr_intr(&s_adc_digi_ctx->hal, IN_SUC_EOF_BIT);
//stop ADC
adc_hal_digi_stop(&s_adc_digi_ctx->hal_dma, &s_adc_digi_ctx->hal_dma_config);
adc_hal_digi_stop(&s_adc_digi_ctx->hal);
//stop DMA
adc_hal_digi_rxdma_stop(&s_adc_digi_ctx->hal);
adc_hal_digi_deinit();
#if CONFIG_PM_ENABLE
if (s_adc_digi_ctx->pm_lock) {
esp_pm_lock_release(s_adc_digi_ctx->pm_lock);
}
#endif //CONFIG_PM_ENABLE
ADC_DIGI_LOCK_RELEASE();
//When using SARADC2 module, this task needs to be protected from WIFI
if (s_adc_digi_ctx->use_adc1) {
SAR_ADC1_LOCK_RELEASE();
}
if (s_adc_digi_ctx->use_adc2) {
SAC_ADC2_LOCK_RELEASE();
SAR_ADC2_LOCK_RELEASE();
}
return ESP_OK;
@ -403,17 +403,19 @@ esp_err_t adc_digi_deinitialize(void)
return ESP_ERR_INVALID_STATE;
}
if (s_adc_digi_ctx->dma_intr_hdl) {
esp_intr_free(s_adc_digi_ctx->dma_intr_hdl);
}
if(s_adc_digi_ctx->ringbuf_hdl) {
if (s_adc_digi_ctx->ringbuf_hdl) {
vRingbufferDelete(s_adc_digi_ctx->ringbuf_hdl);
s_adc_digi_ctx->ringbuf_hdl = NULL;
}
#if CONFIG_PM_ENABLE
if (s_adc_digi_ctx->pm_lock) {
esp_pm_lock_delete(s_adc_digi_ctx->pm_lock);
}
#endif //CONFIG_PM_ENABLE
free(s_adc_digi_ctx->rx_dma_buf);
free(s_adc_digi_ctx->hal_dma_config.rx_desc);
free(s_adc_digi_ctx->hal.rx_desc);
free(s_adc_digi_ctx->digi_controller_config.adc_pattern);
gdma_disconnect(s_adc_digi_ctx->rx_dma_channel);
gdma_del_channel(s_adc_digi_ctx->rx_dma_channel);
@ -432,6 +434,38 @@ esp_err_t adc_digi_deinitialize(void)
static adc_atten_t s_atten1_single[ADC1_CHANNEL_MAX]; //Array saving attenuate of each channel of ADC1, used by single read API
static adc_atten_t s_atten2_single[ADC2_CHANNEL_MAX]; //Array saving attenuate of each channel of ADC2, used by single read API
esp_err_t adc_vref_to_gpio(adc_unit_t adc_unit, gpio_num_t gpio)
{
esp_err_t ret;
uint32_t channel = ADC2_CHANNEL_MAX;
if (adc_unit == ADC_UNIT_2) {
for (int i = 0; i < ADC2_CHANNEL_MAX; i++) {
if (gpio == ADC_GET_IO_NUM(ADC_NUM_2, i)) {
channel = i;
break;
}
}
if (channel == ADC2_CHANNEL_MAX) {
return ESP_ERR_INVALID_ARG;
}
}
adc_hal_set_power_manage(ADC_POWER_SW_ON);
if (adc_unit & ADC_UNIT_1) {
ADC_ENTER_CRITICAL();
adc_hal_vref_output(ADC_NUM_1, channel, true);
ADC_EXIT_CRITICAL()
} else if (adc_unit & ADC_UNIT_2) {
ADC_ENTER_CRITICAL();
adc_hal_vref_output(ADC_NUM_2, channel, true);
ADC_EXIT_CRITICAL()
}
ret = adc_digi_gpio_init(ADC_NUM_2, BIT(channel));
return ret;
}
esp_err_t adc1_config_width(adc_bits_width_t width_bit)
{
//On ESP32C3, the data width is always 12-bits.
@ -459,41 +493,26 @@ esp_err_t adc1_config_channel_atten(adc1_channel_t channel, adc_atten_t atten)
int adc1_get_raw(adc1_channel_t channel)
{
int raw_out = 0;
adc_digi_config_t dig_cfg = {
.conv_limit_en = 0,
.conv_limit_num = 250,
.sample_freq_hz = SOC_ADC_SAMPLE_FREQ_THRES_HIGH,
};
ADC_DIGI_LOCK_ACQUIRE();
periph_module_enable(PERIPH_SARADC_MODULE);
SAR_ADC1_LOCK_ACQUIRE();
adc_atten_t atten = s_atten1_single[channel];
uint32_t cal_val = adc_get_calibration_offset(ADC_NUM_1, channel, atten);
adc_hal_set_calibration_param(ADC_NUM_1, cal_val);
adc_hal_digi_controller_config(&dig_cfg);
ADC_REG_LOCK_ENTER();
adc_hal_set_power_manage(ADC_POWER_SW_ON);
adc_hal_set_atten(ADC_NUM_2, channel, atten);
adc_hal_convert(ADC_NUM_1, channel, &raw_out);
adc_hal_set_power_manage(ADC_POWER_BY_FSM);
ADC_REG_LOCK_EXIT();
adc_hal_intr_clear(ADC_EVENT_ADC1_DONE);
SAR_ADC1_LOCK_RELEASE();
adc_hal_adc1_onetime_sample_enable(true);
adc_hal_onetime_channel(ADC_NUM_1, channel);
adc_hal_set_onetime_atten(atten);
//Trigger single read.
adc_hal_onetime_start(&dig_cfg);
while (!adc_hal_intr_get_raw(ADC_EVENT_ADC1_DONE));
adc_hal_single_read(ADC_NUM_1, &raw_out);
adc_hal_intr_clear(ADC_EVENT_ADC1_DONE);
adc_hal_adc1_onetime_sample_enable(false);
adc_hal_digi_deinit();
periph_module_disable(PERIPH_SARADC_MODULE);
ADC_DIGI_LOCK_RELEASE();
return raw_out;
}
@ -519,42 +538,26 @@ esp_err_t adc2_get_raw(adc2_channel_t channel, adc_bits_width_t width_bit, int *
}
esp_err_t ret = ESP_OK;
adc_digi_config_t dig_cfg = {
.conv_limit_en = 0,
.conv_limit_num = 250,
.sample_freq_hz = SOC_ADC_SAMPLE_FREQ_THRES_HIGH,
};
SAC_ADC2_LOCK_ACQUIRE();
ADC_DIGI_LOCK_ACQUIRE();
periph_module_enable(PERIPH_SARADC_MODULE);
SAR_ADC2_LOCK_ACQUIRE();
adc_atten_t atten = s_atten2_single[channel];
uint32_t cal_val = adc_get_calibration_offset(ADC_NUM_2, channel, atten);
adc_hal_set_calibration_param(ADC_NUM_2, cal_val);
adc_hal_digi_controller_config(&dig_cfg);
ADC_REG_LOCK_ENTER();
adc_hal_set_power_manage(ADC_POWER_SW_ON);
adc_hal_set_atten(ADC_NUM_2, channel, atten);
ret = adc_hal_convert(ADC_NUM_2, channel, raw_out);
adc_hal_set_power_manage(ADC_POWER_BY_FSM);
ADC_REG_LOCK_EXIT();
adc_hal_intr_clear(ADC_EVENT_ADC2_DONE);
SAR_ADC2_LOCK_RELEASE();
adc_hal_adc2_onetime_sample_enable(true);
adc_hal_onetime_channel(ADC_NUM_2, channel);
adc_hal_set_onetime_atten(atten);
//Trigger single read.
adc_hal_onetime_start(&dig_cfg);
while (!adc_hal_intr_get_raw(ADC_EVENT_ADC2_DONE));
ret = adc_hal_single_read(ADC_NUM_2, raw_out);
adc_hal_intr_clear(ADC_EVENT_ADC2_DONE);
adc_hal_adc2_onetime_sample_enable(false);
adc_hal_digi_deinit();
periph_module_disable(PERIPH_SARADC_MODULE);
ADC_DIGI_LOCK_RELEASE();
SAC_ADC2_LOCK_RELEASE();
return ret;
}
@ -581,7 +584,7 @@ esp_err_t adc_digi_controller_config(const adc_digi_config_t *config)
s_adc_digi_ctx->use_adc1 = 0;
s_adc_digi_ctx->use_adc2 = 0;
for (int i = 0; i < config->adc_pattern_len; i++) {
const adc_digi_pattern_table_t* pat = &config->adc_pattern[i];
const adc_digi_pattern_table_t *pat = &config->adc_pattern[i];
if (pat->unit == ADC_NUM_1) {
s_adc_digi_ctx->use_adc1 = 1;
@ -605,86 +608,6 @@ esp_err_t adc_digi_controller_config(const adc_digi_config_t *config)
return ESP_OK;
}
esp_err_t adc_arbiter_config(adc_unit_t adc_unit, adc_arbiter_t *config)
{
if (adc_unit & ADC_UNIT_1) {
return ESP_ERR_NOT_SUPPORTED;
}
ADC_ENTER_CRITICAL();
adc_hal_arbiter_config(config);
ADC_EXIT_CRITICAL();
return ESP_OK;
}
/**
* @brief Set ADC module controller.
* There are five SAR ADC controllers:
* Two digital controller: Continuous conversion mode (DMA). High performance with multiple channel scan modes;
* Two RTC controller: Single conversion modes (Polling). For low power purpose working during deep sleep;
* the other is dedicated for Power detect (PWDET / PKDET), Only support ADC2.
*
* @note Only ADC2 support arbiter to switch controllers automatically. Access to the ADC is based on the priority of the controller.
* @note For ADC1, Controller access is mutually exclusive.
*
* @param adc_unit ADC unit.
* @param ctrl ADC controller, Refer to `adc_controller_t`.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_set_controller(adc_unit_t adc_unit, adc_controller_t ctrl)
{
adc_arbiter_t config = {0};
adc_arbiter_t cfg = ADC_ARBITER_CONFIG_DEFAULT();
if (adc_unit & ADC_UNIT_1) {
adc_hal_set_controller(ADC_NUM_1, ctrl);
}
if (adc_unit & ADC_UNIT_2) {
adc_hal_set_controller(ADC_NUM_2, ctrl);
switch (ctrl) {
case ADC2_CTRL_FORCE_PWDET:
config.pwdet_pri = 2;
config.mode = ADC_ARB_MODE_SHIELD;
adc_hal_arbiter_config(&config);
adc_hal_set_controller(ADC_NUM_2, ADC2_CTRL_PWDET);
break;
case ADC2_CTRL_FORCE_RTC:
config.rtc_pri = 2;
config.mode = ADC_ARB_MODE_SHIELD;
adc_hal_arbiter_config(&config);
adc_hal_set_controller(ADC_NUM_2, ADC_CTRL_RTC);
break;
case ADC2_CTRL_FORCE_DIG:
config.dig_pri = 2;
config.mode = ADC_ARB_MODE_SHIELD;
adc_hal_arbiter_config(&config);
adc_hal_set_controller(ADC_NUM_2, ADC_CTRL_DIG);
break;
default:
adc_hal_arbiter_config(&cfg);
break;
}
}
return ESP_OK;
}
/**
* @brief Reset FSM of adc digital controller.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_reset(void)
{
ADC_ENTER_CRITICAL();
adc_hal_digi_reset();
adc_hal_digi_clear_pattern_table(ADC_NUM_1);
adc_hal_digi_clear_pattern_table(ADC_NUM_2);
ADC_EXIT_CRITICAL();
return ESP_OK;
}
/*************************************/
/* Digital controller filter setting */
/*************************************/
@ -742,90 +665,6 @@ esp_err_t adc_digi_monitor_enable(adc_digi_monitor_idx_t idx, bool enable)
return ESP_OK;
}
/**************************************/
/* Digital controller intr setting */
/**************************************/
esp_err_t adc_digi_intr_enable(adc_unit_t adc_unit, adc_digi_intr_t intr_mask)
{
ADC_ENTER_CRITICAL();
if (adc_unit & ADC_UNIT_1) {
adc_hal_digi_intr_enable(ADC_NUM_1, intr_mask);
}
if (adc_unit & ADC_UNIT_2) {
adc_hal_digi_intr_enable(ADC_NUM_2, intr_mask);
}
ADC_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t adc_digi_intr_disable(adc_unit_t adc_unit, adc_digi_intr_t intr_mask)
{
ADC_ENTER_CRITICAL();
if (adc_unit & ADC_UNIT_1) {
adc_hal_digi_intr_disable(ADC_NUM_1, intr_mask);
}
if (adc_unit & ADC_UNIT_2) {
adc_hal_digi_intr_disable(ADC_NUM_2, intr_mask);
}
ADC_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t adc_digi_intr_clear(adc_unit_t adc_unit, adc_digi_intr_t intr_mask)
{
ADC_ENTER_CRITICAL();
if (adc_unit & ADC_UNIT_1) {
adc_hal_digi_intr_clear(ADC_NUM_1, intr_mask);
}
if (adc_unit & ADC_UNIT_2) {
adc_hal_digi_intr_clear(ADC_NUM_2, intr_mask);
}
ADC_EXIT_CRITICAL();
return ESP_OK;
}
uint32_t adc_digi_intr_get_status(adc_unit_t adc_unit)
{
uint32_t ret = 0;
ADC_ENTER_CRITICAL();
if (adc_unit & ADC_UNIT_1) {
ret = adc_hal_digi_get_intr_status(ADC_NUM_1);
}
if (adc_unit & ADC_UNIT_2) {
ret = adc_hal_digi_get_intr_status(ADC_NUM_2);
}
ADC_EXIT_CRITICAL();
return ret;
}
static bool s_isr_registered = 0;
static intr_handle_t s_adc_isr_handle = NULL;
esp_err_t adc_digi_isr_register(void (*fn)(void *), void *arg, int intr_alloc_flags)
{
ADC_CHECK((fn != NULL), "Parameter error", ESP_ERR_INVALID_ARG);
ADC_CHECK(s_isr_registered == 0, "ADC ISR have installed, can not install again", ESP_FAIL);
esp_err_t ret = esp_intr_alloc(ETS_APB_ADC_INTR_SOURCE, intr_alloc_flags, fn, arg, &s_adc_isr_handle);
if (ret == ESP_OK) {
s_isr_registered = 1;
}
return ret;
}
esp_err_t adc_digi_isr_deregister(void)
{
esp_err_t ret = ESP_FAIL;
if (s_isr_registered) {
ret = esp_intr_free(s_adc_isr_handle);
if (ret == ESP_OK) {
s_isr_registered = 0;
}
}
return ret;
}
/*---------------------------------------------------------------
RTC controller setting
---------------------------------------------------------------*/

Wyświetl plik

@ -22,25 +22,6 @@ extern "C" {
/*---------------------------------------------------------------
Common setting
---------------------------------------------------------------*/
/**
* @brief Config ADC module 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 ADC2 data, and the validity of the data can be judged by the flag bit in the data.
*
* @note Only ADC2 support arbiter.
* @note Default priority: Wi-Fi > RTC > Digital;
* @note In normal use, there is no need to call this interface to config arbiter.
*
* @param adc_unit ADC unit.
* @param config Refer to `adc_arbiter_t`.
*
* @return
* - ESP_OK Success
* - ESP_ERR_NOT_SUPPORTED ADC unit not support arbiter.
*/
esp_err_t adc_arbiter_config(adc_unit_t adc_unit, adc_arbiter_t *config);
/*************************************/
/* Digital controller filter setting */
/*************************************/
@ -114,78 +95,6 @@ esp_err_t adc_digi_monitor_set_config(adc_digi_monitor_idx_t idx, adc_digi_monit
*/
esp_err_t adc_digi_monitor_enable(adc_digi_monitor_idx_t idx, bool enable);
/**************************************/
/* Digital controller intr setting */
/**************************************/
/**
* @brief Enable interrupt of adc digital controller by bitmask.
*
* @param adc_unit ADC unit.
* @param intr_mask Interrupt bitmask. See ``adc_digi_intr_t``.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_intr_enable(adc_unit_t adc_unit, adc_digi_intr_t intr_mask);
/**
* @brief Disable interrupt of adc digital controller by bitmask.
*
* @param adc_unit ADC unit.
* @param intr_mask Interrupt bitmask. See ``adc_digi_intr_t``.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_intr_disable(adc_unit_t adc_unit, adc_digi_intr_t intr_mask);
/**
* @brief Clear interrupt of adc digital controller by bitmask.
*
* @param adc_unit ADC unit.
* @param intr_mask Interrupt bitmask. See ``adc_digi_intr_t``.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_intr_clear(adc_unit_t adc_unit, adc_digi_intr_t intr_mask);
/**
* @brief Get interrupt status mask of adc digital controller.
*
* @param adc_unit ADC unit.
* @return
* - intr Interrupt bitmask, See ``adc_digi_intr_t``.
*/
uint32_t adc_digi_intr_get_status(adc_unit_t adc_unit);
/**
* @brief Register ADC interrupt handler, the handler is an ISR.
* The handler will be attached to the same CPU core that this function is running on.
*
* @param fn Interrupt handler function.
* @param arg Parameter for handler function
* @param intr_alloc_flags Flags used to allocate the interrupt. One or multiple (ORred)
* ESP_INTR_FLAG_* values. See esp_intr_alloc.h for more info.
*
* @return
* - ESP_OK Success
* - ESP_ERR_NOT_FOUND Can not find the interrupt that matches the flags.
* - ESP_ERR_INVALID_ARG Function pointer error.
*/
esp_err_t adc_digi_isr_register(void (*fn)(void *), void *arg, int intr_alloc_flags);
/**
* @brief Deregister ADC interrupt handler, the handler is an ISR.
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG hander error.
* - ESP_FAIL ISR not be registered.
*/
esp_err_t adc_digi_isr_deregister(void);
#ifdef __cplusplus
}
#endif

Wyświetl plik

@ -60,7 +60,7 @@ typedef enum {
ADC1_CHANNEL_1, /*!< ADC1 channel 1 is GPIO1 */
ADC1_CHANNEL_2, /*!< ADC1 channel 2 is GPIO2 */
ADC1_CHANNEL_3, /*!< ADC1 channel 3 is GPIO3 */
ADC1_CHANNEL_4, /*!< ADC1 channel 4 is GPIO34 */
ADC1_CHANNEL_4, /*!< ADC1 channel 4 is GPIO4 */
ADC1_CHANNEL_MAX,
} adc1_channel_t;
#endif // CONFIG_IDF_TARGET_*
@ -175,6 +175,7 @@ void adc_power_acquire(void);
*/
void adc_power_release(void);
#if !CONFIG_IDF_TARGET_ESP32C3
/**
* @brief Initialize ADC pad
* @param adc_unit ADC unit index
@ -184,11 +185,11 @@ void adc_power_release(void);
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t adc_gpio_init(adc_unit_t adc_unit, adc_channel_t channel);
#endif //#if !CONFIG_IDF_TARGET_ESP32C3
/*---------------------------------------------------------------
RTC controller setting
ADC Single Read Setting
---------------------------------------------------------------*/
/**
* @brief Get the GPIO number of a specific ADC1 channel.
*
@ -283,6 +284,7 @@ esp_err_t adc1_config_width(adc_bits_width_t width_bit);
*/
int adc1_get_raw(adc1_channel_t channel);
#if !CONFIG_IDF_TARGET_ESP32C3
/**
* @brief Set ADC data invert
* @param adc_unit ADC unit index
@ -323,6 +325,7 @@ esp_err_t adc_set_data_width(adc_unit_t adc_unit, adc_bits_width_t width_bit);
* to be called to configure ADC1 channels, before ADC1 is used by the ULP.
*/
void adc1_ulp_enable(void);
#endif //#if !CONFIG_IDF_TARGET_ESP32C3
/**
* @brief Get the GPIO number of a specific ADC2 channel.
@ -449,6 +452,7 @@ esp_err_t adc_vref_to_gpio(adc_unit_t adc_unit, gpio_num_t gpio);
* - ESP_ERR_INVALID_ARG: Unsupported GPIO
*/
esp_err_t adc2_vref_to_gpio(gpio_num_t gpio) __attribute__((deprecated));
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
@ -489,7 +493,7 @@ esp_err_t adc_digi_controller_config(const adc_digi_config_t *config);
/**
* @brief Initialize the Digital ADC.
*
* @param init_config Pointer to Digital ADC initilisation config. Refer to ``adc_digi_init_config_t``.
* @param init_config Pointer to Digital ADC initilization config. Refer to ``adc_digi_init_config_t``.
*
* @return
* - ESP_ERR_INVALID_ARG If the combination of arguments is invalid.

Wyświetl plik

@ -23,6 +23,12 @@
#include "soc/gdma_channel.h"
#include "soc/soc.h"
#include "esp_rom_sys.h"
typedef enum {
ADC_EVENT_ADC1_DONE = BIT(0),
ADC_EVENT_ADC2_DONE = BIT(1),
} adc_hal_event_t;
#endif
void adc_hal_init(void)
@ -41,18 +47,6 @@ void adc_hal_deinit(void)
{
adc_ll_set_power_manage(ADC_POWER_SW_OFF);
}
#ifndef CONFIG_IDF_TARGET_ESP32C3
int adc_hal_convert(adc_ll_num_t adc_n, int channel, int *value)
{
adc_ll_rtc_enable_channel(adc_n, channel);
adc_ll_rtc_start_convert(adc_n, channel);
while (adc_ll_rtc_convert_is_done(adc_n) != true);
*value = adc_ll_rtc_get_convert_value(adc_n);
return (int)adc_ll_rtc_analysis_raw_data(adc_n, (uint16_t)(*value));
}
#endif
/*---------------------------------------------------------------
ADC calibration setting
---------------------------------------------------------------*/
@ -99,15 +93,8 @@ static uint32_t read_cal_channel(adc_ll_num_t adc_n, int channel)
#elif CONFIG_IDF_TARGET_ESP32C3
static void cal_setup(adc_ll_num_t adc_n, adc_channel_t channel, adc_atten_t atten, bool internal_gnd)
{
adc_hal_set_controller(adc_n, ADC_CTRL_DIG); //Set controller
adc_digi_config_t dig_cfg = {
.conv_limit_en = 0,
.conv_limit_num = 250,
.sample_freq_hz = SOC_ADC_SAMPLE_FREQ_THRES_HIGH,
};
adc_hal_digi_controller_config(&dig_cfg);
adc_ll_onetime_sample_enable(ADC_NUM_1, false);
adc_ll_onetime_sample_enable(ADC_NUM_2, false);
/* Enable/disable internal connect GND (for calibration). */
if (internal_gnd) {
const int esp32c3_invalid_chan = (adc_n == ADC_NUM_1)? 0xF: 0x1;
@ -116,8 +103,7 @@ static void cal_setup(adc_ll_num_t adc_n, adc_channel_t channel, adc_atten_t att
adc_ll_onetime_set_channel(adc_n, channel);
}
adc_ll_onetime_set_atten(atten);
adc_hal_adc1_onetime_sample_enable((adc_n == ADC_NUM_1));
adc_hal_adc2_onetime_sample_enable((adc_n == ADC_NUM_2));
adc_ll_onetime_sample_enable(adc_n, true);
}
static uint32_t read_cal_channel(adc_ll_num_t adc_n, int channel)
@ -209,11 +195,34 @@ uint32_t adc_hal_self_calibration(adc_ll_num_t adc_n, adc_channel_t channel, adc
/*---------------------------------------------------------------
DMA setting
---------------------------------------------------------------*/
void adc_hal_digi_dma_multi_descriptor(adc_dma_hal_config_t *dma_config, uint8_t *data_buf, uint32_t size, uint32_t num)
void adc_hal_context_config(adc_hal_context_t *hal, const adc_hal_config_t *config)
{
hal->dev = &GDMA;
hal->desc_dummy_head.next = hal->rx_desc;
hal->desc_max_num = config->desc_max_num;
hal->dma_chan = config->dma_chan;
hal->eof_num = config->eof_num;
}
void adc_hal_digi_init(adc_hal_context_t *hal)
{
gdma_ll_clear_interrupt_status(hal->dev, hal->dma_chan, UINT32_MAX);
gdma_ll_enable_interrupt(hal->dev, hal->dma_chan, GDMA_LL_EVENT_RX_SUC_EOF, true);
adc_ll_digi_dma_set_eof_num(hal->eof_num);
adc_ll_onetime_sample_enable(ADC_NUM_1, false);
adc_ll_onetime_sample_enable(ADC_NUM_2, false);
}
void adc_hal_fifo_reset(adc_hal_context_t *hal)
{
adc_ll_digi_reset();
gdma_ll_rx_reset_channel(hal->dev, hal->dma_chan);
}
static void adc_hal_digi_dma_link_descriptors(dma_descriptor_t *desc, uint8_t *data_buf, uint32_t size, uint32_t num)
{
assert(((uint32_t)data_buf % 4) == 0);
assert((size % 4) == 0);
dma_descriptor_t *desc = dma_config->rx_desc;
uint32_t n = 0;
while (num--) {
@ -228,49 +237,55 @@ void adc_hal_digi_dma_multi_descriptor(adc_dma_hal_config_t *dma_config, uint8_t
desc[n-1].next = NULL;
}
void adc_hal_digi_rxdma_start(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config)
void adc_hal_digi_rxdma_start(adc_hal_context_t *hal, uint8_t *data_buf)
{
gdma_ll_rx_reset_channel(adc_dma_ctx->dev, dma_config->dma_chan);
gdma_ll_rx_set_desc_addr(adc_dma_ctx->dev, dma_config->dma_chan, (uint32_t)dma_config->rx_desc);
gdma_ll_rx_start(adc_dma_ctx->dev, dma_config->dma_chan);
//reset the current descriptor address
hal->cur_desc_ptr = &hal->desc_dummy_head;
adc_hal_digi_dma_link_descriptors(hal->rx_desc, data_buf, hal->eof_num * ADC_HAL_DATA_LEN_PER_CONV, hal->desc_max_num);
gdma_ll_rx_set_desc_addr(hal->dev, hal->dma_chan, (uint32_t)hal->rx_desc);
gdma_ll_rx_start(hal->dev, hal->dma_chan);
}
void adc_hal_digi_rxdma_stop(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config)
void adc_hal_digi_start(adc_hal_context_t *hal)
{
gdma_ll_rx_stop(adc_dma_ctx->dev, dma_config->dma_chan);
}
void adc_hal_digi_ena_intr(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config, uint32_t mask)
{
gdma_ll_enable_interrupt(adc_dma_ctx->dev, dma_config->dma_chan, mask, true);
}
void adc_hal_digi_clr_intr(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config, uint32_t mask)
{
gdma_ll_clear_interrupt_status(adc_dma_ctx->dev, dma_config->dma_chan, mask);
}
void adc_hal_digi_dis_intr(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config, uint32_t mask)
{
gdma_ll_enable_interrupt(adc_dma_ctx->dev, dma_config->dma_chan, mask, false);
}
void adc_hal_digi_set_eof_num(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config, uint32_t num)
{
adc_ll_digi_dma_set_eof_num(num);
}
void adc_hal_digi_start(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config)
{
//Set to 1: the ADC data will be sent to the DMA
//the ADC data will be sent to the DMA
adc_ll_digi_dma_enable();
//enable sar adc timer
adc_ll_digi_trigger_enable();
//reset the adc state
adc_ll_digi_reset();
}
void adc_hal_digi_stop(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config)
adc_hal_dma_desc_status_t adc_hal_get_reading_result(adc_hal_context_t *hal, const intptr_t eof_desc_addr, dma_descriptor_t **cur_desc)
{
assert(hal->cur_desc_ptr);
if (!hal->cur_desc_ptr->next) {
return ADC_HAL_DMA_DESC_NULL;
}
if ((intptr_t)hal->cur_desc_ptr == eof_desc_addr) {
return ADC_HAL_DMA_DESC_WAITING;
}
hal->cur_desc_ptr = hal->cur_desc_ptr->next;
*cur_desc = hal->cur_desc_ptr;
return ADC_HAL_DMA_DESC_VALID;
}
void adc_hal_digi_rxdma_stop(adc_hal_context_t *hal)
{
gdma_ll_rx_stop(hal->dev, hal->dma_chan);
}
void adc_hal_digi_clr_intr(adc_hal_context_t *hal, uint32_t mask)
{
gdma_ll_clear_interrupt_status(hal->dev, hal->dma_chan, mask);
}
void adc_hal_digi_dis_intr(adc_hal_context_t *hal, uint32_t mask)
{
gdma_ll_enable_interrupt(hal->dev, hal->dma_chan, mask, false);
}
void adc_hal_digi_stop(adc_hal_context_t *hal)
{
//Set to 0: the ADC data won't be sent to the DMA
adc_ll_digi_dma_disable();
@ -278,18 +293,35 @@ void adc_hal_digi_stop(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t
adc_ll_digi_trigger_disable();
}
void adc_hal_digi_init(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config)
{
adc_dma_ctx->dev = &GDMA;
gdma_ll_clear_interrupt_status(adc_dma_ctx->dev, dma_config->dma_chan, UINT32_MAX);
adc_ll_adc1_onetime_sample_enable(false);
adc_ll_adc2_onetime_sample_enable(false);
}
/*---------------------------------------------------------------
Single Read
---------------------------------------------------------------*/
void adc_hal_onetime_start(adc_digi_config_t *adc_digi_config)
//--------------------INTR-------------------------------//
static adc_ll_intr_t get_event_intr(adc_hal_event_t event)
{
adc_ll_intr_t intr_mask = 0;
if (event & ADC_EVENT_ADC1_DONE) {
intr_mask |= ADC_LL_INTR_ADC1_DONE;
}
if (event & ADC_EVENT_ADC2_DONE) {
intr_mask |= ADC_LL_INTR_ADC2_DONE;
}
return intr_mask;
}
static void adc_hal_intr_clear(adc_hal_event_t event)
{
adc_ll_intr_clear(get_event_intr(event));
}
static bool adc_hal_intr_get_raw(adc_hal_event_t event)
{
return adc_ll_intr_get_raw(get_event_intr(event));
}
//--------------------Single Read-------------------------------//
static void adc_hal_onetime_start(void)
{
/**
* There is a hardware limitation. If the APB clock frequency is high, the step of this reg signal: ``onetime_start`` may not be captured by the
@ -315,74 +347,55 @@ void adc_hal_onetime_start(adc_digi_config_t *adc_digi_config)
//No need to delay here. Becuase if the start signal is not seen, there won't be a done intr.
}
void adc_hal_adc1_onetime_sample_enable(bool enable)
static esp_err_t adc_hal_single_read(adc_ll_num_t adc_n, int *out_raw)
{
adc_ll_adc1_onetime_sample_enable(enable);
}
void adc_hal_adc2_onetime_sample_enable(bool enable)
{
adc_ll_adc2_onetime_sample_enable(enable);
}
void adc_hal_onetime_channel(adc_ll_num_t unit, adc_channel_t channel)
{
adc_ll_onetime_set_channel(unit, channel);
}
void adc_hal_set_onetime_atten(adc_atten_t atten)
{
adc_ll_onetime_set_atten(atten);
}
esp_err_t adc_hal_single_read(adc_ll_num_t unit, int *out_raw)
{
if (unit == ADC_NUM_1) {
if (adc_n == ADC_NUM_1) {
*out_raw = adc_ll_adc1_read();
} else if (unit == ADC_NUM_2) {
} else if (adc_n == ADC_NUM_2) {
*out_raw = adc_ll_adc2_read();
if (adc_ll_analysis_raw_data(unit, *out_raw)) {
if (adc_ll_analysis_raw_data(adc_n, *out_raw)) {
return ESP_ERR_INVALID_STATE;
}
}
return ESP_OK;
}
//--------------------INTR-------------------------------
static adc_ll_intr_t get_event_intr(adc_event_t event)
esp_err_t adc_hal_convert(adc_ll_num_t adc_n, int channel, int *out_raw)
{
adc_ll_intr_t intr_mask = 0;
if (event & ADC_EVENT_ADC1_DONE) {
intr_mask |= ADC_LL_INTR_ADC1_DONE;
esp_err_t ret;
adc_hal_event_t event;
if (adc_n == ADC_NUM_1) {
event = ADC_EVENT_ADC1_DONE;
} else {
event = ADC_EVENT_ADC2_DONE;
}
if (event & ADC_EVENT_ADC2_DONE) {
intr_mask |= ADC_LL_INTR_ADC2_DONE;
adc_hal_intr_clear(event);
adc_ll_onetime_sample_enable(ADC_NUM_1, false);
adc_ll_onetime_sample_enable(ADC_NUM_2, false);
adc_ll_onetime_sample_enable(adc_n, true);
adc_ll_onetime_set_channel(adc_n, channel);
//Trigger single read.
adc_hal_onetime_start();
while (!adc_hal_intr_get_raw(event));
ret = adc_hal_single_read(adc_n, out_raw);
return ret;
}
#else // !CONFIG_IDF_TARGET_ESP32C3
esp_err_t adc_hal_convert(adc_ll_num_t adc_n, int channel, int *out_raw)
{
adc_ll_rtc_enable_channel(adc_n, channel);
adc_ll_rtc_start_convert(adc_n, channel);
while (adc_ll_rtc_convert_is_done(adc_n) != true);
*out_raw = adc_ll_rtc_get_convert_value(adc_n);
if ((int)adc_ll_rtc_analysis_raw_data(adc_n, (uint16_t)(*out_raw))) {
return ESP_ERR_INVALID_STATE;
}
return intr_mask;
}
void adc_hal_intr_enable(adc_event_t event)
{
adc_ll_intr_enable(get_event_intr(event));
return ESP_OK;
}
void adc_hal_intr_disable(adc_event_t event)
{
adc_ll_intr_disable(get_event_intr(event));
}
void adc_hal_intr_clear(adc_event_t event)
{
adc_ll_intr_clear(get_event_intr(event));
}
bool adc_hal_intr_get_raw(adc_event_t event)
{
return adc_ll_intr_get_raw(get_event_intr(event));
}
bool adc_hal_intr_get_status(adc_event_t event)
{
return adc_ll_intr_get_status(get_event_intr(event));
}
#endif
#endif //#if !CONFIG_IDF_TARGET_ESP32C3

Wyświetl plik

@ -45,6 +45,18 @@ void adc_hal_digi_deinit(void)
adc_hal_deinit();
}
/**
* - Set ADC digital controller clock division factor. The clock is divided from `APLL` or `APB` clock.
* Expression: controller_clk = APLL/APB * (div_num + div_a / div_b + 1).
* - Enable clock and select clock source for ADC digital controller.
*/
static void adc_hal_digi_clk_config(void)
{
//Here we set the clock divider factor to make the digital clock to 5M Hz
adc_ll_digi_controller_clk_div(ADC_LL_CLKM_DIV_NUM_DEFAULT, ADC_LL_CLKM_DIV_B_DEFAULT, ADC_LL_CLKM_DIV_A_DEFAULT);
adc_ll_digi_controller_clk_enable(0);
}
void adc_hal_digi_controller_config(const adc_digi_config_t *cfg)
{
//only one pattern table is supported on C3, but LL still needs one argument.
@ -60,7 +72,6 @@ void adc_hal_digi_controller_config(const adc_digi_config_t *cfg)
}
}
adc_ll_set_controller(pattern_both, ADC_CTRL_DIG);
if (cfg->conv_limit_en) {
adc_ll_digi_set_convert_limit_num(cfg->conv_limit_num);
adc_ll_digi_convert_limit_enable();
@ -74,31 +85,6 @@ void adc_hal_digi_controller_config(const adc_digi_config_t *cfg)
adc_hal_digi_clk_config();
}
void adc_hal_digi_clk_config(void)
{
//Here we set the clock divider factor to make the digital clock to 5M Hz
adc_ll_digi_controller_clk_div(ADC_LL_CLKM_DIV_NUM_DEFAULT, ADC_LL_CLKM_DIV_B_DEFAULT, ADC_LL_CLKM_DIV_A_DEFAULT);
adc_ll_digi_controller_clk_enable(0);
}
/**
* Enable digital controller to trigger the measurement.
*/
void adc_hal_digi_enable(void)
{
adc_ll_digi_dma_enable();
adc_ll_digi_trigger_enable();
}
/**
* Disable digital controller to trigger the measurement.
*/
void adc_hal_digi_disable(void)
{
adc_ll_digi_trigger_disable();
adc_ll_digi_dma_disable();
}
static void filter_update(adc_digi_filter_idx_t idx)
{
//ESP32-C3 has no enable bit, the filter will be enabled when the filter channel is configured

Wyświetl plik

@ -46,41 +46,6 @@ void adc_hal_digi_deinit(void);
*/
void adc_hal_digi_controller_config(const adc_digi_config_t *cfg);
/**
* ADC Digital controller output data invert or not.
*
* @param adc_n ADC unit.
* @param inv_en data invert or not.
*/
#define adc_hal_digi_output_invert(adc_n, inv_en) adc_ll_digi_output_invert(adc_n, inv_en)
/**
* Sets the number of interval clock cycles for the digital controller to trigger the measurement.
*
* @note The trigger interval should not be less than the sampling time of the SAR ADC.
* @param cycle The number of clock cycles for the trigger interval. The unit is the divided clock. Range: 40 ~ 4095.
*/
#define adc_hal_digi_set_trigger_interval(cycle) adc_ll_digi_set_trigger_interval(cycle)
/**
* Enable digital controller to trigger the measurement.
*/
void adc_hal_digi_enable(void);
/**
* Disable digital controller to trigger the measurement.
*/
void adc_hal_digi_disable(void);
/**
* Set ADC digital controller clock division factor. The clock divided from `APLL` or `APB` clock.
* Enable clock and select clock source for ADC digital controller.
* Expression: controller_clk = APLL/APB * (div_num + div_a / div_b + 1).
*
* @param clk Refer to `adc_digi_clk_t`.
*/
void adc_hal_digi_clk_config(void);
/**
* Reset adc digital controller filter.
*
@ -132,63 +97,6 @@ void adc_hal_digi_monitor_config(adc_digi_monitor_idx_t mon_idx, adc_digi_monito
*/
void adc_hal_digi_monitor_enable(adc_digi_monitor_idx_t mon_idx, bool enable);
/**
* Enable interrupt of adc digital controller by bitmask.
*
* @param adc_n ADC unit.
* @param intr Interrupt bitmask.
*/
#define adc_hal_digi_intr_enable(adc_n, intr) adc_ll_digi_intr_enable(adc_n, intr)
/**
* Disable interrupt of adc digital controller by bitmask.
*
* @param adc_n ADC unit.
* @param intr Interrupt bitmask.
*/
#define adc_hal_digi_intr_disable(adc_n, intr) adc_ll_digi_intr_disable(adc_n, intr)
/**
* Clear interrupt of adc digital controller by bitmask.
*
* @param adc_n ADC unit.
* @param intr Interrupt bitmask.
*/
#define adc_hal_digi_intr_clear(adc_n, intr) adc_ll_digi_intr_clear(adc_n, intr)
/**
* Get interrupt status mask of adc digital controller.
*
* @param adc_n ADC unit.
* @return
* - intr Interrupt bitmask.
*/
#define adc_hal_digi_get_intr_status(adc_n) adc_ll_digi_get_intr_status(adc_n)
/**
* 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.
*/
#define adc_hal_digi_dma_set_eof_num(num) adc_ll_digi_dma_set_eof_num(num)
/**
* Enable output data to DMA from adc digital controller.
*/
#define adc_hal_digi_dma_enable() adc_ll_digi_dma_enable()
/**
* Disable output data to DMA from adc digital controller.
*/
#define adc_hal_digi_dma_disable() adc_ll_digi_dma_disable()
/**
* Reset adc digital controller.
*/
#define adc_hal_digi_reset() adc_ll_digi_reset()
/*---------------------------------------------------------------
Common setting
---------------------------------------------------------------*/

Wyświetl plik

@ -29,7 +29,6 @@
extern "C" {
#endif
#define ADC_LL_ADC2_CHANNEL_MAX 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
@ -54,9 +53,14 @@ typedef enum {
ADC_RTC_DATA_FAIL = -1,
} adc_ll_rtc_raw_data_t;
//These values should be set according to the HW
typedef enum {
ADC_LL_INTR_ADC2_DONE = BIT(30),
ADC_LL_INTR_ADC1_DONE = BIT(31),
ADC_LL_INTR_THRES1_LOW = BIT(26),
ADC_LL_INTR_THRES0_LOW = BIT(27),
ADC_LL_INTR_THRES1_HIGH = BIT(28),
ADC_LL_INTR_THRES0_HIGH = BIT(29),
ADC_LL_INTR_ADC2_DONE = BIT(30),
ADC_LL_INTR_ADC1_DONE = BIT(31),
} adc_ll_intr_t;
FLAG_ATTR(adc_ll_intr_t)
@ -74,7 +78,7 @@ typedef enum {
ADC2_CTRL_FORCE_PWDET = 3, /*!<For ADC2. Arbiter in shield mode. Force select Wi-Fi controller work. */
ADC2_CTRL_FORCE_RTC = 4, /*!<For ADC2. Arbiter in shield mode. Force select RTC controller work. */
ADC2_CTRL_FORCE_DIG = 6, /*!<For ADC2. Arbiter in shield mode. Force select digital controller work. */
} adc_controller_t;
} adc_ll_controller_t;
/*---------------------------------------------------------------
Digital controller setting
@ -289,7 +293,6 @@ static inline void adc_ll_digi_controller_clk_enable(bool use_apll)
static inline void adc_ll_digi_controller_clk_disable(void)
{
APB_SARADC.ctrl.sar_clk_gated = 0;
APB_SARADC.apb_adc_clkm_conf.clk_sel = 0;
}
/**
@ -393,136 +396,6 @@ static inline void adc_ll_digi_monitor_disable(adc_digi_monitor_idx_t idx)
}
}
/**
* Enable interrupt of adc digital controller by bitmask.
*
* @param adc_n ADC unit.
* @param intr Interrupt bitmask.
*/
static inline void adc_ll_digi_intr_enable(adc_ll_num_t adc_n, adc_digi_intr_t intr)
{
if (adc_n == ADC_NUM_1) {
if (intr & ADC_DIGI_INTR_MASK_MEAS_DONE) {
APB_SARADC.int_ena.adc1_done = 1;
}
} else { // adc_n == ADC_NUM_2
if (intr & ADC_DIGI_INTR_MASK_MEAS_DONE) {
APB_SARADC.int_ena.adc2_done = 1;
}
}
if (intr & ADC_DIGI_INTR_MASK_MONITOR0_HIGH) {
APB_SARADC.int_ena.thres0_high = 1;
}
if (intr & ADC_DIGI_INTR_MASK_MONITOR0_LOW) {
APB_SARADC.int_ena.thres0_low = 1;
}
if (intr & ADC_DIGI_INTR_MASK_MONITOR1_HIGH) {
APB_SARADC.int_ena.thres1_high = 1;
}
if (intr & ADC_DIGI_INTR_MASK_MONITOR1_LOW) {
APB_SARADC.int_ena.thres1_low = 1;
}
}
/**
* Disable interrupt of adc digital controller by bitmask.
*
* @param adc_n ADC unit.
* @param intr Interrupt bitmask.
*/
static inline void adc_ll_digi_intr_disable(adc_ll_num_t adc_n, adc_digi_intr_t intr)
{
if (adc_n == ADC_NUM_1) {
if (intr & ADC_DIGI_INTR_MASK_MEAS_DONE) {
APB_SARADC.int_ena.adc1_done = 0;
}
} else { // adc_n == ADC_NUM_2
if (intr & ADC_DIGI_INTR_MASK_MEAS_DONE) {
APB_SARADC.int_ena.adc2_done = 0;
}
}
if (intr & ADC_DIGI_INTR_MASK_MONITOR0_HIGH) {
APB_SARADC.int_ena.thres0_high = 0;
}
if (intr & ADC_DIGI_INTR_MASK_MONITOR0_LOW) {
APB_SARADC.int_ena.thres0_low = 0;
}
if (intr & ADC_DIGI_INTR_MASK_MONITOR1_HIGH) {
APB_SARADC.int_ena.thres1_high = 0;
}
if (intr & ADC_DIGI_INTR_MASK_MONITOR1_LOW) {
APB_SARADC.int_ena.thres1_low = 0;
}
}
/**
* Clear interrupt of adc digital controller by bitmask.
*
* @param adc_n ADC unit.
* @param intr Interrupt bitmask.
*/
static inline void adc_ll_digi_intr_clear(adc_ll_num_t adc_n, adc_digi_intr_t intr)
{
if (adc_n == ADC_NUM_1) {
if (intr & ADC_DIGI_INTR_MASK_MEAS_DONE) {
APB_SARADC.int_clr.adc1_done = 1;
}
} else { // adc_n == ADC_NUM_2
if (intr & ADC_DIGI_INTR_MASK_MEAS_DONE) {
APB_SARADC.int_clr.adc2_done = 1;
}
}
if (intr & ADC_DIGI_INTR_MASK_MONITOR0_HIGH) {
APB_SARADC.int_clr.thres0_high = 1;
}
if (intr & ADC_DIGI_INTR_MASK_MONITOR0_LOW) {
APB_SARADC.int_clr.thres0_low = 1;
}
if (intr & ADC_DIGI_INTR_MASK_MONITOR1_HIGH) {
APB_SARADC.int_clr.thres1_high = 1;
}
if (intr & ADC_DIGI_INTR_MASK_MONITOR1_LOW) {
APB_SARADC.int_clr.thres1_low = 1;
}
}
/**
* Get interrupt status mask of adc digital controller.
*
* @param adc_n ADC unit.
* @return
* - intr Interrupt bitmask.
*/
static inline uint32_t adc_ll_digi_get_intr_status(adc_ll_num_t adc_n)
{
uint32_t int_st = APB_SARADC.int_st.val;
uint32_t ret_msk = 0;
if (adc_n == ADC_NUM_1) {
if (int_st & APB_SARADC_ADC1_DONE_INT_ST_M) {
ret_msk |= ADC_DIGI_INTR_MASK_MEAS_DONE;
}
} else { // adc_n == ADC_NUM_2
if (int_st & APB_SARADC_ADC2_DONE_INT_ST_M) {
ret_msk |= ADC_DIGI_INTR_MASK_MEAS_DONE;
}
}
if (int_st & APB_SARADC_THRES0_HIGH_INT_ST) {
ret_msk |= ADC_DIGI_INTR_MASK_MONITOR0_HIGH;
}
if (int_st & APB_SARADC_THRES0_LOW_INT_ST_M) {
ret_msk |= ADC_DIGI_INTR_MASK_MONITOR0_LOW;
}
if (int_st & APB_SARADC_THRES1_HIGH_INT_ST_M) {
ret_msk |= ADC_DIGI_INTR_MASK_MONITOR1_HIGH;
}
if (int_st & APB_SARADC_THRES1_LOW_INT_ST_M) {
ret_msk |= ADC_DIGI_INTR_MASK_MONITOR1_LOW;
}
return ret_msk;
}
/**
* 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.
@ -655,21 +528,6 @@ static inline adc_ll_power_t adc_ll_get_power_manage(void)
return manage;
}
/**
* Set ADC module controller.
* There are five SAR ADC controllers:
* Two digital controller: Continuous conversion mode (DMA). High performance with multiple channel scan modes;
* Two RTC controller: Single conversion modes (Polling). For low power purpose working during deep sleep;
* the other is dedicated for Power detect (PWDET / PKDET), Only support ADC2.
*
* @param adc_n ADC unit.
* @param ctrl ADC controller.
*/
static inline void adc_ll_set_controller(adc_ll_num_t adc_n, adc_controller_t ctrl)
{
//NOTE: ULP is removed on C3, please remove ULP related (if there still are any) code and this comment
}
/**
* Set ADC2 module arbiter work mode.
* The arbiter is to improve the use efficiency of ADC2. After the control right is robbed by the high priority,
@ -917,10 +775,13 @@ static inline bool adc_ll_intr_get_status(adc_ll_intr_t mask)
return (APB_SARADC.int_st.val & mask);
}
//--------------------------------adc1------------------------------//
static inline void adc_ll_adc1_onetime_sample_enable(bool enable)
static inline void adc_ll_onetime_sample_enable(adc_ll_num_t adc_n, bool enable)
{
APB_SARADC.onetime_sample.adc1_onetime_sample = enable;
if (adc_n == ADC_NUM_1) {
APB_SARADC.onetime_sample.adc1_onetime_sample = enable;
} else {
APB_SARADC.onetime_sample.adc2_onetime_sample = enable;
}
}
static inline uint32_t adc_ll_adc1_read(void)
@ -929,12 +790,6 @@ static inline uint32_t adc_ll_adc1_read(void)
return (APB_SARADC.apb_saradc1_data_status.adc1_data & 0xfff);
}
//--------------------------------adc2------------------------------//
static inline void adc_ll_adc2_onetime_sample_enable(bool enable)
{
APB_SARADC.onetime_sample.adc2_onetime_sample = enable;
}
static inline uint32_t adc_ll_adc2_read(void)
{
//On ESP32C3, valid data width is 12-bit

Wyświetl plik

@ -3,6 +3,55 @@
#include "soc/soc_caps.h"
#include "hal/adc_types.h"
#include "hal/adc_ll.h"
#include "esp_err.h"
#if CONFIG_IDF_TARGET_ESP32C3
#include "soc/gdma_struct.h"
#include "hal/gdma_ll.h"
#include "hal/dma_types.h"
#include "hal/adc_ll.h"
#include "hal/dma_types.h"
#include "esp_err.h"
//For ADC module, each conversion contains 4 bytes
#define ADC_HAL_DATA_LEN_PER_CONV 4
/**
* @brief Enum for DMA descriptor status
*/
typedef enum adc_hal_dma_desc_status_t {
ADC_HAL_DMA_DESC_VALID = 0, ///< This DMA descriptor is written by HW already
ADC_HAL_DMA_DESC_WAITING = 1, ///< This DMA descriptor is not written by HW yet
ADC_HAL_DMA_DESC_NULL = 2 ///< This DMA descriptor is NULL
} adc_hal_dma_desc_status_t;
/**
* @brief Configuration of the HAL
*/
typedef struct adc_hal_config_t {
uint32_t desc_max_num; ///< Number of the descriptors linked once
uint32_t dma_chan; ///< DMA channel to be used
uint32_t eof_num; ///< Bytes between 2 in_suc_eof interrupts
} adc_hal_config_t;
/**
* @brief Context of the HAL
*/
typedef struct adc_hal_context_t {
/**< this needs to be malloced by the driver layer first */
dma_descriptor_t *rx_desc; ///< DMA descriptors
/**< these will be assigned by hal layer itself */
gdma_dev_t *dev; ///< GDMA address
dma_descriptor_t desc_dummy_head; ///< Dummy DMA descriptor for ``cur_desc_ptr`` to start
dma_descriptor_t *cur_desc_ptr; ///< Pointer to the current descriptor
/**< these need to be configured by `adc_hal_config_t` via driver layer*/
uint32_t desc_max_num; ///< Number of the descriptors linked once
uint32_t dma_chan; ///< DMA channel to be used
uint32_t eof_num; ///< Words between 2 in_suc_eof interrupts
} adc_hal_context_t;
#endif
/*---------------------------------------------------------------
Common setting
@ -17,14 +66,6 @@ void adc_hal_init(void);
*/
void adc_hal_deinit(void);
/**
* Set adc sample cycle.
*
* @note Normally, please use default value.
* @param sample_cycle The number of ADC sampling cycles. Range: 1 ~ 7.
*/
#define adc_hal_set_sample_cycle(sample_cycle) adc_ll_set_sample_cycle(sample_cycle)
/**
* Set ADC module power management.
*
@ -32,14 +73,6 @@ void adc_hal_deinit(void);
*/
#define adc_hal_set_power_manage(manage) adc_ll_set_power_manage(manage)
/**
* Get ADC module power management.
*
* @return
* - ADC power status.
*/
#define adc_hal_get_power_manage() adc_ll_get_power_manage()
/**
* ADC module clock division factor setting. ADC clock devided from APB clock.
*
@ -47,6 +80,7 @@ void adc_hal_deinit(void);
*/
#define adc_hal_digi_set_clk_div(div) adc_ll_digi_set_clk_div(div)
#if !CONFIG_IDF_TARGET_ESP32C3
/**
* ADC SAR clock division factor setting. ADC SAR clock devided from `RTC_FAST_CLK`.
*
@ -65,42 +99,9 @@ void adc_hal_deinit(void);
* @prarm ctrl ADC controller.
*/
#define adc_hal_set_controller(adc_n, ctrl) adc_ll_set_controller(adc_n, ctrl)
#endif //#if !CONFIG_IDF_TARGET_ESP32C3
/**
* Set the attenuation of a particular channel on ADCn.
*
* @note For any given channel, this function must be called before the first time conversion.
*
* The default ADC full-scale voltage is 1.1V. To read higher voltages (up to the pin maximum voltage,
* usually 3.3V) requires setting >0dB signal attenuation for that ADC channel.
*
* When VDD_A is 3.3V:
*
* - 0dB attenuaton (ADC_ATTEN_DB_0) gives full-scale voltage 1.1V
* - 2.5dB attenuation (ADC_ATTEN_DB_2_5) gives full-scale voltage 1.5V
* - 6dB attenuation (ADC_ATTEN_DB_6) gives full-scale voltage 2.2V
* - 11dB attenuation (ADC_ATTEN_DB_11) gives full-scale voltage 3.9V (see note below)
*
* @note The full-scale voltage is the voltage corresponding to a maximum reading (depending on ADC1 configured
* bit width, this value is: 4095 for 12-bits, 2047 for 11-bits, 1023 for 10-bits, 511 for 9 bits.)
*
* @note At 11dB attenuation the maximum voltage is limited by VDD_A, not the full scale voltage.
*
* Due to ADC characteristics, most accurate results are obtained within the following approximate voltage ranges:
*
* - 0dB attenuaton (ADC_ATTEN_DB_0) between 100 and 950mV
* - 2.5dB attenuation (ADC_ATTEN_DB_2_5) between 100 and 1250mV
* - 6dB attenuation (ADC_ATTEN_DB_6) between 150 to 1750mV
* - 11dB attenuation (ADC_ATTEN_DB_11) between 150 to 2450mV
*
* For maximum accuracy, use the ADC calibration APIs and measure voltages within these recommended ranges.
*
* @prarm adc_n ADC unit.
* @prarm channel ADCn channel number.
* @prarm atten The attenuation option.
*/
#define adc_hal_set_atten(adc_n, channel, atten) adc_ll_set_atten(adc_n, channel, atten)
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3
/**
* Get the attenuation of a particular channel on ADCn.
*
@ -109,11 +110,14 @@ void adc_hal_deinit(void);
* @return atten The attenuation option.
*/
#define adc_hal_get_atten(adc_n, channel) adc_ll_get_atten(adc_n, channel)
#endif
#if CONFIG_IDF_TARGET_ESP32
/**
* Close ADC AMP module if don't use it for power save.
*/
#define adc_hal_amp_disable() adc_ll_amp_disable()
#endif
/*---------------------------------------------------------------
PWDET(Power detect) controller setting
@ -135,26 +139,10 @@ void adc_hal_deinit(void);
*/
#define adc_hal_pwdet_get_cct() adc_ll_pwdet_get_cct()
#ifndef CONFIG_IDF_TARGET_ESP32C3
/*---------------------------------------------------------------
RTC controller setting
---------------------------------------------------------------*/
/**
* Get the converted value for each ADCn for RTC controller.
*
* @note It may be block to wait conversion finish.
*
* @prarm adc_n ADC unit.
* @param channel adc channel number.
* @param value Pointer for touch value.
*
* @return
* - 0: The value is valid.
* - ~0: The value is invalid.
*/
int adc_hal_convert(adc_ll_num_t adc_n, int channel, int *value);
#if !CONFIG_IDF_TARGET_ESP32C3
/**
* Set adc output data format for RTC controller.
*
@ -169,7 +157,7 @@ int adc_hal_convert(adc_ll_num_t adc_n, int channel, int *value);
* @prarm adc_n ADC unit.
*/
#define adc_hal_rtc_output_invert(adc_n, inv_en) adc_ll_rtc_output_invert(adc_n, inv_en)
#endif
#endif //#if !CONFIG_IDF_TARGET_ESP32C3
/**
* Enable/disable the output of ADCn's internal reference voltage to one of ADC2's channels.
@ -207,6 +195,73 @@ void adc_hal_digi_controller_config(const adc_digi_config_t *cfg);
*/
#define adc_hal_digi_clear_pattern_table(adc_n) adc_ll_digi_clear_pattern_table(adc_n)
/*---------------------------------------------------------------
ADC Single Read
---------------------------------------------------------------*/
#if !CONFIG_IDF_TARGET_ESP32C3
/**
* Set the attenuation of a particular channel on ADCn.
*
* @note For any given channel, this function must be called before the first time conversion.
*
* The default ADC full-scale voltage is 1.1V. To read higher voltages (up to the pin maximum voltage,
* usually 3.3V) requires setting >0dB signal attenuation for that ADC channel.
*
* When VDD_A is 3.3V:
*
* - 0dB attenuaton (ADC_ATTEN_DB_0) gives full-scale voltage 1.1V
* - 2.5dB attenuation (ADC_ATTEN_DB_2_5) gives full-scale voltage 1.5V
* - 6dB attenuation (ADC_ATTEN_DB_6) gives full-scale voltage 2.2V
* - 11dB attenuation (ADC_ATTEN_DB_11) gives full-scale voltage 3.9V (see note below)
*
* @note The full-scale voltage is the voltage corresponding to a maximum reading (depending on ADC1 configured
* bit width, this value is: 4095 for 12-bits, 2047 for 11-bits, 1023 for 10-bits, 511 for 9 bits.)
*
* @note At 11dB attenuation the maximum voltage is limited by VDD_A, not the full scale voltage.
*
* Due to ADC characteristics, most accurate results are obtained within the following approximate voltage ranges:
*
* - 0dB attenuaton (ADC_ATTEN_DB_0) between 100 and 950mV
* - 2.5dB attenuation (ADC_ATTEN_DB_2_5) between 100 and 1250mV
* - 6dB attenuation (ADC_ATTEN_DB_6) between 150 to 1750mV
* - 11dB attenuation (ADC_ATTEN_DB_11) between 150 to 2450mV
*
* For maximum accuracy, use the ADC calibration APIs and measure voltages within these recommended ranges.
*
* @param adc_n ADC unit.
* @param channel ADCn channel number.
* @param atten ADC attenuation. See ``adc_atten_t``
*/
#define adc_hal_set_atten(adc_n, channel, atten) adc_ll_set_atten(adc_n, channel, atten)
#else // CONFIG_IDF_TARGET_ESP32C3
/**
* Set the attenuation for ADC to single read
*
* @note All ADC units and channels will share the setting. So PLEASE DO save your attenuations and reset them by calling this API again in your driver
*
* @param adc_n Not used, leave here for chip version compatibility
* @param channel Not used, leave here for chip version compatibility
* @param atten ADC attenuation. See ``adc_atten_t``
*/
#define adc_hal_set_atten(adc_n, channel, atten) adc_ll_onetime_set_atten(atten)
#endif
/**
* Start an ADC conversion and get the converted value.
*
* @note It may be block to wait conversion finish.
*
* @param adc_n ADC unit.
* @param channel ADC channel number.
* @param[out] out_raw ADC converted result
*
* @return
* - ESP_OK: The value is valid.
* - ESP_ERR_INVALID_STATE: The value is invalid.
*/
esp_err_t adc_hal_convert(adc_ll_num_t adc_n, int channel, int *out_raw);
/*---------------------------------------------------------------
ADC calibration setting
---------------------------------------------------------------*/
@ -252,68 +307,82 @@ uint32_t adc_hal_self_calibration(adc_ll_num_t adc_n, adc_channel_t channel, adc
/*---------------------------------------------------------------
DMA setting
---------------------------------------------------------------*/
#include "soc/gdma_struct.h"
#include "hal/gdma_ll.h"
#include "hal/dma_types.h"
#include "hal/adc_ll.h"
#include "hal/dma_types.h"
#include "esp_err.h"
/**
* @brief Initialize the hal context
*
* @param hal Context of the HAL
* @param config Configuration of the HAL
*/
void adc_hal_context_config(adc_hal_context_t *hal, const adc_hal_config_t *config);
typedef struct adc_dma_hal_context_t {
gdma_dev_t *dev; //address of the general DMA
} adc_dma_hal_context_t;
/**
* @brief Initialize the HW
*
* @param hal Context of the HAL
*/
void adc_hal_digi_init(adc_hal_context_t *hal);
typedef struct adc_dma_hal_config_t {
dma_descriptor_t *rx_desc; //dma descriptor
dma_descriptor_t *cur_desc_ptr; //pointer to the current descriptor
uint32_t desc_max_num; //number of the descriptors linked once
uint32_t desc_cnt;
uint32_t dma_chan;
} adc_dma_hal_config_t;
/**
* @brief Reset ADC / DMA fifo
*
* @param hal Context of the HAL
*/
void adc_hal_fifo_reset(adc_hal_context_t *hal);
void adc_hal_digi_dma_multi_descriptor(adc_dma_hal_config_t *dma_config, uint8_t *data_buf, uint32_t size, uint32_t num);
/**
* @brief Start DMA
*
* @param hal Context of the HAL
* @param data_buf Pointer to the data buffer, the length should be multiple of ``desc_max_num`` and ``eof_num`` in ``adc_hal_context_t``
*/
void adc_hal_digi_rxdma_start(adc_hal_context_t *hal, uint8_t *data_buf);
void adc_hal_digi_rxdma_start(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config);
/**
* @brief Start ADC
*
* @param hal Context of the HAL
*/
void adc_hal_digi_start(adc_hal_context_t *hal);
void adc_hal_digi_rxdma_stop(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config);
/**
* @brief Get the ADC reading result
*
* @param hal Context of the HAL
* @param eof_desc_addr The last descriptor that is finished by HW. Should be got from DMA
* @param[out] cur_desc The descriptor with ADC reading result (from the 1st one to the last one (``eof_desc_addr``))
*
* @return See ``adc_hal_dma_desc_status_t``
*/
adc_hal_dma_desc_status_t adc_hal_get_reading_result(adc_hal_context_t *hal, const intptr_t eof_desc_addr, dma_descriptor_t **cur_desc);
void adc_hal_digi_ena_intr(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config, uint32_t mask);
/**
* @brief Stop DMA
*
* @param hal Context of the HAL
*/
void adc_hal_digi_rxdma_stop(adc_hal_context_t *hal);
void adc_hal_digi_clr_intr(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config, uint32_t mask);
/**
* @brief Clear interrupt
*
* @param hal Context of the HAL
* @param mask mask of the interrupt
*/
void adc_hal_digi_clr_intr(adc_hal_context_t *hal, uint32_t mask);
void adc_hal_digi_dis_intr(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config, uint32_t mask);
/**
* @brief Enable interrupt
*
* @param hal Context of the HAL
* @param mask mask of the interrupt
*/
void adc_hal_digi_dis_intr(adc_hal_context_t *hal, uint32_t mask);
void adc_hal_digi_set_eof_num(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config, uint32_t num);
void adc_hal_digi_start(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config);
void adc_hal_digi_stop(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config);
void adc_hal_digi_init(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config);
/*---------------------------------------------------------------
Single Read
---------------------------------------------------------------*/
void adc_hal_onetime_start(adc_digi_config_t *adc_digi_config);
void adc_hal_adc1_onetime_sample_enable(bool enable);
void adc_hal_adc2_onetime_sample_enable(bool enable);
void adc_hal_onetime_channel(adc_ll_num_t unit, adc_channel_t channel);
void adc_hal_set_onetime_atten(adc_atten_t atten);
esp_err_t adc_hal_single_read(adc_ll_num_t unit, int *out_raw);
void adc_hal_intr_enable(adc_event_t event);
void adc_hal_intr_disable(adc_event_t event);
void adc_hal_intr_clear(adc_event_t event);
bool adc_hal_intr_get_raw(adc_event_t event);
bool adc_hal_intr_get_status(adc_event_t event);
/**
* @brief Stop ADC
*
* @param hal Context of the HAL
*/
void adc_hal_digi_stop(adc_hal_context_t *hal);
#endif //#if CONFIG_IDF_TARGET_ESP32C3

Wyświetl plik

@ -223,6 +223,7 @@ typedef struct {
} adc_digi_clk_t;
#endif //!CONFIG_IDF_TARGET_ESP32
/**
* @brief ADC digital controller (DMA mode) configuration parameters.
*
@ -294,6 +295,18 @@ typedef struct {
#endif
} adc_digi_config_t;
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3
/**
* @brief ADC digital controller (DMA mode) interrupt type options.
*/
typedef enum {
ADC_DIGI_INTR_MASK_MONITOR = 0x1,
ADC_DIGI_INTR_MASK_MEAS_DONE = 0x2,
ADC_DIGI_INTR_MASK_ALL = 0x3,
} adc_digi_intr_t;
FLAG_ATTR(adc_digi_intr_t)
#endif
#if !CONFIG_IDF_TARGET_ESP32
/**
@ -332,24 +345,6 @@ typedef struct {
.pwdet_pri = 2, \
}
/**
* @brief ADC digital controller (DMA mode) interrupt type options.
*/
typedef enum {
#if CONFIG_IDF_TARGET_ESP32C3
ADC_DIGI_INTR_MASK_MONITOR0_HIGH = BIT(0),
ADC_DIGI_INTR_MASK_MONITOR0_LOW = BIT(1),
ADC_DIGI_INTR_MASK_MONITOR1_HIGH = BIT(2),
ADC_DIGI_INTR_MASK_MONITOR1_LOW = BIT(3),
ADC_DIGI_INTR_MASK_MEAS_DONE = BIT(4),
#else
ADC_DIGI_INTR_MASK_MONITOR = 0x1,
ADC_DIGI_INTR_MASK_MEAS_DONE = 0x2,
ADC_DIGI_INTR_MASK_ALL = 0x3,
#endif
} adc_digi_intr_t;
FLAG_ATTR(adc_digi_intr_t)
/**
* @brief ADC digital controller (DMA mode) filter index options.
*
@ -444,10 +439,3 @@ typedef struct {
} adc_digi_monitor_t;
#endif // CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3
#if CONFIG_IDF_TARGET_ESP32C3
typedef enum {
ADC_EVENT_ADC1_DONE = BIT(0),
ADC_EVENT_ADC2_DONE = BIT(1),
} adc_event_t;
#endif

Wyświetl plik

@ -18,12 +18,10 @@
const int adc_channel_io_map[SOC_ADC_PERIPH_NUM][SOC_ADC_MAX_CHANNEL_NUM] = {
/* ADC1 */
{
ADC1_CHANNEL_0_GPIO_NUM, ADC1_CHANNEL_1_GPIO_NUM, ADC1_CHANNEL_2_GPIO_NUM, ADC1_CHANNEL_3_GPIO_NUM, ADC1_CHANNEL_4_GPIO_NUM,
ADC1_CHANNEL_5_GPIO_NUM, ADC1_CHANNEL_6_GPIO_NUM, ADC1_CHANNEL_7_GPIO_NUM, -1, -1
ADC1_CHANNEL_0_GPIO_NUM, ADC1_CHANNEL_1_GPIO_NUM, ADC1_CHANNEL_2_GPIO_NUM, ADC1_CHANNEL_3_GPIO_NUM, ADC1_CHANNEL_4_GPIO_NUM
},
/* ADC2 */
{
ADC2_CHANNEL_0_GPIO_NUM, ADC2_CHANNEL_1_GPIO_NUM, ADC2_CHANNEL_2_GPIO_NUM, ADC2_CHANNEL_3_GPIO_NUM, ADC2_CHANNEL_4_GPIO_NUM,
ADC2_CHANNEL_5_GPIO_NUM, ADC2_CHANNEL_6_GPIO_NUM, ADC2_CHANNEL_7_GPIO_NUM, ADC2_CHANNEL_8_GPIO_NUM, ADC2_CHANNEL_9_GPIO_NUM
ADC2_CHANNEL_0_GPIO_NUM, -1, -1, -1, -1
}
};

Wyświetl plik

@ -30,49 +30,7 @@
#define ADC1_GPIO5_CHANNEL ADC1_CHANNEL_4
#define ADC1_CHANNEL_4_GPIO_NUM 4
#define ADC1_GPIO6_CHANNEL ADC1_CHANNEL_5
#define ADC1_CHANNEL_5_GPIO_NUM 5
#define ADC1_GPIO7_CHANNEL ADC1_CHANNEL_6
#define ADC1_CHANNEL_6_GPIO_NUM 7
#define ADC1_GPIO8_CHANNEL ADC1_CHANNEL_7
#define ADC1_CHANNEL_7_GPIO_NUM 8
#define ADC1_GPIO9_CHANNEL ADC1_CHANNEL_8
#define ADC1_CHANNEL_8_GPIO_NUM 9
#define ADC1_GPIO10_CHANNEL ADC1_CHANNEL_9
#define ADC1_CHANNEL_9_GPIO_NUM 10
#define ADC2_GPIO11_CHANNEL ADC2_CHANNEL_0
#define ADC2_GPIO5_CHANNEL ADC2_CHANNEL_0
#define ADC2_CHANNEL_0_GPIO_NUM 5
#define ADC2_GPIO12_CHANNEL ADC2_CHANNEL_1
#define ADC2_CHANNEL_1_GPIO_NUM 6
#define ADC2_GPIO13_CHANNEL ADC2_CHANNEL_2
#define ADC2_CHANNEL_2_GPIO_NUM 13
#define ADC2_GPIO14_CHANNEL ADC2_CHANNEL_3
#define ADC2_CHANNEL_3_GPIO_NUM 14
#define ADC2_GPIO15_CHANNEL ADC2_CHANNEL_4
#define ADC2_CHANNEL_4_GPIO_NUM 15
#define ADC2_GPIO16_CHANNEL ADC2_CHANNEL_5
#define ADC2_CHANNEL_5_GPIO_NUM 16
#define ADC2_GPIO17_CHANNEL ADC2_CHANNEL_6
#define ADC2_CHANNEL_6_GPIO_NUM 17
#define ADC2_GPIO18_CHANNEL ADC2_CHANNEL_7
#define ADC2_CHANNEL_7_GPIO_NUM 18
#define ADC2_GPIO19_CHANNEL ADC2_CHANNEL_8
#define ADC2_CHANNEL_8_GPIO_NUM 19
#define ADC2_GPIO20_CHANNEL ADC2_CHANNEL_9
#define ADC2_CHANNEL_9_GPIO_NUM 20
#endif

Wyświetl plik

@ -45,17 +45,6 @@
#define SOC_TWAI_BRP_MIN 2
#define SOC_TWAI_BRP_MAX 32768
#define SOC_ADC_CHANNEL_NUM(PERIPH_NUM) ((PERIPH_NUM==0)? 5 : 1)
#define SOC_ADC_MAX_CHANNEL_NUM (10)
/**
* Check if adc support digital controller (DMA) mode.
* @value
* - 1 : support;
* - 0 : not support;
*/
#define SOC_ADC_SUPPORT_DMA_MODE(PERIPH_NUM) 1
/*--------------------------- SHA CAPS ---------------------------------------*/
/* Max amount of bytes in a single DMA operation is 4095,
@ -113,7 +102,7 @@
#define SOC_ADC_PERIPH_NUM (2)
#define SOC_ADC_PATT_LEN_MAX (16)
#define SOC_ADC_CHANNEL_NUM(PERIPH_NUM) ((PERIPH_NUM==0)? 5 : 1)
#define SOC_ADC_MAX_CHANNEL_NUM (10)
#define SOC_ADC_MAX_CHANNEL_NUM (5)
#define SOC_ADC_MAX_BITWIDTH (12)
#define SOC_ADC_DIGI_FILTER_NUM (2)
#define SOC_ADC_DIGI_MONITOR_NUM (2)

Wyświetl plik

@ -76,7 +76,7 @@ Reading voltage on ADC1 channel 0 ({IDF_TARGET_ADC1_CH0})::
int val = adc1_get_raw(ADC1_CHANNEL_0);
The input voltage in the above example is from 0 to 1.1 V (0 dB attenuation). The input range can be extended by setting a higher attenuation, see :cpp:type:`adc_atten_t`.
An example of using the ADC driver including calibration (discussed below) is available at esp-idf: :example:`peripherals/adc/adc`
An example of using the ADC driver including calibration (discussed below) is available at esp-idf: :example:`peripherals/adc`
Reading voltage on ADC2 channel 7 ({IDF_TARGET_ADC2_CH7})::
@ -95,7 +95,7 @@ Reading voltage on ADC2 channel 7 ({IDF_TARGET_ADC2_CH7})::
}
The reading may fail due to collision with Wi-Fi, should check it.
An example using the ADC2 driver to read the output of DAC is available in esp-idf: :example:`peripherals/adc/adc2`
An example using the ADC2 driver to read the output of DAC is available in esp-idf: :example:`peripherals/adc`
.. only:: esp32