driver: Add esp32c3 ADC driver

Based on internal commit 3ef01301fffa552d4be6d81bc9d199c223224305
This commit is contained in:
Angus Gratton 2020-12-16 20:23:19 +11:00
parent 27a9cf861e
commit f09b8ae7a4
20 changed files with 2144 additions and 162 deletions

View File

@ -67,6 +67,7 @@ endif()
if(IDF_TARGET STREQUAL "esp32c3")
list(APPEND srcs "spi_slave_hd.c"
"esp32c3/adc.c"
"esp32c3/rtc_tempsensor.c")
endif()

View File

@ -118,7 +118,7 @@ esp_err_t adc_i2s_mode_init(adc_unit_t adc_unit, adc_channel_t channel)
}
adc_gpio_init(adc_unit, channel);
ADC_ENTER_CRITICAL();
adc_hal_digi_init();
adc_hal_init();
adc_hal_digi_controller_config(&dig_cfg);
ADC_EXIT_CRITICAL();
@ -128,7 +128,7 @@ esp_err_t adc_i2s_mode_init(adc_unit_t adc_unit, adc_channel_t channel)
esp_err_t adc_digi_init(void)
{
ADC_ENTER_CRITICAL();
adc_hal_digi_init();
adc_hal_init();
ADC_EXIT_CRITICAL();
return ESP_OK;
}

View File

