Merge branch 'feature/esp32s2beta_rtc_driver' into 'feature/esp32s2beta'

Feature/esp32s2beta rtc driver

See merge request espressif/esp-idf!5243
This commit is contained in:
morris 2019-08-07 14:43:17 +08:00
commit 1877a9fcd8
44 changed files with 4909 additions and 1630 deletions

View File

@ -81,11 +81,19 @@ void bootloader_random_enable(void)
*/
SET_PERI_REG_BITS(RTC_CNTL_TEST_MUX_REG, RTC_CNTL_DTEST_RTC, 2, RTC_CNTL_DTEST_RTC_S);
SET_PERI_REG_MASK(RTC_CNTL_TEST_MUX_REG, RTC_CNTL_ENT_RTC);
#if CONFIG_IDF_TARGET_ESP32
SET_PERI_REG_MASK(SENS_SAR_START_FORCE_REG, SENS_SAR2_EN_TEST);
DPORT_SET_PERI_REG_MASK(DPORT_PERIP_CLK_EN_REG, DPORT_I2S0_CLK_EN);
CLEAR_PERI_REG_MASK(SENS_SAR_START_FORCE_REG, SENS_ULP_CP_FORCE_START_TOP);
CLEAR_PERI_REG_MASK(SENS_SAR_START_FORCE_REG, SENS_ULP_CP_START_TOP);
#elif CONFIG_IDF_TARGET_ESP32S2BETA
SET_PERI_REG_MASK(SENS_SAR_MEAS2_CTRL1_REG, SENS_SAR2_EN_TEST);
DPORT_SET_PERI_REG_MASK(DPORT_PERIP_CLK_EN_REG, DPORT_I2S0_CLK_EN);
CLEAR_PERI_REG_MASK(RTC_CNTL_ULP_CP_CTRL_REG, RTC_CNTL_ULP_CP_FORCE_START_TOP);
CLEAR_PERI_REG_MASK(RTC_CNTL_ULP_CP_CTRL_REG, RTC_CNTL_ULP_CP_START_TOP);
#endif
// Test pattern configuration byte 0xAD:
//--[7:4] channel_sel: 10-->en_test
//--[3:2] bit_width : 3-->12bit
@ -94,10 +102,15 @@ void bootloader_random_enable(void)
WRITE_PERI_REG(SYSCON_SARADC_SAR2_PATT_TAB2_REG, 0xADADADAD);
WRITE_PERI_REG(SYSCON_SARADC_SAR2_PATT_TAB3_REG, 0xADADADAD);
WRITE_PERI_REG(SYSCON_SARADC_SAR2_PATT_TAB4_REG, 0xADADADAD);
#if CONFIG_IDF_TARGET_ESP32
SET_PERI_REG_BITS(SENS_SAR_MEAS_WAIT2_REG, SENS_FORCE_XPD_SAR, 3, SENS_FORCE_XPD_SAR_S);
SET_PERI_REG_MASK(SENS_SAR_READ_CTRL_REG, SENS_SAR1_DIG_FORCE);
SET_PERI_REG_MASK(SENS_SAR_READ_CTRL2_REG, SENS_SAR2_DIG_FORCE);
#elif CONFIG_IDF_TARGET_ESP32S2BETA
SET_PERI_REG_BITS(SENS_SAR_POWER_XPD_SAR_REG, SENS_FORCE_XPD_SAR, 3, SENS_FORCE_XPD_SAR_S);
SET_PERI_REG_MASK(SENS_SAR_MEAS1_MUX_REG, SENS_SAR1_DIG_FORCE);
#endif
#if CONFIG_IDF_TARGET_ESP32
SET_PERI_REG_MASK(SYSCON_SARADC_CTRL_REG, SYSCON_SARADC_SAR2_MUX);
#endif
@ -137,18 +150,25 @@ void bootloader_random_disable(void)
CLEAR_PERI_REG_MASK(I2S_CONF_REG(0), I2S_RX_START);
/* Restore SYSCON mode registers */
#if CONFIG_IDF_TARGET_ESP32
CLEAR_PERI_REG_MASK(SENS_SAR_READ_CTRL_REG, SENS_SAR1_DIG_FORCE);
CLEAR_PERI_REG_MASK(SENS_SAR_READ_CTRL2_REG, SENS_SAR2_DIG_FORCE);
#elif CONFIG_IDF_TARGET_ESP32S2BETA
CLEAR_PERI_REG_MASK(SENS_SAR_MEAS1_MUX_REG, SENS_SAR1_DIG_FORCE);
#endif
#if CONFIG_IDF_TARGET_ESP32
/* Restore SAR ADC mode */
CLEAR_PERI_REG_MASK(SENS_SAR_START_FORCE_REG, SENS_SAR2_EN_TEST);
#if CONFIG_IDF_TARGET_ESP32
CLEAR_PERI_REG_MASK(SYSCON_SARADC_CTRL_REG, SYSCON_SARADC_SAR2_MUX
| SYSCON_SARADC_SAR_SEL | SYSCON_SARADC_DATA_TO_I2S);
#elif CONFIG_IDF_TARGET_ESP32S2BETA
CLEAR_PERI_REG_MASK(SYSCON_SARADC_CTRL_REG, SYSCON_SARADC_SAR_SEL | SYSCON_SARADC_DATA_TO_I2S);
#endif
SET_PERI_REG_BITS(SENS_SAR_MEAS_WAIT2_REG, SENS_FORCE_XPD_SAR, 0, SENS_FORCE_XPD_SAR_S);
#elif CONFIG_IDF_TARGET_ESP32S2BETA
CLEAR_PERI_REG_MASK(SENS_SAR_MEAS2_CTRL1_REG, SENS_SAR2_EN_TEST);
CLEAR_PERI_REG_MASK(SYSCON_SARADC_CTRL_REG, SYSCON_SARADC_SAR_SEL | SYSCON_SARADC_DATA_TO_I2S);
SET_PERI_REG_BITS(SENS_SAR_POWER_XPD_SAR_REG, SENS_FORCE_XPD_SAR, 0, SENS_FORCE_XPD_SAR_S);
#endif
#if CONFIG_IDF_TARGET_ESP32
SET_PERI_REG_BITS(SYSCON_SARADC_FSM_REG, SYSCON_SARADC_START_WAIT, 8, SYSCON_SARADC_START_WAIT_S);
#endif

View File

@ -29,6 +29,13 @@ set(COMPONENT_ADD_INCLUDEDIRS "include")
set(COMPONENT_PRIV_INCLUDEDIRS "include/driver")
set(COMPONENT_REQUIRES esp_ringbuf soc) #cannot totally hide soc headers, since there are a lot arguments in the driver are chip-dependent
if(CONFIG_IDF_TARGET_ESP32S2BETA)
list(APPEND COMPONENT_SRCS "${CONFIG_IDF_TARGET}/rtc_tempsensor.c"
"${CONFIG_IDF_TARGET}/rtc_touchpad.c")
list(APPEND COMPONENT_ADD_INCLUDEDIRS "${CONFIG_IDF_TARGET}/include")
endif()
register_component()

View File

@ -1,8 +1,9 @@
#
# Component Makefile
#
COMPONENT_SRCDIRS := . $(IDF_TARGET)
COMPONENT_ADD_INCLUDEDIRS := include
COMPONENT_ADD_INCLUDEDIRS := include $(IDF_TARGET)/include
COMPONENT_PRIV_INCLUDEDIRS := include/driver

View File

@ -0,0 +1,96 @@
// Copyright 2010-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.
#pragma once
#include <stdint.h>
#include "esp_err.h"
#ifdef __cplusplus
extern "C" {
#endif
typedef enum {
TSENS_DAC_L0 = 0, /*!< offset = -2, measure range: 50℃ ~ 125℃, error < 3℃. */
TSENS_DAC_L1, /*!< offset = -1, measure range: 20℃ ~ 100℃, error < 2℃. */
TSENS_DAC_L2, /*!< offset = 0, measure range:-10℃ ~ 80℃, error < 1℃. */
TSENS_DAC_L3, /*!< offset = 1, measure range:-30℃ ~ 50℃, error < 2℃. */
TSENS_DAC_L4, /*!< offset = 2, measure range:-40℃ ~ 20℃, error < 3℃. */
TSENS_DAC_MAX,
TSENS_DAC_DEFAULT = TSENS_DAC_L2,
} temp_sensor_dac_offset_t;
typedef struct {
temp_sensor_dac_offset_t dac_offset; /*!< The temperature measurement range is configured with a built-in temperature offset DAC. */
uint8_t clk_div; /*!< Default: 6 */
} temp_sensor_config_t;
#define TSENS_CONFIG_DEFAULT() {.dac_offset = TSENS_DAC_L2, \
.clk_div = 6}
/**
* @brief Set parameter of temperature sensor.
* @param tsens
* @return
* - ESP_OK Success
*/
esp_err_t temp_sensor_set_config(temp_sensor_config_t tsens);
/**
* @brief Get parameter of temperature sensor.
* @param tsens
* @return
* - ESP_OK Success
*/
esp_err_t temp_sensor_get_config(temp_sensor_config_t *tsens);
/**
* @brief Start temperature sensor measure.
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG
*/
esp_err_t temp_sensor_start(void);
/**
* @brief Stop temperature sensor measure.
* @return
* - ESP_OK Success
*/
esp_err_t temp_sensor_stop(void);
/**
* @brief Read temperature sensor raw data.
* @param tsens_out Pointer to raw data, Range: 0 ~ 255
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG `tsens_out` is NULL
* - ESP_ERR_INVALID_STATE temperature sensor dont start
*/
esp_err_t temp_sensor_read_raw(uint32_t *tsens_out);
/**
* @brief Read temperature sensor data that is converted to degrees Celsius.
* @note Should not be called from interrupt.
* @param celsius The measure output value.
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG ARG is NULL.
* - ESP_ERR_INVALID_STATE The ambient temperature is out of range.
*/
esp_err_t temp_sensor_read_celsius(float *celsius);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,144 @@
// 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 "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "esp_log.h"
#include "soc/rtc_io_reg.h"
#include "soc/rtc_io_struct.h"
#include "soc/sens_reg.h"
#include "soc/sens_struct.h"
#include "temp_sensor.h"
#include "esp32s2beta/rom/ets_sys.h"
static const char *TAG = "tsens";
#define TSENS_CHECK(res, ret_val) ({ \
if (!(res)) { \
ESP_LOGE(TAG, "%s:%d (%s)", __FILE__, __LINE__, __FUNCTION__); \
return (ret_val); \
} \
})
#define TSENS_XPD_WAIT_DEFAULT 0xFF /* Set wait cycle time(8MHz) from power up to reset enable. */
#define TSENS_ADC_FACTOR (0.4386)
#define TSENS_DAC_FACTOR (27.88)
#define TSENS_SYS_OFFSET (20.52)
typedef struct {
int index;
int offset;
int set_val;
int range_min;
int range_max;
int error_max;
} tsens_dac_offset_t;
static const tsens_dac_offset_t dac_offset[TSENS_DAC_MAX] = {
/* DAC Offset reg_val min max error */
{TSENS_DAC_L0, -2, 5, 50, 125, 3},
{TSENS_DAC_L1, -1, 7, 20, 100, 2},
{TSENS_DAC_L2, 0, 15, -10, 80, 1},
{TSENS_DAC_L3, 1, 11, -30, 50, 2},
{TSENS_DAC_L4, 2, 10, -40, 20, 3},
};
static SemaphoreHandle_t rtc_tsens_mux = NULL;
esp_err_t temp_sensor_set_config(temp_sensor_config_t tsens)
{
SENS.sar_tctrl.tsens_dac = dac_offset[tsens.dac_offset].set_val;
SENS.sar_tctrl.tsens_clk_div = tsens.clk_div;
SENS.sar_tctrl.tsens_power_up_force = 1;
SENS.sar_tctrl2.tsens_xpd_wait = TSENS_XPD_WAIT_DEFAULT;
SENS.sar_tctrl2.tsens_xpd_force = 1;
SENS.sar_tctrl2.tsens_reset = 1;// Reset the temp sensor.
SENS.sar_tctrl2.tsens_reset = 0;// Clear the reset status.
ESP_LOGI(TAG, "Config temperature range [%d°C ~ %d°C], error < %d°C",
dac_offset[tsens.dac_offset].range_min,
dac_offset[tsens.dac_offset].range_max,
dac_offset[tsens.dac_offset].error_max);
return ESP_OK;
}
esp_err_t temp_sensor_get_config(temp_sensor_config_t *tsens)
{
TSENS_CHECK(tsens != NULL, ESP_ERR_INVALID_ARG);
tsens->dac_offset = SENS.sar_tctrl.tsens_dac;
for(int i=TSENS_DAC_L0; i<TSENS_DAC_MAX; i++) {
if(tsens->dac_offset == dac_offset[i].set_val) {
tsens->dac_offset = dac_offset[i].index;
break;
}
}
tsens->clk_div = SENS.sar_tctrl.tsens_clk_div;
return ESP_OK;
}
esp_err_t temp_sensor_start(void)
{
if (rtc_tsens_mux == NULL) {
rtc_tsens_mux = xSemaphoreCreateMutex();
}
TSENS_CHECK(rtc_tsens_mux != NULL, ESP_ERR_NO_MEM);
SENS.sar_tctrl.tsens_dump_out = 0;
SENS.sar_tctrl2.tsens_clkgate_en = 1;
SENS.sar_tctrl.tsens_power_up = 1;
return ESP_OK;
}
esp_err_t temp_sensor_stop(void)
{
SENS.sar_tctrl.tsens_power_up = 0;
SENS.sar_tctrl2.tsens_clkgate_en = 0;
if (rtc_tsens_mux != NULL) {
vSemaphoreDelete(rtc_tsens_mux);
rtc_tsens_mux = NULL;
}
return ESP_OK;
}
esp_err_t temp_sensor_read_raw(uint32_t *tsens_out)
{
TSENS_CHECK(tsens_out != NULL, ESP_ERR_INVALID_ARG);
TSENS_CHECK(rtc_tsens_mux != NULL, ESP_ERR_INVALID_STATE);
xSemaphoreTake(rtc_tsens_mux, portMAX_DELAY);
SENS.sar_tctrl.tsens_dump_out = 1;
while (!SENS.sar_tctrl.tsens_ready);
*tsens_out = SENS.sar_tctrl.tsens_out;
SENS.sar_tctrl.tsens_dump_out = 0;
xSemaphoreGive(rtc_tsens_mux);
return ESP_OK;
}
esp_err_t temp_sensor_read_celsius(float *celsius)
{
TSENS_CHECK(celsius != NULL, ESP_ERR_INVALID_ARG);
temp_sensor_config_t tsens;
uint32_t tsens_out = 0;
esp_err_t ret = temp_sensor_get_config(&tsens);
if (ret == ESP_OK) {
ret = temp_sensor_read_raw(&tsens_out);
TSENS_CHECK(ret == ESP_OK, ret);
const tsens_dac_offset_t *dac = &dac_offset[tsens.dac_offset];
*celsius = (TSENS_ADC_FACTOR * (float)tsens_out - TSENS_DAC_FACTOR * dac->offset - TSENS_SYS_OFFSET);
if (*celsius < dac->range_min || *celsius > dac->range_max) {
ESP_LOGW(TAG, "Exceeding the temperature range!");
ret = ESP_ERR_INVALID_STATE;
}
}
return ret;
}

View File

