IDF release/v4.4 f3e0c8bc41 (#6075)

esp-dsp: master 6b25cbb
esp-face: master 925c72e
esp-rainmaker: f1b82c7
esp32-camera: master 221d24d
esp_littlefs: master 5a13cd6

fixes: #5948
This commit is contained in:
Me No Dev
2022-01-18 17:28:10 +02:00
committed by GitHub
parent 77756d8a06
commit 78b2df74f5
460 changed files with 6448 additions and 5463 deletions

View File

@ -1,16 +1,8 @@
// Copyright 2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* SPDX-FileCopyrightText: 2020-2021 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
/*******************************************************************************
* NOTICE
@ -34,18 +26,6 @@ extern "C" {
/*---------------------------------------------------------------
Digital controller setting
---------------------------------------------------------------*/
/**
* Digital controller deinitialization.
*/
void adc_hal_digi_deinit(void);
/**
* Setting the digital controller.
*
* @param cfg Pointer to digital controller paramter.
*/
void adc_hal_digi_controller_config(const adc_digi_config_t *cfg);
/**
* Reset adc digital controller filter.
*

View File

@ -1,30 +1,22 @@
// 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.
/*
* SPDX-FileCopyrightText: 2015-2021 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include <stdbool.h>
#include <stdlib.h>
#include "hal/misc.h"
#include "regi2c_ctrl.h"
#include "esp_attr.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 "hal/misc.h"
#include "hal/adc_types.h"
#ifdef __cplusplus
extern "C" {
@ -54,6 +46,22 @@ typedef enum {
ADC_RTC_DATA_FAIL = -1,
} adc_ll_rtc_raw_data_t;
typedef enum {
ADC_LL_CTRL_DIG = 0, ///< For ADC1. Select DIG controller.
ADC_LL_CTRL_ARB = 1, ///< For ADC2. The controller is selected by the arbiter.
} adc_ll_controller_t;
/**
* @brief ADC digital controller (DMA mode) work mode.
*
* @note The conversion mode affects the sampling frequency:
* ESP32C3 only support ALTER_UNIT mode
* ALTER_UNIT : When the measurement is triggered, ADC1 or ADC2 samples alternately.
*/
typedef enum {
ADC_LL_DIGI_CONV_ALTER_UNIT = 0, // Use both ADC1 and ADC2 for conversion by turn. e.g. ADC1 -> ADC2 -> ADC1 -> ADC2 .....
} adc_ll_digi_convert_mode_t;
//These values should be set according to the HW
typedef enum {
ADC_LL_INTR_THRES1_LOW = BIT(26),
@ -65,21 +73,17 @@ typedef enum {
} adc_ll_intr_t;
FLAG_ATTR(adc_ll_intr_t)
/**
* @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;
typedef struct {
union {
struct {
uint8_t atten: 2;
uint8_t channel: 3;
uint8_t unit: 1;
uint8_t reserved: 2;
};
uint8_t val;
};
} __attribute__((packed)) adc_ll_digi_pattern_table_t;
/*---------------------------------------------------------------
Digital controller setting
@ -157,6 +161,18 @@ 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 ESP32C3 only support ADC1 single mode.
*
* @param mode Conversion mode select.
*/
static inline void adc_ll_digi_set_convert_mode(adc_ll_digi_convert_mode_t mode)
{
//ESP32C3 only supports ADC_CONV_ALTER_UNIT mode
}
/**
* Set pattern table length for digital controller.
* The pattern table that defines the conversion rules for each SAR ADC. Each table has 8 items, in which channel selection,
@ -181,16 +197,18 @@ static inline void adc_ll_digi_set_pattern_table_len(adc_ll_num_t adc_n, uint32_
* @param pattern_index Items index. Range: 0 ~ 7.
* @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)
static inline void adc_ll_digi_set_pattern_table(adc_ll_num_t adc_n, uint32_t pattern_index, adc_digi_pattern_config_t table)
{
uint32_t tab;
uint8_t index = pattern_index / 4;
uint8_t offset = (pattern_index % 4) * 6;
adc_ll_digi_pattern_table_t pattern = {0};
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 & 0x3F) << 18) >> offset; // Fill in the new data
APB_SARADC.sar_patt_tab[index].sar_patt_tab1 = tab; // Write back
pattern.val = (table.atten & 0x3) | ((table.channel & 0x7) << 2) | ((table.unit & 0x1) << 5);
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 & 0x3F) << 18) >> offset; // Fill in the new data
APB_SARADC.sar_patt_tab[index].sar_patt_tab1 = tab; // Write back
}
/**
@ -260,9 +278,9 @@ static inline void adc_ll_digi_trigger_disable(void)
/**
* 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).
* Expression: controller_clk = (APLL or APB) / (div_num + div_a / div_b + 1).
*
* @param div_num Division factor. Range: 1 ~ 255.
* @param div_num Division factor. Range: 0 ~ 255.
* @param div_b Division factor. Range: 1 ~ 63.
* @param div_a Division factor. Range: 0 ~ 63.
*/
@ -278,7 +296,7 @@ static inline void adc_ll_digi_controller_clk_div(uint32_t div_num, uint32_t div
*
* @param use_apll true: use APLL clock; false: use APB clock.
*/
static inline void adc_ll_digi_controller_clk_enable(bool use_apll)
static inline void adc_ll_digi_clk_sel(bool use_apll)
{
if (use_apll) {
APB_SARADC.apb_adc_clkm_conf.clk_sel = 1; // APLL clock
@ -494,8 +512,8 @@ static inline adc_ll_rtc_raw_data_t adc_ll_analysis_raw_data(adc_ll_num_t adc_n,
*/
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 */
/* 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 = 3;
@ -503,30 +521,14 @@ static inline void adc_ll_set_power_manage(adc_ll_power_t manage)
APB_SARADC.ctrl.sar_clk_gated = 1;
APB_SARADC.ctrl.xpd_sar_force = 0;
} else if (manage == ADC_POWER_SW_OFF) {
APB_SARADC.ctrl.xpd_sar_force = 2;
APB_SARADC.ctrl.sar_clk_gated = 0;
APB_SARADC.ctrl.xpd_sar_force = 2;
}
}
/**
* Get ADC module power management.
*
* @return
* - ADC power status.
*/
static inline adc_ll_power_t adc_ll_get_power_manage(void)
static inline void adc_ll_set_controller(adc_ll_num_t adc_n, adc_ll_controller_t ctrl)
{
/* Bit1 0:Fsm 1: SW mode
Bit0 0:SW mode power down 1: SW mode power on */
adc_ll_power_t manage;
if (APB_SARADC.ctrl.xpd_sar_force == 3) {
manage = ADC_POWER_SW_ON;
} else if (APB_SARADC.ctrl.xpd_sar_force == 2) {
manage = ADC_POWER_SW_OFF;
} else {
manage = ADC_POWER_BY_FSM;
}
return manage;
//Not used on ESP32C3
}
/**

View File

@ -1,16 +1,8 @@
// Copyright 2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* SPDX-FileCopyrightText: 2020-2021 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include <stdint.h>
@ -67,6 +59,7 @@ static inline void gdma_ll_enable_clock(gdma_dev_t *dev, bool enable)
/**
* @brief Get DMA RX channel interrupt status word
*/
__attribute__((always_inline))
static inline uint32_t gdma_ll_rx_get_interrupt_status(gdma_dev_t *dev, uint32_t channel)
{
return dev->intr[channel].st.val & GDMA_LL_RX_EVENT_MASK;
@ -87,6 +80,7 @@ static inline void gdma_ll_rx_enable_interrupt(gdma_dev_t *dev, uint32_t channel
/**
* @brief Clear DMA RX channel interrupt
*/
__attribute__((always_inline))
static inline void gdma_ll_rx_clear_interrupt_status(gdma_dev_t *dev, uint32_t channel, uint32_t mask)
{
dev->intr[channel].clr.val = (mask & GDMA_LL_RX_EVENT_MASK);
@ -127,6 +121,7 @@ static inline void gdma_ll_rx_enable_descriptor_burst(gdma_dev_t *dev, uint32_t
/**
* @brief Reset DMA RX channel FSM and FIFO pointer
*/
__attribute__((always_inline))
static inline void gdma_ll_rx_reset_channel(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].in.in_conf0.in_rst = 1;
@ -172,6 +167,7 @@ static inline uint32_t gdma_ll_rx_pop_data(gdma_dev_t *dev, uint32_t channel)
/**
* @brief Set the descriptor link base address for RX channel
*/
__attribute__((always_inline))
static inline void gdma_ll_rx_set_desc_addr(gdma_dev_t *dev, uint32_t channel, uint32_t addr)
{
dev->channel[channel].in.in_link.addr = addr;
@ -180,6 +176,7 @@ static inline void gdma_ll_rx_set_desc_addr(gdma_dev_t *dev, uint32_t channel, u
/**
* @brief Start dealing with RX descriptors
*/
__attribute__((always_inline))
static inline void gdma_ll_rx_start(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].in.in_link.start = 1;
@ -188,6 +185,7 @@ static inline void gdma_ll_rx_start(gdma_dev_t *dev, uint32_t channel)
/**
* @brief Stop dealing with RX descriptors
*/
__attribute__((always_inline))
static inline void gdma_ll_rx_stop(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].in.in_link.stop = 1;
@ -196,6 +194,7 @@ static inline void gdma_ll_rx_stop(gdma_dev_t *dev, uint32_t channel)
/**
* @brief Restart a new inlink right after the last descriptor
*/
__attribute__((always_inline))
static inline void gdma_ll_rx_restart(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].in.in_link.restart = 1;
@ -220,6 +219,7 @@ static inline bool gdma_ll_rx_is_fsm_idle(gdma_dev_t *dev, uint32_t channel)
/**
* @brief Get RX success EOF descriptor's address
*/
__attribute__((always_inline))
static inline uint32_t gdma_ll_rx_get_success_eof_desc_addr(gdma_dev_t *dev, uint32_t channel)
{
return dev->channel[channel].in.in_suc_eof_des_addr;
@ -228,6 +228,7 @@ static inline uint32_t gdma_ll_rx_get_success_eof_desc_addr(gdma_dev_t *dev, uin
/**
* @brief Get RX error EOF descriptor's address
*/
__attribute__((always_inline))
static inline uint32_t gdma_ll_rx_get_error_eof_desc_addr(gdma_dev_t *dev, uint32_t channel)
{
return dev->channel[channel].in.in_err_eof_des_addr;
@ -236,6 +237,7 @@ static inline uint32_t gdma_ll_rx_get_error_eof_desc_addr(gdma_dev_t *dev, uint3
/**
* @brief Get current RX descriptor's address
*/
__attribute__((always_inline))
static inline uint32_t gdma_ll_rx_get_current_desc_addr(gdma_dev_t *dev, uint32_t channel)
{
return dev->channel[channel].in.in_dscr;
@ -261,6 +263,7 @@ static inline void gdma_ll_rx_connect_to_periph(gdma_dev_t *dev, uint32_t channe
/**
* @brief Get DMA TX channel interrupt status word
*/
__attribute__((always_inline))
static inline uint32_t gdma_ll_tx_get_interrupt_status(gdma_dev_t *dev, uint32_t channel)
{
return dev->intr[channel].st.val & GDMA_LL_TX_EVENT_MASK;
@ -281,6 +284,7 @@ static inline void gdma_ll_tx_enable_interrupt(gdma_dev_t *dev, uint32_t channel
/**
* @brief Clear DMA TX channel interrupt
*/
__attribute__((always_inline))
static inline void gdma_ll_tx_clear_interrupt_status(gdma_dev_t *dev, uint32_t channel, uint32_t mask)
{
dev->intr[channel].clr.val = (mask & GDMA_LL_TX_EVENT_MASK);
@ -337,6 +341,7 @@ static inline void gdma_ll_tx_enable_auto_write_back(gdma_dev_t *dev, uint32_t c
/**
* @brief Reset DMA TX channel FSM and FIFO pointer
*/
__attribute__((always_inline))
static inline void gdma_ll_tx_reset_channel(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].out.out_conf0.out_rst = 1;
@ -382,6 +387,7 @@ static inline void gdma_ll_tx_push_data(gdma_dev_t *dev, uint32_t channel, uint3
/**
* @brief Set the descriptor link base address for TX channel
*/
__attribute__((always_inline))
static inline void gdma_ll_tx_set_desc_addr(gdma_dev_t *dev, uint32_t channel, uint32_t addr)
{
dev->channel[channel].out.out_link.addr = addr;
@ -390,6 +396,7 @@ static inline void gdma_ll_tx_set_desc_addr(gdma_dev_t *dev, uint32_t channel, u
/**
* @brief Start dealing with TX descriptors
*/
__attribute__((always_inline))
static inline void gdma_ll_tx_start(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].out.out_link.start = 1;
@ -398,6 +405,7 @@ static inline void gdma_ll_tx_start(gdma_dev_t *dev, uint32_t channel)
/**
* @brief Stop dealing with TX descriptors
*/
__attribute__((always_inline))
static inline void gdma_ll_tx_stop(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].out.out_link.stop = 1;
@ -406,6 +414,7 @@ static inline void gdma_ll_tx_stop(gdma_dev_t *dev, uint32_t channel)
/**
* @brief Restart a new outlink right after the last descriptor
*/
__attribute__((always_inline))
static inline void gdma_ll_tx_restart(gdma_dev_t *dev, uint32_t channel)
{
dev->channel[channel].out.out_link.restart = 1;
@ -422,6 +431,7 @@ static inline bool gdma_ll_tx_is_fsm_idle(gdma_dev_t *dev, uint32_t channel)
/**
* @brief Get TX EOF descriptor's address
*/
__attribute__((always_inline))
static inline uint32_t gdma_ll_tx_get_eof_desc_addr(gdma_dev_t *dev, uint32_t channel)
{
return dev->channel[channel].out.out_eof_des_addr;
@ -430,6 +440,7 @@ static inline uint32_t gdma_ll_tx_get_eof_desc_addr(gdma_dev_t *dev, uint32_t ch
/**
* @brief Get current TX descriptor's address
*/
__attribute__((always_inline))
static inline uint32_t gdma_ll_tx_get_current_desc_addr(gdma_dev_t *dev, uint32_t channel)
{
return dev->channel[channel].out.out_dscr;

View File

@ -1,21 +1,51 @@
/*
* SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include "esp_err.h"
#include "soc/soc_caps.h"
#include "hal/dma_types.h"
#include "hal/adc_types.h"
#include "hal/adc_ll.h"
#include "esp_err.h"
#if CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32H2
#if SOC_GDMA_SUPPORTED
#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"
#endif
#if CONFIG_IDF_TARGET_ESP32S2
//ADC utilises SPI3 DMA on ESP32S2
#include "hal/spi_ll.h"
#endif
#if CONFIG_IDF_TARGET_ESP32
//ADC utilises I2S0 DMA on ESP32
#include "hal/i2s_ll.h"
#endif
#if SOC_GDMA_SUPPORTED
#define ADC_HAL_DMA_INTR_MASK GDMA_LL_EVENT_RX_SUC_EOF
#elif CONFIG_IDF_TARGET_ESP32S2
#define ADC_HAL_DMA_INTR_MASK SPI_LL_INTR_IN_SUC_EOF
#else //CONFIG_IDF_TARGET_ESP32
#define ADC_HAL_DMA_INTR_MASK BIT(9)
#endif
//For ADC module, each conversion contains 4 bytes
#define ADC_HAL_DATA_LEN_PER_CONV 4
typedef enum adc_hal_work_mode_t {
ADC_HAL_ULP_MODE,
ADC_HAL_SINGLE_READ_MODE,
ADC_HAL_CONTINUOUS_READ_MODE,
ADC_HAL_PWDET_MODE
} adc_hal_work_mode_t;
/**
* @brief Enum for DMA descriptor status
*/
@ -29,6 +59,7 @@ typedef enum adc_hal_dma_desc_status_t {
* @brief Configuration of the HAL
*/
typedef struct adc_hal_config_t {
void *dev; ///< DMA peripheral address
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
@ -42,25 +73,30 @@ typedef struct adc_hal_context_t {
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*/
void *dev; ///< DMA address
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
typedef struct adc_hal_digi_ctrlr_cfg_t {
bool conv_limit_en; //1: adc conversion will stop when `conv_limit_num` reaches. 0: won't stop. NOTE: esp32 should always be set to 1.
uint32_t conv_limit_num; //see `conv_limit_en`
uint32_t adc_pattern_len; //total pattern item number, including ADC1 and ADC2
adc_digi_pattern_config_t *adc_pattern; //pattern item
uint32_t sample_freq_hz; //ADC sample frequency
adc_digi_convert_mode_t conv_mode; //controller work mode
uint32_t bit_width; //output data width
} adc_hal_digi_ctrlr_cfg_t;
/*---------------------------------------------------------------
Common setting
---------------------------------------------------------------*/
/**
* ADC module initialization.
*/
void adc_hal_init(void);
/**
* Set ADC module power management.
*
@ -68,51 +104,7 @@ void adc_hal_init(void);
*/
#define adc_hal_set_power_manage(manage) adc_ll_set_power_manage(manage)
/**
* ADC module clock division factor setting. ADC clock devided from APB clock.
*
* @prarm div Division factor.
*/
#define adc_hal_digi_set_clk_div(div) adc_ll_digi_set_clk_div(div)
#if !CONFIG_IDF_TARGET_ESP32C3 && !CONFIG_IDF_TARGET_ESP32H2
/**
* ADC SAR clock division factor setting. ADC SAR clock devided from `RTC_FAST_CLK`.
*
* @prarm div Division factor.
*/
#define adc_hal_set_sar_clk_div(adc_n, div) adc_ll_set_sar_clk_div(adc_n, div)
/**
* 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.
*
* @prarm adc_n ADC unit.
* @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 && !CONFIG_IDF_TARGET_ESP32H2
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3
/**
* Get the attenuation of a particular channel on ADCn.
*
* @param adc_n ADC unit.
* @param channel ADCn channel number.
* @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
void adc_hal_set_controller(adc_ll_num_t unit, adc_hal_work_mode_t work_mode);
#if SOC_ADC_ARBITER_SUPPORTED
//No ADC2 controller arbiter on ESP32
@ -133,7 +125,6 @@ void adc_hal_arbiter_config(adc_arbiter_t *config);
/*---------------------------------------------------------------
PWDET(Power detect) controller setting
---------------------------------------------------------------*/
/**
* Set adc cct for PWDET controller.
*
@ -150,26 +141,6 @@ void adc_hal_arbiter_config(adc_arbiter_t *config);
*/
#define adc_hal_pwdet_get_cct() adc_ll_pwdet_get_cct()
/*---------------------------------------------------------------
RTC controller setting
---------------------------------------------------------------*/
#if !CONFIG_IDF_TARGET_ESP32C3 && !CONFIG_IDF_TARGET_ESP32H2
/**
* Set adc output data format for RTC controller.
*
* @prarm adc_n ADC unit.
* @prarm bits Output data bits width option.
*/
#define adc_hal_rtc_set_output_format(adc_n, bits) adc_ll_rtc_set_output_format(adc_n, bits)
/**
* ADC module output data invert or not.
*
* @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 //#if !CONFIG_IDF_TARGET_ESP32C3 && !CONFIG_IDF_TARGET_ESP32H2
/**
* Enable/disable the output of ADCn's internal reference voltage to one of ADC2's channels.
*
@ -188,28 +159,108 @@ void adc_hal_arbiter_config(adc_arbiter_t *config);
Digital controller setting
---------------------------------------------------------------*/
/**
* Digital controller deinitialization.
* ADC module initialization.
*/
void adc_hal_digi_deinit(void);
void adc_hal_init(void);
/**
* Digital controller deinitialization.
*
* @param hal Context of the HAL
*/
void adc_hal_digi_deinit(adc_hal_context_t *hal);
/**
* @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);
/**
* @brief Initialize the HW
*
* @param hal Context of the HAL
*/
void adc_hal_digi_init(adc_hal_context_t *hal);
/**
* Setting the digital controller.
*
* @param cfg Pointer to digital controller paramter.
* @param hal Context of the HAL
* @param cfg Pointer to digital controller paramter.
*/
void adc_hal_digi_controller_config(const adc_digi_config_t *cfg);
void adc_hal_digi_controller_config(adc_hal_context_t *hal, const adc_hal_digi_ctrlr_cfg_t *cfg);
/**
* Reset the pattern table pointer, then take the measurement rule from table header in next measurement.
* @brief Start Conversion
*
* @param adc_n ADC unit.
* @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``
*/
#define adc_hal_digi_clear_pattern_table(adc_n) adc_ll_digi_clear_pattern_table(adc_n)
void adc_hal_digi_start(adc_hal_context_t *hal, uint8_t *data_buf);
#if !SOC_GDMA_SUPPORTED
/**
* @brief Get the DMA descriptor that Hardware has finished processing.
*
* @param hal Context of the HAL
*
* @return DMA descriptor address
*/
intptr_t adc_hal_get_desc_addr(adc_hal_context_t *hal);
/**
* @brief Check the hardware interrupt event
*
* @param hal Context of the HAL
* @param mask Event mask
*
* @return True: the event is triggered. False: the event is not triggered yet.
*/
bool adc_hal_check_event(adc_hal_context_t *hal, uint32_t mask);
#endif
/**
* @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);
/**
* @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);
/**
* @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);
/**
* @brief Stop conversion
*
* @param hal Context of the HAL
*/
void adc_hal_digi_stop(adc_hal_context_t *hal);
/*---------------------------------------------------------------
ADC Single Read
---------------------------------------------------------------*/
#if !CONFIG_IDF_TARGET_ESP32C3 && !CONFIG_IDF_TARGET_ESP32H2
#if SOC_ADC_RTC_CTRL_SUPPORTED
/**
* Set the attenuation of a particular channel on ADCn.
*
@ -245,7 +296,7 @@ void adc_hal_digi_controller_config(const adc_digi_config_t *cfg);
*/
#define adc_hal_set_atten(adc_n, channel, atten) adc_ll_set_atten(adc_n, channel, atten)
#else // CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32H2
#else // #if !SOC_ADC_RTC_CTRL_SUPPORTED
/**
* Set the attenuation for ADC to single read
*
@ -256,7 +307,7 @@ void adc_hal_digi_controller_config(const adc_digi_config_t *cfg);
* @param atten ADC attenuation. See ``adc_atten_t``
*/
#define adc_hal_set_atten(adc_n, channel, atten) adc_ll_onetime_set_atten(atten)
#endif
#endif //#if SOC_ADC_RTC_CTRL_SUPPORTED
/**
* Start an ADC conversion and get the converted value.
@ -277,7 +328,6 @@ esp_err_t adc_hal_convert(adc_ll_num_t adc_n, int channel, int *out_raw);
ADC calibration setting
---------------------------------------------------------------*/
#if SOC_ADC_CALIBRATION_V1_SUPPORTED
// ESP32-S2, C3 and H2 support HW offset calibration.
/**
* @brief Initialize default parameter for the calibration block.
@ -314,86 +364,21 @@ uint32_t adc_hal_self_calibration(adc_ll_num_t adc_n, adc_channel_t channel, adc
#endif //SOC_ADC_CALIBRATION_V1_SUPPORTED
#if CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32H2
/*---------------------------------------------------------------
DMA setting
RTC controller setting
---------------------------------------------------------------*/
/**
* @brief Initialize the hal context
* Set adc output data format for RTC controller.
*
* @param hal Context of the HAL
* @param config Configuration of the HAL
* @prarm adc_n ADC unit.
* @prarm bits Output data bits width option.
*/
void adc_hal_context_config(adc_hal_context_t *hal, const adc_hal_config_t *config);
#define adc_hal_rtc_set_output_format(adc_n, bits) adc_ll_rtc_set_output_format(adc_n, bits)
/**
* @brief Initialize the HW
* ADC module output data invert or not.
*
* @param hal Context of the HAL
* @prarm adc_n ADC unit.
*/
void adc_hal_digi_init(adc_hal_context_t *hal);
/**
* @brief Reset ADC / DMA fifo
*
* @param hal Context of the HAL
*/
void adc_hal_fifo_reset(adc_hal_context_t *hal);
/**
* @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);
/**
* @brief Start ADC
*
* @param hal Context of the HAL
*/
void adc_hal_digi_start(adc_hal_context_t *hal);
/**
* @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);
/**
* @brief Stop DMA
*
* @param hal Context of the HAL
*/
void adc_hal_digi_rxdma_stop(adc_hal_context_t *hal);
/**
* @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);
/**
* @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);
/**
* @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 || CONFIG_IDF_TARGET_ESP32H2
#define adc_hal_rtc_output_invert(adc_n, inv_en) adc_ll_rtc_output_invert(adc_n, inv_en)

View File

@ -1,16 +1,8 @@
// Copyright 2020 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* SPDX-FileCopyrightText: 2020-2021 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include <stdbool.h>
@ -62,26 +54,9 @@ typedef enum {
ADC_ATTEN_MAX,
} adc_atten_t;
#ifdef CONFIG_IDF_TARGET_ESP32
/**
* @brief ESP32 ADC DMA source selection.
*/
#else
/**
* @brief ESP32 ADC DMA source selection.
*
* @deprecated Not applicable on ESP32-S2 because ESP32-S2 doesn't use I2S DMA.
*/
#endif
typedef enum {
ADC_I2S_DATA_SRC_IO_SIG = 0, /*!< I2S data from GPIO matrix signal */
ADC_I2S_DATA_SRC_ADC = 1, /*!< I2S data from ADC */
ADC_I2S_DATA_SRC_MAX,
} adc_i2s_source_t;
/**
* @brief ADC resolution setting option.
*
* @note Only used in single read mode
*/
typedef enum {
#if CONFIG_IDF_TARGET_ESP32
@ -97,82 +72,56 @@ typedef enum {
ADC_WIDTH_MAX,
} adc_bits_width_t;
/**
* @brief ADC digital controller (DMA mode) work mode.
*
* @note The conversion mode affects the sampling frequency:
* SINGLE_UNIT_1: When the measurement is triggered, only ADC1 is sampled once.
* SINGLE_UNIT_2: When the measurement is triggered, only ADC2 is sampled once.
* BOTH_UNIT : When the measurement is triggered, ADC1 and ADC2 are sampled at the same time.
* ALTER_UNIT : When the measurement is triggered, ADC1 or ADC2 samples alternately.
*/
typedef enum {
ADC_CONV_SINGLE_UNIT_1 = 1, /*!< SAR ADC 1. */
ADC_CONV_SINGLE_UNIT_2 = 2, /*!< SAR ADC 2. */
ADC_CONV_BOTH_UNIT = 3, /*!< SAR ADC 1 and 2. */
ADC_CONV_ALTER_UNIT = 7, /*!< SAR ADC 1 and 2 alternative mode. */
ADC_CONV_SINGLE_UNIT_1 = 1, ///< Only use ADC1 for conversion
ADC_CONV_SINGLE_UNIT_2 = 2, ///< Only use ADC2 for conversion
ADC_CONV_BOTH_UNIT = 3, ///< Use Both ADC1 and ADC2 for conversion simultaneously
ADC_CONV_ALTER_UNIT = 7, ///< Use both ADC1 and ADC2 for conversion by turn. e.g. ADC1 -> ADC2 -> ADC1 -> ADC2 .....
ADC_CONV_UNIT_MAX,
} adc_digi_convert_mode_t;
/**
* @brief ADC digital controller (DMA mode) conversion rules setting.
*/
typedef struct {
union {
struct {
uint8_t atten: 2; /*!< ADC sampling voltage attenuation configuration. Modification of attenuation affects the range of measurements.
0: measurement range 0 - 800mV,
1: measurement range 0 - 1100mV,
2: measurement range 0 - 1350mV,
3: measurement range 0 - 2600mV. */
#if CONFIG_IDF_TARGET_ESP32
uint8_t bit_width: 2; /*!< ADC resolution.
- 0: 9 bit;
- 1: 10 bit;
- 2: 11 bit;
- 3: 12 bit. */
int8_t channel: 4; /*!< ADC channel index. */
#elif CONFIG_IDF_TARGET_ESP32S2
uint8_t reserved: 2; /*!< reserved0 */
uint8_t channel: 4; /*!< ADC channel index. */
#elif CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32H2
uint8_t channel: 3; /*!< ADC channel index. */
uint8_t unit: 1; /*!< ADC unit index. */
uint8_t reserved: 2; /*!< reserved0 */
#endif
};
uint8_t val; /*!<Raw data value */
};
} adc_digi_pattern_table_t;
/**
* @brief ADC digital controller (DMA mode) output data format option.
*/
typedef enum {
ADC_DIGI_FORMAT_12BIT, /*!<ADC to DMA data format, [15:12]-channel, [11: 0]-12 bits ADC data (`adc_digi_output_data_t`).
Note: For single convert mode. */
ADC_DIGI_FORMAT_11BIT, /*!<ADC to DMA data format, [15]-adc unit, [14:11]-channel, [10: 0]-11 bits ADC data (`adc_digi_output_data_t`).
Note: For multi or alter convert mode. */
ADC_DIGI_FORMAT_MAX,
ADC_DIGI_FORMAT_12BIT __attribute__((deprecated)), /*!<ADC to DMA data format, [15:12]-channel, [11: 0]-12 bits ADC data (`adc_digi_output_data_t`). Note: For single convert mode. */
ADC_DIGI_FORMAT_11BIT __attribute__((deprecated)), /*!<ADC to DMA data format, [15]-adc unit, [14:11]-channel, [10: 0]-11 bits ADC data (`adc_digi_output_data_t`). Note: For multi or alter convert mode. */
ADC_DIGI_FORMAT_MAX __attribute__((deprecated)),
ADC_DIGI_OUTPUT_FORMAT_TYPE1, ///< See `adc_digi_output_data_t.type1`
ADC_DIGI_OUTPUT_FORMAT_TYPE2, ///< See `adc_digi_output_data_t.type2`
} adc_digi_output_format_t;
/**
* @brief ADC digital controller pattern configuration
*/
typedef struct {
uint8_t atten; ///< Attenuation of this ADC channel
uint8_t channel; ///< ADC channel
uint8_t unit; ///< ADC unit
uint8_t bit_width; ///< ADC output bit width
} adc_digi_pattern_config_t;
/*---------------------------------------------------------------
Output Format
---------------------------------------------------------------*/
#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.
*
* @note ESP32-S2:
* Member `channel` can be used to judge the validity of the ADC data, because the role of the arbiter may get invalid ADC data.
* @note ESP32: Only `type1` is valid. ADC2 does not support DMA mode.
* @note ESP32-S2: Member `channel` can be used to judge the validity of the ADC data,
* because the role of the arbiter may get invalid ADC data.
*/
typedef struct {
union {
struct {
uint16_t data: 12; /*!<ADC real output data info. Resolution: 12 bit. */
uint16_t channel: 4; /*!<ADC channel index info. For ESP32-S2:
If (channel < ADC_CHANNEL_MAX), The data is valid.
If (channel > ADC_CHANNEL_MAX), The data is invalid. */
} type1; /*!<When the configured output format is 12bit. `ADC_DIGI_FORMAT_12BIT` */
uint16_t channel: 4; /*!<ADC channel index info. */
} type1;
struct {
uint16_t data: 11; /*!<ADC real output data info. Resolution: 11 bit. */
uint16_t channel: 4; /*!<ADC channel index info. For ESP32-S2:
@ -183,8 +132,8 @@ typedef struct {
uint16_t val; /*!<Raw data value */
};
} adc_digi_output_data_t;
#endif
#if CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32H2
#elif CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32H2
/**
* @brief ADC digital controller (DMA mode) output data format.
* Used to analyze the acquired ADC (DMA) data.
@ -203,112 +152,32 @@ typedef struct {
uint32_t val; /*!<Raw data value */
};
} adc_digi_output_data_t;
#endif
#if !CONFIG_IDF_TARGET_ESP32
#elif CONFIG_IDF_TARGET_ESP32S3
/**
* @brief ADC digital controller (DMA mode) clock system setting.
* Calculation formula: controller_clk = (`APLL` or `APB`) / (div_num + div_a / div_b + 1).
*
* @note: The clocks of the DAC digital controller use the ADC digital controller clock divider.
* @brief ADC digital controller (DMA mode) output data format.
* Used to analyze the acquired ADC (DMA) data.
*/
typedef struct {
bool use_apll; /*!<true: use APLL clock; false: use APB clock. */
uint32_t div_num; /*!<Division factor. Range: 0 ~ 255.
Note: When a higher frequency clock is used (the division factor is less than 9),
the ADC reading value will be slightly offset. */
uint32_t div_b; /*!<Division factor. Range: 1 ~ 63. */
uint32_t div_a; /*!<Division factor. Range: 0 ~ 63. */
} adc_digi_clk_t;
#endif //!CONFIG_IDF_TARGET_ESP32
/**
* @brief ADC digital controller (DMA mode) configuration parameters.
*
* Example setting: When using ADC1 channel0 to measure voltage, the sampling rate is required to be 1 kHz:
*
* +---------------------+--------+--------+--------+
* | sample rate | 1 kHz | 1 kHz | 1 kHz |
* +---------------------+--------+--------+--------+
* | conv_mode | single | both | alter |
* | adc1_pattern_len | 1 | 1 | 1 |
* | dig_clk.use_apll | 0 | 0 | 0 |
* | dig_clk.div_num | 99 | 99 | 99 |
* | dig_clk.div_b | 0 | 0 | 0 |
* | dig_clk.div_a | 0 | 0 | 0 |
* | interval | 400 | 400 | 200 |
* +---------------------+--------+--------+--------+
* | `trigger_meas_freq` | 1 kHz | 1 kHz | 2 kHz |
* +---------------------+--------+--------+--------+
*
* Explanation of the relationship between `conv_limit_num`, `dma_eof_num` and the number of DMA outputs:
*
* +---------------------+--------+--------+--------+
* | conv_mode | single | both | alter |
* +---------------------+--------+--------+--------+
* | trigger meas times | 1 | 1 | 1 |
* +---------------------+--------+--------+--------+
* | conv_limit_num | +1 | +1 | +1 |
* | dma_eof_num | +1 | +2 | +1 |
* | dma output (byte) | +2 | +4 | +2 |
* +---------------------+--------+--------+--------+
*/
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. */
#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 || CONFIG_IDF_TARGET_ESP32H2
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_ESP32S2
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. */
#elif CONFIG_IDF_TARGET_ESP32C3 || CONFIG_IDF_TARGET_ESP32H2
uint32_t sample_freq_hz; /*!< The expected ADC sampling frequency in Hz. Range: 611Hz ~ 83333Hz
Fs = Fd / interval / 2
Fs: sampling frequency;
Fd: digital controller frequency, no larger than 5M for better performance
interval: interval between 2 measurement trigger signal, the smallest interval should not be smaller than the ADC measurement period, the largest interval should not be larger than 4095 */
#endif
} adc_digi_config_t;
#if CONFIG_IDF_TARGET_ESP32S2
/**
* @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)
union {
struct {
uint32_t data: 13; /*!<ADC real output data info. Resolution: 13 bit. */
uint32_t channel: 4; /*!<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 reserved17_31: 14; /*!<Reserved17. */
} type2; /*!<When the configured output format is 12bit. `ADC_DIGI_FORMAT_11BIT` */
uint32_t val; /*!<Raw data value */
};
} adc_digi_output_data_t;
#endif
#if !CONFIG_IDF_TARGET_ESP32
#if SOC_ADC_ARBITER_SUPPORTED
/*---------------------------------------------------------------
Arbiter
---------------------------------------------------------------*/
/**
* @brief ADC arbiter work mode option.
*
@ -344,7 +213,12 @@ typedef struct {
.dig_pri = 0, \
.pwdet_pri = 2, \
}
#endif //#if SOC_ADC_ARBITER_SUPPORTED
#if SOC_ADC_FILTER_SUPPORTED
/*---------------------------------------------------------------
Filter
---------------------------------------------------------------*/
/**
* @brief ADC digital controller (DMA mode) filter index options.
*
@ -387,7 +261,12 @@ typedef struct {
For ESP32-S2, it's always `ADC_CHANNEL_MAX` */
adc_digi_filter_mode_t mode;/*!<Set adc filter mode for filter. See ``adc_digi_filter_mode_t``. */
} adc_digi_filter_t;
#endif // #if SOC_ADC_FILTER_SUPPORTED
#if SOC_ADC_MONITOR_SUPPORTED
/*---------------------------------------------------------------
Monitor
---------------------------------------------------------------*/
/**
* @brief ADC digital controller (DMA mode) monitor index options.
*
@ -437,5 +316,41 @@ typedef struct {
uint32_t threshold; /*!<Set monitor threshold of adc digital controller. */
#endif
} adc_digi_monitor_t;
#endif //#if SOC_ADC_MONITOR_SUPPORTED
#endif // CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3
/*---------------------------------------------------------------
To Be Deprecated TODO: IDF-3610
---------------------------------------------------------------*/
#ifdef CONFIG_IDF_TARGET_ESP32
/**
* @brief ESP32 ADC DMA source selection.
*/
#else
/**
* @brief ESP32 ADC DMA source selection.
*
* @deprecated Not applicable on ESP32-S2 because ESP32-S2 doesn't use I2S DMA.
*/
#endif
typedef enum {
ADC_I2S_DATA_SRC_IO_SIG = 0, /*!< I2S data from GPIO matrix signal */
ADC_I2S_DATA_SRC_ADC = 1, /*!< I2S data from ADC */
ADC_I2S_DATA_SRC_MAX,
} adc_i2s_source_t;
#if CONFIG_IDF_TARGET_ESP32S2
/**
* @brief ADC digital controller (DMA mode) clock system setting.
* Calculation formula: controller_clk = (`APLL` or `APB`) / (div_num + div_a / div_b + 1).
*
* @note: The clocks of the DAC digital controller use the ADC digital controller clock divider.
*/
typedef struct {
bool use_apll; /*!<true: use APLL clock; false: use APB clock. */
uint32_t div_num; /*!<Division factor. Range: 0 ~ 255.
Note: When a higher frequency clock is used (the division factor is less than 9),
the ADC reading value will be slightly offset. */
uint32_t div_b; /*!<Division factor. Range: 1 ~ 63. */
uint32_t div_a; /*!<Division factor. Range: 0 ~ 63. */
} adc_digi_clk_t;
#endif

View File

@ -1,16 +1,8 @@
// Copyright 2021 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.
/*
* SPDX-FileCopyrightText: 2021 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
@ -222,7 +214,7 @@ void emac_hal_set_address(emac_hal_context_t *hal, uint8_t *mac_addr);
void emac_hal_start(emac_hal_context_t *hal);
void emac_hal_stop(emac_hal_context_t *hal);
esp_err_t emac_hal_stop(emac_hal_context_t *hal);
uint32_t emac_hal_get_tx_desc_owner(emac_hal_context_t *hal);