@ -0,0 +1,590 @@
// Copyright 2016-2018 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <esp_types.h>
#include <stdlib.h>
#include <ctype.h>
#include "esp_log.h"
#include "sys/lock.h"
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "freertos/timers.h"
#include "esp_intr_alloc.h"
#include "driver/periph_ctrl.h"
#include "driver/rtc_io.h"
#include "driver/rtc_cntl.h"
#include "driver/gpio.h"
#include "driver/adc.h"
#include "sdkconfig.h"
#include "esp32c3/rom/ets_sys.h"
#include "hal/adc_types.h"
#include "hal/adc_hal.h"
#define ADC_CHECK_RET(fun_ret) ({ \
if (fun_ret != ESP_OK) { \
ESP_LOGE(ADC_TAG,"%s:%d\n",__FUNCTION__,__LINE__); \
return ESP_FAIL; \
} \
})
static const char *ADC_TAG = "ADC";
#define ADC_CHECK(a, str, ret_val) ({ \
if (!(a)) { \
ESP_LOGE(ADC_TAG,"%s:%d (%s):%s", __FILE__, __LINE__, __FUNCTION__, str); \
return (ret_val); \
} \
})
#define ADC_GET_IO_NUM(periph, channel) (adc_channel_io_map[periph][channel])
#define ADC_CHANNEL_CHECK(periph, channel) ADC_CHECK(channel < SOC_ADC_CHANNEL_NUM(periph), "ADC"#periph" channel error", ESP_ERR_INVALID_ARG)
extern portMUX_TYPE rtc_spinlock; //TODO: Will be placed in the appropriate position after the rtc module is finished.
#define ADC_ENTER_CRITICAL() portENTER_CRITICAL(&rtc_spinlock)
#define ADC_EXIT_CRITICAL() portEXIT_CRITICAL(&rtc_spinlock)
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
esp_err_t adc_digi_controller_config(const adc_digi_config_t *config)
{
esp_err_t ret = ESP_OK;
ADC_ENTER_CRITICAL();
adc_hal_digi_controller_config(config);
ADC_EXIT_CRITICAL();
return ret;
}
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_ll_controller_t`.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_set_controller(adc_unit_t adc_unit, adc_ll_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 */
/*************************************/
esp_err_t adc_digi_filter_reset(adc_digi_filter_idx_t idx)
{
abort(); // TODO ESP32-C3 IDF-2528
}
esp_err_t adc_digi_filter_set_config(adc_digi_filter_idx_t idx, adc_digi_filter_t *config)
{
abort(); // TODO ESP32-C3 IDF-2528
}
esp_err_t adc_digi_filter_get_config(adc_digi_filter_idx_t idx, adc_digi_filter_t *config)
{
abort(); // TODO ESP32-C3 IDF-2528
}
esp_err_t adc_digi_filter_enable(adc_digi_filter_idx_t idx, bool enable)
{
abort(); // TODO ESP32-C3 IDF-2528
}
/**
* @brief Get the filtered data of adc digital controller filter. For debug.
* The data after each measurement and filtering is updated to the DMA by the digital controller. But it can also be obtained manually through this API.
*
* @note For ESP32S2, The filter will filter all the enabled channel data of the each ADC unit at the same time.
* @param idx Filter index.
* @return Filtered data. if <0, the read data invalid.
*/
int adc_digi_filter_read_data(adc_digi_filter_idx_t idx)
{
abort(); // TODO ESP32-C3 IDF-2528
}
/**************************************/
/* Digital controller monitor setting */
/**************************************/
esp_err_t adc_digi_monitor_set_config(adc_digi_monitor_idx_t idx, adc_digi_monitor_t *config)
{
ADC_ENTER_CRITICAL();
if (idx == ADC_DIGI_MONITOR_IDX0) {
adc_hal_digi_monitor_config(ADC_NUM_1, config);
} else if (idx == ADC_DIGI_MONITOR_IDX1) {
adc_hal_digi_monitor_config(ADC_NUM_2, config);
}
ADC_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t adc_digi_monitor_enable(adc_digi_monitor_idx_t idx, bool enable)
{
ADC_ENTER_CRITICAL();
if (idx == ADC_DIGI_MONITOR_IDX0) {
adc_hal_digi_monitor_enable(ADC_NUM_1, enable);
} else if (idx == ADC_DIGI_MONITOR_IDX1) {
adc_hal_digi_monitor_enable(ADC_NUM_2, enable);
}
ADC_EXIT_CRITICAL();
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 uint8_t 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
---------------------------------------------------------------*/
//This feature is currently supported on ESP32C3, will be supported on other chips soon
/*---------------------------------------------------------------
DMA setting
---------------------------------------------------------------*/
#include "soc/system_reg.h"
#include "hal/dma_types.h"
#include "hal/gdma_ll.h"
#include "hal/adc_hal.h"
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "freertos/ringbuf.h"
#include <string.h>
#define INTERNAL_BUF_NUM 5
#define IN_SUC_EOF_BIT GDMA_LL_EVENT_RX_SUC_EOF
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)
RingbufHandle_t ringbuf_hdl; //RX ringbuffer handler
bool ringbuf_overflow_flag; //1: ringbuffer overflow
bool driver_state_flag; //1: driver is started; 2: driver is stoped
} adc_digi_context_t;
static const char* ADC_DMA_TAG = "ADC_DMA:";
static adc_digi_context_t *adc_digi_ctx = NULL;
static void adc_dma_intr(void* arg);
static int8_t adc_digi_get_io_num(uint8_t adc_unit, uint8_t adc_channel)
{
return adc_channel_io_map[adc_unit][adc_channel];
}
static esp_err_t adc_digi_gpio_init(adc_unit_t adc_unit, uint16_t channel_mask)
{
esp_err_t ret = ESP_OK;
uint64_t gpio_mask = 0;
uint32_t n = 0;
int8_t io = 0;
while (channel_mask) {
if (channel_mask & 0x1) {
io = adc_digi_get_io_num(adc_unit, n);
if (io < 0) {
return ESP_ERR_INVALID_ARG;
}
gpio_mask |= BIT64(io);
}
channel_mask = channel_mask >> 1;
n++;
}
gpio_config_t cfg = {
.pin_bit_mask = gpio_mask,
.mode = GPIO_MODE_DISABLE,
};
gpio_config(&cfg);
return ret;
}
esp_err_t adc_digi_initialize(const adc_digi_init_config_t *init_config)
{
esp_err_t ret = ESP_OK;
adc_digi_ctx = calloc(1, sizeof(adc_digi_context_t));
if (adc_digi_ctx == NULL) {
ret = ESP_ERR_NO_MEM;
goto cleanup;
}
ret = esp_intr_alloc(SOC_GDMA_ADC_INTR_SOURCE, 0, adc_dma_intr, (void *)adc_digi_ctx, &adc_digi_ctx->dma_intr_hdl);
if (ret != ESP_OK) {
goto cleanup;
}
//ringbuffer
adc_digi_ctx->ringbuf_hdl = xRingbufferCreate(init_config->max_store_buf_size, RINGBUF_TYPE_BYTEBUF);
if (!adc_digi_ctx->ringbuf_hdl) {
ret = ESP_ERR_NO_MEM;
goto cleanup;
}
//malloc internal buffer
adc_digi_ctx->bytes_between_intr = init_config->conv_num_each_intr;
adc_digi_ctx->rx_dma_buf = heap_caps_calloc(1, adc_digi_ctx->bytes_between_intr * INTERNAL_BUF_NUM, MALLOC_CAP_INTERNAL);
if (!adc_digi_ctx->rx_dma_buf) {
ret = ESP_ERR_NO_MEM;
goto cleanup;
}
//malloc dma descriptor
adc_digi_ctx->hal_dma_config.rx_desc = heap_caps_calloc(1, (sizeof(dma_descriptor_t)) * INTERNAL_BUF_NUM, MALLOC_CAP_DMA);
if (!adc_digi_ctx->hal_dma_config.rx_desc) {
ret = ESP_ERR_NO_MEM;
goto cleanup;
}
adc_digi_ctx->hal_dma_config.desc_max_num = INTERNAL_BUF_NUM;
adc_digi_ctx->hal_dma_config.dma_chan = init_config->dma_chan;
if (init_config->adc1_chan_mask) {
ret = adc_digi_gpio_init(ADC_NUM_1, init_config->adc1_chan_mask);
if (ret != ESP_OK) {
goto cleanup;
}
}
if (init_config->adc2_chan_mask) {
ret = adc_digi_gpio_init(ADC_NUM_2, init_config->adc2_chan_mask);
if (ret != ESP_OK) {
goto cleanup;
}
}
periph_module_enable(PERIPH_SARADC_MODULE);
periph_module_enable(PERIPH_GDMA_MODULE);
adc_arbiter_t config = ADC_ARBITER_CONFIG_DEFAULT();
ADC_ENTER_CRITICAL();
adc_hal_init();
adc_hal_arbiter_config(&config);
adc_hal_digi_init(&adc_digi_ctx->hal_dma, &adc_digi_ctx->hal_dma_config);
ADC_EXIT_CRITICAL();
return ret;
cleanup:
adc_digi_deinitialize();
return ret;
}
static IRAM_ATTR void adc_dma_intr(void *arg)
{
portBASE_TYPE taskAwoken = 0;
BaseType_t ret;
//clear the in suc eof interrupt
adc_hal_digi_clr_intr(&adc_digi_ctx->hal_dma, &adc_digi_ctx->hal_dma_config, IN_SUC_EOF_BIT);
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;
//start next turns of dma operation
adc_hal_digi_rxdma_start(&adc_digi_ctx->hal_dma, &adc_digi_ctx->hal_dma_config);
}
if(taskAwoken == pdTRUE) {
portYIELD_FROM_ISR();
}
}
esp_err_t adc_digi_start(void)
{
assert(adc_digi_ctx->driver_state_flag == 0 && "the driver is already started");
//reset flags
adc_digi_ctx->ringbuf_overflow_flag = 0;
adc_digi_ctx->driver_state_flag = 1;
//create dma descriptors
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_set_eof_num(&adc_digi_ctx->hal_dma, &adc_digi_ctx->hal_dma_config, (adc_digi_ctx->bytes_between_intr)/4);
//set the current descriptor pointer
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;
//enable in suc eof intr
adc_hal_digi_ena_intr(&adc_digi_ctx->hal_dma, &adc_digi_ctx->hal_dma_config, GDMA_LL_EVENT_RX_SUC_EOF);
//start DMA
adc_hal_digi_rxdma_start(&adc_digi_ctx->hal_dma, &adc_digi_ctx->hal_dma_config);
//start ADC
adc_hal_digi_start(&adc_digi_ctx->hal_dma, &adc_digi_ctx->hal_dma_config);
return ESP_OK;
}
esp_err_t adc_digi_stop(void)
{
assert(adc_digi_ctx->driver_state_flag == 1 && "the driver is already stoped");
adc_digi_ctx->driver_state_flag = 0;
//disable the in suc eof intrrupt
adc_hal_digi_dis_intr(&adc_digi_ctx->hal_dma, &adc_digi_ctx->hal_dma_config, IN_SUC_EOF_BIT);
//clear the in suc eof interrupt
adc_hal_digi_clr_intr(&adc_digi_ctx->hal_dma, &adc_digi_ctx->hal_dma_config, IN_SUC_EOF_BIT);
//stop DMA
adc_hal_digi_rxdma_stop(&adc_digi_ctx->hal_dma, &adc_digi_ctx->hal_dma_config);
//stop ADC
adc_hal_digi_stop(&adc_digi_ctx->hal_dma, &adc_digi_ctx->hal_dma_config);
return ESP_OK;
}
esp_err_t adc_digi_read_bytes(uint8_t *buf, uint32_t length_max, uint32_t *out_length, uint32_t timeout_ms)
{
TickType_t ticks_to_wait;
esp_err_t ret = ESP_OK;
uint8_t *data = NULL;
size_t size = 0;
ticks_to_wait = timeout_ms / portTICK_RATE_MS;
if (timeout_ms == ADC_MAX_DELAY) {
ticks_to_wait = portMAX_DELAY;
}
data = xRingbufferReceiveUpTo(adc_digi_ctx->ringbuf_hdl, &size, ticks_to_wait, length_max);
if (!data) {
ESP_EARLY_LOGW(ADC_DMA_TAG, "No data, increase timeout or reduce conv_num_each_intr");
ret = ESP_ERR_TIMEOUT;
*out_length = 0;
return ret;
}
memcpy(buf, data, size);
vRingbufferReturnItem(adc_digi_ctx->ringbuf_hdl, data);
assert((size % 4) == 0);
*out_length = size;
if (adc_digi_ctx->ringbuf_overflow_flag) {
ret = ESP_ERR_INVALID_STATE;
}
return ret;
}
static esp_err_t adc_digi_deinit(void)
{
ADC_ENTER_CRITICAL();
adc_hal_digi_deinit();
ADC_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t adc_digi_deinitialize(void)
{
assert(adc_digi_ctx->driver_state_flag == 0 && "the driver is not stoped");
if (adc_digi_ctx == NULL) {
return ESP_ERR_INVALID_STATE;
}
if (adc_digi_ctx->dma_intr_hdl) {
esp_intr_free(adc_digi_ctx->dma_intr_hdl);
}
if(adc_digi_ctx->ringbuf_hdl) {
vRingbufferDelete(adc_digi_ctx->ringbuf_hdl);
adc_digi_ctx->ringbuf_hdl = NULL;
}
if (adc_digi_ctx->hal_dma_config.rx_desc) {
free(adc_digi_ctx->hal_dma_config.rx_desc);
}
free(adc_digi_ctx);
adc_digi_ctx = NULL;
adc_digi_deinit();
periph_module_disable(PERIPH_SARADC_MODULE);
periph_module_disable(PERIPH_GDMA_MODULE);
return ESP_OK;
}

View File

@ -0,0 +1,201 @@
// Copyright 2019 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#include "driver/adc_common.h"
#ifdef __cplusplus
extern "C" {
#endif
/*---------------------------------------------------------------
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 */
/*************************************/
/**
* @brief Reset adc digital controller filter.
*
* @param idx Filter index.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_filter_reset(adc_digi_filter_idx_t idx);
/**
* @brief Set adc digital controller filter configuration.
*
* @note For ESP32S2, Filter IDX0/IDX1 can only be used to filter all enabled channels of ADC1/ADC2 unit at the same time.
*
* @param idx Filter index.
* @param config See ``adc_digi_filter_t``.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_filter_set_config(adc_digi_filter_idx_t idx, adc_digi_filter_t *config);
/**
* @brief Get adc digital controller filter configuration.
*
* @note For ESP32S2, Filter IDX0/IDX1 can only be used to filter all enabled channels of ADC1/ADC2 unit at the same time.
*
* @param idx Filter index.
* @param config See ``adc_digi_filter_t``.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_filter_get_config(adc_digi_filter_idx_t idx, adc_digi_filter_t *config);
/**
* @brief Enable/disable adc digital controller filter.
* Filtering the ADC data to obtain smooth data at higher sampling rates.
*
* @note For ESP32S2, Filter IDX0/IDX1 can only be used to filter all enabled channels of ADC1/ADC2 unit at the same time.
*
* @param idx Filter index.
* @param enable Enable/Disable filter.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_filter_enable(adc_digi_filter_idx_t idx, bool enable);
/**************************************/
/* Digital controller monitor setting */
/**************************************/
/**
* @brief Config monitor of adc digital controller.
*
* @note For ESP32S2, The monitor will monitor all the enabled channel data of the each ADC unit at the same time.
*
* @param idx Monitor index.
* @param config See ``adc_digi_monitor_t``.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_monitor_set_config(adc_digi_monitor_idx_t idx, adc_digi_monitor_t *config);
/**
* @brief Enable/disable monitor of adc digital controller.
*
* @note For ESP32S2, The monitor will monitor all the enabled channel data of the each ADC unit at the same time.
*
* @param idx Monitor index.
* @param enable True or false enable monitor.
*
* @return
* - ESP_OK Success
*/
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

View File

@ -71,7 +71,7 @@ esp_err_t adc_digi_init(void)
{
adc_arbiter_t config = ADC_ARBITER_CONFIG_DEFAULT();
ADC_ENTER_CRITICAL();
adc_hal_digi_init();
adc_hal_init();
adc_hal_arbiter_config(&config);
ADC_EXIT_CRITICAL();
return ESP_OK;
@ -148,12 +148,12 @@ esp_err_t adc_arbiter_config(adc_unit_t adc_unit, adc_arbiter_t *config)
* @note For ADC1, Controller access is mutually exclusive.
*
* @param adc_unit ADC unit.
* @param ctrl ADC controller, Refer to `adc_controller_t`.
* @param ctrl ADC controller, Refer to `adc_ll_controller_t`.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_set_controller(adc_unit_t adc_unit, adc_controller_t ctrl)
esp_err_t adc_set_controller(adc_unit_t adc_unit, adc_ll_controller_t ctrl)
{
adc_arbiter_t config = {0};
adc_arbiter_t cfg = ADC_ARBITER_CONFIG_DEFAULT();

View File

@ -239,39 +239,6 @@ esp_err_t adc_digi_isr_register(void (*fn)(void *), void *arg, int intr_alloc_fl
*/
esp_err_t adc_digi_isr_deregister(void);
/*---------------------------------------------------------------
RTC controller setting
---------------------------------------------------------------*/
/*---------------------------------------------------------------
Deprecated API
---------------------------------------------------------------*/
/**
* @brief Set I2S data source
*
* @param src I2S DMA data source, I2S DMA can get data from digital signals or from ADC.
*
* @deprecated The ESP32S2 don't use I2S DMA. Call ``adc_digi_controller_config`` instead.
*
* @return
* - ESP_OK success
*/
esp_err_t adc_set_i2s_data_source(adc_i2s_source_t src) __attribute__((deprecated));
/**
* @brief Initialize I2S ADC mode
*
* @param adc_unit ADC unit index
* @param channel ADC channel index
*
* @deprecated The ESP32S2 don't use I2S DMA. Call ``adc_digi_controller_config`` instead.
*
* @return
* - ESP_OK success
* - ESP_ERR_INVALID_ARG Parameter error
*/
esp_err_t adc_i2s_mode_init(adc_unit_t adc_unit, adc_channel_t channel) __attribute__((deprecated));
#ifdef __cplusplus
}
#endif

View File

@ -24,25 +24,47 @@
extern "C" {
#endif
#if CONFIG_IDF_TARGET_ESP32
/**** `adc1_channel_t` will be deprecated functions, combine into `adc_channel_t` ********/
typedef enum {
ADC1_CHANNEL_0 = 0, /*!< ADC1 channel 0 is GPIO36 (ESP32), GPIO1 (ESP32-S2) */
ADC1_CHANNEL_1, /*!< ADC1 channel 1 is GPIO37 (ESP32), GPIO2 (ESP32-S2) */
ADC1_CHANNEL_2, /*!< ADC1 channel 2 is GPIO38 (ESP32), GPIO3 (ESP32-S2) */
ADC1_CHANNEL_3, /*!< ADC1 channel 3 is GPIO39 (ESP32), GPIO4 (ESP32-S2) */
ADC1_CHANNEL_4, /*!< ADC1 channel 4 is GPIO32 (ESP32), GPIO5 (ESP32-S2) */
ADC1_CHANNEL_5, /*!< ADC1 channel 5 is GPIO33 (ESP32), GPIO6 (ESP32-S2) */
ADC1_CHANNEL_6, /*!< ADC1 channel 6 is GPIO34 (ESP32), GPIO7 (ESP32-S2) */
ADC1_CHANNEL_7, /*!< ADC1 channel 7 is GPIO35 (ESP32), GPIO8 (ESP32-S2) */
#if CONFIG_IDF_TARGET_ESP32
ADC1_CHANNEL_0 = 0, /*!< ADC1 channel 0 is GPIO36 */
ADC1_CHANNEL_1, /*!< ADC1 channel 1 is GPIO37 */
ADC1_CHANNEL_2, /*!< ADC1 channel 2 is GPIO38 */
ADC1_CHANNEL_3, /*!< ADC1 channel 3 is GPIO39 */
ADC1_CHANNEL_4, /*!< ADC1 channel 4 is GPIO32 */
ADC1_CHANNEL_5, /*!< ADC1 channel 5 is GPIO33 */
ADC1_CHANNEL_6, /*!< ADC1 channel 6 is GPIO34 */
ADC1_CHANNEL_7, /*!< ADC1 channel 7 is GPIO35 */
ADC1_CHANNEL_MAX,
#elif CONFIG_IDF_TARGET_ESP32S2
ADC1_CHANNEL_8, /*!< ADC1 channel 6 is GPIO9 (ESP32-S2)*/
ADC1_CHANNEL_9, /*!< ADC1 channel 7 is GPIO10 (ESP32-S2) */
ADC1_CHANNEL_MAX,
#endif
} adc1_channel_t;
#elif CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3 // TODO ESP32-S3 channels are wrong IDF-1776
/**** `adc1_channel_t` will be deprecated functions, combine into `adc_channel_t` ********/
typedef enum {
ADC1_CHANNEL_0 = 0, /*!< ADC1 channel 0 is GPIO1 */
ADC1_CHANNEL_1, /*!< ADC1 channel 1 is GPIO2 */
ADC1_CHANNEL_2, /*!< ADC1 channel 2 is GPIO3 */
ADC1_CHANNEL_3, /*!< ADC1 channel 3 is GPIO4 */
ADC1_CHANNEL_4, /*!< ADC1 channel 4 is GPIO5 */
ADC1_CHANNEL_5, /*!< ADC1 channel 5 is GPIO6 */
ADC1_CHANNEL_6, /*!< ADC1 channel 6 is GPIO7 */
ADC1_CHANNEL_7, /*!< ADC1 channel 7 is GPIO8 */
ADC1_CHANNEL_8, /*!< ADC1 channel 6 is GPIO9 */
ADC1_CHANNEL_9, /*!< ADC1 channel 7 is GPIO10 */
ADC1_CHANNEL_MAX,
} adc1_channel_t;
#elif CONFIG_IDF_TARGET_ESP32C3
/**** `adc1_channel_t` will be deprecated functions, combine into `adc_channel_t` ********/
typedef enum {
ADC1_CHANNEL_0 = 0, /*!< ADC1 channel 0 is GPIO0 */
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_MAX,
} adc1_channel_t;
#endif // CONFIG_IDF_TARGET_*
#if CONFIG_IDF_TARGET_ESP32 || CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3 // TODO ESP32-S3 channels are wrong IDF-1776
/**** `adc2_channel_t` will be deprecated functions, combine into `adc_channel_t` ********/
typedef enum {
ADC2_CHANNEL_0 = 0, /*!< ADC2 channel 0 is GPIO4 (ESP32), GPIO11 (ESP32-S2) */
@ -57,6 +79,14 @@ typedef enum {
ADC2_CHANNEL_9, /*!< ADC2 channel 9 is GPIO26 (ESP32), GPIO20 (ESP32-S2) */
ADC2_CHANNEL_MAX,
} adc2_channel_t;
#elif CONFIG_IDF_TARGET_ESP32C3
/**** `adc2_channel_t` will be deprecated functions, combine into `adc_channel_t` ********/
typedef enum {
ADC2_CHANNEL_0 = 0, /*!< ADC2 channel 0 is GPIO5 */
ADC2_CHANNEL_MAX,
} adc2_channel_t;
#endif
/**
* @brief ADC rtc controller attenuation option.
@ -73,6 +103,13 @@ typedef enum {
#define ADC_WIDTH_11Bit ADC_WIDTH_BIT_11
#define ADC_WIDTH_12Bit ADC_WIDTH_BIT_12
#if CONFIG_IDF_TARGET_ESP32C3
/**
* @brief Digital ADC DMA read max timeout value, it may make the ``adc_digi_read_bytes`` block forever if the OS supports
*/
#define ADC_MAX_DELAY UINT32_MAX
#endif
/**
* @brief ADC digital controller encode option.
*
@ -84,6 +121,20 @@ typedef enum {
ADC_ENCODE_MAX,
} adc_i2s_encode_t;
#if CONFIG_IDF_TARGET_ESP32C3
//This feature is currently supported on ESP32C3, will be supported on other chips soon
/**
* @brief Digital ADC DMA configuration
*/
typedef struct adc_digi_init_config_s {
uint32_t max_store_buf_size; ///< Max length of the converted data that driver can store before they are processed. When this length is reached, driver will dump out all the old data and start to store them again.
uint32_t conv_num_each_intr; ///< Bytes of data that can be converted in 1 interrupt.
uint32_t dma_chan; ///< DMA channel.
uint16_t adc1_chan_mask; ///< Channel list of ADC1 to be initialized.
uint16_t adc2_chan_mask; ///< Channel list of ADC2 to be initialized.
} adc_digi_init_config_t;
#endif
/*---------------------------------------------------------------
Common setting
---------------------------------------------------------------*/
@ -392,7 +443,8 @@ esp_err_t adc2_vref_to_gpio(gpio_num_t gpio) __attribute__((deprecated));
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
#if CONFIG_IDF_TARGET_ESP32 || CONFIG_IDF_TARGET_ESP32S2
//These APIs are only supported on ESP32 and ESP32-S2. On ESP32-C3 and later chips, please use ``adc_digi_initialize`` and ``adc_digi_deinitialize``
/**
* @brief ADC digital controller initialization.
* @return
@ -406,17 +458,78 @@ esp_err_t adc_digi_init(void);
* - ESP_OK Success
*/
esp_err_t adc_digi_deinit(void);
#endif
/**
* @brief Setting the digital controller.
*
* @param config Pointer to digital controller paramter. Refer to `adc_digi_config_t`.
* @param config Pointer to digital controller paramter. Refer to ``adc_digi_config_t``.
*
* @return
* - ESP_OK Success
*/
esp_err_t adc_digi_controller_config(const adc_digi_config_t *config);
#if CONFIG_IDF_TARGET_ESP32C3
//This feature is currently supported on ESP32C3, will be supported on other chips soon
/*---------------------------------------------------------------
DMA setting
---------------------------------------------------------------*/
/**
* @brief Initialize the Digital ADC.
*
* @param init_config Pointer to Digital ADC initilisation config. Refer to ``adc_digi_init_config_t``.
*
* @return
* - ESP_ERR_INVALID_ARG If the combination of arguments is invalid.
* - ESP_ERR_NOT_FOUND No free interrupt found with the specified flags
* - ESP_ERR_NO_MEM If out of memory
* - ESP_OK On success
*/
esp_err_t adc_digi_initialize(const adc_digi_init_config_t *init_config);
/**
* @brief Start the Digital ADC and DMA peripherals. After this, the hardware starts working.
*
* @return
* - ESP_OK On success
*/
esp_err_t adc_digi_start(void);
/**
* @brief Stop the Digital ADC and DMA peripherals. After this, the hardware stops working.
*
* @return
* - ESP_OK On success
*/
esp_err_t adc_digi_stop(void);
/**
* @brief Read bytes from Digital ADC through DMA.
*
* @param[out] buf Buffer to read from ADC.
* @param[in] length_max Expected length of data read from the ADC.
* @param[out] out_length Real length of data read from the ADC via this API.
* @param[in] timeout_ms Time to wait for data via this API, in millisecond.
*
* @return
* - ESP_ERR_INVALID_STATE Driver state is invalid. Usually it means the ADC sampling rate is faster than the task processing rate.
* - ESP_ERR_TIMEOUT Operation timed out
* - ESP_OK On success
*/
esp_err_t adc_digi_read_bytes(uint8_t *buf, uint32_t length_max, uint32_t *out_length, uint32_t timeout_ms);
/**
* @brief Deinitialize the Digital ADC.
*
* @return
* - ESP_ERR_INVALID_STATE Driver state is invalid.
* - ESP_OK On success
*/
esp_err_t adc_digi_deinitialize(void);
#endif //#if CONFIG_IDF_TARGET_ESP32C3
#ifdef __cplusplus
}
#endif

View File

@ -13,7 +13,9 @@
// limitations under the License.
#include "hal/adc_hal.h"
#if !CONFIG_IDF_TARGET_ESP32C3
#include "hal/adc_hal_conf.h"
#endif
void adc_hal_init(void)
{
@ -24,6 +26,7 @@ void adc_hal_init(void)
adc_hal_pwdet_set_cct(SOC_ADC_PWDET_CCT_DEFAULT);
adc_ll_digi_output_invert(ADC_NUM_1, SOC_ADC_DIGI_DATA_INVERT_DEFAULT(ADC_NUM_1));
adc_ll_digi_output_invert(ADC_NUM_2, SOC_ADC_DIGI_DATA_INVERT_DEFAULT(ADC_NUM_2));
adc_ll_digi_set_clk_div(SOC_ADC_DIGI_SAR_CLK_DIV_DEFAULT);
}
void adc_hal_deinit(void)
@ -39,3 +42,84 @@ int adc_hal_convert(adc_ll_num_t adc_n, int channel, int *value)
*value = adc_ll_rtc_get_convert_value(adc_n);
return (int)adc_ll_rtc_analysis_raw_data(adc_n, (uint16_t)(*value));
}
#if CONFIG_IDF_TARGET_ESP32C3
//This feature is currently supported on ESP32C3, will be supported on other chips soon
/*---------------------------------------------------------------
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)
{
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--) {
desc[n].dw0.size = size;
desc[n].dw0.suc_eof = 0;
desc[n].dw0.owner = 1;
desc[n].buffer = data_buf;
desc[n].next = &desc[n+1];
data_buf += size;
n++;
}
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)
{
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);
}
void adc_hal_digi_rxdma_stop(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config)
{
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
adc_ll_digi_dma_enable();
//enable sar adc timer
adc_ll_digi_trigger_enable();
}
void adc_hal_digi_stop(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config)
{
//Set to 0: the ADC data won't be sent to the DMA
adc_ll_digi_dma_disable();
//disable sar adc timer
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_enable_clock(adc_dma_ctx->dev, true);
gdma_ll_clear_interrupt_status(adc_dma_ctx->dev, dma_config->dma_chan, UINT32_MAX);
gdma_ll_rx_connect_to_periph(adc_dma_ctx->dev, dma_config->dma_chan, GDMA_LL_TRIG_SRC_ADC_DAC);
}
#endif

View File

@ -18,12 +18,6 @@
#include "hal/adc_hal_conf.h"
#include "hal/adc_types.h"
void adc_hal_digi_init(void)
{
adc_hal_init();
adc_ll_digi_set_clk_div(SOC_ADC_DIGI_SAR_CLK_DIV_DEFAULT);
}
void adc_hal_digi_deinit(void)
{
adc_ll_digi_clear_pattern_table(ADC_NUM_1);

View File

@ -20,13 +20,6 @@
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
void adc_hal_digi_init(void)
{
adc_hal_init();
adc_ll_digi_set_clk_div(SOC_ADC_DIGI_SAR_CLK_DIV_DEFAULT);
}
void adc_hal_digi_deinit(void)
{
adc_ll_digi_trigger_disable(); // boss
@ -40,37 +33,29 @@ void adc_hal_digi_deinit(void)
adc_hal_deinit();
}
static inline void adc_set_init_code(adc_ll_num_t adc_n, adc_channel_t channel, adc_atten_t atten)
{
uint32_t cal_val = adc_hal_calibration(adc_n, channel, atten, true, false);
adc_hal_set_calibration_param(adc_n, cal_val);
}
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.
const int pattern_both = 0;
/* If enable digtal controller, adc xpd should always on. */
adc_ll_set_power_manage(ADC_POWER_SW_ON);
/* Single channel mode or multi channel mode. */
adc_ll_digi_set_convert_mode(cfg->conv_mode);
if (cfg->conv_mode & ADC_CONV_SINGLE_UNIT_1) {
if (cfg->adc1_pattern_len) {
adc_ll_digi_clear_pattern_table(ADC_NUM_1);
adc_ll_digi_set_pattern_table_len(ADC_NUM_1, cfg->adc1_pattern_len);
for (int i = 0; i < cfg->adc1_pattern_len; i++) {
adc_ll_digi_set_pattern_table(ADC_NUM_1, i, cfg->adc1_pattern[i]);
}
if (cfg->adc_pattern_len) {
adc_ll_digi_clear_pattern_table(pattern_both);
adc_ll_digi_set_pattern_table_len(pattern_both, cfg->adc_pattern_len);
for (int i = 0; i < cfg->adc_pattern_len; i++) {
adc_ll_digi_set_pattern_table(pattern_both, i, cfg->adc_pattern[i]);
adc_set_init_code(pattern_both, cfg->adc_pattern[i].channel, cfg->adc_pattern[i].atten);
}
}
if (cfg->conv_mode & ADC_CONV_SINGLE_UNIT_2) {
if (cfg->adc2_pattern_len) {
adc_ll_digi_clear_pattern_table(ADC_NUM_2);
adc_ll_digi_set_pattern_table_len(ADC_NUM_2, cfg->adc2_pattern_len);
for (int i = 0; i < cfg->adc2_pattern_len; i++) {
adc_ll_digi_set_pattern_table(ADC_NUM_2, i, cfg->adc2_pattern[i]);
}
}
}
if (cfg->conv_mode & ADC_CONV_SINGLE_UNIT_1) {
adc_ll_set_controller(ADC_NUM_1, ADC_CTRL_DIG);
}
if (cfg->conv_mode & ADC_CONV_SINGLE_UNIT_2) {
adc_ll_set_controller(ADC_NUM_2, ADC_CTRL_DIG);
}
adc_ll_digi_set_output_format(cfg->format);
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();
@ -80,7 +65,6 @@ void adc_hal_digi_controller_config(const adc_digi_config_t *cfg)
adc_ll_digi_set_trigger_interval(cfg->interval);
adc_hal_digi_clk_config(&cfg->dig_clk);
adc_ll_digi_dma_set_eof_num(cfg->dma_eof_num);
}
/**
@ -154,27 +138,44 @@ void adc_hal_arbiter_config(adc_arbiter_t *config)
/*---------------------------------------------------------------
ADC calibration setting
---------------------------------------------------------------*/
#define ADC_HAL_CAL_TIMES (10)
#define ADC_HAL_CAL_OFFSET_RANGE (4096)
static uint32_t read_cal_channel(adc_ll_num_t adc_n, int channel)
#define ADC_HAL_CAL_OFFSET_RANGE (4096)
#define ADC_HAL_CAL_TIMES (10)
static uint16_t s_adc_cali_param[ADC_NUM_MAX][ADC_ATTEN_MAX] = { {0}, {0} };
static uint32_t adc_hal_read_self_cal(adc_ll_num_t adc_n, int channel)
{
adc_ll_rtc_start_convert(adc_n, channel);
while (adc_ll_rtc_convert_is_done(adc_n) != true);
return (uint32_t)adc_ll_rtc_get_convert_value(adc_n);
}
uint32_t adc_hal_self_calibration(adc_ll_num_t adc_n, adc_channel_t channel, adc_atten_t atten, bool internal_gnd)
uint32_t adc_hal_calibration(adc_ll_num_t adc_n, adc_channel_t channel, adc_atten_t atten, bool internal_gnd, bool force_cal)
{
adc_hal_set_power_manage(ADC_POWER_SW_ON);
if (!force_cal) {
if (s_adc_cali_param[adc_n][atten]) {
return (uint32_t)s_adc_cali_param[adc_n][atten];
}
}
uint32_t code_list[ADC_HAL_CAL_TIMES] = {0};
uint32_t code_sum = 0;
uint32_t code_h = 0;
uint32_t code_l = 0;
uint32_t chk_code = 0;
uint32_t dout = 0;
adc_hal_set_power_manage(ADC_POWER_SW_ON);
if (adc_n == ADC_NUM_2) {
adc_arbiter_t config = ADC_ARBITER_CONFIG_DEFAULT();
adc_hal_arbiter_config(&config);
}
adc_hal_set_controller(adc_n, ADC_CTRL_RTC); //Set controller
// adc_hal_arbiter_config(adc_arbiter_t *config)
adc_ll_calibration_prepare(adc_n, channel, internal_gnd);
/* Enable/disable internal connect GND (for calibration). */
if (internal_gnd) {
adc_ll_rtc_disable_channel(adc_n, channel);
@ -184,31 +185,25 @@ uint32_t adc_hal_self_calibration(adc_ll_num_t adc_n, adc_channel_t channel, adc
adc_ll_set_atten(adc_n, channel, atten);
}
uint32_t code_list[ADC_HAL_CAL_TIMES] = {0};
uint32_t code_sum = 0;
uint32_t code_h = 0;
uint32_t code_l = 0;
uint32_t chk_code = 0;
for (uint8_t rpt = 0 ; rpt < ADC_HAL_CAL_TIMES ; rpt ++) {
code_h = ADC_HAL_CAL_OFFSET_RANGE;
code_l = 0;
chk_code = (code_h + code_l) / 2;
adc_ll_set_calibration_param(adc_n, chk_code);
uint32_t self_cal = read_cal_channel(adc_n, channel);
dout = adc_hal_read_self_cal(adc_n, channel);
while (code_h - code_l > 1) {
if (self_cal == 0) {
if (dout == 0) {
code_h = chk_code;
} else {
code_l = chk_code;
}
chk_code = (code_h + code_l) / 2;
adc_ll_set_calibration_param(adc_n, chk_code);
self_cal = read_cal_channel(adc_n, channel);
dout = adc_hal_read_self_cal(adc_n, channel);
if ((code_h - code_l == 1)) {
chk_code += 1;
adc_ll_set_calibration_param(adc_n, chk_code);
self_cal = read_cal_channel(adc_n, channel);
dout = adc_hal_read_self_cal(adc_n, channel);
}
}
code_list[rpt] = chk_code;
@ -225,10 +220,12 @@ uint32_t adc_hal_self_calibration(adc_ll_num_t adc_n, adc_channel_t channel, adc
}
}
chk_code = code_h + code_l;
uint32_t ret = ((code_sum - chk_code) % (ADC_HAL_CAL_TIMES - 2) < 4)
dout = ((code_sum - chk_code) % (ADC_HAL_CAL_TIMES - 2) < 4)
? (code_sum - chk_code) / (ADC_HAL_CAL_TIMES - 2)
: (code_sum - chk_code) / (ADC_HAL_CAL_TIMES - 2) + 1;
adc_ll_set_calibration_param(adc_n, dout);
adc_ll_calibration_finish(adc_n);
return ret;
s_adc_cali_param[adc_n][atten] = (uint16_t)dout;
return dout;
}

View File

@ -34,11 +34,6 @@ extern "C" {
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
/**
* Digital controller initialization.
*/
void adc_hal_digi_init(void);
/**
* Digital controller deinitialization.
*/

View File

@ -0,0 +1,975 @@
// Copyright 2015-2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#include <stdbool.h>
#include <stdlib.h>
#include "soc/adc_periph.h"
#include "hal/adc_types.h"
#include "soc/apb_saradc_struct.h"
#include "soc/apb_saradc_reg.h"
#include "soc/rtc_cntl_struct.h"
#include "soc/rtc_cntl_reg.h"
#include "regi2c_ctrl.h"
#ifdef __cplusplus
extern "C" {
#endif
typedef enum {
ADC_NUM_1 = 0, /*!< SAR ADC 1 */
ADC_NUM_2 = 1, /*!< SAR ADC 2 */
ADC_NUM_MAX,
} adc_ll_num_t;
typedef enum {
ADC_POWER_BY_FSM, /*!< ADC XPD controled by FSM. Used for polling mode */
ADC_POWER_SW_ON, /*!< ADC XPD controled by SW. power on. Used for DMA mode */
ADC_POWER_SW_OFF, /*!< ADC XPD controled by SW. power off. */
ADC_POWER_MAX, /*!< For parameter check. */
} adc_ll_power_t;
typedef enum {
ADC_RTC_DATA_OK = 0,
ADC_RTC_CTRL_UNSELECTED = 1,
ADC_RTC_CTRL_BREAK = 2,
ADC_RTC_DATA_FAIL = -1,
} adc_ll_rtc_raw_data_t;
#ifdef _MSC_VER
#pragma pack(push, 1)
#endif /* _MSC_VER */
/**
* @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;
#ifdef _MSC_VER
#pragma pack(pop)
#endif /* _MSC_VER */
/**
* @brief ADC controller type selection.
*
* @note For ADC2, use the force option with care. The system power consumption detection will use ADC2.
* If it is forced to switch to another controller, it may cause the system to obtain incorrect values.
* @note Normally, there is no need to switch the controller manually.
*/
typedef enum {
ADC_CTRL_RTC = 0, /*!<For ADC1. Select RTC controller. For ADC2. The controller is selected by the arbiter. Arbiter in default mode. */
ADC_CTRL_DIG = 2, /*!<For ADC1. Select DIG controller. For ADC2. The controller is selected by the arbiter. Arbiter in default mode. */
ADC2_CTRL_PWDET = 3,/*!<For ADC2. The controller is selected by the arbiter. Arbiter in default mode. */
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_ll_controller_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
APB_SARADC.fsm_wait.rstb_wait = rst_wait;
// Internal FSM start wait time
APB_SARADC.fsm_wait.xpd_wait = start_wait;
// Internal FSM standby wait time
APB_SARADC.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)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Set SAR ADC module clock division factor.
* SAR ADC clock divided from digital controller clock.
*
* @param div Division factor.
*/
static inline void adc_ll_digi_set_clk_div(uint32_t div)
{
/* ADC clock devided from digital controller clock clk */
APB_SARADC.ctrl.sar_clk_div = div;
}
/**
* Set adc output data format for digital controller.
*
* @param format Output data format.
*/
static inline void adc_ll_digi_set_output_format(adc_digi_output_format_t format)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* 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)
{
APB_SARADC.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.
*/
static inline void adc_ll_digi_convert_limit_enable(void)
{
APB_SARADC.ctrl2.meas_num_limit = 1;
}
/**
* Disable max conversion number detection for digital controller.
* If the number of ADC conversion is equal to the maximum, the conversion is stopped.
*/
static inline void adc_ll_digi_convert_limit_disable(void)
{
APB_SARADC.ctrl2.meas_num_limit = 0;
}
/**
* Set adc conversion mode for digital controller.
*
* @note ADC digital controller on C3 only has one pattern table list, and do conversions one by one
*
* @param mode Conversion mode select.
*/
static inline void adc_ll_digi_set_convert_mode(adc_digi_convert_mode_t mode)
{
abort(); // TODO ESP32-C3 IDF-2528
}
/**
* Set pattern table length for digital controller.
*
* @param adc_n ADC unit.
* @param patt_len Items range: 1 ~ 8.
*/
static inline void adc_ll_digi_set_pattern_table_len(adc_ll_num_t adc_n, uint32_t patt_len)
{
/*
* channel 06 04 ADC1 5 ADC2 6 EN_TEST
*/
APB_SARADC.ctrl.sar_patt_len = patt_len - 1;
}
/**
* Set pattern table for digital controller.
*
* @param adc_n ADC unit.
* @param pattern_index Items index. Range: 0 ~ 15.
* @param pattern Stored conversion rules.
*/
static inline void adc_ll_digi_set_pattern_table(adc_ll_num_t adc_n, uint32_t pattern_index, adc_digi_pattern_table_t pattern)
{
/*
* channel 06 04 ADC1 5 ADC2 6 EN_TEST
*/
uint32_t tab;
uint8_t index = pattern_index / 4;
uint8_t offset = (pattern_index % 4) * 6;
tab = APB_SARADC.sar_patt_tab[index].sar_patt_tab1; // Read old register value
tab &= (~(0xFC0000 >> offset)); // clear old data
tab |= ((uint32_t)pattern.val << 18) >> offset; // Fill in the new data
APB_SARADC.sar_patt_tab[index].sar_patt_tab1 = 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_ll_num_t adc_n)
{
/*
* channel 06 04 ADC1 5 ADC2 6 EN_TEST
*/
APB_SARADC.ctrl.sar_patt_p_clear = 1;
APB_SARADC.ctrl.sar_patt_p_clear = 0;
}
/**
* Sets the number of cycles required for the conversion to complete and wait for the arbiter to stabilize.
*
* @note Only ADC2 have arbiter function.
* @param cycle range: 0 ~ 4.
*/
static inline void adc_ll_digi_set_arbiter_stable_cycle(uint32_t cycle)
{
APB_SARADC.ctrl.wait_arb_cycle = cycle;
}
/**
* 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_ll_num_t adc_n, bool inv_en)
{
if (adc_n == ADC_NUM_1) {
APB_SARADC.ctrl2.sar1_inv = inv_en; // Enable / Disable ADC data invert
} else { // adc_n == ADC_NUM_2
APB_SARADC.ctrl2.sar2_inv = inv_en; // Enable / Disable ADC data invert
}
}
/**
* 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.
*/
static inline void adc_ll_digi_set_trigger_interval(uint32_t cycle)
{
APB_SARADC.ctrl2.timer_target = cycle;
}
/**
* Enable digital controller timer to trigger the measurement.
*/
static inline void adc_ll_digi_trigger_enable(void)
{
APB_SARADC.ctrl2.timer_en = 1;
}
/**
* Disable digital controller timer to trigger the measurement.
*/
static inline void adc_ll_digi_trigger_disable(void)
{
APB_SARADC.ctrl2.timer_en = 0;
}
/**
* Set ADC digital controller clock division factor. The clock divided from `APLL` or `APB` clock.
* Expression: controller_clk = APLL/APB * (div_num + div_b / div_a).
*
* @param div_num Division factor. Range: 1 ~ 255.
* @param div_b Division factor. Range: 1 ~ 63.
* @param div_a Division factor. Range: 1 ~ 63.
*/
static inline void adc_ll_digi_controller_clk_div(uint32_t div_num, uint32_t div_b, uint32_t div_a)
{
APB_SARADC.apb_adc_clkm_conf.clkm_div_num = div_num;
APB_SARADC.apb_adc_clkm_conf.clkm_div_b = div_b;
APB_SARADC.apb_adc_clkm_conf.clkm_div_a = div_a;
}
/**
* Enable clock and select clock source for ADC digital controller.
*
* @param use_apll true: use APLL clock; false: use APB clock.
*/
static inline void adc_ll_digi_controller_clk_enable(bool use_apll)
{
if (use_apll) {
APB_SARADC.apb_adc_clkm_conf.clk_sel = 1; // APLL clock
} else {
APB_SARADC.apb_adc_clkm_conf.clk_sel = 2; // APB clock
}
APB_SARADC.ctrl.sar_clk_gated = 1;
}
/**
* Disable clock for ADC digital controller.
*/
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;
}
/**
* Reset adc digital controller filter.
*
* @param adc_n ADC unit.
*/
static inline void adc_ll_digi_filter_reset(adc_ll_num_t adc_n)
{
APB_SARADC.filter_ctrl0.filter_reset = 1;
}
/**
* Set adc digital controller filter factor.
*
* @param adc_n ADC unit.
* @param factor Expression: filter_data = (k-1)/k * last_data + new_data / k. Set values: (2, 4, 8, 16, 64).
*/
static inline void adc_ll_digi_filter_set_factor(adc_ll_num_t adc_n, adc_digi_filter_mode_t factor)
{
adc_channel_t channel = 0;
if (!APB_SARADC.filter_ctrl0.filter_channel0) {
APB_SARADC.filter_ctrl0.filter_channel0 = (adc_n<<4) | channel;
APB_SARADC.filter_ctrl1.filter_factor0 = factor;
} else if (!APB_SARADC.filter_ctrl0.filter_channel1) {
APB_SARADC.filter_ctrl0.filter_channel1 = (adc_n<<4) | channel;
APB_SARADC.filter_ctrl1.filter_factor1 = factor;
}
}
/**
* Get adc digital controller filter factor.
*
* @param adc_n ADC unit.
* @param factor Expression: filter_data = (k-1)/k * last_data + new_data / k. Set values: (2, 4, 8, 16, 64).
*/
static inline void adc_ll_digi_filter_get_factor(adc_ll_num_t adc_n, adc_digi_filter_mode_t *factor)
{
abort(); // TODO ESP32-C3 IDF-2528
}
/**
* Enable/disable adc digital controller filter.
* Filtering the ADC data to obtain smooth data at higher sampling rates.
*
* @note The filter will filter all the enabled channel data of the each ADC unit at the same time.
* @param adc_n ADC unit.
*/
static inline void adc_ll_digi_filter_enable(adc_ll_num_t adc_n, bool enable)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Get the filtered data of adc digital controller filter.
* The data after each measurement and filtering is updated to the DMA by the digital controller. But it can also be obtained manually through this API.
*
* @note The filter will filter all the enabled channel data of the each ADC unit at the same time.
* @param adc_n ADC unit.
* @return Filtered data.
*/
static inline uint32_t adc_ll_digi_filter_read_data(adc_ll_num_t adc_n)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Set monitor mode of adc digital controller.
*
* @note The monitor will monitor all the enabled channel data of the each ADC unit at the same time.
* @param adc_n ADC unit.
* @param is_larger true: If ADC_OUT > threshold, Generates monitor interrupt.
* false: If ADC_OUT < threshold, Generates monitor interrupt.
*/
static inline void adc_ll_digi_monitor_set_mode(adc_ll_num_t adc_n, bool is_larger)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Set monitor threshold of adc digital controller.
*
* @note The monitor will monitor all the enabled channel data of the each ADC unit at the same time.
* @param adc_n ADC unit.
* @param threshold Monitor threshold.
*/
static inline void adc_ll_digi_monitor_set_thres(adc_ll_num_t adc_n, uint32_t threshold)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Enable/disable monitor of adc digital controller.
*
* @note The monitor will monitor all the enabled channel data of the each ADC unit at the same time.
* @param adc_n ADC unit.
*/
static inline void adc_ll_digi_monitor_enable(adc_ll_num_t adc_n, bool enable)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* 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)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* 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)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* 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)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* 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)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* 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)
{
APB_SARADC.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)
{
APB_SARADC.dma_conf.apb_adc_trans = 1;
}
/**
* Disable output data to DMA from adc digital controller.
*/
static inline void adc_ll_digi_dma_disable(void)
{
APB_SARADC.dma_conf.apb_adc_trans = 0;
}
/**
* Reset adc digital controller.
*/
static inline void adc_ll_digi_reset(void)
{
APB_SARADC.dma_conf.apb_adc_reset_fsm = 1;
APB_SARADC.dma_conf.apb_adc_reset_fsm = 0;
}
/*---------------------------------------------------------------
PWDET(Power detect) controller setting
---------------------------------------------------------------*/
/**
* Set adc cct for PWDET controller.
*
* @note Capacitor tuning of the PA power monitor. cct set to the same value with PHY.
* @param cct Range: 0 ~ 7.
*/
static inline void adc_ll_pwdet_set_cct(uint32_t cct)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Get adc cct for PWDET controller.
*
* @note Capacitor tuning of the PA power monitor. cct set to the same value with PHY.
* @return cct Range: 0 ~ 7.
*/
static inline uint32_t adc_ll_pwdet_get_cct(void)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/*---------------------------------------------------------------
RTC controller setting
---------------------------------------------------------------*/
/**
* Set adc output data format for RTC controller.
*
* @note ESP32S2 RTC controller only support 13bit.
* @prarm adc_n ADC unit.
* @prarm bits Output data bits width option.
*/
static inline void adc_ll_rtc_set_output_format(adc_ll_num_t adc_n, adc_bits_width_t bits)
{
return;
}
/**
* Enable adc channel to start convert.
*
* @note Only one channel can be selected for once measurement.
*
* @param adc_n ADC unit.
* @param channel ADC channel number for each ADCn.
*/
static inline void adc_ll_rtc_enable_channel(adc_ll_num_t adc_n, int channel)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Disable adc channel to start convert.
*
* @note Only one channel can be selected in once measurement.
*
* @param adc_n ADC unit.
* @param channel ADC channel number for each ADCn.
*/
static inline void adc_ll_rtc_disable_channel(adc_ll_num_t adc_n, int channel)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Start conversion once by software for RTC controller.
*
* @note It may be block to wait conversion idle for ADC1.
*
* @param adc_n ADC unit.
* @param channel ADC channel number for each ADCn.
*/
static inline void adc_ll_rtc_start_convert(adc_ll_num_t adc_n, int channel)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Check the conversion done flag for each ADCn for RTC controller.
*
* @param adc_n ADC unit.
* @return
* -true : The conversion process is finish.
* -false : The conversion process is not finish.
*/
static inline bool adc_ll_rtc_convert_is_done(adc_ll_num_t adc_n)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Get the converted value for each ADCn for RTC controller.
*
* @param adc_n ADC unit.
* @return
* - Converted value.
*/
static inline int adc_ll_rtc_get_convert_value(adc_ll_num_t adc_n)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* ADC module RTC output data invert or not.
*
* @param adc_n ADC unit.
* @param inv_en data invert or not.
*/
static inline void adc_ll_rtc_output_invert(adc_ll_num_t adc_n, bool inv_en)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Enable ADCn conversion complete interrupt for RTC controller.
*
* @param adc_n ADC unit.
*/
static inline void adc_ll_rtc_intr_enable(adc_ll_num_t adc_n)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Disable ADCn conversion complete interrupt for RTC controller.
*
* @param adc_n ADC unit.
*/
static inline void adc_ll_rtc_intr_disable(adc_ll_num_t adc_n)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Reset RTC controller FSM.
*/
static inline void adc_ll_rtc_reset(void)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Sets the number of cycles required for the conversion to complete and wait for the arbiter to stabilize.
*
* @note Only ADC2 have arbiter function.
* @param cycle range: [0,4].
*/
static inline void adc_ll_rtc_set_arbiter_stable_cycle(uint32_t cycle)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* 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_data ADC raw data input (convert value).
* @return
* - 0: The data is correct to use.
* - 1: The data is invalid. The current controller is not enabled by the arbiter.
* - 2: The data is invalid. The current controller process was interrupted by a higher priority controller.
* - -1: The data is error.
*/
static inline adc_ll_rtc_raw_data_t adc_ll_rtc_analysis_raw_data(adc_ll_num_t adc_n, uint16_t raw_data)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/*---------------------------------------------------------------
Common setting
---------------------------------------------------------------*/
/**
* Set ADC module power management.
*
* @param manage Set ADC power status.
*/
static inline void adc_ll_set_power_manage(adc_ll_power_t manage)
{
// /* Bit1 0:Fsm 1: SW mode
// Bit0 0:SW mode power down 1: SW mode power on */
if (manage == ADC_POWER_SW_ON) {
APB_SARADC.ctrl.sar_clk_gated = 1;
APB_SARADC.ctrl.xpd_sar_force = SENS_FORCE_XPD_SAR_PU;
} else if (manage == ADC_POWER_BY_FSM) {
APB_SARADC.ctrl.sar_clk_gated = 1;
APB_SARADC.ctrl.xpd_sar_force = SENS_FORCE_XPD_SAR_FSM;
} else if (manage == ADC_POWER_SW_OFF) {
APB_SARADC.ctrl.xpd_sar_force = SENS_FORCE_XPD_SAR_PD;
APB_SARADC.ctrl.sar_clk_gated = 1;
}
}
/**
* Get ADC module power management.
*
* @return
* - ADC power status.
*/
static inline adc_ll_power_t adc_ll_get_power_manage(void)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* ADC SAR clock division factor setting. ADC SAR clock devided from `RTC_FAST_CLK`.
*
* @param div Division factor.
*/
static inline void adc_ll_set_sar_clk_div(adc_ll_num_t adc_n, uint32_t div)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* 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 The attenuation option.
*/
static inline void adc_ll_set_atten(adc_ll_num_t adc_n, adc_channel_t channel, adc_atten_t atten)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Get the attenuation of a particular channel on ADCn.
*
* @param adc_n ADC unit.
* @param channel ADCn channel number.
* @return atten The attenuation option.
*/
static inline adc_atten_t adc_ll_get_atten(adc_ll_num_t adc_n, adc_channel_t channel)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* 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_ll_controller_t ctrl)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* 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,
* 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.
*
* @param mode Refer to `adc_arbiter_mode_t`.
*/
static inline void adc_ll_set_arbiter_work_mode(adc_arbiter_mode_t mode)
{
SENS.sar_meas2_mux.sar2_rtc_force = 0; // Enable arbiter in wakeup mode
if (mode == ADC_ARB_MODE_FIX) {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_grant_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_fix_priority = 1;
} else if (mode == ADC_ARB_MODE_LOOP) {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_grant_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_fix_priority = 0;
} else {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_grant_force = 1; // Shield arbiter.
}
}
/**
* 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.
*/
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) {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_rtc_priority = pri_rtc;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_apb_priority = pri_dig;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_wifi_priority = pri_pwdet;
}
/* Should select highest priority controller. */
if (pri_rtc > pri_dig) {
if (pri_rtc > pri_pwdet) {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_apb_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_rtc_force = 1;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_wifi_force = 0;
} else {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_apb_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_rtc_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_wifi_force = 1;
}
} else {
if (pri_dig > pri_pwdet) {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_apb_force = 1;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_rtc_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_wifi_force = 0;
} else {
APB_SARADC.apb_adc_arb_ctrl.adc_arb_apb_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_rtc_force = 0;
APB_SARADC.apb_adc_arb_ctrl.adc_arb_wifi_force = 1;
}
}
}
/**
* Force switch ADC2 to RTC controller in sleep mode. Shield arbiter.
* In sleep mode, the arbiter is in power-down mode.
* Need to switch the controller to RTC to shield the control of the arbiter.
* After waking up, it needs to switch to arbiter control.
*
* @note The hardware will do this automatically. In normal use, there is no need to call this interface to manually switch the controller.
* @note Only support ADC2.
*/
static inline void adc_ll_enable_sleep_controller(void)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/**
* Force switch ADC2 to arbiter in wakeup mode.
* In sleep mode, the arbiter is in power-down mode.
* Need to switch the controller to RTC to shield the control of the arbiter.
* After waking up, it needs to switch to arbiter control.
*
* @note The hardware will do this automatically. In normal use, there is no need to call this interface to manually switch the controller.
* @note Only support ADC2.
*/
static inline void adc_ll_disable_sleep_controller(void)
{
abort(); // TODO ESP32-C3 IDF-2094
}
/* ADC calibration code. */
#define ADC_HAL_CAL_OFFSET_RANGE (4096)
#define ADC_HAL_CAL_TIMES (10)
/**
* Configure the registers for ADC calibration. You need to call the ``adc_ll_calibration_finish`` interface to resume after calibration.
*
* @note Different ADC units and different attenuation options use different calibration data (initial data).
*
* @param adc_n ADC index number.
* @param channel adc channel number.
* @param internal_gnd true: Disconnect from the IO port and use the internal GND as the calibration voltage.
* false: Use IO external voltage as calibration voltage.
*/
static inline void adc_ll_calibration_prepare(adc_ll_num_t adc_n, adc_channel_t channel, bool internal_gnd)
{
// /* Enable i2s_write_reg function. */
// void phy_get_romfunc_addr(void);
// phy_get_romfunc_addr();
// //CLEAR_PERI_REG_MASK(RTC_CNTL_ANA_CONF_REG, RTC_CNTL_SAR_I2C_FORCE_PD_M);
// //SET_PERI_REG_MASK(RTC_CNTL_ANA_CONF_REG, RTC_CNTL_SAR_I2C_FORCE_PU_M);
// CLEAR_PERI_REG_MASK(ANA_CONFIG_REG, BIT(18));
// SET_PERI_REG_MASK(ANA_CONFIG2_REG, BIT(16));
// /* Enable/disable internal connect GND (for calibration). */
// if (adc_n == ADC_NUM_1) {
// REGI2C_WRITE_MASK(I2C_ADC, SAR1_DREF_ADDR, 4);
// if (internal_gnd) {
// REGI2C_WRITE_MASK(I2C_ADC, SAR1_ENCAL_GND_ADDR, 1);
// } else {
// REGI2C_WRITE_MASK(I2C_ADC, SAR1_ENCAL_GND_ADDR, 0);
// }
// } else {
// REGI2C_WRITE_MASK(I2C_ADC, SAR2_DREF_ADDR, 4);
// if (internal_gnd) {
// REGI2C_WRITE_MASK(I2C_ADC, SAR2_ENCAL_GND_ADDR, 1);
// } else {
// REGI2C_WRITE_MASK(I2C_ADC, SAR2_ENCAL_GND_ADDR, 0);
// }
// }
}
/**
* Resume register status after calibration.
*
* @param adc_n ADC index number.
*/
static inline void adc_ll_calibration_finish(adc_ll_num_t adc_n)
{
// if (adc_n == ADC_NUM_1) {
// REGI2C_WRITE_MASK(I2C_ADC, SAR1_ENCAL_GND_ADDR, 0);
// } else {
// REGI2C_WRITE_MASK(I2C_ADC, SAR2_ENCAL_GND_ADDR, 0);
// }
}
/**
* Set the calibration result to ADC.
*
* @note Different ADC units and different attenuation options use different calibration data (initial data).
*
* @param adc_n ADC index number.
*/
static inline void adc_ll_set_calibration_param(adc_ll_num_t adc_n, uint32_t param)
{
// uint8_t msb = param >> 8;
// uint8_t lsb = param & 0xFF;
// /* Enable i2s_write_reg function. */
// void phy_get_romfunc_addr(void);
// phy_get_romfunc_addr();
// //SET_PERI_REG_MASK(RTC_CNTL_ANA_CONF_REG, RTC_CNTL_SAR_I2C_FORCE_PU_M);
// CLEAR_PERI_REG_MASK(ANA_CONFIG_REG, BIT(18));
// SET_PERI_REG_MASK(ANA_CONFIG2_REG, BIT(16));
// if (adc_n == ADC_NUM_1) {
// REGI2C_WRITE_MASK(I2C_ADC, SAR1_INITIAL_CODE_HIGH_ADDR, msb);
// REGI2C_WRITE_MASK(I2C_ADC, SAR1_INITIAL_CODE_LOW_ADDR, lsb);
// } else {
// REGI2C_WRITE_MASK(I2C_ADC, SAR2_INITIAL_CODE_HIGH_ADDR, msb);
// REGI2C_WRITE_MASK(I2C_ADC, SAR2_INITIAL_CODE_LOW_ADDR, lsb);
// }
}
/* Temp code end. */
#ifdef __cplusplus
}
#endif

View File

@ -12,7 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
// The HAL layer for ADC (esp32s2 specific part)
// The HAL layer for ADC (ESP32-S2 specific part)
#include "sdkconfig.h"
#include "hal/adc_hal.h"
@ -23,13 +23,6 @@
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
void adc_hal_digi_init(void)
{
adc_hal_init();
adc_ll_digi_set_clk_div(SOC_ADC_DIGI_SAR_CLK_DIV_DEFAULT);
}
void adc_hal_digi_deinit(void)
{
adc_ll_digi_trigger_disable(); // boss

View File

@ -49,7 +49,7 @@ typedef struct {
};
uint16_t val;
};
} adc_rtc_output_data_t;
} adc_ll_rtc_output_data_t;
/**
* @brief ADC controller type selection.
@ -67,7 +67,7 @@ typedef enum {
ADC2_CTRL_FORCE_RTC = 4, /*!<For ADC2. Arbiter in shield mode. Force select RTC controller work. */
ADC2_CTRL_FORCE_ULP = 5, /*!<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
@ -841,7 +841,7 @@ static inline adc_ll_rtc_raw_data_t adc_ll_rtc_analysis_raw_data(adc_ll_num_t ad
if (adc_n == ADC_NUM_1) {
return ADC_RTC_DATA_OK;
}
adc_rtc_output_data_t *temp = (adc_rtc_output_data_t *)&raw_data;
adc_ll_rtc_output_data_t *temp = (adc_ll_rtc_output_data_t *)&raw_data;
if (temp->flag == 0) {
return ADC_RTC_DATA_OK;
} else if (temp->flag == 1) {
@ -980,7 +980,7 @@ static inline adc_atten_t adc_ll_get_atten(adc_ll_num_t adc_n, adc_channel_t cha
* @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)
static inline void adc_ll_set_controller(adc_ll_num_t adc_n, adc_ll_controller_t ctrl)
{
if (adc_n == ADC_NUM_1) {
switch ( ctrl ) {

View File

@ -34,11 +34,6 @@ extern "C" {
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
/**
* Digital controller initialization.
*/
void adc_hal_digi_init(void);
/**
* Digital controller deinitialization.
*/

View File

@ -64,7 +64,7 @@ typedef struct {
};
uint16_t val;
};
} adc_rtc_output_data_t;
} adc_ll_rtc_output_data_t;
#ifdef _MSC_VER
#pragma pack(pop)
@ -86,7 +86,7 @@ typedef enum {
ADC2_CTRL_FORCE_RTC = 4, /*!<For ADC2. Arbiter in shield mode. Force select RTC controller work. */
ADC2_CTRL_FORCE_ULP = 5, /*!<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
@ -755,7 +755,7 @@ static inline adc_ll_rtc_raw_data_t adc_ll_rtc_analysis_raw_data(adc_ll_num_t ad
if (adc_n == ADC_NUM_1) {
return ADC_RTC_DATA_OK;
}
adc_rtc_output_data_t *temp = (adc_rtc_output_data_t *)&raw_data;
adc_ll_rtc_output_data_t *temp = (adc_ll_rtc_output_data_t *)&raw_data;
if (temp->flag == 0) {
return ADC_RTC_DATA_OK;
} else if (temp->flag == 1) {
@ -872,7 +872,7 @@ static inline adc_atten_t adc_ll_get_atten(adc_ll_num_t adc_n, adc_channel_t cha
* @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)
static inline void adc_ll_set_controller(adc_ll_num_t adc_n, adc_ll_controller_t ctrl)
{
if (adc_n == ADC_NUM_1) {
switch ( ctrl ) {

View File

@ -185,11 +185,6 @@ int adc_hal_convert(adc_ll_num_t adc_n, int channel, int *value);
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
/**
* Digital controller initialization.
*/
void adc_hal_digi_init(void);
/**
* Digital controller deinitialization.
*/
@ -208,3 +203,46 @@ void adc_hal_digi_controller_config(const adc_digi_config_t *cfg);
* @param adc_n ADC unit.
*/
#define adc_hal_digi_clear_pattern_table(adc_n) adc_ll_digi_clear_pattern_table(adc_n)
#if CONFIG_IDF_TARGET_ESP32C3
/*---------------------------------------------------------------
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"
typedef struct adc_dma_hal_context_t {
gdma_dev_t *dev; //address of the general DMA
} adc_dma_hal_context_t;
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;
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_digi_rxdma_start(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config);
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_ena_intr(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config, uint32_t mask);
void adc_hal_digi_clr_intr(adc_dma_hal_context_t *adc_dma_ctx, adc_dma_hal_config_t *dma_config, 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);
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);
#endif //#if CONFIG_IDF_TARGET_ESP32C3

View File

@ -95,6 +95,7 @@ typedef enum {
ADC_WIDTH_MAX,
} adc_bits_width_t;
/**
* @brief ADC digital controller (DMA mode) work mode.
*
@ -123,16 +124,21 @@ typedef struct {
1: measurement range 0 - 1100mV,
2: measurement range 0 - 1350mV,
3: measurement range 0 - 2600mV. */
#ifdef CONFIG_IDF_TARGET_ESP32
#if CONFIG_IDF_TARGET_ESP32
uint8_t bit_width: 2; /*!< ADC resolution.
- 0: 9 bit;
- 1: 10 bit;
- 2: 11 bit;
- 3: 12 bit. */
#else
int8_t channel: 4; /*!< ADC channel index. */
#elif CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3
uint8_t reserved: 2; /*!< reserved0 */
uint8_t channel: 4; /*!< ADC channel index. */
#elif CONFIG_IDF_TARGET_ESP32C3
uint8_t channel: 3; /*!< ADC channel index. */
uint8_t unit: 1; /*!< ADC unit index. */
uint8_t reserved: 2; /*!< reserved0 */
#endif
uint8_t channel: 4; /*!< ADC channel index. */
};
uint8_t val; /*!<Raw data value */
};
@ -149,6 +155,7 @@ typedef enum {
ADC_DIGI_FORMAT_MAX,
} adc_digi_output_format_t;
#if CONFIG_IDF_TARGET_ESP32 || CONFIG_IDF_TARGET_ESP32S2
/**
* @brief ADC digital controller (DMA mode) output data format.
* Used to analyze the acquired ADC (DMA) data.
@ -174,6 +181,26 @@ typedef struct {
uint16_t val; /*!<Raw data value */
};
} adc_digi_output_data_t;
#endif
#if CONFIG_IDF_TARGET_ESP32C3
/**
* @brief ADC digital controller (DMA mode) output data format.
* Used to analyze the acquired ADC (DMA) data.
*/
typedef struct {
union {
struct {
uint32_t data: 13; /*!<ADC real output data info. Resolution: 13 bit. */
uint32_t channel: 3; /*!<ADC channel index info.
If (channel < ADC_CHANNEL_MAX), The data is valid.
If (channel > ADC_CHANNEL_MAX), The data is invalid. */
uint32_t unit: 1; /*!<ADC unit index info. 0: ADC1; 1: ADC2. */
uint32_t reserved: 15;
};
uint32_t val;
};
} adc_digi_output_data_t;
#endif
#if !CONFIG_IDF_TARGET_ESP32
@ -193,7 +220,6 @@ typedef struct {
} adc_digi_clk_t;
#endif //!CONFIG_IDF_TARGET_ESP32
/**
* @brief ADC digital controller (DMA mode) configuration parameters.
*
@ -226,28 +252,36 @@ typedef struct {
* +---------------------+--------+--------+--------+
*/
typedef struct {
bool conv_limit_en; /*!<Enable the function of limiting ADC conversion times.
If the number of ADC conversion trigger count is equal to the `limit_num`, the conversion is stopped. */
uint32_t conv_limit_num; /*!<Set the upper limit of the number of ADC conversion triggers. Range: 1 ~ 255. */
uint32_t adc1_pattern_len; /*!<Pattern table length for digital controller. Range: 0 ~ 16 (0: Don't change the pattern table setting).
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. */
uint32_t adc2_pattern_len; /*!<Refer to ``adc1_pattern_len`` */
bool conv_limit_en; /*!<Enable the function of limiting ADC conversion times.
If the number of ADC conversion trigger count is equal to the `limit_num`, the conversion is stopped. */
uint32_t conv_limit_num; /*!<Set the upper limit of the number of ADC conversion triggers. Range: 1 ~ 255. */
#if CONFIG_IDF_TARGET_ESP32 || CONFIG_IDF_TARGET_ESP32S2
uint32_t adc1_pattern_len; /*!<Pattern table length for digital controller. Range: 0 ~ 16 (0: Don't change the pattern table setting).
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. */
uint32_t adc2_pattern_len; /*!<Refer to ``adc1_pattern_len`` */
adc_digi_pattern_table_t *adc1_pattern; /*!<Pointer to pattern table for digital controller. The table size defined by `adc1_pattern_len`. */
adc_digi_pattern_table_t *adc2_pattern; /*!<Refer to `adc1_pattern` */
adc_digi_convert_mode_t conv_mode; /*!<ADC conversion mode for digital controller. See ``adc_digi_convert_mode_t``. */
adc_digi_output_format_t format; /*!<ADC output data format for digital controller. See ``adc_digi_output_format_t``. */
#elif CONFIG_IDF_TARGET_ESP32C3
uint32_t adc_pattern_len; /*!<Pattern table length for digital controller. Range: 0 ~ 7 (0: Don't change the pattern table setting).
The pattern table that defines the conversion rules for each SAR ADC. Each table has 7 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. */
adc_digi_pattern_table_t *adc_pattern; /*!<Pointer to pattern table for digital controller. The table size defined by `adc_pattern_len`. */
#endif
#if !CONFIG_IDF_TARGET_ESP32
uint32_t interval; /*!<The number of interval clock cycles for the digital controller to trigger the measurement.
The unit is the divided clock. Range: 40 ~ 4095.
Expression: `trigger_meas_freq` = `controller_clk` / 2 / interval. Refer to ``adc_digi_clk_t``.
Note: The sampling rate of each channel is also related to the conversion mode (See ``adc_digi_convert_mode_t``) and pattern table settings. */
adc_digi_clk_t dig_clk; /*!<ADC digital controller clock divider settings. Refer to ``adc_digi_clk_t``.
Note: The clocks of the DAC digital controller use the ADC digital controller clock divider. */
uint32_t dma_eof_num; /*!<DMA eof num of adc digital controller.
If the number of measurements reaches `dma_eof_num`, then `dma_in_suc_eof` signal is generated in DMA.
Note: The converted data in the DMA in link buffer will be multiple of two bytes. */
uint32_t interval; /*!<The number of interval clock cycles for the digital controller to trigger the measurement.
The unit is the divided clock. Range: 40 ~ 4095.
Expression: `trigger_meas_freq` = `controller_clk` / 2 / interval. Refer to ``adc_digi_clk_t``.
Note: The sampling rate of each channel is also related to the conversion mode (See ``adc_digi_convert_mode_t``) and pattern table settings. */
adc_digi_clk_t dig_clk; /*!<ADC digital controller clock divider settings. Refer to ``adc_digi_clk_t``.
Note: The clocks of the DAC digital controller use the ADC digital controller clock divider. */
uint32_t dma_eof_num; /*!<DMA eof num of adc digital controller.
If the number of measurements reaches `dma_eof_num`, then `dma_in_suc_eof` signal is generated in DMA.
Note: The converted data in the DMA in link buffer will be multiple of two bytes. */
#endif
} adc_digi_config_t;

View File

@ -45,6 +45,7 @@ typedef enum {
PERIPH_DS_MODULE,
PERIPH_GDMA_MODULE,
PERIPH_SYSTIMER_MODULE,
PERIPH_SARADC_MODULE,
PERIPH_MODULE_MAX
} periph_module_t;

View File

@ -8,17 +8,21 @@
#define SOC_CPU_CORES_NUM 1
#define SOC_GDMA_SUPPORTED 1
// There are 3 DMA channels on ESP32-C3
// Attention: These fixed DMA channels are temporarily workaround before we have a centralized DMA controller API to help alloc the channel dynamically
// Remove them when GDMA driver API is ready
#define SOC_GDMA_M2M_DMA_CHANNEL (0)
#define SOC_GDMA_SHA_DMA_CHANNEL (1)
#define SOC_GDMA_SPI2_DMA_CHANNEL (2)
#define SOC_GDMA_ADC_DMA_CHANNEL (0)
//NOTE: The CHx number should be consistent with the selected DMA channel above
#define SOC_GDMA_SPI2_INTR_SOURCE ETS_DMA_CH2_INTR_SOURCE
//On C3, there is only 1 GPSPI controller (GPSPI2)
#define SOC_GDMA_SPI3_DMA_CHANNEL SOC_GDMA_SPI2_DMA_CHANNEL
#define SOC_GDMA_ADC_INTR_SOURCE ETS_DMA_CH0_INTR_SOURCE
#include "rmt_caps.h"
#include "adc_caps.h"
#include "dac_caps.h"