@ -0,0 +1,674 @@
// 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 "soc/rtc_periph.h"
#include "soc/sens_periph.h"
#include "soc/rtc_io_reg.h"
#include "soc/rtc_io_struct.h"
#include "soc/sens_reg.h"
#include "soc/sens_struct.h"
#include "soc/rtc_cntl_reg.h"
#include "soc/rtc_cntl_struct.h"
#include "soc/rtc.h"
#include "soc/periph_defs.h"
#include "rtc_io.h"
#include "touch_pad.h"
#include "freertos/FreeRTOS.h"
#include "freertos/xtensa_api.h"
#include "freertos/semphr.h"
#include "freertos/timers.h"
#include "esp_intr_alloc.h"
#include "sys/lock.h"
#include "driver/rtc_cntl.h"
#include "driver/gpio.h"
#include "sdkconfig.h"
#include "esp32s2beta/rom/ets_sys.h"
#ifndef NDEBUG
// Enable built-in checks in queue.h in debug builds
#define INVARIANTS
#endif
#include "sys/queue.h"
#define TOUCH_PAD_FILTER_FACTOR_DEFAULT (4) // IIR filter coefficient.
#define TOUCH_PAD_SHIFT_DEFAULT (4) // Increase computing accuracy.
#define TOUCH_PAD_SHIFT_ROUND_DEFAULT (8) // ROUND = 2^(n-1); rounding off for fractional.
#define TOUCH_PAD_MEASURE_WAIT_DEFAULT (0xFF) // The timer frequency is 8Mhz, the max value is 0xff
#define DAC_ERR_STR_CHANNEL_ERROR "DAC channel error"
#define RTC_MODULE_CHECK(a, str, ret_val) ({ \
if (!(a)) { \
ESP_LOGE(RTC_MODULE_TAG,"%s:%d (%s):%s", __FILE__, __LINE__, __FUNCTION__, str); \
return (ret_val); \
} \
})
#define RTC_RES_CHECK(res, ret_val) ({ \
if ( (res) != ESP_OK) { \
ESP_LOGE(RTC_MODULE_TAG,"%s:%d (%s)", __FILE__, __LINE__, __FUNCTION__);\
return (ret_val); \
} \
})
static portMUX_TYPE rtc_spinlock = portMUX_INITIALIZER_UNLOCKED;
#define RTC_TOUCH_ENTER_CRITICAL() portENTER_CRITICAL(&rtc_spinlock)
#define RTC_TOUCH_EXIT_CRITICAL() portEXIT_CRITICAL(&rtc_spinlock)
static SemaphoreHandle_t rtc_touch_mux = NULL;
static const char *RTC_MODULE_TAG = "RTC_MODULE";
/*---------------------------------------------------------------
Touch Pad
---------------------------------------------------------------*/
esp_err_t touch_pad_isr_register(intr_handler_t fn, void *arg, touch_pad_intr_mask_t intr_mask)
{
assert(fn != NULL);
return rtc_isr_register(fn, arg, TOUCH_PAD_INTR_MASK_ALL & (intr_mask << RTC_CNTL_TOUCH_DONE_INT_ENA_S));
}
esp_err_t touch_pad_isr_deregister(intr_handler_t fn, void *arg)
{
return rtc_isr_deregister(fn, arg);
}
esp_err_t touch_pad_set_meas_time(uint16_t sleep_cycle, uint16_t meas_times)
{
RTC_TOUCH_ENTER_CRITICAL();
// touch sensor sleep cycle Time = sleep_cycle / RTC_SLOW_CLK( can be 150k or 32k depending on the options)
RTCCNTL.touch_ctrl1.touch_sleep_cycles = sleep_cycle;
//The times of charge and discharge in each measure process of touch channels.
RTCCNTL.touch_ctrl1.touch_meas_num = meas_times;
//the waiting cycles (in 8MHz) between TOUCH_START and TOUCH_XPD
RTCCNTL.touch_ctrl2.touch_xpd_wait = TOUCH_PAD_MEASURE_WAIT_DEFAULT; //wait volt stable
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_meas_time(uint16_t *sleep_cycle, uint16_t *meas_times)
{
if (sleep_cycle) {
*sleep_cycle = RTCCNTL.touch_ctrl1.touch_sleep_cycles;
}
if (meas_times) {
*meas_times = RTCCNTL.touch_ctrl1.touch_meas_num;
}
return ESP_OK;
}
esp_err_t touch_pad_set_inactive_connect(touch_pad_conn_type_t type)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_inactive_connection = type;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_inactive_connect(touch_pad_conn_type_t *type)
{
RTC_MODULE_CHECK(type != NULL, "parameter is NULL", ESP_ERR_INVALID_ARG);
*type = RTCCNTL.touch_scan_ctrl.touch_inactive_connection;
return ESP_OK;
}
esp_err_t touch_pad_set_voltage(touch_high_volt_t refh, touch_low_volt_t refl, touch_volt_atten_t atten)
{
RTC_TOUCH_ENTER_CRITICAL();
if (refh > TOUCH_HVOLT_KEEP) {
RTCCNTL.touch_ctrl2.touch_drefh = refh;
}
if (refl > TOUCH_LVOLT_KEEP) {
RTCCNTL.touch_ctrl2.touch_drefl = refl;
}
if (atten > TOUCH_HVOLT_ATTEN_KEEP) {
RTCCNTL.touch_ctrl2.touch_drange = atten;
}
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_voltage(touch_high_volt_t *refh, touch_low_volt_t *refl, touch_volt_atten_t *atten)
{
if (refh) {
*refh = RTCCNTL.touch_ctrl2.touch_drefh;
}
if (refl) {
*refl = RTCCNTL.touch_ctrl2.touch_drefl;
}
if (atten) {
*atten = RTCCNTL.touch_ctrl2.touch_drange;
}
return ESP_OK;
}
esp_err_t touch_pad_set_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t slope, touch_tie_opt_t opt)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCIO.touch_pad[touch_num].tie_opt = opt;
RTCIO.touch_pad[touch_num].dac = slope;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t *slope, touch_tie_opt_t *opt)
{
if (slope) {
*slope = RTCIO.touch_pad[touch_num].dac;
}
if (opt) {
*opt = RTCIO.touch_pad[touch_num].tie_opt;
}
return ESP_OK;
}
esp_err_t touch_pad_io_init(touch_pad_t touch_num)
{
RTC_MODULE_CHECK(touch_num != TOUCH_DENOISE_CHANNEL,
"please use `touch_pad_denoise_enable` to set denoise channel", ESP_ERR_INVALID_ARG);
rtc_gpio_init(touch_num);
rtc_gpio_set_direction(touch_num, RTC_GPIO_MODE_DISABLED);
rtc_gpio_pulldown_dis(touch_num);
rtc_gpio_pullup_dis(touch_num);
return ESP_OK;
}
esp_err_t touch_pad_wait_init_done()
{
// TODO
return ESP_FAIL;
}
esp_err_t touch_pad_fsm_start()
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_ctrl2.touch_clkgate_en = 1; //enable touch clock for FSM. or force enable.
SENS.sar_touch_chn_st.touch_channel_clr = TOUCH_PAD_BIT_MASK_MAX; // clear SENS_TOUCH_SLP_BASELINE
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_fsm_stop()
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_ctrl2.touch_start_en = 0; //stop touch fsm
RTCCNTL.touch_ctrl2.touch_slp_timer_en = 0;
RTCCNTL.touch_ctrl2.touch_clkgate_en = 0; //enable touch clock for FSM. or force enable.
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_set_fsm_mode(touch_fsm_mode_t mode)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_ctrl2.touch_start_en = 0; //stop touch fsm
RTCCNTL.touch_ctrl2.touch_start_force = mode;
RTCCNTL.touch_ctrl2.touch_slp_timer_en = (mode == TOUCH_FSM_MODE_TIMER ? 1 : 0);
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_fsm_mode(touch_fsm_mode_t *mode)
{
assert(mode != NULL);
*mode = RTCCNTL.touch_ctrl2.touch_start_force;
return ESP_OK;
}
bool touch_pad_meas_is_done(void)
{
return SENS.sar_touch_chn_st.touch_meas_done;
}
esp_err_t touch_pad_sw_start(void)
{
RTC_MODULE_CHECK((RTCCNTL.touch_ctrl2.touch_start_force == TOUCH_FSM_MODE_SW),
"touch fsm mode error", ESP_ERR_INVALID_STATE);
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_ctrl2.touch_start_en = 0;
RTCCNTL.touch_ctrl2.touch_start_en = 1;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_set_thresh(touch_pad_t touch_num, uint32_t threshold)
{
RTC_MODULE_CHECK((touch_num < TOUCH_PAD_MAX) && (touch_num != TOUCH_DENOISE_CHANNEL), "touch num error", ESP_ERR_INVALID_ARG);
RTC_TOUCH_ENTER_CRITICAL();
SENS.touch_thresh[touch_num - 1].thresh = threshold;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_thresh(touch_pad_t touch_num, uint32_t *threshold)
{
if (threshold) {
*threshold = SENS.touch_thresh[touch_num - 1].thresh;
}
return ESP_OK;
}
esp_err_t touch_pad_set_group_mask(uint16_t enable_mask)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map |= (enable_mask & TOUCH_PAD_BIT_MASK_MAX);
SENS.sar_touch_conf.touch_outen |= (enable_mask & TOUCH_PAD_BIT_MASK_MAX);
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_group_mask(uint16_t *enable_mask)
{
RTC_TOUCH_ENTER_CRITICAL();
*enable_mask = SENS.sar_touch_conf.touch_outen \
& RTCCNTL.touch_scan_ctrl.touch_scan_pad_map \
& TOUCH_PAD_BIT_MASK_MAX;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_clear_group_mask(uint16_t enable_mask)
{
RTC_TOUCH_ENTER_CRITICAL();
SENS.sar_touch_conf.touch_outen &= ~(enable_mask & TOUCH_PAD_BIT_MASK_MAX);
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map &= ~(enable_mask & TOUCH_PAD_BIT_MASK_MAX);
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
uint32_t IRAM_ATTR touch_pad_get_status(void)
{
return (SENS.sar_touch_chn_st.touch_pad_active & TOUCH_PAD_BIT_MASK_MAX);
}
static esp_err_t touch_pad_clear_status(void)
{
SENS.sar_touch_conf.touch_status_clr = 1;
return ESP_OK;
}
touch_pad_t IRAM_ATTR touch_pad_get_scan_curr(void)
{
return (touch_pad_t)(SENS.sar_touch_status0.touch_scan_curr);
}
esp_err_t touch_pad_intr_enable(touch_pad_intr_mask_t int_mask)
{
RTC_TOUCH_ENTER_CRITICAL();
if (int_mask & TOUCH_PAD_INTR_MASK_DONE) {
RTCCNTL.int_ena.rtc_touch_done = 1;
}
if (int_mask & TOUCH_PAD_INTR_MASK_ACTIVE) {
RTCCNTL.int_ena.rtc_touch_active = 1;
}
if (int_mask & TOUCH_PAD_INTR_MASK_INACTIVE) {
RTCCNTL.int_ena.rtc_touch_inactive = 1;
}
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_intr_disable(touch_pad_intr_mask_t int_mask)
{
RTC_TOUCH_ENTER_CRITICAL();
if (int_mask & TOUCH_PAD_INTR_MASK_DONE) {
RTCCNTL.int_ena.rtc_touch_done = 0;
}
if (int_mask & TOUCH_PAD_INTR_MASK_ACTIVE) {
RTCCNTL.int_ena.rtc_touch_active = 0;
}
if (int_mask & TOUCH_PAD_INTR_MASK_INACTIVE) {
RTCCNTL.int_ena.rtc_touch_inactive = 0;
}
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
uint32_t touch_pad_intr_status_get_mask()
{
return ((REG_READ(RTC_CNTL_INT_ST_REG) >> (RTC_CNTL_TOUCH_DONE_INT_ST_S)) & TOUCH_PAD_INTR_MASK_ALL);
}
esp_err_t touch_pad_config(touch_pad_t touch_num)
{
RTC_MODULE_CHECK(touch_num != TOUCH_DENOISE_CHANNEL, \
"please use `touch_pad_denoise_enable` to set denoise channel", ESP_ERR_INVALID_ARG);
touch_pad_io_init(touch_num);
touch_pad_set_cnt_mode(touch_num, TOUCH_PAD_SLOPE_7, TOUCH_PAD_TIE_OPT_LOW);
touch_pad_set_thresh(touch_num, TOUCH_PAD_THRESHOLD_MAX);
touch_pad_set_group_mask(BIT(touch_num));
return ESP_OK;
}
esp_err_t touch_pad_init()
{
if (rtc_touch_mux == NULL) {
rtc_touch_mux = xSemaphoreCreateMutex();
}
if (rtc_touch_mux == NULL) {
return ESP_ERR_NO_MEM;
}
touch_pad_intr_disable(TOUCH_PAD_INTR_ALL);
touch_pad_clear_group_mask(TOUCH_PAD_BIT_MASK_MAX);
touch_pad_clear_status();
touch_pad_set_meas_time(TOUCH_PAD_SLEEP_CYCLE_DEFAULT, TOUCH_PAD_MEASURE_CYCLE_DEFAULT);
// Set reference voltage for charging/discharging
touch_pad_set_voltage(TOUCH_HVOLT_2V7, TOUCH_LVOLT_0V5, TOUCH_HVOLT_ATTEN_0V5);
touch_pad_set_inactive_connect(TOUCH_PAD_CONN_GND);
return ESP_OK;
}
esp_err_t touch_pad_deinit()
{
RTC_MODULE_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_FAIL);
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
touch_pad_fsm_stop();
touch_pad_clear_status();
touch_pad_intr_disable(TOUCH_PAD_INTR_ALL);
xSemaphoreGive(rtc_touch_mux);
vSemaphoreDelete(rtc_touch_mux);
rtc_touch_mux = NULL;
return ESP_OK;
}
esp_err_t IRAM_ATTR touch_pad_read_raw_data(touch_pad_t touch_num, uint32_t *raw_data)
{
if (raw_data) {
*raw_data = SENS.touch_meas[touch_num].meas_out;
}
return ESP_OK;
}
esp_err_t IRAM_ATTR touch_pad_filter_baseline_read(touch_pad_t touch_num, uint32_t *basedata)
{
RTC_MODULE_CHECK(touch_num != TOUCH_DENOISE_CHANNEL, "denoise channel don't support", ESP_ERR_INVALID_ARG);
if (basedata) {
*basedata = SENS.sar_touch_status[touch_num - 1].touch_pad_baseline;
}
return ESP_OK;
}
esp_err_t touch_pad_filter_debounce_read(touch_pad_t touch_num, uint32_t *debounce)
{
RTC_MODULE_CHECK(touch_num != TOUCH_DENOISE_CHANNEL, "denoise channel don't support", ESP_ERR_INVALID_ARG);
if (debounce) {
*debounce = SENS.sar_touch_status[touch_num - 1].touch_pad_debounce;
}
return ESP_OK;
}
/* Should be call after clk enable and filter enable. */
esp_err_t touch_pad_filter_baseline_reset(touch_pad_t touch_num)
{
RTC_TOUCH_ENTER_CRITICAL();
if (touch_num == TOUCH_PAD_MAX) {
SENS.sar_touch_chn_st.touch_channel_clr = TOUCH_PAD_BIT_MASK_MAX;
} else {
SENS.sar_touch_chn_st.touch_channel_clr = BIT(touch_num);
}
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_filter_set_config(touch_filter_config_t *filter_info)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_filter_ctrl.touch_filter_mode = filter_info->mode;
RTCCNTL.touch_filter_ctrl.touch_debounce = filter_info->debounce_cnt;
RTCCNTL.touch_filter_ctrl.touch_hysteresis = filter_info->hysteresis_thr;
RTCCNTL.touch_filter_ctrl.touch_noise_thres = filter_info->noise_thr;
RTCCNTL.touch_filter_ctrl.touch_neg_noise_thres = filter_info->noise_neg_thr;
RTCCNTL.touch_filter_ctrl.touch_neg_noise_limit = filter_info->neg_noise_limit;
RTCCNTL.touch_filter_ctrl.touch_jitter_step = filter_info->jitter_step;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_filter_get_config(touch_filter_config_t *filter_info)
{
RTC_TOUCH_ENTER_CRITICAL();
filter_info->mode = RTCCNTL.touch_filter_ctrl.touch_filter_mode;
filter_info->debounce_cnt = RTCCNTL.touch_filter_ctrl.touch_debounce;
filter_info->hysteresis_thr = RTCCNTL.touch_filter_ctrl.touch_hysteresis;
filter_info->noise_thr = RTCCNTL.touch_filter_ctrl.touch_noise_thres;
filter_info->noise_neg_thr = RTCCNTL.touch_filter_ctrl.touch_neg_noise_thres;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_filter_enable()
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_filter_ctrl.touch_filter_en = 1;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_filter_disable()
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_filter_ctrl.touch_filter_en = 0;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_enable()
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map &= ~(BIT(TOUCH_DENOISE_CHANNEL));
RTCCNTL.touch_scan_ctrl.touch_denoise_en = 1;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_disable()
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_denoise_en = 0;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_set_config(touch_pad_denoise_t denoise)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCIO.touch_pad[TOUCH_DENOISE_CHANNEL].tie_opt = TOUCH_PAD_TIE_OPT_LOW;
RTCIO.touch_pad[TOUCH_DENOISE_CHANNEL].dac = TOUCH_PAD_SLOPE_7;
RTCCNTL.touch_ctrl2.touch_refc = denoise.cap_level;
RTCCNTL.touch_scan_ctrl.touch_denoise_res = denoise.grade;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_get_config(touch_pad_denoise_t *denoise)
{
RTC_TOUCH_ENTER_CRITICAL();
denoise->grade = RTCCNTL.touch_scan_ctrl.touch_denoise_res;
denoise->cap_level = RTCCNTL.touch_ctrl2.touch_refc;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_data_get(uint32_t *data)
{
if (data) {
*data = SENS.sar_touch_status0.touch_denoise_data;
}
return ESP_OK;
}
esp_err_t touch_pad_waterproof_set_config(touch_pad_waterproof_t waterproof)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_out_ring = waterproof.guard_ring_pad;
RTCCNTL.touch_scan_ctrl.touch_bufdrv = waterproof.shield_driver;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_waterproof_get_config(touch_pad_waterproof_t *waterproof)
{
if (waterproof) {
RTC_TOUCH_ENTER_CRITICAL();
waterproof->guard_ring_pad = RTCCNTL.touch_scan_ctrl.touch_out_ring;
waterproof->shield_driver = RTCCNTL.touch_scan_ctrl.touch_bufdrv;
RTC_TOUCH_EXIT_CRITICAL();
}
return ESP_OK;
}
esp_err_t touch_pad_waterproof_enable()
{
touch_pad_io_init(TOUCH_SHIELD_CHANNEL);
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map &= ~(BIT(TOUCH_SHIELD_CHANNEL));
RTCCNTL.touch_scan_ctrl.touch_shield_pad_en = 1;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_waterproof_disable()
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_shield_pad_en = 0;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_proximity_set_config(touch_pad_proximity_t proximity)
{
RTC_TOUCH_ENTER_CRITICAL();
if (proximity.select_pad0) {
SENS.sar_touch_conf.touch_approach_pad0 = proximity.select_pad0;
}
if (proximity.select_pad1) {
SENS.sar_touch_conf.touch_approach_pad1 = proximity.select_pad1;
}
if (proximity.select_pad2) {
SENS.sar_touch_conf.touch_approach_pad2 = proximity.select_pad2;
}
RTCCNTL.touch_approach.touch_approach_meas_time = proximity.meas_num;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_proximity_get_config(touch_pad_proximity_t *proximity)
{
if (proximity) {
RTC_TOUCH_ENTER_CRITICAL();
proximity->select_pad0 = SENS.sar_touch_conf.touch_approach_pad0;
proximity->select_pad1 = SENS.sar_touch_conf.touch_approach_pad1;
proximity->select_pad2 = SENS.sar_touch_conf.touch_approach_pad2;
proximity->meas_num = RTCCNTL.touch_approach.touch_approach_meas_time;
RTC_TOUCH_EXIT_CRITICAL();
} else {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
esp_err_t touch_pad_proximity_get_meas_cnt(touch_pad_t touch_num, uint32_t *cnt)
{
if (cnt == NULL) {
return ESP_ERR_INVALID_ARG;
}
if (SENS.sar_touch_conf.touch_approach_pad0 == touch_num) {
*cnt = SENS.sar_touch_status16.touch_approach_pad0_cnt;
} else if (SENS.sar_touch_conf.touch_approach_pad1 == touch_num) {
*cnt = SENS.sar_touch_status16.touch_approach_pad1_cnt;
} else if (SENS.sar_touch_conf.touch_approach_pad2 == touch_num) {
*cnt = SENS.sar_touch_status16.touch_approach_pad2_cnt;
} else {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
esp_err_t touch_pad_proximity_data_get(touch_pad_t touch_num, uint32_t *measure_out)
{
if ((SENS.sar_touch_conf.touch_approach_pad0 != touch_num)
&& (SENS.sar_touch_conf.touch_approach_pad1 != touch_num)
&& (SENS.sar_touch_conf.touch_approach_pad2 != touch_num)) {
return ESP_ERR_INVALID_ARG;
}
if (ESP_OK != touch_pad_filter_baseline_read(touch_num, measure_out)) {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
esp_err_t touch_pad_reset()
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_ctrl2.touch_reset = 0;
RTCCNTL.touch_ctrl2.touch_reset = 1;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
/************** sleep pad setting ***********************/
esp_err_t touch_pad_sleep_channel_config(touch_pad_sleep_channel_t slp_config)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_slp_thres.touch_slp_pad = slp_config.touch_num;
RTCCNTL.touch_slp_thres.touch_slp_th = slp_config.sleep_pad_threshold;
RTCCNTL.touch_slp_thres.touch_slp_approach_en = slp_config.en_proximity;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_sleep_channel_baseline_get(uint32_t *baseline)
{
if (baseline) {
*baseline = REG_GET_FIELD(SENS_SAR_TOUCH_STATUS15_REG, SENS_TOUCH_SLP_BASELINE);
} else {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
esp_err_t touch_pad_sleep_channel_debounce_get(uint32_t *debounce)
{
if (debounce) {
*debounce = REG_GET_FIELD(SENS_SAR_TOUCH_STATUS15_REG, SENS_TOUCH_SLP_DEBOUNCE);
} else {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
esp_err_t touch_pad_sleep_channel_proximity_cnt_get(uint32_t *approach_cnt)
{
if (approach_cnt) {
*approach_cnt = REG_GET_FIELD(SENS_SAR_TOUCH_STATUS16_REG, SENS_TOUCH_SLP_APPROACH_CNT);
} else {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
esp_err_t touch_pad_get_wakeup_status(touch_pad_t *pad_num)
{
if (pad_num) {
*pad_num = (touch_pad_t)RTCCNTL.touch_slp_thres.touch_slp_pad;
} else {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}

View File

@ -628,7 +628,6 @@ esp_err_t gpio_force_unhold_all()
SET_PERI_REG_MASK(RTC_CNTL_DIG_ISO_REG, RTC_CNTL_CLR_DG_PAD_AUTOHOLD);
return ESP_OK;
}
#endif
void gpio_iomux_in(uint32_t gpio, uint32_t signal_idx)

View File

@ -53,28 +53,34 @@ typedef enum {
#define ADC_WIDTH_12Bit ADC_WIDTH_BIT_12
typedef enum {
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_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_MAX,
#elif CONFIG_IDF_TARGET_ESP32S2BETA
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;
typedef enum {
ADC2_CHANNEL_0 = 0, /*!< ADC2 channel 0 is GPIO4 */
ADC2_CHANNEL_1, /*!< ADC2 channel 1 is GPIO0 */
ADC2_CHANNEL_2, /*!< ADC2 channel 2 is GPIO2 */
ADC2_CHANNEL_3, /*!< ADC2 channel 3 is GPIO15 */
ADC2_CHANNEL_4, /*!< ADC2 channel 4 is GPIO13 */
ADC2_CHANNEL_5, /*!< ADC2 channel 5 is GPIO12 */
ADC2_CHANNEL_6, /*!< ADC2 channel 6 is GPIO14 */
ADC2_CHANNEL_7, /*!< ADC2 channel 7 is GPIO27 */
ADC2_CHANNEL_8, /*!< ADC2 channel 8 is GPIO25 */
ADC2_CHANNEL_9, /*!< ADC2 channel 9 is GPIO26 */
ADC2_CHANNEL_0 = 0, /*!< ADC2 channel 0 is GPIO4 (ESP32), GPIO11 (ESP32-S2) */
ADC2_CHANNEL_1, /*!< ADC2 channel 1 is GPIO0 (ESP32), GPIO12 (ESP32-S2) */
ADC2_CHANNEL_2, /*!< ADC2 channel 2 is GPIO2 (ESP32), GPIO13 (ESP32-S2) */
ADC2_CHANNEL_3, /*!< ADC2 channel 3 is GPIO15 (ESP32), GPIO14 (ESP32-S2) */
ADC2_CHANNEL_4, /*!< ADC2 channel 4 is GPIO13 (ESP32), GPIO15 (ESP32-S2) */
ADC2_CHANNEL_5, /*!< ADC2 channel 5 is GPIO12 (ESP32), GPIO16 (ESP32-S2) */
ADC2_CHANNEL_6, /*!< ADC2 channel 6 is GPIO14 (ESP32), GPIO17 (ESP32-S2) */
ADC2_CHANNEL_7, /*!< ADC2 channel 7 is GPIO27 (ESP32), GPIO18 (ESP32-S2) */
ADC2_CHANNEL_8, /*!< ADC2 channel 8 is GPIO25 (ESP32), GPIO19 (ESP32-S2) */
ADC2_CHANNEL_9, /*!< ADC2 channel 9 is GPIO26 (ESP32), GPIO20 (ESP32-S2) */
ADC2_CHANNEL_MAX,
} adc2_channel_t;

View File

@ -24,8 +24,8 @@ extern "C" {
#include "soc/dac_periph.h"
typedef enum {
DAC_CHANNEL_1 = 1, /*!< DAC channel 1 is GPIO25 */
DAC_CHANNEL_2, /*!< DAC channel 2 is GPIO26 */
DAC_CHANNEL_1 = 1, /*!< DAC channel 1 is GPIO25 (ESP32), GPIO17 (ESP32-S2) */
DAC_CHANNEL_2, /*!< DAC channel 2 is GPIO26 (ESP32), GPIO18 (ESP32-S2) */
DAC_CHANNEL_MAX,
} dac_channel_t;

View File

@ -316,6 +316,9 @@ typedef enum {
GPIO_NUM_26 = 26, /*!< GPIO26, input and output */
GPIO_NUM_27 = 27, /*!< GPIO27, input and output */
GPIO_NUM_28 = 28, /*!< GPIO28, input and output */
GPIO_NUM_29 = 29, /*!< GPIO29, input and output */
GPIO_NUM_30 = 30, /*!< GPIO30, input and output */
GPIO_NUM_31 = 31, /*!< GPIO31, input and output */
GPIO_NUM_32 = 32, /*!< GPIO32, input and output */
GPIO_NUM_33 = 33, /*!< GPIO33, input and output */
GPIO_NUM_34 = 34, /*!< GPIO34, input and output */

View File

@ -21,6 +21,7 @@ extern "C" {
#include "esp_intr_alloc.h"
#include "soc/touch_periph.h"
#if CONFIG_IDF_TARGET_ESP32
typedef enum {
TOUCH_PAD_NUM0 = 0, /*!< Touch pad channel 0 is GPIO4 */
TOUCH_PAD_NUM1, /*!< Touch pad channel 1 is GPIO0 */
@ -34,6 +35,32 @@ typedef enum {
TOUCH_PAD_NUM9, /*!< Touch pad channel 9 is GPIO32*/
TOUCH_PAD_MAX,
} touch_pad_t;
#elif CONFIG_IDF_TARGET_ESP32S2BETA
typedef enum {
TOUCH_PAD_NUM0 = 0, /*!< Internal channel, be used for denoise */
#define TOUCH_DENOISE_CHANNEL TOUCH_PAD_NUM0 /*!< T0 is an internal channel that does not have a corresponding external GPIO.
T0 will work simultaneously with the measured channel Tn. Finally, the actual
measured value of Tn is the value after subtracting lower bits of T0. */
TOUCH_PAD_NUM1, /*!< Touch channel 1 is GPIO1 */
TOUCH_PAD_NUM2, /*!< Touch channel 2 is GPIO2 */
TOUCH_PAD_NUM3, /*!< Touch channel 3 is GPIO3 */
TOUCH_PAD_NUM4, /*!< Touch channel 4 is GPIO4 */
TOUCH_PAD_NUM5, /*!< Touch channel 5 is GPIO5 */
TOUCH_PAD_NUM6, /*!< Touch channel 6 is GPIO6 */
TOUCH_PAD_NUM7, /*!< Touch channel 7 is GPIO7 */
TOUCH_PAD_NUM8, /*!< Touch channel 8 is GPIO8 */
TOUCH_PAD_NUM9, /*!< Touch channel 9 is GPIO9 */
TOUCH_PAD_NUM10, /*!< Touch channel 9 is GPIO10 */
TOUCH_PAD_NUM11, /*!< Touch channel 9 is GPIO11 */
TOUCH_PAD_NUM12, /*!< Touch channel 9 is GPIO12 */
TOUCH_PAD_NUM13, /*!< Touch channel 9 is GPIO13 */
TOUCH_PAD_NUM14, /*!< Touch channel 9 is GPIO14 */
#define TOUCH_SHIELD_CHANNEL TOUCH_PAD_NUM14 /*!< The waterproof function includes a shielded channel (TOUCH_PAD_NUM14)
The shielded channel outputs the same signal as the channel being measured.
It is generally designed as a grid and is placed around the touch buttons. */
TOUCH_PAD_MAX,
} touch_pad_t;
#endif
typedef enum {
TOUCH_HVOLT_KEEP = -1, /*!<Touch sensor high reference voltage, no change */
@ -74,6 +101,7 @@ typedef enum {
TOUCH_PAD_SLOPE_MAX,
} touch_cnt_slope_t;
#if CONFIG_IDF_TARGET_ESP32
typedef enum {
TOUCH_TRIGGER_BELOW = 0, /*!<Touch interrupt will happen if counter value is less than threshold.*/
TOUCH_TRIGGER_ABOVE = 1, /*!<Touch interrupt will happen if counter value is larger than threshold.*/
@ -85,6 +113,7 @@ typedef enum {
TOUCH_TRIGGER_SOURCE_SET1 = 1, /*!< wakeup interrupt is generated if SET1 is "touched"*/
TOUCH_TRIGGER_SOURCE_MAX,
} touch_trigger_src_t;
#endif
typedef enum {
TOUCH_PAD_TIE_OPT_LOW = 0, /*!<Initial level of charging voltage, low level */
@ -98,9 +127,130 @@ typedef enum {
TOUCH_FSM_MODE_MAX,
} touch_fsm_mode_t;
#if CONFIG_IDF_TARGET_ESP32S2BETA
typedef enum {
TOUCH_PAD_INTR_DONE = 0, /*!<Each enabled channel measure done */
TOUCH_PAD_INTR_ACTIVE = 1, /*!<Each enabled channel be touched */
TOUCH_PAD_INTR_INACTIVE = 2,/*!<Each enabled channel be released */
TOUCH_PAD_INTR_ALL, /*!<All touch interrupt measure done & touched & released */
TOUCH_PAD_INTR_MAX
} touch_pad_intr_type_t;
typedef enum {
TOUCH_PAD_INTR_MASK_DONE = BIT(0), /*!<Each enabled channel measure done */
TOUCH_PAD_INTR_MASK_ACTIVE = BIT(1), /*!<Each enabled channel be touched */
TOUCH_PAD_INTR_MASK_INACTIVE = BIT(2), /*!<Each enabled channel be released */
TOUCH_PAD_INTR_MASK_ALL = BIT(2)|BIT(1)|BIT(0), /*!<All touch interrupt measure done & touched & released */
TOUCH_PAD_INTR_MASK_MAX
} touch_pad_intr_mask_t;
typedef enum {
TOUCH_PAD_DENOISE_BIT12 = 0, /*!<Denoise range is 12bit */
TOUCH_PAD_DENOISE_BIT10 = 1, /*!<Denoise range is 10bit */
TOUCH_PAD_DENOISE_BIT8 = 2, /*!<Denoise range is 8bit */
TOUCH_PAD_DENOISE_BIT4 = 3, /*!<Denoise range is 4bit */
TOUCH_PAD_DENOISE_MAX
} touch_pad_denoise_grade_t;
typedef enum {
TOUCH_PAD_DENOISE_CAP_L0 = 0, /*!<Denoise channel internal reference capacitance is 0pf */
TOUCH_PAD_DENOISE_CAP_L1 = 4, /*!<Denoise channel internal reference capacitance is 1.4pf */
TOUCH_PAD_DENOISE_CAP_L2 = 2, /*!<Denoise channel internal reference capacitance is 2.8pf */
TOUCH_PAD_DENOISE_CAP_L3 = 6, /*!<Denoise channel internal reference capacitance is 4.2pf */
TOUCH_PAD_DENOISE_CAP_L4 = 1, /*!<Denoise channel internal reference capacitance is 5.6pf */
TOUCH_PAD_DENOISE_CAP_L5 = 5, /*!<Denoise channel internal reference capacitance is 7.0pf */
TOUCH_PAD_DENOISE_CAP_L6 = 3, /*!<Denoise channel internal reference capacitance is 8.4pf */
TOUCH_PAD_DENOISE_CAP_L7 = 7, /*!<Denoise channel internal reference capacitance is 9.8pf */
TOUCH_PAD_DENOISE_CAP_MAX
} touch_pad_denoise_cap_t;
typedef struct touch_pad_denoise {
touch_pad_denoise_grade_t grade; /*!<Select denoise channel denoise range.
Determined by measuring the noise amplitude of the denoise channel. */
touch_pad_denoise_cap_t cap_level; /*!<Select denoise channel internal reference capacitance.
Select the appropriate internal reference capacitance value so that
the reading of denoise channel is closest to the reading of the channel being measured. */
} touch_pad_denoise_t;
typedef enum {
TOUCH_PAD_SHIELD_DRV_L0 = 0,/*!<The max equivalent capacitance in shield channel is 40pf */
TOUCH_PAD_SHIELD_DRV_L1, /*!<The max equivalent capacitance in shield channel is 80pf */
TOUCH_PAD_SHIELD_DRV_L2, /*!<The max equivalent capacitance in shield channel is 120pf */
TOUCH_PAD_SHIELD_DRV_L3, /*!<The max equivalent capacitance in shield channel is 160pf */
TOUCH_PAD_SHIELD_DRV_L4, /*!<The max equivalent capacitance in shield channel is 200pf */
TOUCH_PAD_SHIELD_DRV_L5, /*!<The max equivalent capacitance in shield channel is 240pf */
TOUCH_PAD_SHIELD_DRV_L6, /*!<The max equivalent capacitance in shield channel is 280pf */
TOUCH_PAD_SHIELD_DRV_L7, /*!<The max equivalent capacitance in shield channel is 320pf */
TOUCH_PAD_SHIELD_DRV_MAX
} touch_pad_shield_driver_t;
typedef struct touch_pad_waterproof {
touch_pad_t guard_ring_pad; /*!<Waterproof. Select touch channel use for guard pad */
touch_pad_shield_driver_t shield_driver;/*!<Waterproof. Select max equivalent capacitance for sheild pad
Config the Touch14 to the touch sensor and compare the measured
reading to the Touch0 reading to estimate the equivalent capacitance.*/
} touch_pad_waterproof_t;
typedef struct touch_pad_proximity {
touch_pad_t select_pad0; /*!<Select touch channel use for proximity pad1
If clear the proximity channel, point this pad to `TOUCH_PAD_NUM0` */
touch_pad_t select_pad1; /*!<Select touch channel use for proximity pad1 */
touch_pad_t select_pad2; /*!<Select touch channel use for proximity pad1 */
uint8_t meas_num; /*!<Set cumulative number of measurements for proximity pad */
} touch_pad_proximity_t;
typedef enum {
TOUCH_PAD_CONN_HIGHZ = 0, /*!<Idel status of touch channel is high resistance state */
TOUCH_PAD_CONN_GND = 1, /*!<Idel status of touch channel is ground connection */
TOUCH_PAD_CONN_MAX
} touch_pad_conn_type_t;
typedef enum {
TOUCH_PAD_FILTER_IIR_2 = 0, /*!<The filter mode is first-order IIR filter. The coefficient is 2 */
TOUCH_PAD_FILTER_IIR_4, /*!<The filter mode is first-order IIR filter. The coefficient is 4 */
TOUCH_PAD_FILTER_IIR_8, /*!<The filter mode is first-order IIR filter. The coefficient is 8 */
TOUCH_PAD_FILTER_JITTER, /*!<The filter mode is jitter filter */
TOUCH_PAD_FILTER_MAX
} touch_filter_mode_t;
typedef struct touch_filter_config {
touch_filter_mode_t mode; /*!<Set filter mode. The filtered value is baseline
The baseline is an important parameter of the touch algorithm */
uint8_t debounce_cnt; /*!<Set debounce count is n. If the measured values continue to exceed
the threshold for n times, it is determined that the touch sensor state changes.
Range: 0 ~ 7 */
uint8_t hysteresis_thr; /*!<Hysteresis threshold coefficient. hysteresis = hysteresis_thr * touch threshold.
If (raw data - baseline) > (touch threshold + hysteresis), the touch channel be touched.
If (raw data - baseline) < (touch threshold - hysteresis), the touch channel be released.
Range: 0 ~ 3. The coefficient is 0: 1/8; 1: 3/32; 2: 1/16; 3: 1/32 */
uint8_t noise_thr; /*!<Noise threshold coefficient. noise = noise_thr * touch threshold.
If (raw data - baseline) > (noise), the baseline stop updating.
If (raw data - baseline) < (noise), the baseline start updating.
Range: 0 ~ 3. The coefficient is 0: 1/2; 1: 3/8; 2: 1/4; 3: 1/8; */
uint8_t noise_neg_thr; /*!<Negative noise threshold coefficient. negative noise = noise_neg_thr * touch threshold.
If (raw data - baseline) > (- negative noise), the baseline start updating.
If (raw data - baseline) < (- negative noise), the baseline stop updating.
Range: 0 ~ 3. The coefficient is 0: 1/2; 1: 3/8; 2: 1/4; 3: 1/8; */
uint8_t neg_noise_limit; /*!<Set negative noise limit count is n. If the measured values continue to exceed
the negative noise threshold for n times, it is determined that the baseline reset to raw data.
Range: 0 ~ 15 */
uint8_t jitter_step; /*!<Set jitter filter step size. Range: 0 ~ 15 */
} touch_filter_config_t;
typedef struct {
touch_pad_t touch_num; /*!<touch pad index */
uint32_t sleep_pad_threshold; /*!<threshold in sleep mode */
bool en_proximity; /*!<enable proximity function for sleep pad */
} touch_pad_sleep_channel_t;
#define TOUCH_PAD_THRESHOLD_MAX 0x1FFFFF /*!<If set touch threshold max value, The touch sensor can't be in touched status */
#endif // CONFIG_IDF_TARGET_ESP32S2BETA
typedef intr_handle_t touch_isr_handle_t;
#if CONFIG_IDF_TARGET_ESP32
#define TOUCH_PAD_SLEEP_CYCLE_DEFAULT (0x1000) /*!<The timer frequency is RTC_SLOW_CLK (can be 150k or 32k depending on the options), max value is 0xffff */
#define TOUCH_PAD_MEASURE_CYCLE_DEFAULT (0x7fff) /*!<The timer frequency is 8Mhz, the max value is 0x7fff */
#define TOUCH_PAD_MEASURE_WAIT_DEFAULT (0xFF) /*!<The timer frequency is 8Mhz, the max value is 0xff */
@ -109,13 +259,24 @@ typedef intr_handle_t touch_isr_handle_t;
#define TOUCH_TRIGGER_SOURCE_DEFAULT (TOUCH_TRIGGER_SOURCE_SET1) /*!<The wakeup trigger source can be SET1 or both SET1 and SET2 */
#define TOUCH_PAD_BIT_MASK_MAX (0x3ff)
#elif CONFIG_IDF_TARGET_ESP32S2BETA
#define TOUCH_PAD_SLEEP_CYCLE_DEFAULT (0xf) /*!<The number of sleep cycle in each measure process of touch channels.
The timer frequency is RTC_SLOW_CLK (can be 150k or 32k depending on the options).
Range: 0 ~ 0xffff */
#define TOUCH_PAD_MEASURE_CYCLE_DEFAULT (300) /*!<The times of charge and discharge in each measure process of touch channels.
The timer frequency is 8Mhz.
Range: 0 ~ 0xffff */
#define TOUCH_PAD_BIT_MASK_MAX (0x7fff)/*! 15 Touch channels */
#endif // CONFIG_IDF_TARGET_ESP32
/**
* @brief Initialize touch module.
* @note The default FSM mode is 'TOUCH_FSM_MODE_SW'. If you want to use interrupt trigger mode,
* then set it using function 'touch_pad_set_fsm_mode' to 'TOUCH_FSM_MODE_TIMER' after calling 'touch_pad_init'.
* @note If default parameter don't match the usage scenario, it can be changed after this function.
* @return
* - ESP_OK Success
* - ESP_FAIL Touch pad init error
* - ESP_ERR_NO_MEM Touch pad init error
*/
esp_err_t touch_pad_init();
@ -128,6 +289,121 @@ esp_err_t touch_pad_init();
*/
esp_err_t touch_pad_deinit();
/**
* @brief Deregister the handler previously registered using touch_pad_isr_handler_register
* @param fn handler function to call (as passed to touch_pad_isr_handler_register)
* @param arg argument of the handler (as passed to touch_pad_isr_handler_register)
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_STATE if a handler matching both fn and
* arg isn't registered
*/
esp_err_t touch_pad_isr_deregister(void(*fn)(void *), void *arg);
/**
* @brief Set touch sensor reference voltage, if the voltage gap between high and low reference voltage get less,
* the charging and discharging time would be faster, accordingly, the counter value would be larger.
* In the case of detecting very slight change of capacitance, we can narrow down the gap so as to increase
* the sensitivity. On the other hand, narrow voltage gap would also introduce more noise, but we can use a
* software filter to pre-process the counter value.
* @param refh the value of DREFH
* @param refl the value of DREFL
* @param atten the attenuation on DREFH
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_set_voltage(touch_high_volt_t refh, touch_low_volt_t refl, touch_volt_atten_t atten);
/**
* @brief Get touch sensor reference voltage,
* @param refh pointer to accept DREFH value
* @param refl pointer to accept DREFL value
* @param atten pointer to accept the attenuation on DREFH
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_voltage(touch_high_volt_t *refh, touch_low_volt_t *refl, touch_volt_atten_t *atten);
/**
* @brief Set touch sensor charge/discharge speed for each pad.
* If the slope is 0, the counter would always be zero.
* If the slope is 1, the charging and discharging would be slow, accordingly, the counter value would be small.
* If the slope is set 7, which is the maximum value, the charging and discharging would be fast, accordingly, the
* counter value would be larger.
* @param touch_num touch pad index
* @param slope touch pad charge/discharge speed
* @param opt the initial voltage
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_set_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t slope, touch_tie_opt_t opt);
/**
* @brief Get touch sensor charge/discharge speed for each pad
* @param touch_num touch pad index
* @param slope pointer to accept touch pad charge/discharge slope
* @param opt pointer to accept the initial voltage
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_get_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t *slope, touch_tie_opt_t *opt);
/**
* @brief Initialize touch pad GPIO
* @param touch_num touch pad index
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_io_init(touch_pad_t touch_num);
/**
* @brief Set touch sensor FSM mode, the test action can be triggered by the timer,
* as well as by the software.
* @param mode FSM mode
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_set_fsm_mode(touch_fsm_mode_t mode);
/**
* @brief Get touch sensor FSM mode
* @param mode pointer to accept FSM mode
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_fsm_mode(touch_fsm_mode_t *mode);
/**
* @brief Trigger a touch sensor measurement, only support in SW mode of FSM
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_sw_start();
/**
* @brief Get the touch sensor status bit mask. usually used in ISR to decide which pads are 'touched'.
* If status bit is 1, this pad is be touched, else, this pad is released.
* @return
* - touch status
*/
uint32_t touch_pad_get_status();
/**
* @brief Get the touch pad which caused wakeup from sleep
* @param pad_num pointer to touch pad which caused wakeup
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG parameter is NULL
*/
esp_err_t touch_pad_get_wakeup_status(touch_pad_t *pad_num);
#if CONFIG_IDF_TARGET_ESP32
/**
* @brief Configure touch pad interrupt threshold.
*
@ -248,17 +524,6 @@ esp_err_t touch_pad_isr_handler_register(void(*fn)(void *), void *arg, int unuse
*/
esp_err_t touch_pad_isr_register(intr_handler_t fn, void* arg);
/**
* @brief Deregister the handler previously registered using touch_pad_isr_handler_register
* @param fn handler function to call (as passed to touch_pad_isr_handler_register)
* @param arg argument of the handler (as passed to touch_pad_isr_handler_register)
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_STATE if a handler matching both fn and
* arg isn't registered
*/
esp_err_t touch_pad_isr_deregister(void(*fn)(void *), void *arg);
/**
* @brief Set touch sensor measurement and sleep time
* @param sleep_cycle The touch sensor will sleep after each measurement.
@ -281,91 +546,6 @@ esp_err_t touch_pad_set_meas_time(uint16_t sleep_cycle, uint16_t meas_cycle);
*/
esp_err_t touch_pad_get_meas_time(uint16_t *sleep_cycle, uint16_t *meas_cycle);
/**
* @brief Set touch sensor reference voltage, if the voltage gap between high and low reference voltage get less,
* the charging and discharging time would be faster, accordingly, the counter value would be larger.
* In the case of detecting very slight change of capacitance, we can narrow down the gap so as to increase
* the sensitivity. On the other hand, narrow voltage gap would also introduce more noise, but we can use a
* software filter to pre-process the counter value.
* @param refh the value of DREFH
* @param refl the value of DREFL
* @param atten the attenuation on DREFH
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_set_voltage(touch_high_volt_t refh, touch_low_volt_t refl, touch_volt_atten_t atten);
/**
* @brief Get touch sensor reference voltage,
* @param refh pointer to accept DREFH value
* @param refl pointer to accept DREFL value
* @param atten pointer to accept the attenuation on DREFH
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_voltage(touch_high_volt_t *refh, touch_low_volt_t *refl, touch_volt_atten_t *atten);
/**
* @brief Set touch sensor charge/discharge speed for each pad.
* If the slope is 0, the counter would always be zero.
* If the slope is 1, the charging and discharging would be slow, accordingly, the counter value would be small.
* If the slope is set 7, which is the maximum value, the charging and discharging would be fast, accordingly, the
* counter value would be larger.
* @param touch_num touch pad index
* @param slope touch pad charge/discharge speed
* @param opt the initial voltage
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_set_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t slope, touch_tie_opt_t opt);
/**
* @brief Get touch sensor charge/discharge speed for each pad
* @param touch_num touch pad index
* @param slope pointer to accept touch pad charge/discharge slope
* @param opt pointer to accept the initial voltage
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_get_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t *slope, touch_tie_opt_t *opt);
/**
* @brief Initialize touch pad GPIO
* @param touch_num touch pad index
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_io_init(touch_pad_t touch_num);
/**
* @brief Set touch sensor FSM mode, the test action can be triggered by the timer,
* as well as by the software.
* @param mode FSM mode
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_set_fsm_mode(touch_fsm_mode_t mode);
/**
* @brief Get touch sensor FSM mode
* @param mode pointer to accept FSM mode
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_fsm_mode(touch_fsm_mode_t *mode);
/**
* @brief Trigger a touch sensor measurement, only support in SW mode of FSM
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_sw_start();
/**
* @brief Set touch sensor interrupt threshold
* @param touch_num touch pad index
@ -470,13 +650,6 @@ esp_err_t touch_pad_clear_group_mask(uint16_t set1_mask, uint16_t set2_mask, uin
*/
esp_err_t touch_pad_clear_status();
/**
* @brief Get the touch sensor status, usually used in ISR to decide which pads are 'touched'.
* @return
* - touch status
*/
uint32_t touch_pad_get_status();
/**
* @brief To enable touch pad interrupt
* @return
@ -550,14 +723,449 @@ esp_err_t touch_pad_filter_stop();
*/
esp_err_t touch_pad_filter_delete();
#elif CONFIG_IDF_TARGET_ESP32S2BETA
/**
* @brief Get the touch pad which caused wakeup from sleep
* @param pad_num pointer to touch pad which caused wakeup
* @brief Set touch sensor FSM start
* @note Start FSM after the touch sensor FSM mode is set.
* @note Call this function will reset beseline of all touch channels.
* @return
* - ESP_OK Success
* - ESP_FAIL get status err
* - ESP_OK on success
*/
esp_err_t touch_pad_get_wakeup_status(touch_pad_t *pad_num);
esp_err_t touch_pad_fsm_start();
/**
* @brief Stop touch sensor FSM.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_fsm_stop();
/**
* @brief Set touch sensor measurement and sleep time
* @param sleep_cycle The touch sensor will sleep after each measurement.
* sleep_cycle decide the interval between each measurement.
* t_sleep = sleep_cycle / (RTC_SLOW_CLK frequency).
* The approximate frequency value of RTC_SLOW_CLK can be obtained using rtc_clk_slow_freq_get_hz function.
* @param meas_timers The times of charge and discharge in each measure process of touch channels.
* The timer frequency is 8Mhz. Range: 0 ~ 0xffff.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_set_meas_time(uint16_t sleep_cycle, uint16_t meas_times);
/**
* @brief Get touch sensor measurement and sleep time
* @param sleep_cycle Pointer to accept sleep cycle number
* @param meas_times Pointer to accept measurement times count.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_meas_time(uint16_t *sleep_cycle, uint16_t *meas_times);
/**
* @brief Set idel status of touch channel. The measurement of each touch channel is not in same time,
* So, The value of touch channel can be effected by other's inactive status.
* The high resistance setting increases the sensitivity of adjacent touch channels.
* The grounding setting increases the stability of adjacent touch channels.
* @param type Select connect to high resistance state or ground.
* Default: TOUCH_PAD_CONN_GND.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_set_inactive_connect(touch_pad_conn_type_t type);
/**
* @brief Get idel status of touch channel. The measurement of each touch channel is not in same time,
* So, The value of touch channel can be effected by other's inactive status.
* The high resistance setting increases the sensitivity of adjacent touch channels.
* The grounding setting increases the stability of adjacent touch channels.
* @param type Pointer to connection type.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_inactive_connect(touch_pad_conn_type_t *type);
/**
* @brief Set the trigger threshold of touch sensor.
* The threshold determines the sensitivity of the touch sensor.
* threshold < (touched raw data - released raw data).
* @note If set "TOUCH_PAD_THRESHOLD_MAX", the touch is never be trigered.
* @param touch_num touch pad index
* @param threshold threshold of touch sensor. Should be less than the max change value of touch.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_set_thresh(touch_pad_t touch_num, uint32_t threshold);
/**
* @brief Get touch sensor trigger threshold
* @param touch_num touch pad index
* @param threshold pointer to accept threshold
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_get_thresh(touch_pad_t touch_num, uint32_t *threshold);
/**
* @brief Register touch channel into touch sensor scan group.
* The working mode of the touch sensor is cyclically scanned.
* This function will set the scan bits according to the given bitmask.
* @note If set this mask, the FSM timer should be stop firsty.
* @note The touch sensor that in scan map, should be deinit GPIO function firstly by `touch_pad_io_init`.
* @param enable_mask bitmask of touch sensor scan group.
* e.g. TOUCH_PAD_NUM14 -> BIT(14)
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_set_group_mask(uint16_t enable_mask);
/**
* @brief Get the touch sensor scan group bit mask.
* @param enable_mask Pointer to bitmask of touch sensor scan group.
* e.g. TOUCH_PAD_NUM14 -> BIT(14)
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_group_mask(uint16_t *enable_mask);
/**
* @brief Clear touch channel from touch sensor scan group.
* The working mode of the touch sensor is cyclically scanned.
* This function will clear the scan bits according to the given bitmask.
* @note If clear all mask, the FSM timer should be stop firsty.
* @param enable_mask bitmask of touch sensor scan group.
* e.g. TOUCH_PAD_NUM14 -> BIT(14)
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_clear_group_mask(uint16_t enable_mask);
/**
* @brief Configure parameter for each touch channel.
* @note Touch num 0 is denoise channel, please use `touch_pad_denoise_enable` to set denoise function
* @param touch_num touch pad index
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG if argument wrong
* - ESP_FAIL if touch pad not initialized
*/
esp_err_t touch_pad_config(touch_pad_t touch_num);
/**
* @brief Reset the whole of touch module.
* @note Call this funtion after `touch_pad_fsm_stop`,
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_reset();
/**
* @brief Check touch sensor measurement status.
* If doing measurement, the flag will be clear.
* If finish measurement. the flag will be set.
* @return
* - TRUE finish measurement
* - FALSE doing measurement
*/
bool touch_pad_meas_is_done(void);
/**
* @brief Get the current scan channel.
* usually used in ISR to decide channel scaning, and then, get the current measurement value.
* The role of each bit is reference to type `touch_pad_intr_mask_t`.
* @return
* - touch channel number
*/
touch_pad_t touch_pad_get_scan_curr();
/**
* @brief Get the touch sensor interrupt status mask. usually used in ISR to decide interrupt type.
* The role of each bit is reference to type `touch_pad_intr_mask_t`.
* @return
* - touch intrrupt bit
*/
uint32_t touch_pad_intr_status_get_mask();
/**
* @brief Enable touch sensor interrupt.
* @param type interrupt type
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_intr_enable(touch_pad_intr_mask_t int_mask);
/**
* @brief Disable touch sensor interrupt.
* @param type interrupt type
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_intr_disable(touch_pad_intr_mask_t int_mask);
/**
* @brief Register touch-pad ISR.
* The handler will be attached to the same CPU core that this function is running on.
* @param fn Pointer to ISR handler
* @param arg Parameter for ISR
* @return
* - ESP_OK Success ;
* - ESP_ERR_INVALID_ARG GPIO error
* - ESP_ERR_NO_MEM No memory
*/
esp_err_t touch_pad_isr_register(intr_handler_t fn, void* arg, touch_pad_intr_mask_t intr_mask);
/**
* @brief get raw data of touch sensor.
* @note After the initialization is complete, the "raw_data" is max value. You need to wait for a measurement
* cycle before you can read the correct touch value.
* @param touch_num touch pad index
* @param raw_data pointer to accept touch sensor value
* @return
* - ESP_OK Success
* - ESP_FAIL Touch channel 0 havent this parameter.
*/
esp_err_t touch_pad_read_raw_data(touch_pad_t touch_num, uint32_t *raw_data);
/**
* @brief get baseline of touch sensor.
* @note After the initialization is complete, the "touch_value" is max value. You need to wait for a measurement
* cycle before you can read the correct touch value.
* @param touch_num touch pad index
* @param touch_value pointer to accept touch sensor value
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Touch channel 0 havent this parameter.
*/
esp_err_t touch_pad_filter_baseline_read(touch_pad_t touch_num, uint32_t *basedata);
/**
* @brief Reset baseline to raw data of touch sensor.
* @param touch_num touch pad index
* - TOUCH_PAD_MAX Reset basaline of all channels
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_filter_baseline_reset(touch_pad_t touch_num);
/**
* @brief get debounce count of touch sensor.
* @param touch_num touch pad index
* @param debounce pointer to debounce value
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Touch channel 0 havent this parameter.
*/
esp_err_t touch_pad_filter_debounce_read(touch_pad_t touch_num, uint32_t *debounce);
/**
* @brief set parameter of touch sensor filter and detection algorithm.
* For more details on the detection algorithm, please refer to the application documentation.
* @param filter_info select filter type and threshold of detection algorithm
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_filter_set_config(touch_filter_config_t *filter_info);
/**
* @brief get parameter of touch sensor filter and detection algorithm.
* For more details on the detection algorithm, please refer to the application documentation.
* @param filter_info select filter type and threshold of detection algorithm
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_filter_get_config(touch_filter_config_t *filter_info);
/**
* @brief enable touch sensor filter and detection algorithm.
* For more details on the detection algorithm, please refer to the application documentation.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_filter_enable();
/**
* @brief diaable touch sensor filter and detection algorithm.
* For more details on the detection algorithm, please refer to the application documentation.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_filter_disable();
/**
* @brief set parameter of denoise pad (TOUCH_PAD_NUM0).
* T0 is an internal channel that does not have a corresponding external GPIO.
* T0 will work simultaneously with the measured channel Tn. Finally, the actual
* measured value of Tn is the value after subtracting lower bits of T0.
* This denoise function filters out interference introduced on all channels,
* such as noise introduced by the power supply and external EMI.
* @param denoise parameter of denoise
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_denoise_set_config(touch_pad_denoise_t denoise);
/**
* @brief get parameter of denoise pad (TOUCH_PAD_NUM0).
* @param denoise Pointer to parameter of denoise
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_denoise_get_config(touch_pad_denoise_t *denoise);
/**
* @brief enable denoise function.
* T0 is an internal channel that does not have a corresponding external GPIO.
* T0 will work simultaneously with the measured channel Tn. Finally, the actual
* measured value of Tn is the value after subtracting lower bits of T0.
* This denoise function filters out interference introduced on all channels,
* such as noise introduced by the power supply and external EMI.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_denoise_enable();
/**
* @brief disable denoise function.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_denoise_disable();
/**
* @brief get denoise measure value (TOUCH_PAD_NUM0).
* @param denoise value of denoise
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_denoise_data_get(uint32_t *data);
/**
* @brief set parameter of waterproof function.
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
* @param waterproof parameter of waterproof
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_waterproof_set_config(touch_pad_waterproof_t waterproof);
/**
* @brief get parameter of waterproof function.
* @param waterproof parameter of waterproof
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_waterproof_get_config(touch_pad_waterproof_t *waterproof);
/**
* @brief Enable parameter of waterproof function.
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_waterproof_enable();
/**
* @brief Enable parameter of waterproof function.
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_waterproof_disable();
/**
* @brief Set parameter of proximity channel. Three proximity sensing channels can be set.
* The proximity sensor measurement is the accumulation of touch channel measurements.
* @note If stop the proximity function for the channel, point this proximity channel to `TOUCH_PAD_NUM0`.
* @param proximity parameter of proximity
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_proximity_set_config(touch_pad_proximity_t proximity);
/**
* @brief Get parameter of proximity channel. Three proximity sensing channels can be set.
* The proximity sensor measurement is the accumulation of touch channel measurements.
* @param proximity parameter of proximity
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_proximity_get_config(touch_pad_proximity_t *proximity);
/**
* @brief Get measure count of proximity channel.
* The proximity sensor measurement is the accumulation of touch channel measurements.
* @param touch_num touch pad index
* @param proximity parameter of proximity
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG parameter is NULL
*/
esp_err_t touch_pad_proximity_get_meas_cnt(touch_pad_t touch_num, uint32_t *cnt);
/**
* @brief Get the accumulated measurement of the proximity sensor.
* The proximity sensor measurement is the accumulation of touch channel measurements.
* @param touch_num touch pad index
* @param measure_out If the accumulation process does not end, the `measure_out` is the process value.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_proximity_data_get(touch_pad_t touch_num, uint32_t *measure_out);
/**
* @brief Set parameter of touch sensor in sleep mode.
* In order to achieve low power consumption in sleep mode, other circuits except the RTC part of the register are in a power-off state.
* Only one touch channel is supported in the sleep state, which can be used as a wake-up function.
* If in non-sleep mode, the sleep parameters do not work.
* @param slp_config touch pad config
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_sleep_channel_config(touch_pad_sleep_channel_t slp_config);
/**
* @brief get baseline of touch sensor in sleep mode.
* @param baseline pointer to accept touch sensor baseline value
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG parameter is NULL
*/
esp_err_t touch_pad_sleep_channel_baseline_get(uint32_t *baseline);
/**
* @brief get debounce of touch sensor in sleep mode.
* @param debounce pointer to accept touch sensor debounce value
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG parameter is NULL
*/
esp_err_t touch_pad_sleep_channel_debounce_get(uint32_t *debounce);
/**
* @brief get proximity count of touch sensor in sleep mode.
* @param proximity_cnt pointer to accept touch sensor proximity count value
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG parameter is NULL
*/
esp_err_t touch_pad_sleep_channel_proximity_cnt_get(uint32_t *proximity_cnt);
#endif // CONFIG_IDF_TARGET_ESP32S2BETA
#ifdef __cplusplus
}

View File

@ -86,7 +86,9 @@ static const char *RTC_MODULE_TAG = "RTC_MODULE";
} }while (0)
portMUX_TYPE rtc_spinlock = portMUX_INITIALIZER_UNLOCKED;
#if CONFIG_IDF_TARGET_ESP32
static SemaphoreHandle_t rtc_touch_mux = NULL;
#endif
/*
In ADC2, there're two locks used for different cases:
1. lock shared with app and WIFI:
@ -109,6 +111,7 @@ portMUX_TYPE adc2_spinlock = portMUX_INITIALIZER_UNLOCKED;
//prevent ADC1 being used by I2S dma and other tasks at the same time.
static _lock_t adc1_i2s_lock;
#if CONFIG_IDF_TARGET_ESP32
typedef struct {
TimerHandle_t timer;
uint16_t filtered_val[TOUCH_PAD_MAX];
@ -121,6 +124,7 @@ static touch_pad_filter_t *s_touch_pad_filter = NULL;
// check if touch pad be inited.
static uint16_t s_touch_pad_init_bit = 0x0000;
static filter_cb_t s_filter_cb = NULL;
#endif
typedef enum {
ADC_CTRL_RTC = 0,
@ -455,6 +459,11 @@ esp_err_t rtc_gpio_hold_en(gpio_num_t gpio_num)
portENTER_CRITICAL(&rtc_spinlock);
SET_PERI_REG_MASK(rtc_gpio_desc[gpio_num].reg, rtc_gpio_desc[gpio_num].hold);
portEXIT_CRITICAL(&rtc_spinlock);
#elif CONFIG_IDF_TARGET_ESP32S2BETA
RTC_MODULE_CHECK(rtc_gpio_is_valid_gpio(gpio_num), "RTC_GPIO number error", ESP_ERR_INVALID_ARG);
portENTER_CRITICAL(&rtc_spinlock);
RTCCNTL.pad_hold.val |= BIT(gpio_num);
portEXIT_CRITICAL(&rtc_spinlock);
#endif
return ESP_OK;
}
@ -469,16 +478,24 @@ esp_err_t rtc_gpio_hold_dis(gpio_num_t gpio_num)
portENTER_CRITICAL(&rtc_spinlock);
CLEAR_PERI_REG_MASK(rtc_gpio_desc[gpio_num].reg, rtc_gpio_desc[gpio_num].hold);
portEXIT_CRITICAL(&rtc_spinlock);
#elif CONFIG_IDF_TARGET_ESP32S2BETA
RTC_MODULE_CHECK(rtc_gpio_is_valid_gpio(gpio_num), "RTC_GPIO number error", ESP_ERR_INVALID_ARG);
portENTER_CRITICAL(&rtc_spinlock);
RTCCNTL.pad_hold.val &= ~(BIT(gpio_num));
portEXIT_CRITICAL(&rtc_spinlock);
#endif
return ESP_OK;
}
esp_err_t rtc_gpio_isolate(gpio_num_t gpio_num)
{
#if CONFIG_IDF_TARGET_ESP32
if (rtc_gpio_desc[gpio_num].reg == 0) {
return ESP_ERR_INVALID_ARG;
}
#elif CONFIG_IDF_TARGET_ESP32S2BETA
RTC_MODULE_CHECK(rtc_gpio_is_valid_gpio(gpio_num), "RTC_GPIO number error", ESP_ERR_INVALID_ARG);
#endif
rtc_gpio_pullup_dis(gpio_num);
rtc_gpio_pulldown_dis(gpio_num);
rtc_gpio_set_direction(gpio_num, RTC_GPIO_MODE_DISABLED);
@ -560,7 +577,7 @@ esp_err_t rtc_gpio_force_hold_all()
return ESP_OK;
}
#endif
#if CONFIG_IDF_TARGET_ESP32
/*---------------------------------------------------------------
Touch Pad
---------------------------------------------------------------*/
@ -940,11 +957,9 @@ uint32_t IRAM_ATTR touch_pad_get_status()
return TOUCH_BITS_SWAP(status);
}
esp_err_t IRAM_ATTR touch_pad_clear_status()
esp_err_t touch_pad_clear_status()
{
portENTER_CRITICAL(&rtc_spinlock);
SENS.sar_touch_ctrl2.touch_meas_en_clr = 1;
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
@ -1206,13 +1221,28 @@ esp_err_t touch_pad_get_wakeup_status(touch_pad_t *pad_num)
*pad_num = touch_pad_num_wrap((touch_pad_t)(__builtin_ffs(touch_mask) - 1));
return ESP_OK;
}
#endif
/*---------------------------------------------------------------
ADC Common
---------------------------------------------------------------*/
#if CONFIG_IDF_TARGET_ESP32S2BETA
#define SENS_FORCE_XPD_AMP_FSM 0 // Use FSM to control power down
#define SENS_FORCE_XPD_AMP_PD 2 // Force power down
#define SENS_FORCE_XPD_AMP_PU 3 // Force power up
#define SENS_SAR1_ATTEN_VAL_MASK 0x3
#define SENS_SAR2_ATTEN_VAL_MASK 0x3
#define SENS_FORCE_XPD_SAR_SW_M (BIT(1))
#define SENS_FORCE_XPD_SAR_FSM 0 // Use FSM to control power down
#define SENS_FORCE_XPD_SAR_PD 2 // Force power down
#define SENS_FORCE_XPD_SAR_PU 3 // Force power up
#endif
static esp_err_t adc_set_fsm_time(int rst_wait, int start_wait, int standby_wait, int sample_cycle)
{
portENTER_CRITICAL(&rtc_spinlock);
#if CONFIG_IDF_TARGET_ESP32
// Internal FSM reset wait time
if (rst_wait >= 0) {
SYSCON.saradc_fsm.rstb_wait = rst_wait;
@ -1225,6 +1255,20 @@ static esp_err_t adc_set_fsm_time(int rst_wait, int start_wait, int standby_wait
if (standby_wait >= 0) {
SYSCON.saradc_fsm.standby_wait = standby_wait;
}
#elif CONFIG_IDF_TARGET_ESP32S2BETA
// Internal FSM reset wait time
if (rst_wait >= 0) {
SYSCON.saradc_fsm_wait.rstb_wait = rst_wait;
}
// Internal FSM start wait time
if (start_wait >= 0) {
SYSCON.saradc_fsm_wait.xpd_wait = start_wait;
}
// Internal FSM standby wait time
if (standby_wait >= 0) {
SYSCON.saradc_fsm_wait.standby_wait = standby_wait;
}
#endif
// Internal FSM standby sample cycle
if (sample_cycle >= 0) {
SYSCON.saradc_fsm.sample_cycle = sample_cycle;
@ -1303,13 +1347,18 @@ static esp_err_t adc_set_atten(adc_unit_t adc_unit, adc_channel_t channel, adc_a
void adc_power_always_on()
{
portENTER_CRITICAL(&rtc_spinlock);
#if CONFIG_IDF_TARGET_ESP32
SENS.sar_meas_wait2.force_xpd_sar = SENS_FORCE_XPD_SAR_PU;
#elif CONFIG_IDF_TARGET_ESP32S2BETA
SENS.sar_power_xpd_sar.force_xpd_sar = SENS_FORCE_XPD_SAR_PU;
#endif
portEXIT_CRITICAL(&rtc_spinlock);
}
void adc_power_on()
{
portENTER_CRITICAL(&rtc_spinlock);
#if CONFIG_IDF_TARGET_ESP32
//The power FSM controlled mode saves more power, while the ADC noise may get increased.
#ifndef CONFIG_ADC_FORCE_XPD_FSM
//Set the power always on to increase precision.
@ -1321,6 +1370,20 @@ void adc_power_on()
} else {
SENS.sar_meas_wait2.force_xpd_sar = SENS_FORCE_XPD_SAR_FSM;
}
#endif
#elif CONFIG_IDF_TARGET_ESP32S2BETA
//The power FSM controlled mode saves more power, while the ADC noise may get increased.
#ifndef CONFIG_ADC_FORCE_XPD_FSM
//Set the power always on to increase precision.
SENS.sar_power_xpd_sar.force_xpd_sar = SENS_FORCE_XPD_SAR_PU;
#else
//Use the FSM to turn off the power while not used to save power.
if (SENS.sar_power_xpd_sar.force_xpd_sar & SENS_FORCE_XPD_SAR_SW_M) {
SENS.sar_power_xpd_sar.force_xpd_sar = SENS_FORCE_XPD_SAR_PU;
} else {
SENS.sar_power_xpd_sar.force_xpd_sar = SENS_FORCE_XPD_SAR_FSM;
}
#endif
#endif
portEXIT_CRITICAL(&rtc_spinlock);
}
@ -1328,9 +1391,14 @@ void adc_power_on()
void adc_power_off()
{
portENTER_CRITICAL(&rtc_spinlock);
#if CONFIG_IDF_TARGET_ESP32
//Bit1 0:Fsm 1: SW mode
//Bit0 0:SW mode power down 1: SW mode power on
SENS.sar_meas_wait2.force_xpd_sar = SENS_FORCE_XPD_SAR_PD;
#elif CONFIG_IDF_TARGET_ESP32S2BETA
SENS.sar_power_xpd_sar.force_xpd_sar = SENS_FORCE_XPD_SAR_PD;
#endif
portEXIT_CRITICAL(&rtc_spinlock);
}
@ -1371,6 +1439,7 @@ esp_err_t adc_gpio_init(adc_unit_t adc_unit, adc_channel_t channel)
esp_err_t adc_set_data_inv(adc_unit_t adc_unit, bool inv_en)
{
portENTER_CRITICAL(&rtc_spinlock);
#if CONFIG_IDF_TARGET_ESP32
if (adc_unit & ADC_UNIT_1) {
// Enable ADC data invert
SENS.sar_read_ctrl.sar1_data_inv = inv_en;
@ -1379,6 +1448,16 @@ esp_err_t adc_set_data_inv(adc_unit_t adc_unit, bool inv_en)
// Enable ADC data invert
SENS.sar_read_ctrl2.sar2_data_inv = inv_en;
}
#elif CONFIG_IDF_TARGET_ESP32S2BETA
if (adc_unit & ADC_UNIT_1) {
// Enable ADC data invert
SENS.sar_reader1_ctrl.sar1_data_inv = inv_en;
}
if (adc_unit & ADC_UNIT_2) {
// Enable ADC data invert
SENS.sar_reader2_ctrl.sar2_data_inv = inv_en;
}
#endif
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
@ -1388,6 +1467,7 @@ esp_err_t adc_set_data_width(adc_unit_t adc_unit, adc_bits_width_t bits)
ADC_CHECK_UNIT(adc_unit);
RTC_MODULE_CHECK(bits < ADC_WIDTH_MAX, "ADC bit width error", ESP_ERR_INVALID_ARG);
portENTER_CRITICAL(&rtc_spinlock);
#if CONFIG_IDF_TARGET_ESP32
if (adc_unit & ADC_UNIT_1) {
SENS.sar_start_force.sar1_bit_width = bits;
SENS.sar_read_ctrl.sar1_sample_bit = bits;
@ -1396,6 +1476,16 @@ esp_err_t adc_set_data_width(adc_unit_t adc_unit, adc_bits_width_t bits)
SENS.sar_start_force.sar2_bit_width = bits;
SENS.sar_read_ctrl2.sar2_sample_bit = bits;
}
#elif CONFIG_IDF_TARGET_ESP32S2BETA
if (adc_unit & ADC_UNIT_1) {
SENS.sar_meas1_ctrl1.sar1_bit_width = bits;
SENS.sar_reader1_ctrl.sar1_sample_bit = bits;
}
if (adc_unit & ADC_UNIT_2) {
SENS.sar_meas2_ctrl1.sar2_bit_width = bits;
SENS.sar_reader2_ctrl.sar2_sample_bit = bits;
}
#endif
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
@ -1403,6 +1493,7 @@ esp_err_t adc_set_data_width(adc_unit_t adc_unit, adc_bits_width_t bits)
// this function should be called in the critical section
static void adc_set_controller(adc_unit_t unit, adc_controller_t ctrl )
{
#if CONFIG_IDF_TARGET_ESP32
if ( unit == ADC_UNIT_1 ) {
switch( ctrl ) {
case ADC_CTRL_RTC:
@ -1463,18 +1554,75 @@ static void adc_set_controller(adc_unit_t unit, adc_controller_t ctrl )
break;
default:
ESP_LOGE(TAG, "adc2 selects invalid controller");
break;
break;
}
} else {
ESP_LOGE(TAG, "invalid adc unit");
assert(0);
}
#elif CONFIG_IDF_TARGET_ESP32S2BETA
if ( unit == ADC_UNIT_1 ) {
switch( ctrl ) {
case ADC_CTRL_RTC:
SENS.sar_meas1_mux.sar1_dig_force = false; //RTC controller controls the ADC, not digital controller
SENS.sar_meas1_ctrl2.meas1_start_force = true; //RTC controller controls the ADC,not ulp coprocessor
SENS.sar_meas1_ctrl2.sar1_en_pad_force = true; //RTC controller controls the data port, not ulp coprocessor
SENS.sar_hall_ctrl.xpd_hall_force = true; // RTC controller controls the hall sensor power,not ulp coprocessor
SENS.sar_hall_ctrl.hall_phase_force = true; // RTC controller controls the hall sensor phase,not ulp coprocessor
break;
case ADC_CTRL_ULP:
SENS.sar_meas1_mux.sar1_dig_force = false;
SENS.sar_meas1_ctrl2.meas1_start_force = false;
SENS.sar_meas1_ctrl2.sar1_en_pad_force = false;
SENS.sar_hall_ctrl.xpd_hall_force = false;
SENS.sar_hall_ctrl.hall_phase_force = false;
break;
case ADC_CTRL_DIG:
SENS.sar_meas1_mux.sar1_dig_force = true;
SENS.sar_meas1_ctrl2.meas1_start_force = true;
SENS.sar_meas1_ctrl2.sar1_en_pad_force = true;
SENS.sar_hall_ctrl.xpd_hall_force = true;
SENS.sar_hall_ctrl.hall_phase_force = true;
break;
default:
ESP_LOGE(TAG, "adc1 selects invalid controller");
break;
}
} else if ( unit == ADC_UNIT_2) {
switch( ctrl ) {
case ADC_CTRL_RTC:
SENS.sar_meas2_ctrl2.meas2_start_force = true; //RTC controller controls the ADC,not ulp coprocessor
SENS.sar_meas2_ctrl2.sar2_en_pad_force = true; //RTC controller controls the data port, not ulp coprocessor
break;
case ADC_CTRL_ULP:
SENS.sar_meas2_ctrl2.meas2_start_force = false;
SENS.sar_meas2_ctrl2.sar2_en_pad_force = false;
break;
case ADC_CTRL_DIG:
SENS.sar_meas2_ctrl2.meas2_start_force = true;
SENS.sar_meas2_ctrl2.sar2_en_pad_force = true;
break;
case ADC2_CTRL_PWDET:
//currently only used by Wi-Fi
SENS.sar_meas2_ctrl2.meas2_start_force = true;
SENS.sar_meas2_ctrl2.sar2_en_pad_force = true;
break;
default:
ESP_LOGE(TAG, "adc2 selects invalid controller");
break;
}
} else {
ESP_LOGE(TAG, "invalid adc unit");
assert(0);
}
#endif
}
// this function should be called in the critical section
static int adc_convert( adc_unit_t unit, int channel)
{
uint16_t adc_value;
uint16_t adc_value = 0;
#if CONFIG_IDF_TARGET_ESP32
if ( unit == ADC_UNIT_1 ) {
SENS.sar_meas_start1.sar1_en_pad = (1 << channel); //only one channel is selected.
while (SENS.sar_slave_addr1.meas_status != 0);
@ -1493,6 +1641,26 @@ static int adc_convert( adc_unit_t unit, int channel)
ESP_LOGE(TAG, "invalid adc unit");
return ESP_ERR_INVALID_ARG;
}
#elif CONFIG_IDF_TARGET_ESP32S2BETA
if ( unit == ADC_UNIT_1 ) {
SENS.sar_meas1_ctrl2.sar1_en_pad = (1 << channel); //only one channel is selected.
while (SENS.sar_slave_addr1.meas_status != 0);
SENS.sar_meas1_ctrl2.meas1_start_sar = 0;
SENS.sar_meas1_ctrl2.meas1_start_sar = 1;
while (SENS.sar_meas1_ctrl2.meas1_done_sar == 0);
adc_value = SENS.sar_meas1_ctrl2.meas1_data_sar;
} else if ( unit == ADC_UNIT_2 ) {
SENS.sar_meas2_ctrl2.sar2_en_pad = (1 << channel); //only one channel is selected.
SENS.sar_meas2_ctrl2.meas2_start_sar = 0; //start force 0
SENS.sar_meas2_ctrl2.meas2_start_sar = 1; //start force 1
while (SENS.sar_meas2_ctrl2.meas2_done_sar == 0) {}; //read done
adc_value = SENS.sar_meas2_ctrl2.meas2_data_sar;
} else {
ESP_LOGE(TAG, "invalid adc unit");
return ESP_ERR_INVALID_ARG;
}
#endif
return adc_value;
}
@ -1633,6 +1801,7 @@ esp_err_t adc1_config_width(adc_bits_width_t width_bit)
static inline void adc1_fsm_disable()
{
#if CONFIG_IDF_TARGET_ESP32
//channel is set in the convert function
SENS.sar_meas_wait2.force_xpd_amp = SENS_FORCE_XPD_AMP_PD;
//disable FSM, it's only used by the LNA.
@ -1641,7 +1810,18 @@ static inline void adc1_fsm_disable()
SENS.sar_meas_ctrl.amp_short_ref_gnd_fsm = 0;
SENS.sar_meas_wait1.sar_amp_wait1 = 1;
SENS.sar_meas_wait1.sar_amp_wait2 = 1;
SENS.sar_meas_wait2.sar_amp_wait3 = 1;
SENS.sar_meas_wait2.sar_amp_wait3 = 1;
#elif CONFIG_IDF_TARGET_ESP32S2BETA
//channel is set in the convert function
SENS.sar_meas1_ctrl1.force_xpd_amp = SENS_FORCE_XPD_AMP_PD;
//disable FSM, it's only used by the LNA.
SENS.sar_amp_ctrl3.amp_rst_fb_fsm = 0;
SENS.sar_amp_ctrl3.amp_short_ref_fsm = 0;
SENS.sar_amp_ctrl3.amp_short_ref_gnd_fsm = 0;
SENS.sar_amp_ctrl1.sar_amp_wait1 = 1;
SENS.sar_amp_ctrl1.sar_amp_wait2 = 1;
SENS.sar_amp_ctrl2.sar_amp_wait3 = 1;
#endif
}
esp_err_t adc1_i2s_mode_acquire()
@ -1651,9 +1831,15 @@ esp_err_t adc1_i2s_mode_acquire()
_lock_acquire( &adc1_i2s_lock );
ESP_LOGD( RTC_MODULE_TAG, "i2s mode takes adc1 lock." );
portENTER_CRITICAL(&rtc_spinlock);
#if CONFIG_IDF_TARGET_ESP32
SENS.sar_meas_wait2.force_xpd_sar = SENS_FORCE_XPD_SAR_PU;
//switch SARADC into DIG channel
SENS.sar_read_ctrl.sar1_dig_force = 1;
#elif CONFIG_IDF_TARGET_ESP32S2BETA
SENS.sar_power_xpd_sar.force_xpd_sar = SENS_FORCE_XPD_SAR_PU;
//switch SARADC into DIG channel
SENS.sar_meas1_mux.sar1_dig_force = 1;
#endif
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
@ -1663,13 +1849,18 @@ esp_err_t adc1_adc_mode_acquire()
//lazy initialization
//for adc1, block until acquire the lock
_lock_acquire( &adc1_i2s_lock );
ESP_LOGD( RTC_MODULE_TAG, "adc mode takes adc1 lock." );
portENTER_CRITICAL(&rtc_spinlock);
// for now the WiFi would use ADC2 and set xpd_sar force on.
// so we can not reset xpd_sar to fsm mode directly.
// We should handle this after the synchronization mechanism is established.
//switch SARADC into RTC channel
#if CONFIG_IDF_TARGET_ESP32
SENS.sar_read_ctrl.sar1_dig_force = 0;
#elif CONFIG_IDF_TARGET_ESP32S2BETA
SENS.sar_meas1_mux.sar1_dig_force = 0;
#endif
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
@ -1822,6 +2013,7 @@ esp_err_t adc2_config_channel_atten(adc2_channel_t channel, adc_atten_t atten)
static inline void adc2_config_width(adc_bits_width_t width_bit)
{
portENTER_CRITICAL(&rtc_spinlock);
#if CONFIG_IDF_TARGET_ESP32
//sar_start_force shared with ADC1
SENS.sar_start_force.sar2_bit_width = width_bit;
//cct set to the same value with PHY
@ -1832,15 +2024,34 @@ static inline void adc2_config_width(adc_bits_width_t width_bit)
SENS.sar_read_ctrl2.sar2_data_inv = 1;
//Set The adc sample width,invert adc value,must digital sar2_bit_width[1:0]=3
SENS.sar_read_ctrl2.sar2_sample_bit = width_bit;
#elif CONFIG_IDF_TARGET_ESP32S2BETA
//sar_start_force shared with ADC1
SENS.sar_meas2_ctrl1.sar2_bit_width = width_bit;
//cct set to the same value with PHY
SENS.sar_meas2_mux.sar2_pwdet_cct = 4;
portEXIT_CRITICAL(&rtc_spinlock);
//Invert the adc value,the Output value is invert
SENS.sar_reader2_ctrl.sar2_data_inv = 1;
//Set The adc sample width,invert adc value,must digital sar2_bit_width[1:0]=3
SENS.sar_reader2_ctrl.sar2_sample_bit = width_bit;
#endif
}
static inline void adc2_dac_disable( adc2_channel_t channel)
{
#if CONFIG_IDF_TARGET_ESP32
if ( channel == ADC2_CHANNEL_8 ) { // the same as DAC channel 1
dac_output_set_enable( DAC_CHANNEL_1, false );
} else if ( channel == ADC2_CHANNEL_9 ) {
dac_output_set_enable( DAC_CHANNEL_2, false );
}
#elif CONFIG_IDF_TARGET_ESP32S2BETA
if ( channel == ADC2_CHANNEL_6 ) { // the same as DAC channel 1
dac_output_set_enable( DAC_CHANNEL_1, false );
} else if ( channel == ADC2_CHANNEL_7 ) {
dac_output_set_enable( DAC_CHANNEL_2, false );
}
#endif
}
//registers in critical section with adc1:
@ -1884,7 +2095,6 @@ esp_err_t adc2_vref_to_gpio(gpio_num_t gpio)
{
#if CONFIG_IDF_TARGET_ESP32
int channel;
if(gpio == GPIO_NUM_25){
channel = 8; //Channel 8 bit
}else if (gpio == GPIO_NUM_26){

View File

@ -406,9 +406,10 @@ touch_pad_t esp_sleep_get_touchpad_wakeup_status()
if (esp_sleep_get_wakeup_cause() != ESP_SLEEP_WAKEUP_TOUCHPAD) {
return TOUCH_PAD_MAX;
}
uint32_t touch_mask = REG_GET_FIELD(SENS_SAR_TOUCH_CTRL2_REG, SENS_TOUCH_MEAS_EN);
assert(touch_mask != 0 && "wakeup reason is RTC_TOUCH_TRIG_EN but SENS_TOUCH_MEAS_EN is zero");
return (touch_pad_t) (__builtin_ffs(touch_mask) - 1);
touch_pad_t pad_num;
esp_err_t ret = touch_pad_get_wakeup_status(&pad_num);
assert(ret == ESP_OK && "wakeup reason is RTC_TOUCH_TRIG_EN but SENS_TOUCH_MEAS_EN is zero");
return pad_num;
}
esp_err_t esp_sleep_enable_ext0_wakeup(gpio_num_t gpio_num, int level)
@ -423,7 +424,7 @@ esp_err_t esp_sleep_enable_ext0_wakeup(gpio_num_t gpio_num, int level)
ESP_LOGE(TAG, "Conflicting wake-up triggers: touch / ULP");
return ESP_ERR_INVALID_STATE;
}
s_config.ext0_rtc_gpio_num = rtc_gpio_desc[gpio_num].rtc_num;
s_config.ext0_rtc_gpio_num = gpio_num;
s_config.ext0_trigger_level = level;
s_config.wakeup_triggers |= RTC_EXT0_TRIG_EN;
return ESP_OK;
@ -437,13 +438,12 @@ static void ext0_wakeup_prepare()
// Set level which will trigger wakeup
SET_PERI_REG_BITS(RTC_CNTL_EXT_WAKEUP_CONF_REG, 0x1,
s_config.ext0_trigger_level, RTC_CNTL_EXT_WAKEUP0_LV_S);
// Find GPIO descriptor in the rtc_gpio_desc table and configure the pad
// Find GPIO descriptor in the rtc_gpio_reg table and configure the pad
for (size_t gpio_num = 0; gpio_num < GPIO_PIN_COUNT; ++gpio_num) {
const rtc_gpio_desc_t* desc = &rtc_gpio_desc[gpio_num];
if (desc->rtc_num == rtc_gpio_num) {
REG_SET_BIT(desc->reg, desc->mux);
SET_PERI_REG_BITS(desc->reg, 0x3, 0, desc->func);
REG_SET_BIT(desc->reg, desc->ie);
if (gpio_num == rtc_gpio_num && RTC_GPIO_IS_VALID_GPIO(gpio_num)) {
rtc_gpio_reg[gpio_num]->mux_sel = 1;
rtc_gpio_reg[gpio_num]->fun_sel = 0;
rtc_gpio_reg[gpio_num]->fun_ie = 1;
break;
}
}
@ -464,7 +464,7 @@ esp_err_t esp_sleep_enable_ext1_wakeup(uint64_t mask, esp_sleep_ext1_wakeup_mode
ESP_LOGE(TAG, "Not an RTC IO: GPIO%d", gpio);
return ESP_ERR_INVALID_ARG;
}
rtc_gpio_mask |= BIT(rtc_gpio_desc[gpio].rtc_num);
rtc_gpio_mask |= BIT(gpio);
}
s_config.ext1_rtc_gpio_mask = rtc_gpio_mask;
s_config.ext1_trigger_mode = mode;
@ -477,26 +477,27 @@ static void ext1_wakeup_prepare()
// Configure all RTC IOs selected as ext1 wakeup inputs
uint32_t rtc_gpio_mask = s_config.ext1_rtc_gpio_mask;
for (int gpio = 0; gpio < GPIO_PIN_COUNT && rtc_gpio_mask != 0; ++gpio) {
int rtc_pin = rtc_gpio_desc[gpio].rtc_num;
if ((rtc_gpio_mask & BIT(rtc_pin)) == 0) {
if(!RTC_GPIO_IS_VALID_GPIO(gpio)) {
continue;
}
if ((rtc_gpio_mask & BIT(gpio)) == 0) {
continue;
}
const rtc_gpio_desc_t* desc = &rtc_gpio_desc[gpio];
// Route pad to RTC
REG_SET_BIT(desc->reg, desc->mux);
SET_PERI_REG_BITS(desc->reg, 0x3, 0, desc->func);
rtc_gpio_reg[gpio]->mux_sel = 1;
rtc_gpio_reg[gpio]->fun_sel = 0;
// set input enable in sleep mode
REG_SET_BIT(desc->reg, desc->ie);
rtc_gpio_reg[gpio]->fun_ie = 1;
// Pad configuration depends on RTC_PERIPH state in sleep mode
if (s_config.pd_options[ESP_PD_DOMAIN_RTC_PERIPH] != ESP_PD_OPTION_ON) {
// RTC_PERIPH will be powered down, so RTC_IO_ registers will
// loose their state. Lock pad configuration.
// Pullups/pulldowns also need to be disabled.
REG_CLR_BIT(desc->reg, desc->pulldown);
REG_CLR_BIT(desc->reg, desc->pullup);
rtc_gpio_reg[gpio]->rue = 0;
rtc_gpio_reg[gpio]->rde = 0;
}
// Keep track of pins which are processed to bail out early
rtc_gpio_mask &= ~BIT(rtc_pin);
rtc_gpio_mask &= ~BIT(gpio);
}
// Clear state from previous wakeup
REG_SET_BIT(RTC_CNTL_EXT_WAKEUP1_REG, RTC_CNTL_EXT_WAKEUP1_STATUS_CLR);
@ -519,7 +520,7 @@ uint64_t esp_sleep_get_ext1_wakeup_status()
if (!RTC_GPIO_IS_VALID_GPIO(gpio)) {
continue;
}
int rtc_pin = rtc_gpio_desc[gpio].rtc_num;
int rtc_pin = gpio;
if ((status & BIT(rtc_pin)) == 0) {
continue;
}

View File

@ -91,14 +91,8 @@ typedef volatile struct {
} saradc_fsm_wait;
uint32_t saradc_sar1_status; /**/
uint32_t saradc_sar2_status; /**/
uint32_t saradc_sar1_patt_tab1; /*item 0 ~ 3 for pattern table 1 (each item one byte)*/
uint32_t saradc_sar1_patt_tab2; /*Item 4 ~ 7 for pattern table 1 (each item one byte)*/
uint32_t saradc_sar1_patt_tab3; /*Item 8 ~ 11 for pattern table 1 (each item one byte)*/
uint32_t saradc_sar1_patt_tab4; /*Item 12 ~ 15 for pattern table 1 (each item one byte)*/
uint32_t saradc_sar2_patt_tab1; /*item 0 ~ 3 for pattern table 2 (each item one byte)*/
uint32_t saradc_sar2_patt_tab2; /*Item 4 ~ 7 for pattern table 2 (each item one byte)*/
uint32_t saradc_sar2_patt_tab3; /*Item 8 ~ 11 for pattern table 2 (each item one byte)*/
uint32_t saradc_sar2_patt_tab4; /*Item 12 ~ 15 for pattern table 2 (each item one byte)*/
uint32_t saradc_sar1_patt_tab[4]; /*item 0 ~ 15 for pattern table 1 (each item one byte)*/
uint32_t saradc_sar2_patt_tab[4]; /*item 0 ~ 15 for pattern table 2 (each item one byte)*/
union {
struct {
uint32_t reserved0: 2;
@ -310,11 +304,22 @@ typedef volatile struct {
};
uint32_t val;
} redcy_sig1;
uint32_t reserved_cc;
uint32_t reserved_d0;
uint32_t reserved_d4;
uint32_t reserved_d8;
uint32_t reserved_dc;
uint32_t wifi_bb_cfg; /**/
uint32_t wifi_bb_cfg_2; /**/
uint32_t wifi_clk_en; /**/
uint32_t wifi_rst_en; /**/
union {
struct {
uint32_t agc_mem_force_pu: 1;
uint32_t agc_mem_force_pd: 1;
uint32_t pbus_mem_force_pu: 1;
uint32_t pbus_mem_force_pd: 1;
uint32_t dc_mem_force_pu: 1;
uint32_t dc_mem_force_pd: 1;
uint32_t reserved6: 26;
};
uint32_t val;
} front_end_mem_pd;
uint32_t reserved_e0;
uint32_t reserved_e4;
uint32_t reserved_e8;

View File

@ -336,7 +336,7 @@ extern "C" {
#define RTC_CNTL_XTL_BUF_WAIT_M ((RTC_CNTL_XTL_BUF_WAIT_V)<<(RTC_CNTL_XTL_BUF_WAIT_S))
#define RTC_CNTL_XTL_BUF_WAIT_V 0x3FF
#define RTC_CNTL_XTL_BUF_WAIT_S 14
#define RTC_CNTL_XTL_BUF_WAIT_DEFAULT 20
#define RTC_CNTL_XTL_BUF_WAIT_DEFAULT 100
/* RTC_CNTL_CK8M_WAIT : R/W ;bitpos:[13:6] ;default: 8'h10 ; */
/*description: CK8M wait cycles in slow_clk_rtc*/
#define RTC_CNTL_CK8M_WAIT 0x000000FF
@ -1451,7 +1451,7 @@ extern "C" {
#define RTC_CNTL_DBG_ATTEN_V 0xF
#define RTC_CNTL_DBG_ATTEN_S 22
/* reserved for driver to check */
#define RTC_CNTL_DBG_ATTEN_DEFAULT 3
#define RTC_CNTL_DBG_ATTEN_DEFAULT 15
#define RTC_CNTL_REG (DR_REG_RTCCNTL_BASE + 0x0084)
/* RTC_CNTL_REGULATOR_FORCE_PU : R/W ;bitpos:[31] ;default: 1'd1 ; */

View File

@ -1,9 +1,9 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
// Copyright 2017-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
@ -64,37 +64,34 @@ typedef volatile struct {
} slp_timer1;
union {
struct {
uint32_t reserved0: 30;
uint32_t reserved0: 27;
uint32_t timer_sys_stall: 1; /*Enable to record system stall time*/
uint32_t timer_xtl_off: 1; /*Enable to record 40M XTAL OFF time*/
uint32_t timer_sys_rst: 1; /*enable to record system reset time*/
uint32_t valid: 1; /*To indicate the register is updated*/
uint32_t update: 1; /*Set 1: to update register with RTC timer*/
};
uint32_t val;
} time_update;
uint32_t time0; /*RTC timer low 32 bits*/
uint32_t time_low0; /*RTC timer low 32 bits*/
union {
struct {
uint32_t time_hi: 16; /*RTC timer high 16 bits*/
uint32_t reserved16: 16;
uint32_t rtc_timer_value0_high:16; /*RTC timer high 16 bits*/
uint32_t reserved16: 16;
};
uint32_t val;
} time1;
} time_high0;
union {
struct {
uint32_t reserved0: 18;
uint32_t cocpu_wakeup: 1; /*riscV cocpu wake up register*/
uint32_t cocpu_wakeup_force_en: 1; /*riscV cocpu force wake up*/
uint32_t touch_wakeup_force_en: 1; /*touch controller force wake up*/
uint32_t ulp_cp_wakeup_force_en: 1; /*ULP-coprocessor force wake up*/
uint32_t apb2rtc_bridge_sel: 1; /*1: APB to RTC using bridge 0: APB to RTC using sync*/
uint32_t touch_slp_timer_en: 1; /*touch timer enable bit*/
uint32_t ulp_cp_slp_timer_en: 1; /*ULP-coprocessor timer enable bit*/
uint32_t ulp_cp_gpio_wakeup_ena: 1; /*ULP-coprocessor wakeup by GPIO enable*/
uint32_t ulp_cp_gpio_wakeup_clr: 1; /*ULP-coprocessor wakeup by GPIO state clear*/
uint32_t reserved27: 1;
uint32_t sdio_active_ind: 1; /*SDIO active indication*/
uint32_t slp_wakeup: 1; /*leep wakeup bit*/
uint32_t slp_reject: 1; /*leep reject bit*/
uint32_t sleep_en: 1; /*sleep enable bit*/
uint32_t rtc_sw_cpu_int: 1; /*rtc software interrupt to main cpu*/
uint32_t rtc_slp_reject_cause_clr: 1; /*clear rtc sleep reject cause*/
uint32_t reserved2: 20;
uint32_t apb2rtc_bridge_sel: 1; /*1: APB to RTC using bridge 0: APB to RTC using sync*/
uint32_t reserved23: 5;
uint32_t sdio_active_ind: 1; /*SDIO active indication*/
uint32_t slp_wakeup: 1; /*leep wakeup bit*/
uint32_t slp_reject: 1; /*leep reject bit*/
uint32_t sleep_en: 1; /*sleep enable bit*/
};
uint32_t val;
} state0;
@ -136,10 +133,10 @@ typedef volatile struct {
} timer4;
union {
struct {
uint32_t ulp_cp_subtimer_prediv: 8;
uint32_t min_slp_val: 8; /*minimal sleep cycles in slow_clk_rtc*/
uint32_t rtcmem_wait_timer: 9;
uint32_t rtcmem_powerup_timer: 7;
uint32_t reserved0: 8;
uint32_t min_slp_val: 8; /*minimal sleep cycles in slow_clk_rtc*/
uint32_t rtcmem_wait_timer: 9;
uint32_t rtcmem_powerup_timer: 7;
};
uint32_t val;
} timer5;
@ -153,9 +150,7 @@ typedef volatile struct {
} timer6;
union {
struct {
uint32_t reserved0: 19;
uint32_t pkdet_cal_force_en: 2; /*pkdet force option*/
uint32_t pwdet_cal_force_en: 2; /*pwdet force option*/
uint32_t reserved0: 23;
uint32_t plla_force_pd: 1; /*PLLA force power down*/
uint32_t plla_force_pu: 1; /*PLLA force power up*/
uint32_t bbpll_cal_slp_start: 1; /*start BBPLL calibration during sleep*/
@ -180,95 +175,130 @@ typedef volatile struct {
} reset_state;
union {
struct {
uint32_t wakeup_cause: 12; /*wakeup cause*/
uint32_t rtc_wakeup_ena: 12; /*wakeup enable bitmap*/
uint32_t wakeup_cause: 15; /*wakeup cause*/
uint32_t rtc_wakeup_ena: 15; /*wakeup enable bitmap*/
uint32_t gpio_wakeup_filter: 1; /*enable filter for gpio wakeup event*/
uint32_t reserved25: 7;
uint32_t reserved31: 1;
};
uint32_t val;
} wakeup_state;
union {
struct {
uint32_t slp_wakeup: 1; /*enable sleep wakeup interrupt*/
uint32_t slp_reject: 1; /*enable sleep reject interrupt*/
uint32_t sdio_idle: 1; /*enable SDIO idle interrupt*/
uint32_t rtc_wdt: 1; /*enable RTC WDT interrupt*/
uint32_t rtc_time_valid: 1; /*enable RTC time valid interrupt*/
uint32_t rtc_ulp_cp: 1; /*enable ULP-coprocessor interrupt*/
uint32_t rtc_touch: 1; /*enable touch interrupt*/
uint32_t rtc_brown_out: 1; /*enable brown out interrupt*/
uint32_t rtc_main_timer: 1; /*enable RTC main timer interrupt*/
uint32_t rtc_saradc1: 1; /*enable saradc1 interrupt*/
uint32_t rtc_tsens: 1; /*enable tsens interrupt*/
uint32_t rtc_cocpu: 1; /*enable riscV cocpu interrupt*/
uint32_t rtc_saradc2: 1; /*enable saradc2 interrupt*/
uint32_t reserved13: 19;
uint32_t slp_wakeup: 1; /*enable sleep wakeup interrupt*/
uint32_t slp_reject: 1; /*enable sleep reject interrupt*/
uint32_t sdio_idle: 1; /*enable SDIO idle interrupt*/
uint32_t rtc_wdt: 1; /*enable RTC WDT interrupt*/
uint32_t rtc_time_valid: 1; /*enable RTC time valid interrupt*/
uint32_t rtc_ulp_cp: 1; /*enable ULP-coprocessor interrupt*/
uint32_t rtc_touch_done: 1; /*enable touch done interrupt*/
uint32_t rtc_touch_active: 1; /*enable touch active interrupt*/
uint32_t rtc_touch_inactive: 1; /*enable touch inactive interrupt*/
uint32_t rtc_brown_out: 1; /*enable brown out interrupt*/
uint32_t rtc_main_timer: 1; /*enable RTC main timer interrupt*/
uint32_t rtc_saradc1: 1; /*enable saradc1 interrupt*/
uint32_t rtc_tsens: 1; /*enable tsens interrupt*/
uint32_t rtc_cocpu: 1; /*enable riscV cocpu interrupt*/
uint32_t rtc_saradc2: 1; /*enable saradc2 interrupt*/
uint32_t rtc_swd: 1; /*enable super watch dog interrupt*/
uint32_t rtc_xtal32k_dead: 1; /*enable cocpu trap interrupt*/
uint32_t rtc_cocpu_trap: 1;
uint32_t reserved18: 14;
};
uint32_t val;
} int_ena;
union {
struct {
uint32_t slp_wakeup: 1; /*sleep wakeup interrupt raw*/
uint32_t slp_reject: 1; /*sleep reject interrupt raw*/
uint32_t sdio_idle: 1; /*SDIO idle interrupt raw*/
uint32_t rtc_wdt: 1; /*RTC WDT interrupt raw*/
uint32_t rtc_time_valid: 1; /*RTC time valid interrupt raw*/
uint32_t rtc_ulp_cp: 1; /*ULP-coprocessor interrupt raw*/
uint32_t rtc_touch: 1; /*touch interrupt raw*/
uint32_t rtc_brown_out: 1; /*brown out interrupt raw*/
uint32_t rtc_main_timer: 1; /*RTC main timer interrupt raw*/
uint32_t rtc_saradc1: 1; /*saradc1 interrupt raw*/
uint32_t rtc_tsens: 1; /*tsens interrupt raw*/
uint32_t rtc_cocpu: 1; /*riscV cocpu interrupt raw*/
uint32_t rtc_saradc2: 1; /*saradc2 interrupt raw*/
uint32_t reserved13: 19;
uint32_t slp_wakeup: 1; /*sleep wakeup interrupt raw*/
uint32_t slp_reject: 1; /*sleep reject interrupt raw*/
uint32_t sdio_idle: 1; /*SDIO idle interrupt raw*/
uint32_t rtc_wdt: 1; /*RTC WDT interrupt raw*/
uint32_t rtc_time_valid: 1; /*RTC time valid interrupt raw*/
uint32_t rtc_ulp_cp: 1; /*ULP-coprocessor interrupt raw*/
uint32_t rtc_touch_done: 1; /*touch interrupt raw*/
uint32_t rtc_touch_active: 1; /*touch active interrupt raw*/
uint32_t rtc_touch_inactive: 1; /*touch inactive interrupt raw*/
uint32_t rtc_brown_out: 1; /*brown out interrupt raw*/
uint32_t rtc_main_timer: 1; /*RTC main timer interrupt raw*/
uint32_t rtc_saradc1: 1; /*saradc1 interrupt raw*/
uint32_t rtc_tsens: 1; /*tsens interrupt raw*/
uint32_t rtc_cocpu: 1; /*riscV cocpu interrupt raw*/
uint32_t rtc_saradc2: 1; /*saradc2 interrupt raw*/
uint32_t rtc_swd: 1; /*super watch dog interrupt raw*/
uint32_t rtc_xtal32k_dead: 1; /*xtal32k dead detection interrupt raw*/
uint32_t rtc_cocpu_trap: 1; /*cocpu trap interrupt raw*/
uint32_t reserved18: 14;
};
uint32_t val;
} int_raw;
union {
struct {
uint32_t slp_wakeup: 1; /*sleep wakeup interrupt state*/
uint32_t slp_reject: 1; /*sleep reject interrupt state*/
uint32_t sdio_idle: 1; /*SDIO idle interrupt state*/
uint32_t rtc_wdt: 1; /*RTC WDT interrupt state*/
uint32_t rtc_time_valid: 1; /*RTC time valid interrupt state*/
uint32_t rtc_ulp_cp: 1; /*ULP-coprocessor interrupt state*/
uint32_t rtc_touch: 1; /*touch interrupt state*/
uint32_t rtc_brown_out: 1; /*brown out interrupt state*/
uint32_t rtc_main_timer: 1; /*RTC main timer interrupt state*/
uint32_t rtc_saradc1: 1; /*saradc1 interrupt state*/
uint32_t rtc_tsens: 1; /*tsens interrupt state*/
uint32_t rtc_cocpu: 1; /*riscV cocpu interrupt state*/
uint32_t rtc_saradc2: 1; /*saradc2 interrupt state*/
uint32_t reserved13: 19;
uint32_t slp_wakeup: 1; /*sleep wakeup interrupt state*/
uint32_t slp_reject: 1; /*sleep reject interrupt state*/
uint32_t sdio_idle: 1; /*SDIO idle interrupt state*/
uint32_t rtc_wdt: 1; /*RTC WDT interrupt state*/
uint32_t rtc_time_valid: 1; /*RTC time valid interrupt state*/
uint32_t rtc_ulp_cp: 1; /*ULP-coprocessor interrupt state*/
uint32_t rtc_touch_done: 1; /*touch done interrupt state*/
uint32_t rtc_touch_active: 1; /*touch active interrupt state*/
uint32_t rtc_touch_inactive: 1; /*touch inactive interrupt state*/
uint32_t rtc_brown_out: 1; /*brown out interrupt state*/
uint32_t rtc_main_timer: 1; /*RTC main timer interrupt state*/
uint32_t rtc_saradc1: 1; /*saradc1 interrupt state*/
uint32_t rtc_tsens: 1; /*tsens interrupt state*/
uint32_t rtc_cocpu: 1; /*riscV cocpu interrupt state*/
uint32_t rtc_saradc2: 1; /*saradc2 interrupt state*/
uint32_t rtc_swd: 1; /*super watch dog interrupt state*/
uint32_t rtc_xtal32k_dead: 1; /*xtal32k dead detection interrupt state*/
uint32_t rtc_cocpu_trap: 1; /*cocpu trap interrupt state*/
uint32_t reserved18: 14;
};
uint32_t val;
} int_st;
union {
struct {
uint32_t slp_wakeup: 1; /*Clear sleep wakeup interrupt state*/
uint32_t slp_reject: 1; /*Clear sleep reject interrupt state*/
uint32_t sdio_idle: 1; /*Clear SDIO idle interrupt state*/
uint32_t rtc_wdt: 1; /*Clear RTC WDT interrupt state*/
uint32_t rtc_time_valid: 1; /*Clear RTC time valid interrupt state*/
uint32_t rtc_ulp_cp: 1; /*Clear ULP-coprocessor interrupt state*/
uint32_t rtc_touch: 1; /*Clear touch interrupt state*/
uint32_t rtc_brown_out: 1; /*Clear brown out interrupt state*/
uint32_t rtc_main_timer: 1; /*Clear RTC main timer interrupt state*/
uint32_t rtc_saradc1: 1; /*Clear saradc1 interrupt state*/
uint32_t rtc_tsens: 1; /*Clear tsens interrupt state*/
uint32_t rtc_cocpu: 1; /*Clear riscV cocpu interrupt state*/
uint32_t rtc_saradc2: 1; /*Clear saradc2 interrupt state*/
uint32_t reserved13: 19;
uint32_t slp_wakeup: 1; /*Clear sleep wakeup interrupt state*/
uint32_t slp_reject: 1; /*Clear sleep reject interrupt state*/
uint32_t sdio_idle: 1; /*Clear SDIO idle interrupt state*/
uint32_t rtc_wdt: 1; /*Clear RTC WDT interrupt state*/
uint32_t rtc_time_valid: 1; /*Clear RTC time valid interrupt state*/
uint32_t rtc_ulp_cp: 1; /*Clear ULP-coprocessor interrupt state*/
uint32_t rtc_touch_done: 1; /*Clear touch done interrupt state*/
uint32_t rtc_touch_active: 1; /*Clear touch active interrupt state*/
uint32_t rtc_touch_inactive: 1; /*Clear touch inactive interrupt state*/
uint32_t rtc_brown_out: 1; /*Clear brown out interrupt state*/
uint32_t rtc_main_timer: 1; /*Clear RTC main timer interrupt state*/
uint32_t rtc_saradc1: 1; /*Clear saradc1 interrupt state*/
uint32_t rtc_tsens: 1; /*Clear tsens interrupt state*/
uint32_t rtc_cocpu: 1; /*Clear riscV cocpu interrupt state*/
uint32_t rtc_saradc2: 1; /*Clear saradc2 interrupt state*/
uint32_t rtc_swd: 1; /*Clear super watch dog interrupt state*/
uint32_t rtc_xtal32k_dead: 1; /*Clear RTC WDT interrupt state*/
uint32_t rtc_cocpu_trap: 1; /*Clear cocpu trap interrupt state*/
uint32_t reserved18: 14;
};
uint32_t val;
} int_clr;
uint32_t store[4]; /**/
union {
struct {
uint32_t reserved0: 30;
uint32_t ctr_lv: 1; /*0: power down XTAL at high level 1: power down XTAL at low level*/
uint32_t ctr_en: 1;
uint32_t xtal32k_wdt_en: 1; /*xtal 32k watch dog enable*/
uint32_t xtal32k_wdt_clk_fo: 1; /*xtal 32k watch dog clock force on*/
uint32_t xtal32k_wdt_reset: 1; /*xtal 32k watch dog sw reset*/
uint32_t xtal32k_ext_clk_fo: 1; /*xtal 32k external xtal clock force on*/
uint32_t xtal32k_auto_backup: 1; /*xtal 32k switch to back up clock when xtal is dead*/
uint32_t xtal32k_auto_restart: 1; /*xtal 32k restart xtal when xtal is dead*/
uint32_t xtal32k_auto_return: 1; /*xtal 32k switch back xtal when xtal is restarted*/
uint32_t xtal32k_xpd_force: 1; /*Xtal 32k xpd control by sw or fsm*/
uint32_t enckinit_xtal_32k: 1; /*apply an internal clock to help xtal 32k to start*/
uint32_t dbuf_xtal_32k: 1; /*0: single-end buffer 1: differential buffer*/
uint32_t dgm_xtal_32k: 3; /*xtal_32k gm control*/
uint32_t dres_xtal_32k: 3; /*DRES_XTAL_32K*/
uint32_t xpd_xtal_32k: 1; /*XPD_XTAL_32K*/
uint32_t dac_xtal_32k: 6; /*DAC_XTAL_32K*/
uint32_t rtc_xtal32k_gpio_sel: 1; /*XTAL_32K sel. 0: external XTAL_32K 1: CLK from RTC pad X32P_C*/
uint32_t reserved24: 6;
uint32_t ctr_lv: 1; /*0: power down XTAL at high level 1: power down XTAL at low level*/
uint32_t ctr_en: 1;
};
uint32_t val;
} ext_xtl_conf;
@ -282,12 +312,10 @@ typedef volatile struct {
} ext_wakeup_conf;
union {
struct {
uint32_t reserved0: 24;
uint32_t gpio_reject_en: 1; /*enable GPIO reject*/
uint32_t sdio_reject_en: 1; /*enable SDIO reject*/
uint32_t light_slp_reject_en: 1; /*enable reject for light sleep*/
uint32_t deep_slp_reject_en: 1; /*enable reject for deep sleep*/
uint32_t reject_cause: 4;
uint32_t reject_cause: 15; /*sleep reject cause*/
uint32_t rtc_sleep_reject_ena:15; /*sleep reject enable*/
uint32_t light_slp_reject_en: 1; /*enable reject for light sleep*/
uint32_t deep_slp_reject_en: 1; /*enable reject for deep sleep*/
};
uint32_t val;
} slp_reject_conf;
@ -331,12 +359,7 @@ typedef volatile struct {
} clk_conf;
union {
struct {
uint32_t reserved0: 14;
uint32_t dbias_xtal_32k: 2; /*DBIAS_XTAL_32K*/
uint32_t dres_xtal_32k: 2; /*DRES_XTAL_32K*/
uint32_t xpd_xtal_32k: 1; /*XPD_XTAL_32K*/
uint32_t dac_xtal_32k: 2; /*DAC_XTAL_32K*/
uint32_t rtc_xtal32k_gpio_sel: 1; /*XTAL_32K sel. 0: external XTAL_32K 1: CLK from RTC pad X32P_C*/
uint32_t reserved0: 22;
uint32_t rtc_ana_clk_div_vld: 1; /*used to sync div bus. clear vld before set reg_rtc_ana_clk_div then set vld to actually switch the clk*/
uint32_t rtc_ana_clk_div: 8;
uint32_t slow_clk_next_edge: 1;
@ -345,22 +368,30 @@ typedef volatile struct {
} slow_clk_conf;
union {
struct {
uint32_t reserved0: 21;
uint32_t sdio_pd_en: 1; /*power down SDIO_REG in sleep. Only active when reg_sdio_force = 0*/
uint32_t sdio_force: 1; /*1: use SW option to control SDIO_REG 0: use state machine*/
uint32_t sdio_tieh: 1; /*SW option for SDIO_TIEH. Only active when reg_sdio_force = 1*/
uint32_t reg1p8_ready: 1; /*read only register for REG1P8_READY*/
uint32_t drefl_sdio: 2; /*SW option for DREFL_SDIO. Only active when reg_sdio_force = 1*/
uint32_t drefm_sdio: 2; /*SW option for DREFM_SDIO. Only active when reg_sdio_force = 1*/
uint32_t drefh_sdio: 2; /*SW option for DREFH_SDIO. Only active when reg_sdio_force = 1*/
uint32_t xpd_sdio: 1;
uint32_t sdio_timer_target: 8; /*timer count to apply reg_sdio_dcap after sdio power on*/
uint32_t reserved8: 1;
uint32_t sdio_dthdrv: 2; /*Tieh = 1 mode drive ability. Initially set to 0 to limit charge current set to 3 after several us.*/
uint32_t sdio_dcap: 2; /*ability to prevent LDO from overshoot*/
uint32_t sdio_initi: 2; /*add resistor from ldo output to ground. 0: no res 1: 6k 2: 4k 3: 2k*/
uint32_t sdio_en_initi: 1; /*0 to set init[1:0]=0*/
uint32_t sdio_dcurlim: 3; /*tune current limit threshold when tieh = 0. About 800mA/(8+d)*/
uint32_t sdio_modecurlim: 1; /*select current limit mode*/
uint32_t sdio_encurlim: 1; /*enable current limit*/
uint32_t sdio_pd_en: 1; /*power down SDIO_REG in sleep. Only active when reg_sdio_force = 0*/
uint32_t sdio_force: 1; /*1: use SW option to control SDIO_REG 0: use state machine*/
uint32_t sdio_tieh: 1; /*SW option for SDIO_TIEH. Only active when reg_sdio_force = 1*/
uint32_t reg1p8_ready: 1; /*read only register for REG1P8_READY*/
uint32_t drefl_sdio: 2; /*SW option for DREFL_SDIO. Only active when reg_sdio_force = 1*/
uint32_t drefm_sdio: 2; /*SW option for DREFM_SDIO. Only active when reg_sdio_force = 1*/
uint32_t drefh_sdio: 2; /*SW option for DREFH_SDIO. Only active when reg_sdio_force = 1*/
uint32_t xpd_sdio: 1;
};
uint32_t val;
} sdio_conf;
union {
struct {
uint32_t reserved0: 24;
uint32_t dbg_atten: 2; /*DBG_ATTEN*/
uint32_t reserved0: 22;
uint32_t dbg_atten: 4; /*DBG_ATTEN*/
uint32_t enb_sck_xtal: 1; /*ENB_SCK_XTAL*/
uint32_t inc_heartbeat_refresh: 1; /*INC_HEARTBEAT_REFRESH*/
uint32_t dec_heartbeat_period: 1; /*DEC_HEARTBEAT_PERIOD*/
@ -408,14 +439,8 @@ typedef volatile struct {
uint32_t rtc_force_pd: 1; /*rtc_peri force power down*/
uint32_t rtc_force_pu: 1; /*rtc_peri force power up*/
uint32_t rtc_pd_en: 1; /*enable power down rtc_peri in sleep*/
uint32_t rtc_pad_autohold: 1; /*read only register to indicate rtc pad auto-hold status*/
uint32_t clr_rtc_pad_autohold: 1; /*wtite only register to clear rtc pad auto-hold*/
uint32_t rtc_pad_autohold_en: 1; /*rtc pad enable auto-hold*/
uint32_t rtc_pad_force_noiso: 1; /*rtc pad force no ISO*/
uint32_t rtc_pad_force_iso: 1; /*rtc pad force ISO*/
uint32_t rtc_pad_force_unhold: 1; /*rtc pad force un-hold*/
uint32_t rtc_pad_force_hold: 1; /*rtc pad force hold*/
uint32_t reserved28: 4;
uint32_t reserved22: 10;
};
uint32_t val;
} rtc_pwc;
@ -487,15 +512,14 @@ typedef volatile struct {
} dig_iso;
union {
struct {
uint32_t reserved0: 7;
uint32_t chip_reset_width: 8; /*chip reset siginal pulse width*/
uint32_t chip_reset_en: 1; /*wdt reset whole chip enable*/
uint32_t pause_in_slp: 1; /*pause WDT in sleep*/
uint32_t appcpu_reset_en: 1; /*enable WDT reset APP CPU*/
uint32_t procpu_reset_en: 1; /*enable WDT reset PRO CPU*/
uint32_t flashboot_mod_en: 1; /*enable WDT in flash boot*/
uint32_t sys_reset_length: 3; /*system reset counter length*/
uint32_t cpu_reset_length: 3; /*CPU reset counter length*/
uint32_t level_int_en: 1; /*N/A*/
uint32_t edge_int_en: 1; /*N/A*/
uint32_t stg3: 3; /*1: interrupt stage en 2: CPU reset stage en 3: system reset stage en 4: RTC reset stage en*/
uint32_t stg2: 3; /*1: interrupt stage en 2: CPU reset stage en 3: system reset stage en 4: RTC reset stage en*/
uint32_t stg1: 3; /*1: interrupt stage en 2: CPU reset stage en 3: system reset stage en 4: RTC reset stage en*/
@ -518,7 +542,22 @@ typedef volatile struct {
uint32_t wdt_wprotect; /**/
union {
struct {
uint32_t reserved0: 29;
uint32_t swd_reset_flag: 1; /*swd reset flag*/
uint32_t swd_feed_int: 1; /*swd interrupt for feeding*/
uint32_t reserved2: 16;
uint32_t swd_signal_width:10; /*adjust signal width send to swd*/
uint32_t swd_rst_flag_clr: 1; /*reset swd reset flag*/
uint32_t swd_feed: 1; /*Sw feed swd*/
uint32_t swd_disable: 1; /*disabel SWD*/
uint32_t swd_auto_feed_en: 1; /*automatically feed swd when int comes*/
};
uint32_t val;
} swd_conf;
uint32_t swd_wprotect; /*swd write protect*/
union {
struct {
uint32_t reserved0: 28;
uint32_t ent_tsens: 1; /*ENT_TSENS*/
uint32_t ent_rtc: 1; /*ENT_RTC*/
uint32_t dtest_rtc: 2;
};
@ -547,14 +586,14 @@ typedef volatile struct {
uint32_t xpd_wifi: 1; /*wifi wrap power down*/
uint32_t dig_iso: 1; /*digital wrap iso*/
uint32_t xpd_dig: 1; /*digital wrap power down*/
uint32_t rtc_touch_start: 1; /*touch should start to work*/
uint32_t rtc_touch_state_start: 1; /*touch should start to work*/
uint32_t rtc_touch_state_switch: 1; /*touch is about to working. Switch rtc main state*/
uint32_t rtc_touch_slp: 1; /*touch is in sleep state*/
uint32_t rtc_touch_done: 1; /*touch is done*/
uint32_t rtc_cocpu_start: 1; /*ulp/cocpu should start to work*/
uint32_t rtc_touch_state_slp: 1; /*touch is in sleep state*/
uint32_t rtc_touch_state_done: 1; /*touch is done*/
uint32_t rtc_cocpu_state_start: 1; /*ulp/cocpu should start to work*/
uint32_t rtc_cocpu_state_switch: 1; /*ulp/cocpu is about to working. Switch rtc main state*/
uint32_t rtc_cocpu_slp: 1; /*ulp/cocpu is in sleep state*/
uint32_t rtc_cocpu_done: 1; /*ulp/cocpu is done*/
uint32_t rtc_cocpu_state_slp: 1; /*ulp/cocpu is in sleep state*/
uint32_t rtc_cocpu_state_done: 1; /*ulp/cocpu is done*/
uint32_t rtc_main_state_xtal_iso: 1; /*no use any more*/
uint32_t rtc_main_state_pll_on: 1; /*rtc main state machine is in states that pll should be running*/
uint32_t rtc_rdy_for_wakeup: 1; /*rtc is ready to receive wake up trigger from wake up source*/
@ -573,62 +612,216 @@ typedef volatile struct {
uint32_t diag0; /**/
union {
struct {
uint32_t adc1_hold_force: 1;
uint32_t adc2_hold_force: 1;
uint32_t pdac1_hold_force: 1;
uint32_t pdac2_hold_force: 1;
uint32_t sense1_hold_force: 1;
uint32_t sense2_hold_force: 1;
uint32_t sense3_hold_force: 1;
uint32_t sense4_hold_force: 1;
uint32_t touch_pad0_hold_force: 1;
uint32_t touch_pad1_hold_force: 1;
uint32_t touch_pad2_hold_force: 1;
uint32_t touch_pad3_hold_force: 1;
uint32_t touch_pad4_hold_force: 1;
uint32_t touch_pad5_hold_force: 1;
uint32_t touch_pad6_hold_force: 1;
uint32_t touch_pad7_hold_force: 1;
uint32_t x32p_hold_force: 1;
uint32_t x32n_hold_force: 1;
uint32_t reserved18: 14;
uint32_t touch_pad0_hold: 1;
uint32_t touch_pad1_hold: 1;
uint32_t touch_pad2_hold: 1;
uint32_t touch_pad3_hold: 1;
uint32_t touch_pad4_hold: 1;
uint32_t touch_pad5_hold: 1;
uint32_t touch_pad6_hold: 1;
uint32_t touch_pad7_hold: 1;
uint32_t touch_pad8_hold: 1;
uint32_t touch_pad9_hold: 1;
uint32_t touch_pad10_hold: 1;
uint32_t touch_pad11_hold: 1;
uint32_t touch_pad12_hold: 1;
uint32_t touch_pad13_hold: 1;
uint32_t touch_pad14_hold: 1;
uint32_t x32p_hold: 1;
uint32_t x32n_hold: 1;
uint32_t pdac1_hold: 1;
uint32_t pdac2_hold: 1;
uint32_t rtc_pad19_hold: 1;
uint32_t rtc_pad20_hold: 1;
uint32_t rtc_pad21_hold: 1;
uint32_t reserved22: 10;
};
uint32_t val;
} hold_force;
} pad_hold;
uint32_t dig_pad_hold; /**/
union {
struct {
uint32_t sel: 18; /*Bitmap to select RTC pads for ext wakeup1*/
uint32_t sel: 22; /*Bitmap to select RTC pads for ext wakeup1*/
uint32_t status_clr: 1; /*clear ext wakeup1 status*/
uint32_t reserved19: 13;
uint32_t reserved23: 9;
};
uint32_t val;
} ext_wakeup1;
union {
struct {
uint32_t status: 18; /*ext wakeup1 status*/
uint32_t reserved18: 14;
uint32_t status: 22; /*ext wakeup1 status*/
uint32_t reserved22: 10;
};
uint32_t val;
} ext_wakeup1_status;
union {
struct {
uint32_t reserved0: 14;
uint32_t reserved0: 4;
uint32_t int_wait: 10; /*brown out interrupt wait cycles*/
uint32_t close_flash_ena: 1; /*enable close flash when brown out happens*/
uint32_t pd_rf_ena: 1; /*enable power down RF when brown out happens*/
uint32_t rst_wait: 10; /*brown out reset wait cycles*/
uint32_t rst_ena: 1; /*enable brown out reset*/
uint32_t thres: 3; /*brown out threshold*/
uint32_t reserved27: 2;
uint32_t cnt_clr: 1; /*clear brown out counter*/
uint32_t ena: 1; /*enable brown out*/
uint32_t det: 1;
};
uint32_t val;
} brown_out;
uint32_t reserved_3c;
uint32_t reserved_40;
uint32_t reserved_44;
uint32_t reserved_48;
uint32_t reserved_4c;
uint32_t time_low1; /*RTC timer low 32 bits*/
union {
struct {
uint32_t rtc_timer_value1_high:16; /*RTC timer high 16 bits*/
uint32_t reserved16: 16;
};
uint32_t val;
} time_high1;
uint32_t xtal32k_clk_factor; /*xtal 32k watch dog backup clock factor*/
union {
struct {
uint32_t xtal32k_return_wait: 4; /*cycles to wait to return noral xtal 32k*/
uint32_t xtal32k_restart_wait:16; /*cycles to wait to repower on xtal 32k*/
uint32_t xtal32k_wdt_timeout: 8; /*If no clock detected for this amount of time 32k is regarded as dead*/
uint32_t xtal32k_stable_thres: 4; /*if restarted xtal32k period is smaller than this it is regarded as stable*/
};
uint32_t val;
} xtal32k_conf;
union {
struct {
uint32_t ulp_cp_pc_init: 11; /*ULP-coprocessor PC initial address*/
uint32_t reserved11: 1;
uint32_t ulp_cp_timer_slp_cycle:16; /*sleep cycles for ULP-coprocessor timer*/
uint32_t reserved28: 1;
uint32_t ulp_cp_gpio_wakeup_ena: 1; /*ULP-coprocessor wakeup by GPIO enable*/
uint32_t ulp_cp_gpio_wakeup_clr: 1; /*ULP-coprocessor wakeup by GPIO state clear*/
uint32_t ulp_cp_slp_timer_en: 1; /*ULP-coprocessor timer enable bit*/
};
uint32_t val;
} ulp_cp_timer;
union {
struct {
uint32_t ulp_cp_mem_addr_init: 11;
uint32_t ulp_cp_mem_addr_size: 11;
uint32_t ulp_cp_mem_offst_clr: 1;
uint32_t reserved23: 5;
uint32_t ulp_cp_clk_fo: 1; /*ulp coprocessor clk force on*/
uint32_t ulp_cp_reset: 1; /*ulp coprocessor clk software reset*/
uint32_t ulp_cp_force_start_top: 1; /*1: ULP-coprocessor is started by SW*/
uint32_t ulp_cp_start_top: 1; /*Write 1 to start ULP-coprocessor*/
};
uint32_t val;
} ulp_cp_ctrl;
union {
struct {
uint32_t cocpu_clk_fo: 1; /*cocpu clk force on*/
uint32_t cocpu_start_2_reset_dis: 6; /*time from start cocpu to pull down reset*/
uint32_t cocpu_start_2_intr_en: 6; /*time from start cocpu to give start interrupt*/
uint32_t cocpu_shut: 1; /*to shut cocpu*/
uint32_t cocpu_shut_2_clk_dis: 6; /*time from shut cocpu to disable clk*/
uint32_t cocpu_shut_reset_en: 1; /*to reset cocpu*/
uint32_t cocpu_sel: 1; /*1: old ULP 0: new riscV*/
uint32_t cocpu_done_force: 1; /*1: select riscv done 0: select ulp done*/
uint32_t cocpu_done: 1; /*done signal used by riscv to control timer.*/
uint32_t cocpu_sw_int_trigger: 1; /*trigger cocpu register interrupt*/
uint32_t reserved25: 7;
};
uint32_t val;
} cocpu_ctrl;
union {
struct {
uint32_t touch_sleep_cycles:16; /*sleep cycles for timer*/
uint32_t touch_meas_num: 16; /*the meas length (in 8MHz)*/
};
uint32_t val;
} touch_ctrl1;
union {
struct {
uint32_t reserved0: 2;
uint32_t touch_drange: 2; /*TOUCH_DRANGE*/
uint32_t touch_drefl: 2; /*TOUCH_DREFL*/
uint32_t touch_drefh: 2; /*TOUCH_DREFH*/
uint32_t touch_xpd_bias: 1; /*TOUCH_XPD_BIAS*/
uint32_t touch_refc: 3; /*TOUCH pad0 reference cap*/
uint32_t reserved12: 1;
uint32_t touch_slp_timer_en: 1; /*touch timer enable bit*/
uint32_t touch_start_fsm_en: 1; /*1: TOUCH_START & TOUCH_XPD is controlled by touch fsm*/
uint32_t touch_start_en: 1; /*1: start touch fsm*/
uint32_t touch_start_force: 1; /*1: to start touch fsm by SW*/
uint32_t touch_xpd_wait: 8; /*the waiting cycles (in 8MHz) between TOUCH_START and TOUCH_XPD*/
uint32_t touch_slp_cyc_div: 2; /*when a touch pad is active sleep cycle could be divided by this number*/
uint32_t reserved27: 2;
uint32_t touch_reset: 1; /*reset upgrade touch*/
uint32_t touch_clk_fo: 1; /*touch clock force on*/
uint32_t touch_clkgate_en: 1; /*touch clock enable*/
};
uint32_t val;
} touch_ctrl2;
union {
struct {
uint32_t touch_denoise_res: 2; /*De-noise resolution: 12/10/8/4 bit*/
uint32_t touch_denoise_en: 1; /*touch pad0 will be used to de-noise*/
uint32_t reserved3: 5;
uint32_t touch_inactive_connection: 1; /*inactive touch pads connect to 1: gnd 0: HighZ*/
uint32_t touch_shield_pad_en: 1; /*touch pad14 will be used as shield*/
uint32_t touch_scan_pad_map: 15; /*touch scan mode pad enable map*/
uint32_t touch_bufdrv: 3; /*touch7 buffer driver strength*/
uint32_t touch_out_ring: 4; /*select out ring pad*/
};
uint32_t val;
} touch_scan_ctrl;
union {
struct {
uint32_t touch_slp_th: 22; /*the threshold for sleep touch pad*/
uint32_t reserved22: 4;
uint32_t touch_slp_approach_en: 1; /*sleep pad approach function enable*/
uint32_t touch_slp_pad: 5;
};
uint32_t val;
} touch_slp_thres;
union {
struct {
uint32_t reserved0: 23;
uint32_t touch_slp_channel_clr: 1; /*clear touch slp channel*/
uint32_t touch_approach_meas_time: 8; /*approach pads total meas times*/
};
uint32_t val;
} touch_approach;
union {
struct {
uint32_t reserved0: 12;
uint32_t touch_jitter_step: 4; /*touch jitter step*/
uint32_t touch_neg_noise_limit: 4; /*negative threshold counter limit*/
uint32_t touch_neg_noise_thres: 2;
uint32_t touch_noise_thres: 2;
uint32_t touch_hysteresis: 2;
uint32_t touch_debounce: 3; /*debounce counter*/
uint32_t touch_filter_mode: 2; /*0: IIR ? 1: IIR ? 2: IIR 1/8 3: Jitter*/
uint32_t touch_filter_en: 1; /*touch filter enable*/
};
uint32_t val;
} touch_filter_ctrl;
union {
struct {
uint32_t usb_vrefh: 2;
uint32_t usb_vrefl: 2;
uint32_t usb_vref_override: 1;
uint32_t usb_pad_pull_override: 1;
uint32_t usb_dp_pullup: 1;
uint32_t usb_dp_pulldown: 1;
uint32_t usb_dm_pullup: 1;
uint32_t usb_dm_pulldown: 1;
uint32_t usb_pullup_value: 1;
uint32_t usb_pad_enable_override: 1;
uint32_t usb_pad_enable: 1;
uint32_t usb_txm: 1;
uint32_t usb_txp: 1;
uint32_t usb_tx_en: 1;
uint32_t usb_tx_en_override: 1;
uint32_t reserved17: 15;
};
uint32_t val;
} usb_conf;
union {
struct {
uint32_t date: 28;

View File

@ -171,13 +171,9 @@ typedef volatile struct {
} fifo_data;
union {
struct {
uint32_t byte_num: 8; /*Byte_num represent the number of data need to be send or data need to be received.*/
uint32_t ack_en: 1; /*ack_check_en ack_exp and ack value are used to control the ack bit.*/
uint32_t ack_exp: 1; /*ack_check_en ack_exp and ack value are used to control the ack bit.*/
uint32_t ack_val: 1; /*ack_check_en ack_exp and ack value are used to control the ack bit.*/
uint32_t op_code: 3; /*op_code is the command 0RSTART 1WRITE 2READ 3STOP . 4:END.*/
uint32_t command: 14; /*command*/
uint32_t reserved14: 17;
uint32_t done: 1; /*command0_done*/
uint32_t done: 1; /*command_done*/
};
uint32_t val;
} command[16];

File diff suppressed because it is too large Load Diff

View File

@ -1,9 +1,9 @@
// Copyright 2015-2016 Espressif Systems (Shanghai) PTE LTD
// Copyright 2017-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
@ -20,82 +20,143 @@ extern "C" {
typedef volatile struct {
union {
struct {
uint32_t sar1_clk_div: 8; /*clock divider*/
uint32_t sar1_sample_cycle: 8; /*sample cycles for SAR ADC1*/
uint32_t sar1_sample_bit: 2; /*00: for 9-bit width 01: for 10-bit width 10: for 11-bit width 11: for 12-bit width*/
uint32_t sar1_clk_div: 8; /*clock divider*/
uint32_t sar1_sample_cycle: 8; /*sample cycles for SAR ADC1*/
uint32_t sar1_sample_bit: 2; /*00: for 9-bit width*/
uint32_t sar1_clk_gated: 1;
uint32_t sar1_sample_num: 8;
uint32_t sar1_dig_force: 1; /*1: SAR ADC1 controlled by DIG ADC1 CTRL 0: SAR ADC1 controlled by RTC ADC1 CTRL*/
uint32_t sar1_data_inv: 1; /*Invert SAR ADC1 data*/
uint32_t reserved29: 3;
uint32_t reserved27: 1;
uint32_t sar1_data_inv: 1; /*Invert SAR ADC1 data*/
uint32_t sar1_int_en: 1; /*enable saradc1 to send out interrupt*/
uint32_t reserved30: 2;
};
uint32_t val;
} sar_read_ctrl;
uint32_t sar_read_status1; /**/
} sar_reader1_ctrl;
uint32_t sar_reader1_status; /**/
union {
struct {
uint32_t sar1_bit_width: 2; /*00: 9 bit*/
uint32_t sar1_stop: 1; /*stop SAR ADC1 conversion*/
uint32_t reserved3: 21;
uint32_t force_xpd_amp: 2;
uint32_t amp_rst_fb_force: 2;
uint32_t amp_short_ref_force: 2;
uint32_t amp_short_ref_gnd_force: 2;
};
uint32_t val;
} sar_meas1_ctrl1;
union {
struct {
uint32_t meas1_data_sar: 16; /*SAR ADC1 data*/
uint32_t meas1_done_sar: 1; /*SAR ADC1 conversion done indication*/
uint32_t meas1_start_sar: 1; /*SAR ADC1 controller (in RTC) starts conversion*/
uint32_t meas1_start_force: 1; /*1: SAR ADC1 controller (in RTC) is started by SW*/
uint32_t sar1_en_pad: 12; /*SAR ADC1 pad enable bitmap*/
uint32_t sar1_en_pad_force: 1; /*1: SAR ADC1 pad enable bitmap is controlled by SW*/
};
uint32_t val;
} sar_meas1_ctrl2;
union {
struct {
uint32_t reserved0: 31;
uint32_t sar1_dig_force: 1; /*1: SAR ADC1 controlled by DIG ADC1 CTRL*/
};
uint32_t val;
} sar_meas1_mux;
uint32_t sar_atten1; /*2-bit attenuation for each pad*/
union {
struct {
uint32_t sar_amp_wait1:16;
uint32_t sar_amp_wait2:16;
};
uint32_t val;
} sar_meas_wait1;
} sar_amp_ctrl1;
union {
struct {
uint32_t sar_amp_wait3: 16;
uint32_t force_xpd_amp: 2;
uint32_t force_xpd_sar: 2;
uint32_t sar2_rstb_wait: 8;
uint32_t reserved28: 4;
uint32_t sar1_dac_xpd_fsm_idle: 1;
uint32_t xpd_sar_amp_fsm_idle: 1;
uint32_t amp_rst_fb_fsm_idle: 1;
uint32_t amp_short_ref_fsm_idle: 1;
uint32_t amp_short_ref_gnd_fsm_idle: 1;
uint32_t xpd_sar_fsm_idle: 1;
uint32_t sar_rstb_fsm_idle: 1;
uint32_t reserved7: 9;
uint32_t sar_amp_wait3: 16;
};
uint32_t val;
} sar_meas_wait2;
} sar_amp_ctrl2;
union {
struct {
uint32_t sar1_dac_xpd_fsm: 4;
uint32_t xpd_sar_amp_fsm: 4;
uint32_t amp_rst_fb_fsm: 4;
uint32_t amp_short_ref_fsm: 4;
uint32_t amp_short_ref_gnd_fsm: 4;
uint32_t xpd_sar_fsm: 4;
uint32_t sar_rstb_fsm: 4;
uint32_t sar2_xpd_wait: 8;
uint32_t reserved28: 4;
};
uint32_t val;
} sar_meas_ctrl;
uint32_t sar_read_status2; /**/
uint32_t ulp_cp_sleep_cyc0; /*sleep cycles for ULP-coprocessor timer*/
uint32_t ulp_cp_sleep_cyc1; /**/
uint32_t ulp_cp_sleep_cyc2; /**/
uint32_t ulp_cp_sleep_cyc3; /**/
uint32_t ulp_cp_sleep_cyc4; /**/
} sar_amp_ctrl3;
union {
struct {
uint32_t sar1_bit_width: 2; /*00: 9 bit 01: 10 bits 10: 11bits 11: 12bits*/
uint32_t sar2_bit_width: 2; /*00: 9 bit 01: 10 bits 10: 11bits 11: 12bits*/
uint32_t sar2_en_test: 1; /*SAR2_EN_TEST only active when reg_sar2_dig_force = 0*/
uint32_t sar2_pwdet_cct: 3; /*SAR2_PWDET_CCT PA power detector capacitance tuning.*/
uint32_t ulp_cp_force_start_top: 1; /*1: ULP-coprocessor is started by SW 0: ULP-coprocessor is started by timer*/
uint32_t ulp_cp_start_top: 1; /*Write 1 to start ULP-coprocessor only active when reg_ulp_cp_force_start_top = 1*/
uint32_t sarclk_en: 1;
uint32_t pc_init: 11; /*initialized PC for ULP-coprocessor*/
uint32_t sar2_stop: 1; /*stop SAR ADC2 conversion*/
uint32_t sar1_stop: 1; /*stop SAR ADC1 conversion*/
uint32_t sar2_pwdet_en: 1; /*N/A*/
uint32_t reserved25: 7;
uint32_t sar2_clk_div: 8; /*clock divider*/
uint32_t sar2_sample_cycle: 8; /*sample cycles for SAR ADC2*/
uint32_t sar2_sample_bit: 2; /*00: for 9-bit width*/
uint32_t sar2_clk_gated: 1;
uint32_t sar2_sample_num: 8;
uint32_t reserved27: 2;
uint32_t sar2_data_inv: 1; /*Invert SAR ADC2 data*/
uint32_t sar2_int_en: 1; /*enable saradc2 to send out interrupt*/
uint32_t reserved31: 1;
};
uint32_t val;
} sar_start_force;
} sar_reader2_ctrl;
uint32_t sar_reader2_status; /**/
union {
struct {
uint32_t mem_wr_addr_init: 11;
uint32_t mem_wr_addr_size: 11;
uint32_t rtc_mem_wr_offst_clr: 1;
uint32_t ulp_cp_clk_fo: 1; /*ulp coprocessor clk force on*/
uint32_t reserved24: 8;
uint32_t sar2_bit_width: 2; /*00: 9 bit*/
uint32_t sar2_stop: 1; /*stop SAR ADC2 conversion*/
uint32_t sar2_pwdet_cal_en: 1; /*rtc control pwdet enable*/
uint32_t sar2_pkdet_cal_en: 1; /*rtc control pkdet enable*/
uint32_t sar2_en_test: 1; /*SAR2_EN_TEST*/
uint32_t sar2_rstb_force: 2;
uint32_t sar2_standby_wait: 8;
uint32_t sar2_rstb_wait: 8;
uint32_t sar2_xpd_wait: 8;
};
uint32_t val;
} sar_mem_wr_ctrl;
uint32_t sar_atten1; /*2-bit attenuation for each pad 11:1dB 10:6dB 01:3dB 00:0dB*/
uint32_t sar_atten2; /*2-bit attenuation for each pad 11:1dB 10:6dB 01:3dB 00:0dB*/
} sar_meas2_ctrl1;
union {
struct {
uint32_t meas2_data_sar: 16; /*SAR ADC2 data*/
uint32_t meas2_done_sar: 1; /*SAR ADC2 conversion done indication*/
uint32_t meas2_start_sar: 1; /*SAR ADC2 controller (in RTC) starts conversion*/
uint32_t meas2_start_force: 1; /*1: SAR ADC2 controller (in RTC) is started by SW*/
uint32_t sar2_en_pad: 12; /*SAR ADC2 pad enable bitmap*/
uint32_t sar2_en_pad_force: 1; /*1: SAR ADC2 pad enable bitmap is controlled by SW*/
};
uint32_t val;
} sar_meas2_ctrl2;
union {
struct {
uint32_t reserved0: 28;
uint32_t sar2_pwdet_cct: 3; /*SAR2_PWDET_CCT*/
uint32_t sar2_rtc_force: 1; /*in sleep force to use rtc to control ADC*/
};
uint32_t val;
} sar_meas2_mux;
uint32_t sar_atten2; /*2-bit attenuation for each pad*/
union {
struct {
uint32_t reserved0: 23;
uint32_t sar2_dref: 3; /*Adjust saradc2 offset*/
uint32_t sar1_dref: 3; /*Adjust saradc1 offset*/
uint32_t force_xpd_sar: 2;
uint32_t sarclk_en: 1;
};
uint32_t val;
} sar_power_xpd_sar;
union {
struct {
uint32_t i2c_slave_addr1: 11;
@ -117,9 +178,7 @@ typedef volatile struct {
struct {
uint32_t i2c_slave_addr5:11;
uint32_t i2c_slave_addr4:11;
uint32_t tsens_out: 8; /*temperature sensor data out*/
uint32_t tsens_rdy_out: 1; /*indicate temperature sensor out ready*/
uint32_t reserved31: 1;
uint32_t reserved22: 10;
};
uint32_t val;
} sar_slave_addr3;
@ -127,236 +186,227 @@ typedef volatile struct {
struct {
uint32_t i2c_slave_addr7:11;
uint32_t i2c_slave_addr6:11;
uint32_t i2c_rdata: 8; /*I2C read data*/
uint32_t i2c_done: 1; /*indicate I2C done*/
uint32_t reserved31: 1;
uint32_t reserved22: 10;
};
uint32_t val;
} sar_slave_addr4;
union {
struct {
uint32_t tsens_xpd_wait: 12;
uint32_t tsens_xpd_force: 1;
uint32_t tsens_clk_inv: 1;
uint32_t tsens_clk_gated: 1;
uint32_t tsens_in_inv: 1; /*invert temperature sensor data*/
uint32_t tsens_clk_div: 8; /*temperature sensor clock divider*/
uint32_t tsens_power_up: 1; /*temperature sensor power up*/
uint32_t tsens_power_up_force: 1; /*1: dump out & power up controlled by SW 0: by FSM*/
uint32_t tsens_dump_out: 1; /*temperature sensor dump out only active when reg_tsens_power_up_force = 1*/
uint32_t tsens_dos: 4; /*Temperature sensor calibration bits*/
uint32_t tsens_force: 1; /*1: select saradc_reg 0: select efuse*/
uint32_t tsens_out: 8; /*temperature sensor data out*/
uint32_t tsens_ready: 1; /*indicate temperature sensor out ready*/
uint32_t reserved9: 3;
uint32_t tsens_int_en: 1; /*enable temperature sensor to send out interrupt*/
uint32_t tsens_in_inv: 1; /*invert temperature sensor data*/
uint32_t tsens_clk_div: 8; /*temperature sensor clock divider*/
uint32_t tsens_power_up: 1; /*temperature sensor power up*/
uint32_t tsens_power_up_force: 1; /*1: dump out & power up controlled by SW*/
uint32_t tsens_dump_out: 1; /*temperature sensor dump out*/
uint32_t tsens_diz: 1; /*ADC input short*/
uint32_t tsens_div_chop: 2; /*0 for steady phase 0 1 for steady phase 1 2 for chopping with ½ frequency of TSENS_CK 3 for chopping with ¼*/
uint32_t tsens_dac: 4; /*Temperature sensor offset dac. 15 for 0 offset 5 for -2 7 for -1 11 for 1 10 for 2*/
};
uint32_t val;
} sar_tctrl;
union {
struct {
uint32_t sar_i2c_ctrl: 28; /*I2C control data only active when reg_sar_i2c_start_force = 1*/
uint32_t sar_i2c_start: 1; /*start I2C only active when reg_sar_i2c_start_force = 1*/
uint32_t sar_i2c_start_force: 1; /*1: I2C started by SW 0: I2C started by FSM*/
uint32_t tsens_xpd_wait: 12;
uint32_t tsens_xpd_force: 2;
uint32_t tsens_clk_inv: 1;
uint32_t tsens_clkgate_en: 1; /*temperature sensor clock enable*/
uint32_t tsens_reset: 1; /*temperature sensor reset*/
uint32_t reserved17: 15;
};
uint32_t val;
} sar_tctrl2;
union {
struct {
uint32_t sar_i2c_ctrl: 28; /*I2C control data*/
uint32_t sar_i2c_start: 1; /*start I2C*/
uint32_t sar_i2c_start_force: 1; /*1: I2C started by SW*/
uint32_t reserved30: 2;
};
uint32_t val;
} sar_i2c_ctrl;
union {
struct {
uint32_t meas1_data_sar: 16; /*SAR ADC1 data*/
uint32_t meas1_done_sar: 1; /*SAR ADC1 conversion done indication*/
uint32_t meas1_start_sar: 1; /*SAR ADC1 controller (in RTC) starts conversion only active when reg_meas1_start_force = 1*/
uint32_t meas1_start_force: 1; /*1: SAR ADC1 controller (in RTC) is started by SW 0: SAR ADC1 controller is started by ULP-coprocessor*/
uint32_t sar1_en_pad: 12; /*SAR ADC1 pad enable bitmap only active when reg_sar1_en_pad_force = 1*/
uint32_t sar1_en_pad_force: 1; /*1: SAR ADC1 pad enable bitmap is controlled by SW 0: SAR ADC1 pad enable bitmap is controlled by ULP-coprocessor*/
uint32_t touch_outen: 15; /*touch controller output enable*/
uint32_t touch_status_clr: 1; /*clear all touch active status*/
uint32_t reserved16: 4;
uint32_t touch_approach_pad2: 4; /*indicate which pad is approach pad2*/
uint32_t touch_approach_pad1: 4; /*indicate which pad is approach pad1*/
uint32_t touch_approach_pad0: 4; /*indicate which pad is approach pad0*/
};
uint32_t val;
} sar_meas_start1;
} sar_touch_conf;
union {
struct {
uint32_t touch_meas_delay:16; /*the meas length (in 8MHz)*/
uint32_t touch_xpd_wait: 8; /*the waiting cycles (in 8MHz) between TOUCH_START and TOUCH_XPD*/
uint32_t touch_out_sel: 1; /*1: when the counter is greater then the threshold the touch pad is considered as “touched” 0: when the counter is less than the threshold the touch pad is considered as “touched”*/
uint32_t touch_out_1en: 1; /*1: wakeup interrupt is generated if SET1 is “touched” 0: wakeup interrupt is generated only if SET1 & SET2 is both “touched”*/
uint32_t xpd_hall_force: 1; /*1: XPD HALL is controlled by SW. 0: XPD HALL is controlled by FSM in ULP-coprocessor*/
uint32_t hall_phase_force: 1; /*1: HALL PHASE is controlled by SW 0: HALL PHASE is controlled by FSM in ULP-coprocessor*/
uint32_t reserved28: 4;
uint32_t thresh: 22; /*Finger threshold for touch pad 1*/
uint32_t reserved22: 10;
};
uint32_t val;
} sar_touch_ctrl1;
} touch_thresh[14];
union {
struct {
uint32_t l_thresh: 16; /*the threshold for touch pad 1*/
uint32_t h_thresh: 16; /*the threshold for touch pad 0*/
uint32_t meas_out: 22; /*the counter for touch pad 1*/
uint32_t reserved22: 10;
};
uint32_t val;
} touch_thresh[5];
} touch_meas[15];
union {
struct {
uint32_t l_val: 16; /*the counter for touch pad 1*/
uint32_t h_val: 16; /*the counter for touch pad 0*/
uint32_t touch_pad_active: 15; /*touch active status*/
uint32_t touch_channel_clr:15; /*Clear touch channel*/
uint32_t reserved30: 1;
uint32_t touch_meas_done: 1;
};
uint32_t val;
} touch_meas[5];
} sar_touch_chn_st;
union {
struct {
uint32_t touch_meas_en: 10; /*10-bit register to indicate which pads are “touched”*/
uint32_t touch_meas_done: 1; /*fsm set 1 to indicate touch touch meas is done*/
uint32_t touch_start_fsm_en: 1; /*1: TOUCH_START & TOUCH_XPD is controlled by touch fsm 0: TOUCH_START & TOUCH_XPD is controlled by registers*/
uint32_t touch_start_en: 1; /*1: start touch fsm valid when reg_touch_start_force is set*/
uint32_t touch_start_force: 1; /*1: to start touch fsm by SW 0: to start touch fsm by timer*/
uint32_t touch_sleep_cycles:16; /*sleep cycles for timer*/
uint32_t touch_meas_en_clr: 1; /*to clear reg_touch_meas_en*/
uint32_t reserved31: 1;
uint32_t touch_denoise_data:22; /*the counter for touch pad 0*/
uint32_t touch_scan_curr: 4;
uint32_t reserved26: 6;
};
uint32_t val;
} sar_touch_ctrl2;
uint32_t reserved_88;
} sar_touch_status0;
union {
struct {
uint32_t touch_pad_worken:10; /*Bitmap defining the working set during the measurement.*/
uint32_t touch_pad_outen2:10; /*Bitmap defining SET2 for generating wakeup interrupt. SET2 is “touched” only if at least one of touch pad in SET2 is “touched”.*/
uint32_t touch_pad_outen1:10; /*Bitmap defining SET1 for generating wakeup interrupt. SET1 is “touched” only if at least one of touch pad in SET1 is “touched”.*/
uint32_t reserved30: 2;
uint32_t touch_pad_baseline: 22;
uint32_t reserved22: 7;
uint32_t touch_pad_debounce: 3;
};
uint32_t val;
} sar_touch_enable;
} sar_touch_status[14];
union {
struct {
uint32_t touch_meas_raw:10; /*touch sensor raw result*/
uint32_t reserved10: 22;
uint32_t touch_approach_pad2_cnt: 8;
uint32_t touch_approach_pad1_cnt: 8;
uint32_t touch_approach_pad0_cnt: 8;
uint32_t touch_slp_approach_cnt: 8;
};
uint32_t val;
} sar_touch_ctrl3;
} sar_touch_status16;
union {
struct {
uint32_t sar2_clk_div: 8; /*clock divider*/
uint32_t sar2_sample_cycle: 8; /*sample cycles for SAR ADC2*/
uint32_t sar2_sample_bit: 2; /*00: for 9-bit width 01: for 10-bit width 10: for 11-bit width 11: for 12-bit width*/
uint32_t sar2_clk_gated: 1;
uint32_t sar2_sample_num: 8;
uint32_t sar2_pwdet_force: 1;
uint32_t sar2_dig_force: 1; /*1: SAR ADC2 controlled by DIG ADC2 CTRL or PWDET CTRL 0: SAR ADC2 controlled by RTC ADC2 CTRL*/
uint32_t sar2_data_inv: 1; /*Invert SAR ADC2 data*/
uint32_t reserved30: 2;
};
uint32_t val;
} sar_read_ctrl2;
union {
struct {
uint32_t meas2_data_sar: 16; /*SAR ADC2 data*/
uint32_t meas2_done_sar: 1; /*SAR ADC2 conversion done indication*/
uint32_t meas2_start_sar: 1; /*SAR ADC2 controller (in RTC) starts conversion only active when reg_meas2_start_force = 1*/
uint32_t meas2_start_force: 1; /*1: SAR ADC2 controller (in RTC) is started by SW 0: SAR ADC2 controller is started by ULP-coprocessor*/
uint32_t sar2_en_pad: 12; /*SAR ADC2 pad enable bitmap only active when reg_sar2_en_pad_force = 1*/
uint32_t sar2_en_pad_force: 1; /*1: SAR ADC2 pad enable bitmap is controlled by SW 0: SAR ADC2 pad enable bitmap is controlled by ULP-coprocessor*/
};
uint32_t val;
} sar_meas_start2;
union {
struct {
uint32_t sw_fstep: 16; /*frequency step for CW generator can be used to adjust the frequency*/
uint32_t sw_tone_en: 1; /*1: enable CW generator 0: disable CW generator*/
uint32_t sw_fstep: 16; /*frequency step for CW generator*/
uint32_t sw_tone_en: 1; /*1: enable CW generator*/
uint32_t debug_bit_sel: 5;
uint32_t dac_dig_force: 1; /*1: DAC1 & DAC2 use DMA 0: DAC1 & DAC2 do not use DMA*/
uint32_t dac_clk_force_low: 1; /*1: force PDAC_CLK to low*/
uint32_t dac_clk_force_high: 1; /*1: force PDAC_CLK to high*/
uint32_t dac_clk_inv: 1; /*1: invert PDAC_CLK*/
uint32_t dac_dig_force: 1; /*1: DAC1 & DAC2 use DMA*/
uint32_t dac_clk_force_low: 1; /*1: force PDAC_CLK to low*/
uint32_t dac_clk_force_high: 1; /*1: force PDAC_CLK to high*/
uint32_t dac_clk_inv: 1; /*1: invert PDAC_CLK*/
uint32_t reserved26: 6;
};
uint32_t val;
} sar_dac_ctrl1;
union {
struct {
uint32_t dac_dc1: 8; /*DC offset for DAC1 CW generator*/
uint32_t dac_dc2: 8; /*DC offset for DAC2 CW generator*/
uint32_t dac_scale1: 2; /*00: no scale 01: scale to 1/2 10: scale to 1/4 scale to 1/8*/
uint32_t dac_scale2: 2; /*00: no scale 01: scale to 1/2 10: scale to 1/4 scale to 1/8*/
uint32_t dac_inv1: 2; /*00: do not invert any bits 01: invert all bits 10: invert MSB 11: invert all bits except MSB*/
uint32_t dac_inv2: 2; /*00: do not invert any bits 01: invert all bits 10: invert MSB 11: invert all bits except MSB*/
uint32_t dac_cw_en1: 1; /*1: to select CW generator as source to PDAC1_DAC[7:0] 0: to select register reg_pdac1_dac[7:0] as source to PDAC1_DAC[7:0]*/
uint32_t dac_cw_en2: 1; /*1: to select CW generator as source to PDAC2_DAC[7:0] 0: to select register reg_pdac2_dac[7:0] as source to PDAC2_DAC[7:0]*/
uint32_t dac_dc1: 8; /*DC offset for DAC1 CW generator*/
uint32_t dac_dc2: 8; /*DC offset for DAC2 CW generator*/
uint32_t dac_scale1: 2; /*00: no scale*/
uint32_t dac_scale2: 2; /*00: no scale*/
uint32_t dac_inv1: 2; /*00: do not invert any bits*/
uint32_t dac_inv2: 2; /*00: do not invert any bits*/
uint32_t dac_cw_en1: 1; /*1: to select CW generator as source to PDAC1_DAC[7:0]*/
uint32_t dac_cw_en2: 1; /*1: to select CW generator as source to PDAC2_DAC[7:0]*/
uint32_t reserved26: 6;
};
uint32_t val;
} sar_dac_ctrl2;
union {
struct {
uint32_t sar1_dac_xpd_fsm: 4;
uint32_t sar1_dac_xpd_fsm_idle: 1;
uint32_t xpd_sar_amp_fsm_idle: 1;
uint32_t amp_rst_fb_fsm_idle: 1;
uint32_t amp_short_ref_fsm_idle: 1;
uint32_t amp_short_ref_gnd_fsm_idle: 1;
uint32_t xpd_sar_fsm_idle: 1;
uint32_t sar_rstb_fsm_idle: 1;
uint32_t sar2_rstb_force: 2;
uint32_t amp_rst_fb_force: 2;
uint32_t amp_short_ref_force: 2;
uint32_t amp_short_ref_gnd_force: 2;
uint32_t reserved19: 13;
uint32_t reserved0: 25;
uint32_t dbg_trigger: 1; /*trigger cocpu debug registers*/
uint32_t clk_en: 1; /*check cocpu whether clk on*/
uint32_t reset_n: 1; /*check cocpu whether in reset state*/
uint32_t eoi: 1; /*check cocpu whether in interrupt state*/
uint32_t trap: 1; /*check cocpu whether in trap state*/
uint32_t ebreak: 1; /*check cocpu whether in ebreak*/
uint32_t reserved31: 1;
};
uint32_t val;
} sar_meas_ctrl2;
} sar_cocpu_state;
union {
struct {
uint32_t clk_fo: 1; /*cocpu clk force on*/
uint32_t start_2_reset_dis: 6; /*time from start cocpu to pull down reset*/
uint32_t start_2_intr_en: 6; /*time from start cocpu to give start interrupt*/
uint32_t shut: 1; /*to shut cocpu*/
uint32_t shut_2_clk_dis: 6; /*time from shut cocpu to disable clk*/
uint32_t shut_reset_en: 1; /*to reset cocpu*/
uint32_t sel: 1; /*1: old ULP 0: new riscV*/
uint32_t done_force: 1; /*1: select riscv done 0: select ulp done*/
uint32_t done: 1; /*done signal used by riscv to control timer.*/
uint32_t int_trigger: 1; /*trigger cocpu register interrupt*/
uint32_t clk_en: 1; /*check cocpu whether clk on*/
uint32_t reset_n: 1; /*check cocpu whether in reset state*/
uint32_t eoi: 1; /*check cocpu whether in interrupt state*/
uint32_t trap: 1; /*check cocpu whether in trap state*/
uint32_t reserved29: 3;
uint32_t touch_done: 1; /*int from touch done*/
uint32_t touch_inactive: 1; /*int from touch inactive*/
uint32_t touch_active: 1; /*int from touch active*/
uint32_t saradc1: 1; /*int from saradc1*/
uint32_t saradc2: 1; /*int from saradc2*/
uint32_t tsens: 1; /*int from tsens*/
uint32_t start: 1; /*int from start*/
uint32_t sw: 1; /*int from software*/
uint32_t swd: 1; /*int from super watch dog*/
uint32_t reserved9: 23;
};
uint32_t val;
} sar_cocpu_ctrl;
} sar_cocpu_int_raw;
union {
struct {
uint32_t saradc_int_ena: 1;
uint32_t tsens_int_ena: 1;
uint32_t start_int_ena: 1;
uint32_t cocpu_int_ena: 1;
uint32_t ebreak_int_ena: 1; /*int enable entry*/
uint32_t reserved5: 5;
uint32_t saradc_int_clr: 1;
uint32_t tsens_int_clr: 1;
uint32_t start_int_clr: 1;
uint32_t cocpu_int_clr: 1;
uint32_t ebreak_int_clr: 1; /*int clear entry*/
uint32_t reserved15: 5;
uint32_t saradc_int: 1; /*int from saradc*/
uint32_t tsens_int: 1; /*int from tsens*/
uint32_t start_int: 1; /*int from start*/
uint32_t cocpu_int: 1; /*int from register*/
uint32_t ebreak_int: 1; /*int from ebreak*/
uint32_t reserved25: 7;
uint32_t touch_done: 1;
uint32_t touch_inactive: 1;
uint32_t touch_active: 1;
uint32_t saradc1: 1;
uint32_t saradc2: 1;
uint32_t tsens: 1;
uint32_t start: 1;
uint32_t sw: 1; /*cocpu int enable*/
uint32_t swd: 1;
uint32_t reserved9: 23;
};
uint32_t val;
} sar_cocpu_int;
uint32_t reserved_b0;
uint32_t reserved_b4;
uint32_t reserved_b8;
uint32_t reserved_bc;
uint32_t reserved_c0;
uint32_t reserved_c4;
uint32_t reserved_c8;
uint32_t reserved_cc;
uint32_t reserved_d0;
uint32_t reserved_d4;
uint32_t reserved_d8;
uint32_t reserved_dc;
uint32_t reserved_e0;
uint32_t reserved_e4;
uint32_t reserved_e8;
uint32_t reserved_ec;
uint32_t reserved_f0;
uint32_t reserved_f4;
uint32_t sar_nouse; /**/
} sar_cocpu_int_ena;
union {
struct {
uint32_t touch_done: 1;
uint32_t touch_inactive: 1;
uint32_t touch_active: 1;
uint32_t saradc1: 1;
uint32_t saradc2: 1;
uint32_t tsens: 1;
uint32_t start: 1;
uint32_t sw: 1; /*cocpu int status*/
uint32_t swd: 1;
uint32_t reserved9: 23;
};
uint32_t val;
} sar_cocpu_int_st;
union {
struct {
uint32_t touch_done: 1;
uint32_t touch_inactive: 1;
uint32_t touch_active: 1;
uint32_t saradc1: 1;
uint32_t saradc2: 1;
uint32_t tsens: 1;
uint32_t start: 1;
uint32_t sw: 1; /*cocpu int clear*/
uint32_t swd: 1;
uint32_t reserved9: 23;
};
uint32_t val;
} sar_cocpu_int_clr;
union {
struct {
uint32_t pc: 13; /*cocpu Program counter*/
uint32_t mem_vld: 1; /*cocpu mem valid output*/
uint32_t mem_rdy: 1; /*cocpu mem ready input*/
uint32_t mem_wen: 4; /*cocpu mem write enable output*/
uint32_t mem_addr: 13; /*cocpu mem address output*/
};
uint32_t val;
} sar_cocpu_debug;
union {
struct {
uint32_t reserved0: 28;
uint32_t xpd_hall: 1; /*Power on hall sensor and connect to VP and VN*/
uint32_t xpd_hall_force: 1; /*1: XPD HALL is controlled by SW. 0: XPD HALL is controlled by FSM in ULP-coprocessor*/
uint32_t hall_phase: 1; /*Reverse phase of hall sensor*/
uint32_t hall_phase_force: 1; /*1: HALL PHASE is controlled by SW 0: HALL PHASE is controlled by FSM in ULP-coprocessor*/
};
uint32_t val;
} sar_hall_ctrl;
uint32_t sar_nouse; /**/
union {
struct {
uint32_t sar_date: 28;

View File

@ -21,98 +21,505 @@ extern "C" {
typedef volatile struct {
union {
struct {
uint32_t pre_div: 10;
uint32_t clk_320m_en: 1;
uint32_t clk_en: 1;
uint32_t rst_tick: 1;
uint32_t quick_clk_chng: 1;
uint32_t reserved14: 18;
uint32_t pre_div: 10;
uint32_t clk_320m_en: 1;
uint32_t clk_en: 1;
uint32_t rst_tick: 1;
uint32_t reserved13: 1;
uint32_t soc_clk_sel: 2;
uint32_t reserved16: 16;
};
uint32_t val;
}clk_conf;
} clk_conf;
union {
struct {
uint32_t xtal_tick: 8;
uint32_t reserved8: 24;
};
uint32_t val;
}xtal_tick_conf;
union {
struct {
uint32_t pll_tick: 8;
uint32_t reserved8: 24;
};
uint32_t val;
}pll_tick_conf;
union {
struct {
uint32_t ck8m_tick: 8;
uint32_t reserved8: 24;
uint32_t tick_enable: 1;
uint32_t reserved17: 15;
};
uint32_t val;
}ck8m_tick_conf;
} tick_conf;
union {
struct {
uint32_t start_force: 1;
uint32_t start: 1;
uint32_t sar2_mux: 1; /*1: SAR ADC2 is controlled by DIG ADC2 CTRL 0: SAR ADC2 is controlled by PWDET CTRL*/
uint32_t work_mode: 2; /*0: single mode 1: double mode 2: alternate mode*/
uint32_t sar_sel: 1; /*0: SAR1 1: SAR2 only work for single SAR mode*/
uint32_t sar_clk_gated: 1;
uint32_t sar_clk_div: 8; /*SAR clock divider*/
uint32_t sar1_patt_len: 4; /*0 ~ 15 means length 1 ~ 16*/
uint32_t sar2_patt_len: 4; /*0 ~ 15 means length 1 ~ 16*/
uint32_t sar1_patt_p_clear: 1; /*clear the pointer of pattern table for DIG ADC1 CTRL*/
uint32_t sar2_patt_p_clear: 1; /*clear the pointer of pattern table for DIG ADC2 CTRL*/
uint32_t data_sar_sel: 1; /*1: sar_sel will be coded by the MSB of the 16-bit output data in this case the resolution should not be larger than 11 bits.*/
uint32_t data_to_i2s: 1; /*1: I2S input data is from SAR ADC (for DMA) 0: I2S input data is from GPIO matrix*/
uint32_t reserved27: 5;
uint32_t start_force: 1;
uint32_t start: 1;
uint32_t reserved2: 1;
uint32_t work_mode: 2; /*0: single mode 1: double mode 2: alternate mode*/
uint32_t sar_sel: 1; /*0: SAR1 1: SAR2 only work for single SAR mode*/
uint32_t sar_clk_gated: 1;
uint32_t sar_clk_div: 8; /*SAR clock divider*/
uint32_t sar1_patt_len: 4; /*0 ~ 15 means length 1 ~ 16*/
uint32_t sar2_patt_len: 4; /*0 ~ 15 means length 1 ~ 16*/
uint32_t sar1_patt_p_clear: 1; /*clear the pointer of pattern table for DIG ADC1 CTRL*/
uint32_t sar2_patt_p_clear: 1; /*clear the pointer of pattern table for DIG ADC2 CTRL*/
uint32_t data_sar_sel: 1; /*1: sar_sel will be coded by the MSB of the 16-bit output data in this case the resolution should not be larger than 11 bits.*/
uint32_t data_to_i2s: 1; /*1: I2S input data is from SAR ADC (for DMA) 0: I2S input data is from GPIO matrix*/
uint32_t xpd_sar_force: 2; /*force option to xpd sar blocks*/
uint32_t reserved29: 3;
};
uint32_t val;
}saradc_ctrl;
} saradc_ctrl;
union {
struct {
uint32_t meas_num_limit: 1;
uint32_t max_meas_num: 8; /*max conversion number*/
uint32_t sar1_inv: 1; /*1: data to DIG ADC1 CTRL is inverted otherwise not*/
uint32_t sar2_inv: 1; /*1: data to DIG ADC2 CTRL is inverted otherwise not*/
uint32_t reserved11: 21;
uint32_t meas_num_limit: 1;
uint32_t max_meas_num: 8; /*max conversion number*/
uint32_t sar1_inv: 1; /*1: data to DIG ADC1 CTRL is inverted otherwise not*/
uint32_t sar2_inv: 1; /*1: data to DIG ADC2 CTRL is inverted otherwise not*/
uint32_t timer_sel: 1; /*1: select saradc timer 0: i2s_ws trigger*/
uint32_t timer_target: 8; /*to set saradc timer target*/
uint32_t timer_en: 1; /*to enable saradc timer trigger*/
uint32_t reserved21: 11;
};
uint32_t val;
}saradc_ctrl2;
} saradc_ctrl2;
union {
struct {
uint32_t rstb_wait: 8;
uint32_t standby_wait: 8;
uint32_t start_wait: 8;
uint32_t sample_cycle: 8; /*sample cycles*/
uint32_t reserved0: 16;
uint32_t sample_num: 8; /*sample number*/
uint32_t sample_cycle: 8; /*sample cycles*/
};
uint32_t val;
}saradc_fsm;
uint32_t saradc_sar1_patt_tab[4]; /*item 0 ~ 3 for ADC1 pattern table*/
uint32_t saradc_sar2_patt_tab[4]; /*item 0 ~ 3 for ADC2 pattern table*/
} saradc_fsm;
union {
struct {
uint32_t apll_tick: 8;
uint32_t reserved8: 24;
uint32_t xpd_wait: 8;
uint32_t rstb_wait: 8;
uint32_t standby_wait: 8;
uint32_t reserved24: 8;
};
uint32_t val;
}apll_tick_conf;
uint32_t reserved_40;
uint32_t reserved_44;
uint32_t reserved_48;
uint32_t reserved_4c;
uint32_t reserved_50;
uint32_t reserved_54;
uint32_t reserved_58;
uint32_t reserved_5c;
uint32_t reserved_60;
uint32_t reserved_64;
uint32_t reserved_68;
uint32_t reserved_6c;
uint32_t reserved_70;
uint32_t reserved_74;
uint32_t reserved_78;
} saradc_fsm_wait;
uint32_t saradc_sar1_status; /**/
uint32_t saradc_sar2_status; /**/
uint32_t saradc_sar1_patt_tab[4]; /*item 0 ~ 15 for pattern table 1 (each item one byte)*/
uint32_t saradc_sar2_patt_tab[4]; /*item 0 ~ 15 for pattern table 2 (each item one byte)*/
union {
struct {
uint32_t reserved0: 2;
uint32_t adc_arb_apb_force: 1; /*adc2 arbiter force to enableapb controller*/
uint32_t adc_arb_rtc_force: 1; /*adc2 arbiter force to enable rtc controller*/
uint32_t adc_arb_wifi_force: 1; /*adc2 arbiter force to enable wifi controller*/
uint32_t adc_arb_grant_force: 1; /*adc2 arbiter force grant*/
uint32_t adc_arb_apb_priority: 2; /*Set adc2 arbiterapb priority*/
uint32_t adc_arb_rtc_priority: 2; /*Set adc2 arbiter rtc priority*/
uint32_t adc_arb_wifi_priority: 2; /*Set adc2 arbiter wifi priority*/
uint32_t adc_arb_fix_priority: 1; /*adc2 arbiter uses fixed priority*/
uint32_t reserved13: 19;
};
uint32_t val;
} adc_arb_ctrl;
union {
struct {
uint32_t clk20_oen: 1;
uint32_t clk22_oen: 1;
uint32_t clk44_oen: 1;
uint32_t clk_bb_oen: 1;
uint32_t clk80_oen: 1;
uint32_t clk160_oen: 1;
uint32_t clk_320m_oen: 1;
uint32_t clk_adc_inf_oen: 1;
uint32_t clk_dac_cpu_oen: 1;
uint32_t clk40x_bb_oen: 1;
uint32_t clk_xtal_oen: 1;
uint32_t reserved11: 21;
};
uint32_t val;
} clk_out_en;
union {
struct {
uint32_t peri_io_swap: 8;
uint32_t spi0_hold: 1;
uint32_t spi1_hold: 1;
uint32_t reserved10: 3;
uint32_t spi_prior: 1;
uint32_t reserved14: 18;
};
uint32_t val;
} host_inf_sel;
union {
struct {
uint32_t ext_mem_pms_lock: 1;
uint32_t reserved1: 31;
};
uint32_t val;
} ext_mem_pms_lock;
union {
struct {
uint32_t flash_ace0_attr: 3;
uint32_t reserved3: 29;
};
uint32_t val;
} flash_ace0_attr;
union {
struct {
uint32_t flash_ace1_attr: 3;
uint32_t reserved3: 29;
};
uint32_t val;
} flash_ace1_attr;
union {
struct {
uint32_t flash_ace2_attr: 3;
uint32_t reserved3: 29;
};
uint32_t val;
} flash_ace2_attr;
union {
struct {
uint32_t flash_ace3_attr: 3;
uint32_t reserved3: 29;
};
uint32_t val;
} flash_ace3_attr;
uint32_t flash_ace0_addr; /**/
uint32_t flash_ace1_addr; /**/
uint32_t flash_ace2_addr; /**/
uint32_t flash_ace3_addr; /**/
union {
struct {
uint32_t flash_ace0_size:16;
uint32_t reserved16: 16;
};
uint32_t val;
} flash_ace0_size;
union {
struct {
uint32_t flash_ace1_size:16;
uint32_t reserved16: 16;
};
uint32_t val;
} flash_ace1_size;
union {
struct {
uint32_t flash_ace2_size:16;
uint32_t reserved16: 16;
};
uint32_t val;
} flash_ace2_size;
union {
struct {
uint32_t flash_ace3_size:16;
uint32_t reserved16: 16;
};
uint32_t val;
} flash_ace3_size;
union {
struct {
uint32_t sram_ace0_attr: 3;
uint32_t reserved3: 29;
};
uint32_t val;
} sram_ace0_attr;
union {
struct {
uint32_t sram_ace1_attr: 3;
uint32_t reserved3: 29;
};
uint32_t val;
} sram_ace1_attr;
union {
struct {
uint32_t sram_ace2_attr: 3;
uint32_t reserved3: 29;
};
uint32_t val;
} sram_ace2_attr;
union {
struct {
uint32_t sram_ace3_attr: 3;
uint32_t reserved3: 29;
};
uint32_t val;
} sram_ace3_attr;
uint32_t sram_ace0_addr; /**/
uint32_t sram_ace1_addr; /**/
uint32_t sram_ace2_addr; /**/
uint32_t sram_ace3_addr; /**/
union {
struct {
uint32_t sram_ace0_size:16;
uint32_t reserved16: 16;
};
uint32_t val;
} sram_ace0_size;
union {
struct {
uint32_t sram_ace1_size:16;
uint32_t reserved16: 16;
};
uint32_t val;
} sram_ace1_size;
union {
struct {
uint32_t sram_ace2_size:16;
uint32_t reserved16: 16;
};
uint32_t val;
} sram_ace2_size;
union {
struct {
uint32_t sram_ace3_size:16;
uint32_t reserved16: 16;
};
uint32_t val;
} sram_ace3_size;
union {
struct {
uint32_t spi0_reject_int: 1;
uint32_t spi0_reject_clr: 1;
uint32_t spi0_reject_cde: 5;
uint32_t reserved7: 25;
};
uint32_t val;
} spi0_pms_ctrl;
uint32_t spi0_reject_addr; /**/
union {
struct {
uint32_t spi1_reject_int: 1;
uint32_t spi1_reject_clr: 1;
uint32_t spi1_reject_cde: 5;
uint32_t reserved7: 25;
};
uint32_t val;
} spi1_pms_ctrl;
uint32_t spi1_reject_addr; /**/
union {
struct {
uint32_t sdio_win_access_en: 1;
uint32_t reserved1: 31;
};
uint32_t val;
} sdio_ctrl;
union {
struct {
uint32_t redcy_sig0: 31;
uint32_t redcy_andor: 1;
};
uint32_t val;
} redcy_sig0;
union {
struct {
uint32_t redcy_sig1: 31;
uint32_t redcy_nandor: 1;
};
uint32_t val;
} redcy_sig1;
uint32_t wifi_bb_cfg; /**/
uint32_t wifi_bb_cfg_2; /**/
uint32_t wifi_clk_en; /**/
uint32_t wifi_rst_en; /**/
union {
struct {
uint32_t agc_mem_force_pu: 1;
uint32_t agc_mem_force_pd: 1;
uint32_t pbus_mem_force_pu: 1;
uint32_t pbus_mem_force_pd: 1;
uint32_t dc_mem_force_pu: 1;
uint32_t dc_mem_force_pd: 1;
uint32_t reserved6: 26;
};
uint32_t val;
} front_end_mem_pd;
uint32_t reserved_e0;
uint32_t reserved_e4;
uint32_t reserved_e8;
uint32_t reserved_ec;
uint32_t reserved_f0;
uint32_t reserved_f4;
uint32_t reserved_f8;
uint32_t reserved_fc;
uint32_t reserved_100;
uint32_t reserved_104;
uint32_t reserved_108;
uint32_t reserved_10c;
uint32_t reserved_110;
uint32_t reserved_114;
uint32_t reserved_118;
uint32_t reserved_11c;
uint32_t reserved_120;
uint32_t reserved_124;
uint32_t reserved_128;
uint32_t reserved_12c;
uint32_t reserved_130;
uint32_t reserved_134;
uint32_t reserved_138;
uint32_t reserved_13c;
uint32_t reserved_140;
uint32_t reserved_144;
uint32_t reserved_148;
uint32_t reserved_14c;
uint32_t reserved_150;
uint32_t reserved_154;
uint32_t reserved_158;
uint32_t reserved_15c;
uint32_t reserved_160;
uint32_t reserved_164;
uint32_t reserved_168;
uint32_t reserved_16c;
uint32_t reserved_170;
uint32_t reserved_174;
uint32_t reserved_178;
uint32_t reserved_17c;
uint32_t reserved_180;
uint32_t reserved_184;
uint32_t reserved_188;
uint32_t reserved_18c;
uint32_t reserved_190;
uint32_t reserved_194;
uint32_t reserved_198;
uint32_t reserved_19c;
uint32_t reserved_1a0;
uint32_t reserved_1a4;
uint32_t reserved_1a8;
uint32_t reserved_1ac;
uint32_t reserved_1b0;
uint32_t reserved_1b4;
uint32_t reserved_1b8;
uint32_t reserved_1bc;
uint32_t reserved_1c0;
uint32_t reserved_1c4;
uint32_t reserved_1c8;
uint32_t reserved_1cc;
uint32_t reserved_1d0;
uint32_t reserved_1d4;
uint32_t reserved_1d8;
uint32_t reserved_1dc;
uint32_t reserved_1e0;
uint32_t reserved_1e4;
uint32_t reserved_1e8;
uint32_t reserved_1ec;
uint32_t reserved_1f0;
uint32_t reserved_1f4;
uint32_t reserved_1f8;
uint32_t reserved_1fc;
uint32_t reserved_200;
uint32_t reserved_204;
uint32_t reserved_208;
uint32_t reserved_20c;
uint32_t reserved_210;
uint32_t reserved_214;
uint32_t reserved_218;
uint32_t reserved_21c;
uint32_t reserved_220;
uint32_t reserved_224;
uint32_t reserved_228;
uint32_t reserved_22c;
uint32_t reserved_230;
uint32_t reserved_234;
uint32_t reserved_238;
uint32_t reserved_23c;
uint32_t reserved_240;
uint32_t reserved_244;
uint32_t reserved_248;
uint32_t reserved_24c;
uint32_t reserved_250;
uint32_t reserved_254;
uint32_t reserved_258;
uint32_t reserved_25c;
uint32_t reserved_260;
uint32_t reserved_264;
uint32_t reserved_268;
uint32_t reserved_26c;
uint32_t reserved_270;
uint32_t reserved_274;
uint32_t reserved_278;
uint32_t reserved_27c;
uint32_t reserved_280;
uint32_t reserved_284;
uint32_t reserved_288;
uint32_t reserved_28c;
uint32_t reserved_290;
uint32_t reserved_294;
uint32_t reserved_298;
uint32_t reserved_29c;
uint32_t reserved_2a0;
uint32_t reserved_2a4;
uint32_t reserved_2a8;
uint32_t reserved_2ac;
uint32_t reserved_2b0;
uint32_t reserved_2b4;
uint32_t reserved_2b8;
uint32_t reserved_2bc;
uint32_t reserved_2c0;
uint32_t reserved_2c4;
uint32_t reserved_2c8;
uint32_t reserved_2cc;
uint32_t reserved_2d0;
uint32_t reserved_2d4;
uint32_t reserved_2d8;
uint32_t reserved_2dc;
uint32_t reserved_2e0;
uint32_t reserved_2e4;
uint32_t reserved_2e8;
uint32_t reserved_2ec;
uint32_t reserved_2f0;
uint32_t reserved_2f4;
uint32_t reserved_2f8;
uint32_t reserved_2fc;
uint32_t reserved_300;
uint32_t reserved_304;
uint32_t reserved_308;
uint32_t reserved_30c;
uint32_t reserved_310;
uint32_t reserved_314;
uint32_t reserved_318;
uint32_t reserved_31c;
uint32_t reserved_320;
uint32_t reserved_324;
uint32_t reserved_328;
uint32_t reserved_32c;
uint32_t reserved_330;
uint32_t reserved_334;
uint32_t reserved_338;
uint32_t reserved_33c;
uint32_t reserved_340;
uint32_t reserved_344;
uint32_t reserved_348;
uint32_t reserved_34c;
uint32_t reserved_350;
uint32_t reserved_354;
uint32_t reserved_358;
uint32_t reserved_35c;
uint32_t reserved_360;
uint32_t reserved_364;
uint32_t reserved_368;
uint32_t reserved_36c;
uint32_t reserved_370;
uint32_t reserved_374;
uint32_t reserved_378;
uint32_t reserved_37c;
uint32_t reserved_380;
uint32_t reserved_384;
uint32_t reserved_388;
uint32_t reserved_38c;
uint32_t reserved_390;
uint32_t reserved_394;
uint32_t reserved_398;
uint32_t reserved_39c;
uint32_t reserved_3a0;
uint32_t reserved_3a4;
uint32_t reserved_3a8;
uint32_t reserved_3ac;
uint32_t reserved_3b0;
uint32_t reserved_3b4;
uint32_t reserved_3b8;
uint32_t reserved_3bc;
uint32_t reserved_3c0;
uint32_t reserved_3c4;
uint32_t reserved_3c8;
uint32_t reserved_3cc;
uint32_t reserved_3d0;
uint32_t reserved_3d4;
uint32_t reserved_3d8;
uint32_t reserved_3dc;
uint32_t reserved_3e0;
uint32_t reserved_3e4;
uint32_t reserved_3e8;
uint32_t reserved_3ec;
uint32_t reserved_3f0;
uint32_t reserved_3f4;
uint32_t reserved_3f8;
uint32_t date; /**/
} syscon_dev_t;

View File

@ -16,34 +16,46 @@
#define _SOC_TOUCH_CHANNEL_H
//Touch channels
#define TOUCH_PAD_GPIO4_CHANNEL TOUCH_PAD_NUM0
#define TOUCH_PAD_NUM0_GPIO_NUM 4
#define TOUCH_PAD_GPIO0_CHANNEL TOUCH_PAD_NUM1
#define TOUCH_PAD_NUM1_GPIO_NUM 0
#define TOUCH_PAD_GPIO1_CHANNEL TOUCH_PAD_NUM1
#define TOUCH_PAD_NUM1_GPIO_NUM 1
#define TOUCH_PAD_GPIO2_CHANNEL TOUCH_PAD_NUM2
#define TOUCH_PAD_NUM2_GPIO_NUM 2
#define TOUCH_PAD_GPIO15_CHANNEL TOUCH_PAD_NUM3
#define TOUCH_PAD_NUM3_GPIO_NUM 15
#define TOUCH_PAD_GPIO3_CHANNEL TOUCH_PAD_NUM3
#define TOUCH_PAD_NUM3_GPIO_NUM 3
#define TOUCH_PAD_GPIO13_CHANNEL TOUCH_PAD_NUM4
#define TOUCH_PAD_NUM4_GPIO_NUM 13
#define TOUCH_PAD_GPIO4_CHANNEL TOUCH_PAD_NUM4
#define TOUCH_PAD_NUM4_GPIO_NUM 4
#define TOUCH_PAD_GPIO12_CHANNEL TOUCH_PAD_NUM5
#define TOUCH_PAD_NUM5_GPIO_NUM 12
#define TOUCH_PAD_GPIO5_CHANNEL TOUCH_PAD_NUM5
#define TOUCH_PAD_NUM5_GPIO_NUM 5
#define TOUCH_PAD_GPIO14_CHANNEL TOUCH_PAD_NUM6
#define TOUCH_PAD_NUM6_GPIO_NUM 14
#define TOUCH_PAD_GPIO6_CHANNEL TOUCH_PAD_NUM6
#define TOUCH_PAD_NUM6_GPIO_NUM 6
#define TOUCH_PAD_GPIO27_CHANNEL TOUCH_PAD_NUM7
#define TOUCH_PAD_NUM7_GPIO_NUM 27
#define TOUCH_PAD_GPIO7_CHANNEL TOUCH_PAD_NUM7
#define TOUCH_PAD_NUM7_GPIO_NUM 7
#define TOUCH_PAD_GPIO33_CHANNEL TOUCH_PAD_NUM8
#define TOUCH_PAD_NUM8_GPIO_NUM 33
#define TOUCH_PAD_GPIO8_CHANNEL TOUCH_PAD_NUM8
#define TOUCH_PAD_NUM8_GPIO_NUM 8
#define TOUCH_PAD_GPIO32_CHANNEL TOUCH_PAD_NUM9
#define TOUCH_PAD_NUM9_GPIO_NUM 32
#define TOUCH_PAD_GPIO9_CHANNEL TOUCH_PAD_NUM9
#define TOUCH_PAD_NUM9_GPIO_NUM 9
#define TOUCH_PAD_GPIO10_CHANNEL TOUCH_PAD_NUM10
#define TOUCH_PAD_NUM10_GPIO_NUM 10
#define TOUCH_PAD_GPIO11_CHANNEL TOUCH_PAD_NUM11
#define TOUCH_PAD_NUM11_GPIO_NUM 11
#define TOUCH_PAD_GPIO12_CHANNEL TOUCH_PAD_NUM12
#define TOUCH_PAD_NUM12_GPIO_NUM 12
#define TOUCH_PAD_GPIO13_CHANNEL TOUCH_PAD_NUM13
#define TOUCH_PAD_NUM13_GPIO_NUM 13
#define TOUCH_PAD_GPIO14_CHANNEL TOUCH_PAD_NUM14
#define TOUCH_PAD_NUM14_GPIO_NUM 14
#endif

View File

@ -48,6 +48,7 @@ static const char* TAG = "ulp";
esp_err_t ulp_run(uint32_t entry_point)
{
#if CONFIG_IDF_TARGET_ESP32
// disable ULP timer
CLEAR_PERI_REG_MASK(RTC_CNTL_STATE0_REG, RTC_CNTL_ULP_CP_SLP_TIMER_EN);
// wait for at least 1 RTC_SLOW_CLK cycle
@ -64,6 +65,7 @@ esp_err_t ulp_run(uint32_t entry_point)
SET_PERI_REG_MASK(RTC_CNTL_OPTIONS0_REG, RTC_CNTL_BIAS_SLEEP_FOLW_8M);
// enable ULP timer
SET_PERI_REG_MASK(RTC_CNTL_STATE0_REG, RTC_CNTL_ULP_CP_SLP_TIMER_EN);
#endif
return ESP_OK;
}
@ -112,6 +114,7 @@ esp_err_t ulp_load_binary(uint32_t load_addr, const uint8_t* program_binary, siz
esp_err_t ulp_set_wakeup_period(size_t period_index, uint32_t period_us)
{
#if CONFIG_IDF_TARGET_ESP32
if (period_index > 4) {
return ESP_ERR_INVALID_ARG;
}
@ -128,5 +131,6 @@ esp_err_t ulp_set_wakeup_period(size_t period_index, uint32_t period_us)
}
REG_SET_FIELD(SENS_ULP_CP_SLEEP_CYC0_REG + period_index * sizeof(uint32_t),
SENS_SLEEP_CYCLES_S0, (uint32_t) period_cycles);
#endif
return ESP_OK;
}

View File

@ -83,6 +83,7 @@ INPUT = \
../../components/driver/include/driver/spi_common.h \
../../components/driver/include/driver/spi_master.h \
../../components/driver/include/driver/spi_slave.h \
../../components/driver/esp32s2beta/include/temp_sensor.h \
../../components/driver/include/driver/timer.h \
../../components/driver/include/driver/touch_pad.h \
../../components/driver/include/driver/uart.h \

View File

@ -22,6 +22,7 @@ Peripherals API
Sigma-delta Modulation <sigmadelta>
SPI Master <spi_master>
SPI Slave <spi_slave>
Temp sensor <temp_sensor>
Timer <timer>
Touch Sensor <touch_pad>
UART <uart>

View File

@ -0,0 +1,32 @@
ESP32-S2 Temperature Sensor
==================
Overview
--------
The ESP32-S2 has a built-in temperature sensor. The temperature sensor module contains an 8-bit Sigma-Delta ADC and a temperature offset DAC.
The conversion relationship is the first columns of the table below. Among them, offset = 0 is the main measurement option, and other values are extended measurement options.
+--------+------------------------+------------------------+
| offset | measure range(Celsius) | measure error(Celsius) |
+========+========================+========================+
| -2 | 50 ~ 125 | < 3 |
+--------+------------------------+------------------------+
| -1 | 20 ~ 100 | < 2 |
+--------+------------------------+------------------------+
| 0 | -10 ~ 80 | < 1 |
+--------+------------------------+------------------------+
| 1 | -30 ~ 50 | < 2 |
+--------+------------------------+------------------------+
| 2 | -40 ~ 20 | < 3 |
+--------+------------------------+------------------------+
Application Example
-------------------
Temperature sensor reading example: :example:`peripherals/temp_sensor`.
API Reference - Normal Temp Sensor
----------------------------------
.. include:: /_build/inc/temp_sensor.inc

View File

@ -22,6 +22,7 @@
Sigma-delta Modulation <sigmadelta>
SPI Master <spi_master>
SPI Slave <spi_slave>
Temp sensor <temp_sensor>
Timer <timer>
Touch Sensor <touch_pad>
UART <uart>

View File

@ -0,0 +1 @@
.. include:: ../../../en/api-reference/peripherals/temp_sensor.rst

View File

@ -12,16 +12,23 @@
#include "freertos/task.h"
#include "driver/gpio.h"
#include "driver/adc.h"
#if CONFIG_IDF_TARGET_ESP32
#include "esp_adc_cal.h"
#endif
#define DEFAULT_VREF 1100 //Use adc2_vref_to_gpio() to obtain a better estimate
#define NO_OF_SAMPLES 64 //Multisampling
#if CONFIG_IDF_TARGET_ESP32
static esp_adc_cal_characteristics_t *adc_chars;
static const adc_channel_t channel = ADC_CHANNEL_6; //GPIO34 if ADC1, GPIO14 if ADC2
#elif CONFIG_IDF_TARGET_ESP32S2BETA
static const adc_channel_t channel = ADC_CHANNEL_6; // GPIO7 if ADC1, GPIO17 if ADC2
#endif
static const adc_atten_t atten = ADC_ATTEN_DB_0;
static const adc_unit_t unit = ADC_UNIT_1;
#if CONFIG_IDF_TARGET_ESP32
static void check_efuse()
{
//Check TP is burned into eFuse
@ -49,11 +56,14 @@ static void print_char_val_type(esp_adc_cal_value_t val_type)
printf("Characterized using Default Vref\n");
}
}
#endif
void app_main()
{
#if CONFIG_IDF_TARGET_ESP32
//Check if Two Point or Vref are burned into eFuse
check_efuse();
#endif
//Configure ADC
if (unit == ADC_UNIT_1) {
@ -63,10 +73,12 @@ void app_main()
adc2_config_channel_atten((adc2_channel_t)channel, atten);
}
#if CONFIG_IDF_TARGET_ESP32
//Characterize ADC
adc_chars = calloc(1, sizeof(esp_adc_cal_characteristics_t));
esp_adc_cal_value_t val_type = esp_adc_cal_characterize(unit, atten, ADC_WIDTH_BIT_12, DEFAULT_VREF, adc_chars);
print_char_val_type(val_type);
#endif
//Continuously sample ADC1
while (1) {
@ -82,11 +94,13 @@ void app_main()
}
}
adc_reading /= NO_OF_SAMPLES;
#if CONFIG_IDF_TARGET_ESP32
//Convert adc_reading to voltage in mV
uint32_t voltage = esp_adc_cal_raw_to_voltage(adc_reading, adc_chars);
printf("Raw: %d\tVoltage: %dmV\n", adc_reading, voltage);
#elif CONFIG_IDF_TARGET_ESP32S2BETA
printf("ADC%d CH%d Raw: %d\t\n", unit, channel, adc_reading);
#endif
vTaskDelay(pdMS_TO_TICKS(1000));
}
}

View File

@ -15,7 +15,6 @@
#include "driver/adc.h"
#include "driver/dac.h"
#include "esp_system.h"
#include "esp_adc_cal.h"
#define DAC_EXAMPLE_CHANNEL CONFIG_EXAMPLE_DAC_CHANNEL
#define ADC2_EXAMPLE_CHANNEL CONFIG_EXAMPLE_ADC2_CHANNEL

View File

@ -0,0 +1,6 @@
# The following lines of boilerplate have to be in your project's CMakeLists
# in this exact order for cmake to work correctly
cmake_minimum_required(VERSION 3.5)
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
project(temp_sensor_esp32s2)

View File

@ -0,0 +1,9 @@
#
# This is a project Makefile. It is assumed the directory this Makefile resides in is a
# project subdirectory.
#
PROJECT_NAME := temp_sensor_esp32s2
include $(IDF_PATH)/make/project.mk

View File

@ -0,0 +1,27 @@
# ESP32-S2 Temperature Sensor Example
The ESP32-S2 has a built-in temperature sensor. The temperature sensor module contains an 8-bit Sigma-Delta ADC and a temperature offset DAC.
The conversion relationship is the first two columns of the table below. Among them, `offset = 0`(default) is the main measurement option, and other values are extended measurement options.
DAC level | offset | measure range(℃) | measure error(℃)
:-: | :-: | :-: | :-:
0 | -2 | 50 ~ 125 | < 3
1 | -1 | 20 ~ 100 | < 2
2 | 0 | -10 ~ 80 | < 1
3 | 1 | -30 ~ 50 | < 2
4 | 2 | -40 ~ 20 | < 3
* Log output :
```
I (243) TempSensor: Initializing Temperature sensor
I (243) TempSensor: default dac 2, clk_div 6
I (243) TempSensor: Config temperature range [-10°C ~ 80°C], error < 1°C
I (253) TempSensor: Temperature sensor started
I (1253) TempSensor: Temperature out celsius 27.287399°C
I (2253) TempSensor: Temperature out celsius 26.848801°C
I (3253) TempSensor: Temperature out celsius 26.848801°C
I (4253) TempSensor: Temperature out celsius 27.287399°C
I (5253) TempSensor: Temperature out celsius 27.287399°C
```

View File

@ -0,0 +1,4 @@
set(COMPONENT_SRCS "temp_sensor_main.c")
set(COMPONENT_ADD_INCLUDEDIRS ".")
register_component()

View File

@ -0,0 +1,5 @@
#
# "main" pseudo-component makefile.
#
# (Uses default behaviour of compiling all source files in directory, adding 'include' to include path.)

View File

@ -0,0 +1,54 @@
/* Temperature Sensor Example
This example code is in the Public Domain (or CC0 licensed, at your option.)
Unless required by applicable law or agreed to in writing, this
software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
CONDITIONS OF ANY KIND, either express or implied.
*/
#include <stdio.h>
#include <stdlib.h>
#include "esp_log.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
/* Note: ESP32 don't support temperature sensor */
#if CONFIG_IDF_TARGET_ESP32S2BETA
#include "temp_sensor.h"
static const char *TAG = "TempSensor";
void tempsensor_example(void *arg)
{
// Initialize touch pad peripheral, it will start a timer to run a filter
ESP_LOGI(TAG, "Initializing Temperature sensor");
float tsens_out;
temp_sensor_config_t temp_sensor = TSENS_CONFIG_DEFAULT();
temp_sensor_get_config(&temp_sensor);
ESP_LOGI(TAG, "default dac %d, clk_div %d", temp_sensor.dac_offset, temp_sensor.clk_div);
temp_sensor.dac_offset = TSENS_DAC_DEFAULT; // DEFAULT: range:-10℃ ~ 80℃, error < 1℃.
temp_sensor_set_config(temp_sensor);
temp_sensor_start();
ESP_LOGI(TAG, "Temperature sensor started");
while (1) {
vTaskDelay(1000 / portTICK_RATE_MS);
temp_sensor_read_celsius(&tsens_out);
ESP_LOGI(TAG, "Temperature out celsius %f°C", tsens_out);
}
vTaskDelete(NULL);
}
void app_main()
{
xTaskCreate(tempsensor_example, "temp", 2048, NULL, 5, NULL);
}
#elif CONFIG_IDF_TARGET_ESP32
void app_main()
{
printf("ESP32 don't support temperature sensor\n");
}
#endif

View File

@ -1,4 +1,3 @@
set(COMPONENT_SRCS "tp_interrupt_main.c")
set(COMPONENT_ADD_INCLUDEDIRS ".")
set(COMPONENT_SRCS "${CONFIG_IDF_TARGET}/tp_interrupt_main.c")
register_component()

View File

@ -3,3 +3,4 @@
#
# (Uses default behaviour of compiling all source files in directory, adding 'include' to include path.)
COMPONENT_SRCDIRS := $(IDF_TARGET)

View File

@ -9,13 +9,15 @@
#include <stdio.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include "esp_log.h"
#include "driver/touch_pad.h"
#include "soc/rtc_periph.h"
#include "soc/sens_periph.h"
static const char* TAG = "Touch pad";
static const char *TAG = "Touch pad";
#define TOUCH_THRESH_NO_USE (0)
#define TOUCH_THRESH_PERCENT (80)
#define TOUCHPAD_FILTER_TOUCH_PERIOD (10)
@ -35,7 +37,7 @@ static uint32_t s_pad_init_val[TOUCH_PAD_MAX];
static void tp_example_set_thresholds(void)
{
uint16_t touch_value;
for (int i = 0; i<TOUCH_PAD_MAX; i++) {
for (int i = 0; i < TOUCH_PAD_MAX; i++) {
//read filtered value
touch_pad_read_filtered(i, &touch_value);
s_pad_init_val[i] = touch_value;
@ -113,7 +115,7 @@ static void tp_example_read_task(void *pvParameter)
// We can compare the two different mode.
if (change_mode++ % 2000 == 0) {
filter_mode = !filter_mode;
ESP_LOGW(TAG, "Change mode...%s", filter_mode == 0? "interrupt mode": "filter mode");
ESP_LOGW(TAG, "Change mode...%s", filter_mode == 0 ? "interrupt mode" : "filter mode");
}
}
}
@ -122,7 +124,7 @@ static void tp_example_read_task(void *pvParameter)
Handle an interrupt triggered when a pad is touched.
Recognize what pad has been touched and save it in a table.
*/
static void tp_example_rtc_intr(void * arg)
static void tp_example_rtc_intr(void *arg)
{
uint32_t pad_intr = touch_pad_get_status();
//clear interrupt
@ -139,7 +141,7 @@ static void tp_example_rtc_intr(void * arg)
*/
static void tp_example_touch_pad_init()
{
for (int i = 0;i< TOUCH_PAD_MAX;i++) {
for (int i = 0; i < TOUCH_PAD_MAX; i++) {
//init RTC IO and mode for touch pad.
touch_pad_config(i, TOUCH_THRESH_NO_USE);
}

View File

@ -0,0 +1,201 @@
/* Touch Pad Interrupt Example
This example code is in the Public Domain (or CC0 licensed, at your option.)
Unless required by applicable law or agreed to in writing, this
software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
CONDITIONS OF ANY KIND, either express or implied.
*/
#include <stdio.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include "esp_log.h"
#include "driver/touch_pad.h"
#include "soc/rtc_periph.h"
#include "soc/sens_periph.h"
static const char *TAG = "Touch pad";
static QueueHandle_t que_touch = NULL;
typedef struct touch_msg {
touch_pad_intr_mask_t intr_mask;
uint32_t pad_num;
uint32_t pad_status;
uint32_t pad_val;
} touch_event_t;
#define TOUCH_BUTTON_NUM 4
#define TOUCH_BUTTON_WATERPROOF_ENABLE 1
#define TOUCH_BUTTON_DENOISE_ENABLE 1
static const touch_pad_t button[TOUCH_BUTTON_NUM] = {
TOUCH_PAD_NUM7, // 'SELECT' button.
TOUCH_PAD_NUM9, // 'MENU' button.
TOUCH_PAD_NUM11, // 'BACK' button.
TOUCH_PAD_NUM13, // Guard ring for waterproof design.
// if this pad be touched, other pads no response.
};
/*
* Touch threshold. The threshold determines the sensitivity of the touch.
* This threshold is derived by testing changes in readings from different touch channels.
* If (raw_data - baseline) > baseline * threshold, the pad be actived.
* If (raw_data - baseline) < baseline * threshold, the pad be inactived.
*/
static const float button_threshold[TOUCH_BUTTON_NUM] = {
0.2, // 20%.
0.2, // 20%.
0.2, // 20%.
0.1, // 10%.
};
/*
Handle an interrupt triggered when a pad is touched.
Recognize what pad has been touched and save it in a table.
*/
static void touchsensor_interrupt_cb(void *arg)
{
int task_awoken = pdFALSE;
touch_event_t evt;
evt.intr_mask = touch_pad_intr_status_get_mask();
evt.pad_status = touch_pad_get_status();
evt.pad_num = touch_pad_get_scan_curr();
if (evt.intr_mask & TOUCH_PAD_INTR_MASK_DONE) {
touch_pad_filter_baseline_read(evt.pad_num, &evt.pad_val);
}
xQueueSendFromISR(que_touch, &evt, &task_awoken);
if (task_awoken == pdTRUE) {
portYIELD_FROM_ISR();
}
}
static void tp_example_set_thresholds(void)
{
uint32_t touch_value;
for (int i = 0; i < TOUCH_BUTTON_NUM; i++) {
//read baseline value
touch_pad_read_raw_data(button[i], &touch_value);
//set interrupt threshold.
touch_pad_set_thresh(button[i], touch_value * button_threshold[i]);
ESP_LOGI(TAG, "test init: touch pad [%d] base %d, thresh %d", \
button[i], touch_value, (uint32_t)(touch_value * button_threshold[i]));
}
}
static void touchsensor_filter_set(touch_filter_mode_t mode)
{
/* Filter function */
touch_filter_config_t filter_info = {
.mode = mode, // Test jitter and filter 1/4.
.debounce_cnt = 1, // 1 time count.
.hysteresis_thr = 1, // 9.4%
.noise_thr = 1, // 37.5%
.noise_neg_thr = 1, // 37.5%
.neg_noise_limit = 10, // 10 time count.
.jitter_step = 4, // use for jitter mode.
};
touch_pad_filter_set_config(&filter_info);
touch_pad_filter_enable();
touch_pad_filter_baseline_reset(TOUCH_PAD_MAX);
ESP_LOGI(TAG, "touch pad filter init %d", mode);
}
static void tp_example_read_task(void *pvParameter)
{
touch_event_t evt = {0};
static uint8_t guard_mode_flag = 0;
/* Wait touch sensor init done */
vTaskDelay(100 / portTICK_RATE_MS);
tp_example_set_thresholds();
while (1) {
int ret = xQueueReceive(que_touch, &evt, (portTickType)portMAX_DELAY);
if (ret != pdTRUE) {
continue;
}
if (evt.intr_mask & TOUCH_PAD_INTR_MASK_ACTIVE) {
/* if guard pad be touched, other pads no response. */
if (evt.pad_num == button[3]) {
guard_mode_flag = 1;
ESP_LOGW(TAG, "TouchSensor [%d] be actived, enter guard mode", evt.pad_num);
} else {
if (guard_mode_flag == 0) {
ESP_LOGI(TAG, "TouchSensor [%d] be actived, status mask 0x%x", evt.pad_num, evt.pad_status);
} else {
ESP_LOGW(TAG, "In guard mode. No response");
}
}
}
if (evt.intr_mask & TOUCH_PAD_INTR_MASK_INACTIVE) {
/* if guard pad be touched, other pads no response. */
if (evt.pad_num == button[3]) {
guard_mode_flag = 0;
ESP_LOGW(TAG, "TouchSensor [%d] be actived, exit guard mode", evt.pad_num);
} else {
if (guard_mode_flag == 0) {
ESP_LOGI(TAG, "TouchSensor [%d] be inactived, status mask 0x%x", evt.pad_num, evt.pad_status);
}
}
}
if (evt.intr_mask & TOUCH_PAD_INTR_MASK_DONE) {
ESP_LOGI(TAG, "TouchSensor [%d] measure done, raw data %d", evt.pad_num, evt.pad_val);
}
}
}
void app_main()
{
if (que_touch == NULL) {
que_touch = xQueueCreate(TOUCH_BUTTON_NUM, sizeof(touch_event_t));
}
// Initialize touch pad peripheral, it will start a timer to run a filter
ESP_LOGI(TAG, "Initializing touch pad");
/* Initialize touch pad peripheral. */
touch_pad_init();
for (int i = 0; i < TOUCH_BUTTON_NUM; i++) {
touch_pad_config(button[i]);
touch_pad_set_thresh(button[i], TOUCH_PAD_THRESHOLD_MAX);
}
#if TOUCH_BUTTON_DENOISE_ENABLE
/* Denoise setting at TouchSensor 0. */
touch_pad_denoise_t denoise = {
/* The bits to be cancelled are determined according to the noise level. */
.grade = TOUCH_PAD_DENOISE_BIT4,
.cap_level = TOUCH_PAD_DENOISE_CAP_L7,
};
touch_pad_denoise_set_config(denoise);
touch_pad_denoise_enable();
ESP_LOGI(TAG, "Denoise function init");
#endif
#if TOUCH_BUTTON_WATERPROOF_ENABLE
/* Waterproof function */
touch_pad_waterproof_t waterproof = {
.guard_ring_pad = button[3], // If no ring pad, set 0;
/* It depends on the number of the parasitic capacitance of the shield pad. */
.shield_driver = TOUCH_PAD_SHIELD_DRV_L0, //40pf
};
touch_pad_waterproof_set_config(waterproof);
touch_pad_waterproof_enable();
ESP_LOGI(TAG, "touch pad waterproof init");
#endif
/* Filter setting */
touchsensor_filter_set(TOUCH_PAD_FILTER_IIR_8);
/* Register touch interrupt ISR, enable intr type. */
touch_pad_isr_register(touchsensor_interrupt_cb, NULL, TOUCH_PAD_INTR_MASK_ALL);
touch_pad_intr_enable(TOUCH_PAD_INTR_MASK_ACTIVE | TOUCH_PAD_INTR_MASK_INACTIVE);
// touch_pad_intr_enable(TOUCH_PAD_INTR_MASK_DONE); // Use for debug
/* Enable touch sensor clock. Work mode is "timer trigger". */
touch_pad_set_fsm_mode(TOUCH_FSM_MODE_TIMER);
touch_pad_fsm_start();
// Start a task to show what pads have been touched
xTaskCreate(&tp_example_read_task, "touch_pad_read_task", 2048, NULL, 5, NULL);
}

View File

@ -1,4 +1,3 @@
set(COMPONENT_SRCS "tp_read_main.c")
set(COMPONENT_ADD_INCLUDEDIRS ".")
set(COMPONENT_SRCS "${CONFIG_IDF_TARGET}/tp_read_main.c")
register_component()

View File

@ -3,3 +3,4 @@
#
# (Uses default behaviour of compiling all source files in directory, adding 'include' to include path.)
COMPONENT_SRCDIRS := $(IDF_TARGET)

View File

@ -10,6 +10,7 @@
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "driver/touch_pad.h"
#include "esp_log.h"
#define TOUCH_PAD_NO_CHANGE (-1)
#define TOUCH_THRESH_NO_USE (0)

View File

@ -0,0 +1,82 @@
/* Touch Pad Read Example
This example code is in the Public Domain (or CC0 licensed, at your option.)
Unless required by applicable law or agreed to in writing, this
software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
CONDITIONS OF ANY KIND, either express or implied.
*/
#include <stdio.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "driver/touch_pad.h"
#include "esp_log.h"
#define TOUCH_BUTTON_NUM 14
static const char * TAG = "touch read";
static const touch_pad_t button[TOUCH_BUTTON_NUM] = {
TOUCH_PAD_NUM1,
TOUCH_PAD_NUM2,
TOUCH_PAD_NUM3,
TOUCH_PAD_NUM4,
TOUCH_PAD_NUM5,
TOUCH_PAD_NUM6,
TOUCH_PAD_NUM7,
TOUCH_PAD_NUM8,
TOUCH_PAD_NUM9,
TOUCH_PAD_NUM10,
TOUCH_PAD_NUM11,
TOUCH_PAD_NUM12,
TOUCH_PAD_NUM13,
TOUCH_PAD_NUM14
};
/*
Read values sensed at all available touch pads.
Print out values in a loop on a serial monitor.
*/
static void tp_example_read_task(void *pvParameter)
{
uint32_t touch_value;
/* Wait touch sensor init done */
vTaskDelay(100 / portTICK_RATE_MS);
printf("Touch Sensor read, the output format is: \nTouchpad num:[raw data]\n\n");
while (1) {
for (int i = 0; i < TOUCH_BUTTON_NUM; i++) {
touch_pad_read_raw_data(button[i], &touch_value); // read raw data.
printf("T%d: [%4d] ", button[i], touch_value);
}
printf("\n");
vTaskDelay(200 / portTICK_PERIOD_MS);
}
}
void app_main()
{
/* Initialize touch pad peripheral. */
touch_pad_init();
for (int i = 0; i < TOUCH_BUTTON_NUM; i++) {
touch_pad_config(button[i]);
touch_pad_set_thresh(button[i], TOUCH_PAD_THRESHOLD_MAX);
}
/* Denoise setting at TouchSensor 0. */
touch_pad_denoise_t denoise = {
/* The bits to be cancelled are determined according to the noise level. */
.grade = TOUCH_PAD_DENOISE_BIT4,
.cap_level = TOUCH_PAD_DENOISE_CAP_L7,
};
touch_pad_denoise_set_config(denoise);
touch_pad_denoise_enable();
ESP_LOGI(TAG, "Denoise function init");
/* Enable touch sensor clock. Work mode is "timer trigger". */
touch_pad_set_fsm_mode(TOUCH_FSM_MODE_TIMER);
touch_pad_fsm_start();
/* Start task to read values by pads. */
xTaskCreate(&tp_example_read_task, "touch_pad_read_task", 2048, NULL, 5, NULL);
}

View File

@ -145,6 +145,7 @@ void app_main()
esp_sleep_enable_ext1_wakeup(ext_wakeup_pin_1_mask | ext_wakeup_pin_2_mask, ESP_EXT1_WAKEUP_ANY_HIGH);
#ifdef CONFIG_ENABLE_TOUCH_WAKEUP
#if CONFIG_IDF_TARGET_ESP32
// Initialize touch pad peripheral.
// The default fsm mode is software trigger mode.
touch_pad_init();
@ -160,9 +161,50 @@ void app_main()
touch_pad_config(TOUCH_PAD_NUM9, TOUCH_THRESH_NO_USE);
calibrate_touch_pad(TOUCH_PAD_NUM8);
calibrate_touch_pad(TOUCH_PAD_NUM9);
#elif CONFIG_IDF_TARGET_ESP32S2BETA
/* Initialize touch pad peripheral. */
touch_pad_init();
/* Only support one touch channel in sleep mode. */
touch_pad_set_thresh(TOUCH_PAD_NUM8, TOUCH_PAD_THRESHOLD_MAX);
touch_pad_sleep_channel_t slp_config = {
.touch_num = TOUCH_PAD_NUM8,
.sleep_pad_threshold = TOUCH_PAD_THRESHOLD_MAX,
.en_proximity = false,
};
touch_pad_sleep_channel_config(slp_config);
/* Filter setting */
touch_filter_config_t filter_info = {
.mode = TOUCH_PAD_FILTER_IIR_8,
.debounce_cnt = 1, // 1 time count.
.hysteresis_thr = 1, // 9.4%
.noise_thr = 1, // 37.5%
.noise_neg_thr = 1, // 37.5%
.neg_noise_limit = 10, // 10 time count.
.jitter_step = 4, // use for jitter mode.
};
touch_pad_filter_set_config(&filter_info);
touch_pad_filter_enable();
touch_pad_filter_baseline_reset(TOUCH_PAD_MAX);
printf("touch pad filter init %d", TOUCH_PAD_FILTER_IIR_8);
/* Enable touch sensor clock. Work mode is "timer trigger". */
touch_pad_fsm_start(TOUCH_FSM_MODE_TIMER);
uint32_t touch_value;
//read baseline value
touch_pad_read_raw(TOUCH_PAD_NUM8, &touch_value);
//set interrupt threshold.
touch_pad_sleep_channel_t slp_config = {
.touch_num = TOUCH_PAD_NUM8,
.sleep_pad_threshold = touch_value * 0.2,
.en_proximity = false,
};
touch_pad_sleep_channel_config(slp_config); //20%
printf("test init: touch pad [%d] base %d, thresh %d", \
TOUCH_PAD_NUM8, touch_value, (uint32_t)(touch_value * 0.2));
#endif
printf("Enabling touch pad wakeup\n");
esp_sleep_enable_touchpad_wakeup();
#endif // CONFIG_ENABLE_TOUCH_WAKEUP
#ifdef CONFIG_ENABLE_ULP_TEMPERATURE_WAKEUP
@ -186,6 +228,7 @@ void app_main()
}
#ifdef CONFIG_ENABLE_TOUCH_WAKEUP
#if CONFIG_IDF_TARGET_ESP32
static void calibrate_touch_pad(touch_pad_t pad)
{
int avg = 0;
@ -207,6 +250,7 @@ static void calibrate_touch_pad(touch_pad_t pad)
touch_pad_config(pad, threshold);
}
}
#endif
#endif // CONFIG_ENABLE_TOUCH_WAKEUP
#ifdef CONFIG_ENABLE_ULP_TEMPERATURE_WAKEUP