feat(touch): support touch driver on p4 (soc)

This commit is contained in:
laokaiyao 2023-08-25 16:52:05 +08:00 committed by Kevin (Lao Kaiyao)
parent dd5b091a8b
commit f35ec64a0b
27 changed files with 1237 additions and 1190 deletions

View File

@ -149,11 +149,11 @@ components/driver/test_apps/temperature_sensor:
components/driver/test_apps/touch_sensor_v1:
disable:
- if: SOC_TOUCH_VERSION_1 != 1
- if: SOC_TOUCH_SENSOR_VERSION != 1
components/driver/test_apps/touch_sensor_v2:
disable:
- if: SOC_TOUCH_VERSION_2 != 1
- if: SOC_TOUCH_SENSOR_VERSION != 2
components/driver/test_apps/twai:
disable:

View File

@ -57,7 +57,7 @@ void test_pxp_deinit_io(void)
}
#endif
#define TOUCH_READ_INVALID_VAL (SOC_TOUCH_PAD_THRESHOLD_MAX)
#define TOUCH_READ_INVALID_VAL (TOUCH_PAD_THRESHOLD_MAX)
#define TOUCH_READ_ERROR_THRESH (0.1) // 10% error
#define TOUCH_INTR_THRESHOLD (0.1)
#define TOUCH_EXCEED_TIME_MS (1000)

View File

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -32,6 +32,8 @@ extern "C" {
#define TOUCH_LL_BIT_SWAP(data, n, m) (((data >> n) & 0x1) == ((data >> m) & 0x1) ? (data) : ((data) ^ ((0x1 <<n) | (0x1 << m))))
#define TOUCH_LL_BITS_SWAP(v) TOUCH_LL_BIT_SWAP(v, TOUCH_PAD_NUM8, TOUCH_PAD_NUM9)
#define TOUCH_LL_PAD_MEASURE_WAIT_MAX (0xFF) /*!<The timer frequency is 8Mhz, the max value is 0xff */
/**
* Swap the number of touch8 and touch9.
*
@ -58,7 +60,7 @@ static inline void touch_ll_set_meas_time(uint16_t meas_time)
//touch sensor measure time= meas_cycle / 8Mhz
HAL_FORCE_MODIFY_U32_REG_FIELD(SENS.sar_touch_ctrl1, touch_meas_delay, meas_time);
//the waiting cycles (in 8MHz) between TOUCH_START and TOUCH_XPD
HAL_FORCE_MODIFY_U32_REG_FIELD(SENS.sar_touch_ctrl1, touch_xpd_wait, SOC_TOUCH_PAD_MEASURE_WAIT_MAX);
HAL_FORCE_MODIFY_U32_REG_FIELD(SENS.sar_touch_ctrl1, touch_xpd_wait, TOUCH_LL_PAD_MEASURE_WAIT_MAX);
}
/**

View File

@ -0,0 +1,948 @@
/*
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
/*******************************************************************************
* NOTICE
* The ll is not public api, don't use in application code.
* See readme.md in hal/include/hal/readme.md
******************************************************************************/
#pragma once
#include <stdlib.h>
#include <stdbool.h>
#include "hal/misc.h"
#include "hal/assert.h"
#include "soc/touch_sensor_periph.h"
#include "soc/lp_analog_peri_struct.h"
#include "soc/touch_struct.h"
#include "soc/pmu_struct.h"
#include "soc/soc_caps.h"
#include "hal/touch_sensor_types.h"
#ifdef __cplusplus
extern "C" {
#endif
#define TOUCH_LL_READ_RAW 0x0
#define TOUCH_LL_READ_BENCHMARK 0x2
#define TOUCH_LL_READ_SMOOTH 0x3
#define TOUCH_LL_TIMER_FORCE_DONE_BY_SW 0x1
#define TOUCH_LL_TIMER_DONE_BY_FSM 0x0
// Interrupt mask
#define TOUCH_LL_INTR_MASK_SCAN_DONE BIT(1)
#define TOUCH_LL_INTR_MASK_DONE BIT(2)
#define TOUCH_LL_INTR_MASK_ACTIVE BIT(3)
#define TOUCH_LL_INTR_MASK_INACTIVE BIT(4)
#define TOUCH_LL_INTR_MASK_TIMEOUT BIT(5)
#define TOUCH_LL_INTR_MASK_APPROACH_DONE BIT(6)
#define TOUCH_LL_INTR_MASK_ALL (0x3F)
#define TOUCH_LL_FULL_CHANNEL_MASK ((uint16_t)((1U << SOC_TOUCH_SENSOR_NUM) - 1))
#define TOUCH_LL_NULL_CHANNEL (15) // Null Channel id. Used for disabling some functions like sleep/approach/waterproof
#define TOUCH_LL_PAD_MEASURE_WAIT_MAX (0x7FFF) // The timer frequency is 8Mhz, the max value is 0xff
/**
* Enable/disable clock gate of touch sensor.
*
* @param enable true/false.
*/
static inline void touch_ll_enable_clock(bool enable)
{
LP_ANA_PERI.date.clk_en = enable;
}
/**
* Set the power on wait cycle
*
* @param wait_cycles
*/
static inline void touch_ll_set_power_on_wait_cycle(uint32_t wait_cycles)
{
LP_ANA_PERI.touch_scan_ctrl1.touch_xpd_wait = wait_cycles;
}
/**
* Set touch sensor touch sensor charge and discharge times of every measurement on a pad.
*
* @param sampler_id The sampler index
* @param charge_times The times of charge and discharge in each measure process of touch channels.
* The timer frequency is 8Mhz. Range: 0 ~ 0xffff.
*/
static inline void touch_ll_set_charge_times(uint8_t sampler_id, uint16_t charge_times)
{
//The times of charge and discharge in each measure process of touch channels.
switch (sampler_id) {
case 0:
LP_ANA_PERI.touch_work_meas_num.touch_meas_num0 = charge_times;
break;
case 1:
LP_ANA_PERI.touch_work_meas_num.touch_meas_num1 = charge_times;
break;
case 2:
LP_ANA_PERI.touch_work_meas_num.touch_meas_num2 = charge_times;
break;
default:
abort();
}
}
/**
* Get touch sensor times of charge and discharge.
*
* @param meas_times Pointer to accept times count of charge and discharge.
*/
static inline void touch_ll_get_charge_times(uint8_t sampler_id, uint16_t *charge_times)
{
switch (sampler_id) {
case 0:
*charge_times = LP_ANA_PERI.touch_work_meas_num.touch_meas_num0;
break;
case 1:
*charge_times = LP_ANA_PERI.touch_work_meas_num.touch_meas_num1;
break;
case 2:
*charge_times = LP_ANA_PERI.touch_work_meas_num.touch_meas_num2;
break;
default:
abort();
}
}
/**
* Set touch sensor sleep time.
*
* @param interval_ticks The touch sensor will sleep for some cycles after each measurement.
* interval_ticks decide the interval between each measurement.
* t_sleep = interval_ticks / (RTC_SLOW_CLK frequency).
* The approximate frequency value of RTC_SLOW_CLK can be obtained using rtc_clk_slow_freq_get_hz function.
*/
static inline void touch_ll_set_measure_interval_ticks(uint16_t interval_ticks)
{
// touch sensor sleep cycle Time = interval_ticks / RTC_SLOW_CLK
HAL_FORCE_MODIFY_U32_REG_FIELD(PMU.touch_pwr_cntl, touch_sleep_cycles, interval_ticks);
}
/**
* Get touch sensor sleep time.
*
* @param interval_ticks Pointer to accept measurement interval (sleep) cycle number.
*/
static inline void touch_ll_get_measure_interval_ticks(uint16_t *interval_ticks)
{
*interval_ticks = HAL_FORCE_READ_U32_REG_FIELD(PMU.touch_pwr_cntl, touch_sleep_cycles);
}
/**
* Set touch sensor FSM mode.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
*
* @param mode FSM mode.
* TOUCH_FSM_MODE_TIMER: the FSM will trigger scanning repeatedly under the control of the hardware timer
* TOUCH_FSM_MODE_SW: the FSM will trigger scanning once under the control of the software
*/
static inline void touch_ll_set_fsm_mode(touch_fsm_mode_t mode)
{
// FSM controlled by timer or software
LP_ANA_PERI.touch_mux0.touch_fsm_en = mode;
// Start by timer or software
LP_ANA_PERI.touch_mux0.touch_start_force = mode;
// Stop by timer or software
LP_ANA_PERI.touch_mux0.touch_done_force = mode;
}
/**
* Get touch sensor FSM mode.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
*
* @param mode FSM mode.
*/
static inline void touch_ll_get_fsm_mode(touch_fsm_mode_t *mode)
{
*mode = (touch_fsm_mode_t)LP_ANA_PERI.touch_mux0.touch_fsm_en;
}
/**
* Is touch sensor FSM using hardware timer to trigger scanning.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
*
* @return Whether FSM timer enabled.
*/
static inline bool touch_ll_is_fsm_using_timer(void)
{
return !LP_ANA_PERI.touch_mux0.touch_start_force;
}
/**
* Touch timer trigger measurement and always wait measurement done.
* Force done for touch timer ensures that the timer always can get the measurement done signal.
*/
static inline void touch_ll_force_done_curr_measurement(void)
{
if (touch_ll_is_fsm_using_timer()) {
LP_ANA_PERI.touch_mux0.touch_done_force = TOUCH_LL_TIMER_FORCE_DONE_BY_SW;
LP_ANA_PERI.touch_mux0.touch_done_en = 1;
LP_ANA_PERI.touch_mux0.touch_done_en = 0;
LP_ANA_PERI.touch_mux0.touch_done_force = TOUCH_LL_TIMER_DONE_BY_FSM;
} else {
LP_ANA_PERI.touch_mux0.touch_done_en = 1;
LP_ANA_PERI.touch_mux0.touch_done_en = 0;
}
}
/**
* Start touch sensor FSM timer to run FSM repeatedly
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
* @note
* The timer should be triggered
* @param is_sleep Whether in sleep state
*/
static inline void touch_ll_start_fsm_repeated_timer(bool is_sleep)
{
/**
* Touch timer trigger measurement and always wait measurement done.
* Force done for touch timer ensures that the timer always can get the measurement done signal.
*/
touch_ll_force_done_curr_measurement();
if (is_sleep) {
PMU.touch_pwr_cntl.touch_sleep_timer_en = 1;
} else {
LP_ANA_PERI.touch_mux0.touch_start_en = 1;
}
}
/**
* Stop touch sensor FSM timer.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
* @param is_sleep Whether in sleep state
*/
static inline void touch_ll_stop_fsm_repeated_timer(bool is_sleep)
{
if (is_sleep) {
PMU.touch_pwr_cntl.touch_sleep_timer_en = 0;
} else {
LP_ANA_PERI.touch_mux0.touch_start_en = 0;
}
touch_ll_force_done_curr_measurement();
}
/**
* Start touch sensor FSM once by software
* @note Every trigger means measuring one channel, not scanning all enabled channels
*/
static inline void touch_ll_start_fsm_once(void)
{
/* Trigger once measurement */
LP_ANA_PERI.touch_mux0.touch_start_en = 1;
LP_ANA_PERI.touch_mux0.touch_start_en = 0;
}
static inline void touch_ll_measure_channel_once(uint16_t chan_mask)
{
LP_ANA_PERI.touch_mux1.touch_start = chan_mask;
}
/**
* Set touch sensor threshold of charge cycles that triggers pad active state.
* The threshold determines the sensitivity of the touch sensor.
* The threshold is the original value of the trigger state minus the benchmark value.
*
* @note If set "TOUCH_PAD_THRESHOLD_MAX", the touch is never be triggered.
* @param touch_num The touch pad id
* @param sampler_id The sampler index
* @param thresh The threshold of charge cycles
*/
static inline void touch_ll_set_chan_active_threshold(uint32_t touch_num, uint8_t sampler_id, uint32_t thresh)
{
HAL_ASSERT(sampler_id < SOC_TOUCH_SAMPLER_NUM);
HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_padx_thn[touch_num].thn[sampler_id], threshold, thresh);
}
/**
* Enable touch sensor channel. Register touch channel into touch sensor measurement group.
* The working mode of the touch sensor is simultaneous measurement.
* This function will set the measure bits according to the given bitmask.
*
* @note If set this mask, the FSM timer should be stop firstly.
* @note The touch sensor that in scan map, should be deinit GPIO function firstly.
* @param enable_mask bitmask of touch sensor scan group.
* e.g. TOUCH_PAD_NUM1 -> BIT(1)
* @return
* - ESP_OK on success
*/
static inline void touch_ll_set_channel_mask(uint16_t enable_mask)
{
uint16_t mask = enable_mask & TOUCH_PAD_BIT_MASK_ALL;
LP_ANA_PERI.touch_scan_ctrl1.touch_scan_pad_map = mask;
LP_ANA_PERI.touch_filter2.touch_outen = mask;
}
/**
* @brief Power on the channel by mask
*
* @param chan_mask The channel mask that needs to power on
*/
static inline void touch_ll_channel_power_on(uint16_t chan_mask)
{
uint32_t curr_mask = LP_ANA_PERI.touch_mux1.touch_xpd;
LP_ANA_PERI.touch_mux1.touch_xpd = chan_mask | curr_mask;
}
/**
* @brief Power off the channel by mask
*
* @param chan_mask The channel mask that needs to power off
*/
static inline void touch_ll_channel_power_off(uint16_t chan_mask)
{
uint32_t curr_mask = LP_ANA_PERI.touch_mux1.touch_xpd;
LP_ANA_PERI.touch_mux1.touch_xpd = (~chan_mask) & curr_mask;
}
/**
* @brief Start channel by mask
* @note Only start the specified channels
*
* @param chan_mask The channel mask that needs to start
*/
static inline void touch_ll_channel_start(uint16_t chan_mask)
{
uint32_t curr_mask = LP_ANA_PERI.touch_mux1.touch_start;
LP_ANA_PERI.touch_mux1.touch_start = chan_mask | curr_mask;
LP_ANA_PERI.touch_mux1.touch_start = (~chan_mask) & curr_mask;
}
/**
* Get the touch sensor active channel mask, usually used in ISR to decide which channels are 'touched'.
*
* @param active_mask The touch channel status. e.g. Touch1 trigger status is `status_mask & (BIT1)`.
*/
static inline void touch_ll_get_active_channel_mask(uint32_t *active_mask)
{
*active_mask = LP_TOUCH.chn_status.pad_active;
}
/**
* Clear all touch sensor channels active status.
*
* @note Generally no manual removal is required.
*/
static inline void touch_ll_clear_active_channel_status(void)
{
LP_ANA_PERI.touch_clr.touch_status_clr = 1;
}
/**
* Get the data of the touch channel according to the types
*
* @param touch_num touch pad index
* @param sampler_id The sampler index
* @param type data type
* 0/1: TOUCH_LL_READ_RAW, the raw data of the touch channel
* 2: TOUCH_LL_READ_BENCHMARK, benchmark value of touch channel,
* the benchmark value is the maximum during the first measurement period
* 3: TOUCH_LL_READ_SMOOTH, the smoothed data that obtained by filtering the raw data.
* @param data pointer to the data
*/
__attribute__((always_inline))
static inline void touch_ll_read_chan_data(uint32_t touch_num, uint8_t sampler_id, uint8_t type, uint32_t *data)
{
HAL_ASSERT(sampler_id < SOC_TOUCH_SAMPLER_NUM);
HAL_ASSERT(type <= TOUCH_LL_READ_SMOOTH);
LP_ANA_PERI.touch_mux0.touch_freq_sel = sampler_id + 1;
LP_ANA_PERI.touch_mux0.touch_data_sel = type;
*data = LP_TOUCH.chn_data[touch_num - 1].pad_data;
}
/**
* Get touch sensor measure status. No block.
*
* @return
* - If touch sensors measure done.
*/
static inline bool touch_ll_is_measure_done(uint32_t *touch_num)
{
*touch_num = (uint32_t)(LP_TOUCH.chn_status.scan_curr);
return (bool)LP_TOUCH.chn_status.meas_done;
}
/**
* Select the counting mode of the binarized touch out wave
*
* @param mode 0: as data, the value will be smaller than actual value but more sensitive when the frequency of touch_out is close to the source clock
* 1: as clock, the value is accurate but less sensitive when the frequency of touch_out is close to the source clock
* No big difference when the frequency of touch_out is far more lower than the source clock
*/
static inline void touch_ll_set_out_mode(touch_out_mode_t mode)
{
LP_ANA_PERI.touch_work.touch_out_sel = mode;
}
/**
* @brief Set the clock division of the sampling frequency
*
* @param sampler_id The sampler index
* @param div_num Division number
*/
static inline void touch_ll_set_clock_div(uint8_t sampler_id, uint32_t div_num)
{
switch (sampler_id) {
case 0:
LP_ANA_PERI.touch_work.div_num0 = div_num;
break;
case 1:
LP_ANA_PERI.touch_work.div_num1 = div_num;
break;
case 2:
LP_ANA_PERI.touch_work.div_num2 = div_num;
break;
default:
// invalid sampler_id
abort();
}
}
/**
* Set connection type of touch channel in idle status.
* When a channel is in measurement mode, other initialized channels are in idle mode.
* The touch channel is generally adjacent to the trace, so the connection state of the idle channel
* affects the stability and sensitivity of the test channel.
* The `CONN_HIGHZ`(high resistance) setting increases the sensitivity of touch channels.
* The `CONN_GND`(grounding) setting increases the stability of touch channels.
* @note This option does not take effect, it is default to HIGH Z
* Only remained here to be compatible to other version
*
* @param type Select idle channel connect to high resistance state or ground. (No effect)
*/
static inline void touch_ll_set_idle_channel_connect(touch_pad_conn_type_t type)
{
(void)type;
}
/**
* Get the current channel that under measuring.
*
* @return
* - touch channel number
*/
__attribute__((always_inline))
static inline uint32_t touch_ll_get_current_meas_channel(void)
{
return (uint32_t)(LP_TOUCH.chn_status.scan_curr);
}
/**
* Enable touch sensor interrupt by bitmask.
*
* @param int_mask interrupt mask
*/
static inline void touch_ll_intr_enable(uint32_t int_mask)
{
uint32_t mask = LP_TOUCH.int_ena.val;
mask |= (int_mask & TOUCH_LL_INTR_MASK_ALL);
LP_TOUCH.int_ena.val = mask;
}
/**
* Disable touch sensor interrupt by bitmask.
*
* @param int_mask interrupt mask
*/
static inline void touch_ll_intr_disable(uint32_t int_mask)
{
uint32_t mask = LP_TOUCH.int_ena.val;
mask &= ~(int_mask & TOUCH_LL_INTR_MASK_ALL);
LP_TOUCH.int_ena.val = mask;
}
/**
* Clear touch sensor interrupt by bitmask.
*
* @param int_mask Pad mask to clear interrupts
*/
static inline void touch_ll_intr_clear_all(void)
{
LP_TOUCH.int_clr.val = TOUCH_LL_INTR_MASK_ALL;
}
/**
* Get the bitmask of touch sensor interrupt status.
*
* @return type interrupt type
*/
static inline uint32_t touch_ll_get_intr_status_mask(void)
{
uint32_t intr_st = LP_TOUCH.int_st.val;
return (intr_st & TOUCH_LL_INTR_MASK_ALL);
}
/**
* Enable the timeout check for all touch sensor channels measurements.
* When the touch reading of a touch channel exceeds the measurement threshold,
* If enable: a timeout interrupt will be generated and it will go to the next channel measurement.
* If disable: the FSM is always on the channel, until the measurement of this channel is over.
*
* @param timeout_cycles The maximum time cycles of the measurement on one channel.
*/
static inline void touch_ll_timeout_enable(uint32_t timeout_cycles)
{
LP_ANA_PERI.touch_scan_ctrl2.touch_timeout_num = timeout_cycles;
LP_ANA_PERI.touch_scan_ctrl2.touch_timeout_en = 1;
}
/**
* Disable the timeout check for all touch sensor channels measurements.
* When the touch reading of a touch channel exceeds the measurement threshold,
* If enable: a timeout interrupt will be generated and it will go to the next channel measurement.
* If disable: the FSM is always on the channel, until the measurement of this channel is over.
*/
static inline void touch_ll_timeout_disable(void)
{
LP_ANA_PERI.touch_scan_ctrl2.touch_timeout_en = 0;
}
/**
* Set the engaged sampler number
*
* @param sampler_num The enabled sampler number, range 0~3.
* 0/1 means only one sampler enabled, which can not support frequency hopping
*/
static inline void touch_ll_sampler_set_engaged_num(uint8_t sampler_num)
{
HAL_ASSERT(sampler_num < SOC_TOUCH_SAMPLER_NUM);
LP_ANA_PERI.touch_scan_ctrl2.freq_scan_en = !!sampler_num;
LP_ANA_PERI.touch_scan_ctrl2.freq_scan_cnt_limit = sampler_num ? sampler_num : 1;
}
/**
* Set capacitance and resistance of the RC filter of the sampling frequency.
*
* @param sampler_id The sampler index
* @param cap Capacitance of the RC filter.
* @param res Resistance of the RC filter.
*/
static inline void touch_ll_sampler_set_rc_filter(uint8_t sampler_id, uint32_t cap, uint32_t res)
{
HAL_ASSERT(sampler_id < SOC_TOUCH_SAMPLER_NUM);
LP_ANA_PERI.touch_freq_scan_para[sampler_id].touch_freq_dcap_lpf = cap;
LP_ANA_PERI.touch_freq_scan_para[sampler_id].touch_freq_dres_lpf = res;
}
/**
* @brief Set the driver of the sampling frequency
*
* @param sampler_id The sampler index
* @param ls_drv Low speed touch driver
* @param hs_drv High speed touch driver
*/
static inline void touch_ll_sampler_set_driver(uint8_t sampler_id, uint32_t ls_drv, uint32_t hs_drv)
{
HAL_ASSERT(sampler_id < SOC_TOUCH_SAMPLER_NUM);
LP_ANA_PERI.touch_freq_scan_para[sampler_id].touch_freq_drv_ls = ls_drv;
LP_ANA_PERI.touch_freq_scan_para[sampler_id].touch_freq_drv_hs = hs_drv;
}
/**
* Set the touch internal LDO bias voltage of the sampling frequency
*
* @param sampler_id The sampler index
* @param bias_volt LDO bias voltage
*/
static inline void touch_ll_sampler_set_bias_voltage(uint8_t sampler_id, uint32_t bias_volt)
{
HAL_ASSERT(sampler_id < SOC_TOUCH_SAMPLER_NUM);
LP_ANA_PERI.touch_freq_scan_para[sampler_id].touch_freq_dbias = bias_volt;
}
/**
* @brief Set the internal loop capacitance
* Can simulate the touch signal via the internal capacitance
* Need to turn off touch pad
* @param cap The internal capacitance
*/
static inline void touch_ll_set_internal_loop_capacitance(int cap)
{
bool enable = cap > 0;
LP_ANA_PERI.touch_ana_para.touch_touch_en_cal = enable;
LP_ANA_PERI.touch_ana_para.touch_touch_dcap_cal = enable ? cap : 0;
}
/************************ Filter register setting ************************/
/**
* Force reset benchmark to raw data of touch sensor.
*
* @note If call this API, make sure enable clock gate(`touch_ll_clkgate`) first.
* @param chan_mask touch channel mask
*/
static inline void touch_ll_reset_chan_benchmark(uint32_t chan_mask)
{
LP_ANA_PERI.touch_clr.touch_channel_clr = chan_mask;
}
/**
* Set filter mode. The input of the filter is the raw value of touch reading,
* and the output of the filter is involved in the judgment of the touch state.
*
* @param mode Filter mode type. Refer to ``touch_filter_mode_t``.
*/
static inline void touch_ll_filter_set_filter_mode(touch_filter_mode_t mode)
{
LP_ANA_PERI.touch_filter1.touch_filter_mode = mode;
}
/**
* Set filter mode. The input to the filter is raw data and the output is the smooth data.
* The smooth data is used to determine the touch status.
*
* @param mode Filter mode type. Refer to ``touch_smooth_mode_t``.
*/
static inline void touch_ll_filter_set_smooth_mode(touch_smooth_mode_t mode)
{
LP_ANA_PERI.touch_filter1.touch_smooth_lvl = mode;
}
/**
* Set debounce count, such as `n`. If the measured values continue to exceed
* the threshold for `n+1` times, it is determined that the touch sensor state changes.
*
* @param dbc_cnt Debounce count value.
*/
static inline void touch_ll_filter_set_debounce(uint32_t dbc_cnt)
{
LP_ANA_PERI.touch_filter1.touch_debounce_limit = dbc_cnt;
}
/**
* Set the positive noise threshold coefficient. Higher = More noise resistance.
* The benchmark will update to the new value if the touch data is within (benchmark + active_threshold * pos_coeff)
*
*
* @param pos_noise_thresh Range [-1 ~ 3]. The coefficient is -1: always; 0: 4/8; 1: 3/8; 2: 2/8; 3: 1;
* -1: the benchmark will always update to the new touch data without considering the positive noise threshold
*/
static inline void touch_ll_filter_set_pos_noise_thresh(int pos_noise_thresh)
{
bool always_update = pos_noise_thresh < 0;
LP_ANA_PERI.touch_filter2.touch_bypass_noise_thres = always_update;
LP_ANA_PERI.touch_filter1.touch_noise_thres = always_update ? 0 : pos_noise_thresh;
}
/**
* Set the negative noise threshold coefficient. Higher = More noise resistance.
* The benchmark will update to the new value if the touch data is greater than (benchmark - active_threshold * neg_coeff)
*
* @param neg_noise_thresh Range [-2 ~ 3]. The coefficient is -2: never; -1: always; 0: 4/8; 1: 3/8; 2: 2/8; 3: 1;
* -1: the benchmark will always update to the new touch data without considering the negative noise threshold
* -2: the benchmark will never update to the new touch data with negative growth
* @param neg_noise_limit Only when neg_noise_thresh >= 0, if the touch data keep blow the negative threshold for mare than neg_noise_limit ticks,
* the benchmark will still update to the new value.
* It is normally used for updating the benchmark at the first scanning
*/
static inline void touch_ll_filter_set_neg_noise_thresh(int neg_noise_thresh, uint8_t neg_noise_limit)
{
bool always_update = neg_noise_thresh == -1;
bool stop_update = neg_noise_thresh == -2;
LP_ANA_PERI.touch_filter2.touch_bypass_neg_noise_thres = always_update;
LP_ANA_PERI.touch_filter1.touch_neg_noise_disupdate_baseline_en = stop_update;
LP_ANA_PERI.touch_filter1.touch_neg_noise_thres = always_update || stop_update ? 0 : neg_noise_thresh;
LP_ANA_PERI.touch_filter1.touch_neg_noise_limit = always_update || stop_update ? 5 : neg_noise_limit; // 5 is the default value
}
/**
* Set the hysteresis value of the active threshold
* While the touch data is greater than active_threshold + hysteresis and last for several ticks, the channel is activated,
* and while the touch data is smaller than active_threshold - hysteresis and last for several ticks, the channel is inactivated
*
* @param hysteresis The hysteresis value of active threshold
*/
static inline void touch_ll_filter_set_active_hysteresis(uint32_t hysteresis)
{
LP_ANA_PERI.touch_filter1.touch_hysteresis = hysteresis;
}
/**
* Set jitter filter step size.
* If filter mode is jitter, should set filter step for jitter.
* Range: 0 ~ 15
*
* @param step The step size of the data change.
*/
static inline void touch_ll_filter_set_jitter_step(uint32_t step)
{
LP_ANA_PERI.touch_filter1.touch_jitter_step = step;
}
/**
* Enable or disable touch sensor filter and detection algorithm.
* For more details on the detection algorithm, please refer to the application documentation.
*/
static inline void touch_ll_filter_enable(bool enable)
{
LP_ANA_PERI.touch_filter1.touch_filter_en = enable;
}
/**
* Force the update the benchmark by software
* @note This benchmark will be applied to all enabled channel and all sampling frequency
*
* @param benchmark The benchmark specified by software
*/
static inline void touch_ll_force_update_benchmark(uint32_t benchmark)
{
HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_filter3, touch_baseline_sw, benchmark);
LP_ANA_PERI.touch_filter3.touch_update_baseline_sw = 1;
// waiting for update
while (LP_ANA_PERI.touch_filter3.touch_update_baseline_sw);
}
/************************ Waterproof register setting ************************/
/**
* Set touch channel use for guard pad.
*
* @param pad_num Touch sensor channel number.
*/
static inline void touch_ll_waterproof_set_guard_chan(uint32_t pad_num)
{
LP_ANA_PERI.touch_scan_ctrl2.touch_out_ring = pad_num;
}
/**
* Enable or disable parameter of waterproof function.
*
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* Guard pad is used to detect the large area of water covering the touch panel.
* Shield pad is used to shield the influence of water droplets covering the touch panel.
* It is generally designed as a grid and is placed around the touch buttons.
*/
static inline void touch_ll_waterproof_enable(bool enable)
{
LP_ANA_PERI.touch_scan_ctrl1.touch_shield_pad_en = enable;
}
/**
* Set the shield channel mask
*
* @param mask The channels that set in the mask will be used as shield channel
*/
static inline void touch_ll_waterproof_set_shield_chan_mask(uint32_t mask)
{
LP_ANA_PERI.touch_mux0.touch_bufsel = (mask & TOUCH_LL_FULL_CHANNEL_MASK);
}
/**
* Set the touch buff driver for the shield channel.
*
* @param driver_level The driver level of the touch buff
*/
static inline void touch_ll_waterproof_set_shield_driver(touch_pad_shield_driver_t driver_level)
{
LP_ANA_PERI.touch_ana_para.touch_touch_buf_drv = driver_level;
}
/************************ Approach register setting ************************/
/**
* Set the approach channel to the specific touch channel
* To disable the approach channel, point this pad to `TOUCH_LL_NULL_CHANNEL`
*
* @param aprch_chan approach channel.
* @param touch_num The touch channel that supposed to be used as approach channel
*/
static inline void touch_ll_set_approach_channel(uint8_t aprch_chan, uint32_t touch_num)
{
switch (aprch_chan) {
case 0:
LP_ANA_PERI.touch_approach.touch_approach_pad0 = touch_num;
break;
case 1:
LP_ANA_PERI.touch_approach.touch_approach_pad1 = touch_num;
break;
case 2:
LP_ANA_PERI.touch_approach.touch_approach_pad2 = touch_num;
break;
default:
// invalid approach channel
abort();
}
}
/**
* Set cumulative measurement times for approach channel.
*
* @param sampler_id The sampler index
* @param times The cumulative number of measurement cycles.
*/
static inline void touch_ll_approach_set_measure_times(uint8_t sampler_id, uint32_t times)
{
switch (sampler_id) {
case 0:
LP_ANA_PERI.touch_approach_work_meas_num.touch_approach_meas_num0 = times;
break;
case 1:
LP_ANA_PERI.touch_approach_work_meas_num.touch_approach_meas_num1 = times;
break;
case 2:
LP_ANA_PERI.touch_approach_work_meas_num.touch_approach_meas_num2 = times;
break;
default:
// invalid sampler_id
abort();
}
}
/**
* Read current cumulative measurement times for approach channel.
*
* @param aprch_chan approach channel.
* @param cnt The cumulative number of measurement cycles.
*/
static inline void touch_ll_approach_read_measure_cnt(uint8_t aprch_chan, uint32_t *cnt)
{
switch (aprch_chan) {
case 0:
*cnt = HAL_FORCE_READ_U32_REG_FIELD(LP_TOUCH.aprch_ch_data, approach_pad0_cnt);
break;
case 1:
*cnt = HAL_FORCE_READ_U32_REG_FIELD(LP_TOUCH.aprch_ch_data, approach_pad1_cnt);
break;
case 2:
*cnt = HAL_FORCE_READ_U32_REG_FIELD(LP_TOUCH.aprch_ch_data, approach_pad2_cnt);
break;
default: // sleep channel
*cnt = HAL_FORCE_READ_U32_REG_FIELD(LP_TOUCH.aprch_ch_data, slp_approach_cnt);
break;
}
}
/**
* Check if the touch sensor channel is the approach channel.
*
* @param touch_num The touch sensor channel number.
*/
static inline bool touch_ll_is_approach_channel(uint32_t touch_num)
{
if ((LP_ANA_PERI.touch_approach.touch_approach_pad0 != touch_num)
&& (LP_ANA_PERI.touch_approach.touch_approach_pad1 != touch_num)
&& (LP_ANA_PERI.touch_approach.touch_approach_pad2 != touch_num)) {
return false;
} else {
return true;
}
}
/************** sleep channel setting ***********************/
/**
* Set touch channel number for sleep channel.
*
* @note Only one touch sensor channel is supported in deep sleep mode.
* @param touch_num Touch sensor channel number.
*/
static inline void touch_ll_sleep_set_channel_num(uint32_t touch_num)
{
LP_ANA_PERI.touch_slp0.touch_slp_pad = touch_num;
}
/**
* Get touch channel number for sleep pad.
*
* @note Only one touch sensor channel is supported in deep sleep mode.
* @param touch_num Touch sensor channel number.
*/
static inline void touch_ll_sleep_get_channel_num(uint32_t *touch_num)
{
*touch_num = (uint32_t)(LP_ANA_PERI.touch_slp0.touch_slp_pad);
}
/**
* Set the trigger threshold of touch sensor in deep sleep.
* The threshold determines the sensitivity of the touch sensor.
* The threshold is the original value of the trigger state minus the benchmark value.
*
* @note In general, the touch threshold during sleep can use the threshold parameter parameters before sleep.
*/
static inline void touch_ll_sleep_set_threshold(uint8_t sampler_id, uint32_t touch_thresh)
{
switch (sampler_id) {
case 0:
HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_slp0, touch_slp_th0, touch_thresh);
break;
case 1:
HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_slp1, touch_slp_th1, touch_thresh);
break;
case 2:
HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_slp1, touch_slp_th2, touch_thresh);
break;
default:
// invalid sampler_id
abort();
}
}
/**
* Enable approach function for sleep channel.
*/
static inline void touch_ll_sleep_enable_approach(bool enable)
{
LP_ANA_PERI.touch_approach.touch_slp_approach_en = enable;
}
/**
* Get the data of the touch channel according to the types
*
* @param sampler_id The sampler index
* @param type data type
* 0/1: TOUCH_LL_READ_RAW, the raw data of the touch channel
* 2: TOUCH_LL_READ_BENCHMARK, benchmark value of touch channel,
* the benchmark value is the maximum during the first measurement period
* 3: TOUCH_LL_READ_SMOOTH, the smoothed data that obtained by filtering the raw data.
* @param smooth_data pointer to smoothed data
*/
__attribute__((always_inline))
static inline void touch_ll_sleep_read_chan_data(uint8_t type, uint8_t sampler_id, uint32_t *data)
{
HAL_ASSERT(type <= TOUCH_LL_READ_SMOOTH);
LP_ANA_PERI.touch_mux0.touch_freq_sel = sampler_id + 1;
LP_ANA_PERI.touch_mux0.touch_data_sel = type;
*data = HAL_FORCE_READ_U32_REG_FIELD(LP_TOUCH.slp_ch_data, slp_data);
}
/**
* @brief Reset the benchmark of the sleep channel
*
*/
static inline void touch_ll_sleep_reset_benchmark(void)
{
LP_ANA_PERI.touch_slp0.touch_slp_channel_clr = 1;
}
/**
* Read debounce of touch sensor for sleep channel.
*
* @param debounce Pointer to accept touch sensor debounce value.
*/
static inline void touch_ll_sleep_read_debounce(uint32_t *debounce)
{
*debounce = LP_TOUCH.slp_ch_data.slp_debounce_cnt;
}
/**
* Read approach count of touch sensor for sleep channel.
* @param approach_cnt Pointer to accept touch sensor approach count value.
*/
static inline void touch_ll_sleep_read_approach_cnt(uint32_t *approach_cnt)
{
*approach_cnt = HAL_FORCE_READ_U32_REG_FIELD(LP_TOUCH.aprch_ch_data, slp_approach_cnt);
}
#ifdef __cplusplus
}
#endif

View File

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -34,6 +34,8 @@ extern "C" {
#define TOUCH_LL_TIMER_FORCE_DONE 0x3
#define TOUCH_LL_TIMER_DONE 0x0
#define TOUCH_LL_PAD_MEASURE_WAIT_MAX (0xFF) /*!<The timer frequency is 8Mhz, the max value is 0xff */
/**
* Set touch sensor touch sensor times of charge and discharge.
*
@ -45,7 +47,7 @@ static inline void touch_ll_set_meas_times(uint16_t meas_time)
//The times of charge and discharge in each measure process of touch channels.
HAL_FORCE_MODIFY_U32_REG_FIELD(RTCCNTL.touch_ctrl1, touch_meas_num, meas_time);
//the waiting cycles (in 8MHz) between TOUCH_START and TOUCH_XPD
HAL_FORCE_MODIFY_U32_REG_FIELD(RTCCNTL.touch_ctrl2, touch_xpd_wait, SOC_TOUCH_PAD_MEASURE_WAIT_MAX); //wait volt stable
HAL_FORCE_MODIFY_U32_REG_FIELD(RTCCNTL.touch_ctrl2, touch_xpd_wait, TOUCH_LL_PAD_MEASURE_WAIT_MAX); //wait volt stable
}
/**

View File

@ -142,7 +142,7 @@ void touch_hal_sleep_channel_enable(touch_pad_t pad_num, bool enable)
{
if (enable) {
touch_ll_sleep_set_channel_num(pad_num);
touch_ll_sleep_set_threshold(SOC_TOUCH_PAD_THRESHOLD_MAX);
touch_ll_sleep_set_threshold(TOUCH_PAD_THRESHOLD_MAX);
touch_ll_sleep_reset_benchmark();
} else {
touch_ll_sleep_set_channel_num(TOUCH_PAD_NUM0);

View File

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2021 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -34,6 +34,8 @@ extern "C" {
#define TOUCH_LL_TIMER_FORCE_DONE 0x3
#define TOUCH_LL_TIMER_DONE 0x0
#define TOUCH_LL_PAD_MEASURE_WAIT_MAX (0xFF) /*!<The timer frequency is 8Mhz, the max value is 0xff */
/**
* Set touch sensor touch sensor times of charge and discharge.
*
@ -45,7 +47,7 @@ static inline void touch_ll_set_meas_times(uint16_t meas_time)
//The times of charge and discharge in each measure process of touch channels.
HAL_FORCE_MODIFY_U32_REG_FIELD(RTCCNTL.touch_ctrl1, touch_meas_num, meas_time);
//the waiting cycles (in 8MHz) between TOUCH_START and TOUCH_XPD
HAL_FORCE_MODIFY_U32_REG_FIELD(RTCCNTL.touch_ctrl2, touch_xpd_wait, SOC_TOUCH_PAD_MEASURE_WAIT_MAX); //wait volt stable
HAL_FORCE_MODIFY_U32_REG_FIELD(RTCCNTL.touch_ctrl2, touch_xpd_wait, TOUCH_LL_PAD_MEASURE_WAIT_MAX); //wait volt stable
}
/**

View File

@ -142,7 +142,7 @@ void touch_hal_sleep_channel_enable(touch_pad_t pad_num, bool enable)
{
if (enable) {
touch_ll_sleep_set_channel_num(pad_num);
touch_ll_sleep_set_threshold(SOC_TOUCH_PAD_THRESHOLD_MAX);
touch_ll_sleep_set_threshold(TOUCH_PAD_THRESHOLD_MAX);
touch_ll_sleep_reset_benchmark();
} else {
touch_ll_sleep_set_channel_num(TOUCH_PAD_NUM0);

View File

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -119,7 +119,13 @@ typedef enum {
#define TOUCH_PAD_LOW_VOLTAGE_THRESHOLD (TOUCH_LVOLT_0V5)
#define TOUCH_PAD_ATTEN_VOLTAGE_THRESHOLD (TOUCH_HVOLT_ATTEN_0V5)
#define TOUCH_PAD_IDLE_CH_CONNECT_DEFAULT (TOUCH_PAD_CONN_GND)
#define TOUCH_PAD_THRESHOLD_MAX (SOC_TOUCH_PAD_THRESHOLD_MAX) /*!<If set touch threshold max value, The touch sensor can't be in touched status */
#if SOC_TOUCH_SENSOR_VERSION == 1
#define TOUCH_PAD_THRESHOLD_MAX (0) /*!< If set touch threshold max value, The touch sensor can't be in touched status */
#elif SOC_TOUCH_SENSOR_VERSION == 2
#define TOUCH_PAD_THRESHOLD_MAX (0x1FFFFF) /*!< If set touch threshold max value, The touch sensor can't be in touched status */
#elif SOC_TOUCH_SENSOR_VERSION == 3
#define TOUCH_PAD_THRESHOLD_MAX (0xFFFF) /*!< If set touch threshold max value, The touch sensor can't be in touched status */
#endif
#ifdef CONFIG_IDF_TARGET_ESP32
@ -146,6 +152,7 @@ typedef enum {
Recommended typical value: Modify this value to make the measurement time around 1ms.
Range: 0 ~ 0xffff */
// TODO: replace by ll macro
typedef enum {
TOUCH_PAD_INTR_MASK_DONE = BIT(0), /*!<Measurement done for one of the enabled channels. */
TOUCH_PAD_INTR_MASK_ACTIVE = BIT(1), /*!<Active for one of the enabled channels. */
@ -268,6 +275,21 @@ typedef enum {
TOUCH_PAD_SMOOTH_MAX,
} touch_smooth_mode_t;
#if CONFIG_IDF_TARGET_ESP32P4
/**
* @brief Touch channel counting mode of the binarized touch output
*
*/
typedef enum {
TOUCH_PAD_OUT_AS_DATA, /*!< Counting the output of touch channel as data.
* The value will be smaller than actual value but more sensitive when the frequency of touch_out is close to the source clock
*/
TOUCH_PAD_OUT_AS_CLOCK, /*!< Counting the output of touch channel as clock.
* The value is accurate but less sensitive when the frequency of touch_out is close to the source clock
*/
} touch_out_mode_t;
#endif
/** Touch sensor filter configuration */
typedef struct touch_filter_config {
touch_filter_mode_t mode; /*!<Set filter mode. The input of the filter is the raw value of touch reading,

View File

@ -12,7 +12,7 @@
void touch_hal_config(touch_pad_t touch_num)
{
touch_ll_set_threshold(touch_num, SOC_TOUCH_PAD_THRESHOLD_MAX);
touch_ll_set_threshold(touch_num, TOUCH_PAD_THRESHOLD_MAX);
touch_ll_set_slope(touch_num, TOUCH_PAD_SLOPE_DEFAULT);
touch_ll_set_tie_option(touch_num, TOUCH_PAD_TIE_OPT_DEFAULT);
}

View File

@ -659,21 +659,17 @@ config SOC_TIMER_GROUP_SUPPORT_APB
bool
default y
config SOC_TOUCH_VERSION_1
bool
default y
config SOC_TOUCH_SENSOR_VERSION
int
default 1
config SOC_TOUCH_SENSOR_NUM
int
default 10
config SOC_TOUCH_PAD_MEASURE_WAIT_MAX
hex
default 0xFF
config SOC_TOUCH_PAD_THRESHOLD_MAX
bool
default n
config SOC_TOUCH_SAMPLER_NUM
int
default 1
config SOC_TWAI_CONTROLLER_NUM
int

View File

@ -316,11 +316,10 @@
#define SOC_TIMER_GROUP_SUPPORT_APB (1)
/*-------------------------- TOUCH SENSOR CAPS -------------------------------*/
#define SOC_TOUCH_VERSION_1 (1) /*!<Hardware version of touch sensor */
#define SOC_TOUCH_SENSOR_VERSION (1U) /*!<Hardware version of touch sensor */
#define SOC_TOUCH_SENSOR_NUM (10)
#define SOC_TOUCH_PAD_MEASURE_WAIT_MAX (0xFF) /*!<The timer frequency is 8Mhz, the max value is 0xff */
#define SOC_TOUCH_PAD_THRESHOLD_MAX (0) /*!<If set touch threshold max value, The touch sensor can't be in touched status */
#define SOC_TOUCH_SAMPLER_NUM (1U) /*!< The sampler number in total, each sampler can be used to sample on one frequency */
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL

View File

@ -1039,6 +1039,26 @@ config SOC_MWDT_SUPPORT_XTAL
bool
default y
config SOC_TOUCH_SENSOR_VERSION
int
default 3
config SOC_TOUCH_SENSOR_NUM
int
default 14
config SOC_TOUCH_PROXIMITY_CHANNEL_NUM
int
default 3
config SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED
bool
default y
config SOC_TOUCH_SAMPLER_NUM
int
default 3
config SOC_TWAI_CONTROLLER_NUM
int
default 3

View File

@ -466,7 +466,8 @@ typedef union {
*/
uint32_t div_num0:3;
/** touch_out_sel : R/W; bitpos: [25]; default: 0;
* need_des
* 0: Select the output of the touch as data
* 1: Select the output of the touch as clock
*/
uint32_t touch_out_sel:1;
/** touch_out_reset : WT; bitpos: [26]; default: 0;
@ -680,95 +681,37 @@ typedef union {
uint32_t val;
} lp_analog_peri_touch_approach_reg_t;
/** Type of touch_freq0_scan_para register
/** Type of touch_freq_scan_para register
* need_des
*/
typedef union {
struct {
/** touch_freq0_dcap_lpf : R/W; bitpos: [6:0]; default: 0;
* need_des
/** touch_freq_dcap_lpf : R/W; bitpos: [6:0]; default: 0;
* Capacity of the RC low pass filter
* 0 ~ 2.54 pF, step 20fF
*/
uint32_t touch_freq0_dcap_lpf:7;
/** touch_freq0_dres_lpf : R/W; bitpos: [8:7]; default: 0;
* need_des
uint32_t touch_freq_dcap_lpf:7;
/** touch_freq_dres_lpf : R/W; bitpos: [8:7]; default: 0;
* Resistance of the RC low pass filter
* 0 ~ 4.5 K, step 1.5 K
*/
uint32_t touch_freq0_dres_lpf:2;
/** touch_freq0_drv_ls : R/W; bitpos: [12:9]; default: 0;
* need_des
uint32_t touch_freq_dres_lpf:2;
/** touch_freq_drv_ls : R/W; bitpos: [12:9]; default: 0;
* Low speed touch driver, effective when high speed driver is disabled
*/
uint32_t touch_freq0_drv_ls:4;
/** touch_freq0_drv_hs : R/W; bitpos: [17:13]; default: 0;
* need_des
uint32_t touch_freq_drv_ls:4;
/** touch_freq_drv_hs : R/W; bitpos: [17:13]; default: 0;
* High speed touch driver
*/
uint32_t touch_freq0_drv_hs:5;
/** touch_freq0_dbias : R/W; bitpos: [22:18]; default: 0;
* need_des
uint32_t touch_freq_drv_hs:5;
/** touch_freq_dbias : R/W; bitpos: [22:18]; default: 0;
* Internal LDO voltage
*/
uint32_t touch_freq0_dbias:5;
uint32_t touch_freq_dbias:5;
uint32_t reserved_23:9;
};
uint32_t val;
} lp_analog_peri_touch_freq0_scan_para_reg_t;
/** Type of touch_freq1_scan_para register
* need_des
*/
typedef union {
struct {
/** touch_freq1_dcap_lpf : R/W; bitpos: [6:0]; default: 0;
* need_des
*/
uint32_t touch_freq1_dcap_lpf:7;
/** touch_freq1_dres_lpf : R/W; bitpos: [8:7]; default: 0;
* need_des
*/
uint32_t touch_freq1_dres_lpf:2;
/** touch_freq1_drv_ls : R/W; bitpos: [12:9]; default: 0;
* need_des
*/
uint32_t touch_freq1_drv_ls:4;
/** touch_freq1_drv_hs : R/W; bitpos: [17:13]; default: 0;
* need_des
*/
uint32_t touch_freq1_drv_hs:5;
/** touch_freq1_dbias : R/W; bitpos: [22:18]; default: 0;
* need_des
*/
uint32_t touch_freq1_dbias:5;
uint32_t reserved_23:9;
};
uint32_t val;
} lp_analog_peri_touch_freq1_scan_para_reg_t;
/** Type of touch_freq2_scan_para register
* need_des
*/
typedef union {
struct {
/** touch_freq2_dcap_lpf : R/W; bitpos: [6:0]; default: 0;
* need_des
*/
uint32_t touch_freq2_dcap_lpf:7;
/** touch_freq2_dres_lpf : R/W; bitpos: [8:7]; default: 0;
* need_des
*/
uint32_t touch_freq2_dres_lpf:2;
/** touch_freq2_drv_ls : R/W; bitpos: [12:9]; default: 0;
* need_des
*/
uint32_t touch_freq2_drv_ls:4;
/** touch_freq2_drv_hs : R/W; bitpos: [17:13]; default: 0;
* need_des
*/
uint32_t touch_freq2_drv_hs:5;
/** touch_freq2_dbias : R/W; bitpos: [22:18]; default: 0;
* need_des
*/
uint32_t touch_freq2_dbias:5;
uint32_t reserved_23:9;
};
uint32_t val;
} lp_analog_peri_touch_freq2_scan_para_reg_t;
} lp_analog_peri_touch_freq_scan_para_reg_t;
/** Type of touch_ana_para register
* need_des
@ -776,15 +719,17 @@ typedef union {
typedef union {
struct {
/** touch_touch_buf_drv : R/W; bitpos: [2:0]; default: 0;
* need_des
* The driver of water proof touch buff
*/
uint32_t touch_touch_buf_drv:3;
/** touch_touch_en_cal : R/W; bitpos: [3]; default: 0;
* need_des
* Enable internal loop. Need to turn off touch pad.
* Tuning 'dcap_cal' to change the frequency
*/
uint32_t touch_touch_en_cal:1;
/** touch_touch_dcap_cal : R/W; bitpos: [10:4]; default: 0;
* need_des
* The internal capacitor connected to the touch pad. Effective when 'en_cal' enabled
* Normally set to 0
*/
uint32_t touch_touch_dcap_cal:7;
uint32_t reserved_11:21;
@ -799,35 +744,45 @@ typedef union {
struct {
uint32_t reserved_0:8;
/** touch_data_sel : R/W; bitpos: [9:8]; default: 0;
* need_des
* The type of the output data for debugging
* 0/1: raw data
* 2: baseline
* 3: smooth data
*/
uint32_t touch_data_sel:2;
/** touch_freq_sel : R/W; bitpos: [11:10]; default: 0;
* need_des
* The frequency id of the output data for debugging
* 0: invalid
* 1: Frequency 1
* 2: Frequency 2
* 3: Frequency 3
*/
uint32_t touch_freq_sel:2;
/** touch_bufsel : R/W; bitpos: [26:12]; default: 0;
* need_des
* The bitmap of the shield pad
*/
uint32_t touch_bufsel:15;
/** touch_done_en : R/W; bitpos: [27]; default: 0;
* need_des
* Force to terminate the touch by software
*/
uint32_t touch_done_en:1;
/** touch_done_force : R/W; bitpos: [28]; default: 0;
* need_des
* 0: Select touch_meas_done as the touch timer input
* 1: Select software termination as the touch timer input
*/
uint32_t touch_done_force:1;
/** touch_fsm_en : R/W; bitpos: [29]; default: 1;
* need_des
* 0: Select software configured parameters for ana
* 1: Select hardware calculated parameters for ana
*/
uint32_t touch_fsm_en:1;
/** touch_start_en : R/W; bitpos: [30]; default: 0;
* need_des
* Force to start the touch by software
*/
uint32_t touch_start_en:1;
/** touch_start_force : R/W; bitpos: [31]; default: 0;
* need_des
* 0: Select the touch timer to start the touch scanning
* 1: Select the software to start the touch scanning
*/
uint32_t touch_start_force:1;
};
@ -840,11 +795,11 @@ typedef union {
typedef union {
struct {
/** touch_start : R/W; bitpos: [14:0]; default: 0;
* need_des
* The bitmap of the start touch channels
*/
uint32_t touch_start:15;
/** touch_xpd : R/W; bitpos: [29:15]; default: 0;
* need_des
* The bitmap of the power on touch channels
*/
uint32_t touch_xpd:15;
uint32_t reserved_30:2;
@ -858,629 +813,13 @@ typedef union {
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad0_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
/** touch_pad_th : R/W; bitpos: [31:16]; default: 0;
* The threshold to activate a touch channel
*/
uint32_t touch_pad0_th0:16;
uint32_t threshold:16;
};
uint32_t val;
} lp_analog_peri_touch_pad0_th0_reg_t;
/** Type of touch_pad0_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad0_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad0_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad0_th1_reg_t;
/** Type of touch_pad0_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad0_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad0_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad0_th2_reg_t;
/** Type of touch_pad1_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad1_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad1_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad1_th0_reg_t;
/** Type of touch_pad1_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad1_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad1_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad1_th1_reg_t;
/** Type of touch_pad1_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad1_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad1_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad1_th2_reg_t;
/** Type of touch_pad2_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad2_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad2_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad2_th0_reg_t;
/** Type of touch_pad2_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad2_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad2_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad2_th1_reg_t;
/** Type of touch_pad2_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad2_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad2_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad2_th2_reg_t;
/** Type of touch_pad3_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad3_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad3_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad3_th0_reg_t;
/** Type of touch_pad3_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad3_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad3_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad3_th1_reg_t;
/** Type of touch_pad3_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad3_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad3_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad3_th2_reg_t;
/** Type of touch_pad4_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad4_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad4_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad4_th0_reg_t;
/** Type of touch_pad4_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad4_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad4_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad4_th1_reg_t;
/** Type of touch_pad4_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad4_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad4_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad4_th2_reg_t;
/** Type of touch_pad5_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad5_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad5_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad5_th0_reg_t;
/** Type of touch_pad5_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad5_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad5_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad5_th1_reg_t;
/** Type of touch_pad5_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad5_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad5_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad5_th2_reg_t;
/** Type of touch_pad6_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad6_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad6_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad6_th0_reg_t;
/** Type of touch_pad6_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad6_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad6_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad6_th1_reg_t;
/** Type of touch_pad6_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad6_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad6_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad6_th2_reg_t;
/** Type of touch_pad7_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad7_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad7_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad7_th0_reg_t;
/** Type of touch_pad7_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad7_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad7_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad7_th1_reg_t;
/** Type of touch_pad7_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad7_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad7_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad7_th2_reg_t;
/** Type of touch_pad8_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad8_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad8_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad8_th0_reg_t;
/** Type of touch_pad8_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad8_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad8_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad8_th1_reg_t;
/** Type of touch_pad8_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad8_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad8_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad8_th2_reg_t;
/** Type of touch_pad9_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad9_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad9_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad9_th0_reg_t;
/** Type of touch_pad9_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad9_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad9_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad9_th1_reg_t;
/** Type of touch_pad9_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad9_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad9_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad9_th2_reg_t;
/** Type of touch_pad10_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad10_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad10_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad10_th0_reg_t;
/** Type of touch_pad10_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad10_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad10_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad10_th1_reg_t;
/** Type of touch_pad10_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad10_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad10_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad10_th2_reg_t;
/** Type of touch_pad11_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad11_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad11_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad11_th0_reg_t;
/** Type of touch_pad11_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad11_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad11_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad11_th1_reg_t;
/** Type of touch_pad11_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad11_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad11_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad11_th2_reg_t;
/** Type of touch_pad12_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad12_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad12_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad12_th0_reg_t;
/** Type of touch_pad12_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad12_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad12_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad12_th1_reg_t;
/** Type of touch_pad12_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad12_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad12_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad12_th2_reg_t;
/** Type of touch_pad13_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad13_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad13_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad13_th0_reg_t;
/** Type of touch_pad13_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad13_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad13_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad13_th1_reg_t;
/** Type of touch_pad13_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad13_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad13_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad13_th2_reg_t;
/** Type of touch_pad14_th0 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad14_th0 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad14_th0:16;
};
uint32_t val;
} lp_analog_peri_touch_pad14_th0_reg_t;
/** Type of touch_pad14_th1 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad14_th1 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad14_th1:16;
};
uint32_t val;
} lp_analog_peri_touch_pad14_th1_reg_t;
/** Type of touch_pad14_th2 register
* need_des
*/
typedef union {
struct {
uint32_t reserved_0:16;
/** touch_pad14_th2 : R/W; bitpos: [31:16]; default: 0;
* Reserved
*/
uint32_t touch_pad14_th2:16;
};
uint32_t val;
} lp_analog_peri_touch_pad14_th2_reg_t;
} lp_analog_peri_touch_pad_thn_reg_t;
/** Type of date register
* need_des
@ -1500,6 +839,10 @@ typedef union {
} lp_analog_peri_date_reg_t;
typedef struct {
volatile lp_analog_peri_touch_pad_thn_reg_t thn[3];
} lp_analog_peri_touch_padx_thn_reg_t;
typedef struct {
volatile lp_analog_peri_bod_mode0_cntl_reg_t bod_mode0_cntl;
volatile lp_analog_peri_bod_mode1_cntl_reg_t bod_mode1_cntl;
@ -1530,61 +873,16 @@ typedef struct {
volatile lp_analog_peri_touch_slp1_reg_t touch_slp1;
volatile lp_analog_peri_touch_clr_reg_t touch_clr;
volatile lp_analog_peri_touch_approach_reg_t touch_approach;
volatile lp_analog_peri_touch_freq0_scan_para_reg_t touch_freq0_scan_para;
volatile lp_analog_peri_touch_freq1_scan_para_reg_t touch_freq1_scan_para;
volatile lp_analog_peri_touch_freq2_scan_para_reg_t touch_freq2_scan_para;
volatile lp_analog_peri_touch_freq_scan_para_reg_t touch_freq_scan_para[3];
volatile lp_analog_peri_touch_ana_para_reg_t touch_ana_para;
volatile lp_analog_peri_touch_mux0_reg_t touch_mux0;
volatile lp_analog_peri_touch_mux1_reg_t touch_mux1;
volatile lp_analog_peri_touch_pad0_th0_reg_t touch_pad0_th0;
volatile lp_analog_peri_touch_pad0_th1_reg_t touch_pad0_th1;
volatile lp_analog_peri_touch_pad0_th2_reg_t touch_pad0_th2;
volatile lp_analog_peri_touch_pad1_th0_reg_t touch_pad1_th0;
volatile lp_analog_peri_touch_pad1_th1_reg_t touch_pad1_th1;
volatile lp_analog_peri_touch_pad1_th2_reg_t touch_pad1_th2;
volatile lp_analog_peri_touch_pad2_th0_reg_t touch_pad2_th0;
volatile lp_analog_peri_touch_pad2_th1_reg_t touch_pad2_th1;
volatile lp_analog_peri_touch_pad2_th2_reg_t touch_pad2_th2;
volatile lp_analog_peri_touch_pad3_th0_reg_t touch_pad3_th0;
volatile lp_analog_peri_touch_pad3_th1_reg_t touch_pad3_th1;
volatile lp_analog_peri_touch_pad3_th2_reg_t touch_pad3_th2;
volatile lp_analog_peri_touch_pad4_th0_reg_t touch_pad4_th0;
volatile lp_analog_peri_touch_pad4_th1_reg_t touch_pad4_th1;
volatile lp_analog_peri_touch_pad4_th2_reg_t touch_pad4_th2;
volatile lp_analog_peri_touch_pad5_th0_reg_t touch_pad5_th0;
volatile lp_analog_peri_touch_pad5_th1_reg_t touch_pad5_th1;
volatile lp_analog_peri_touch_pad5_th2_reg_t touch_pad5_th2;
volatile lp_analog_peri_touch_pad6_th0_reg_t touch_pad6_th0;
volatile lp_analog_peri_touch_pad6_th1_reg_t touch_pad6_th1;
volatile lp_analog_peri_touch_pad6_th2_reg_t touch_pad6_th2;
volatile lp_analog_peri_touch_pad7_th0_reg_t touch_pad7_th0;
volatile lp_analog_peri_touch_pad7_th1_reg_t touch_pad7_th1;
volatile lp_analog_peri_touch_pad7_th2_reg_t touch_pad7_th2;
volatile lp_analog_peri_touch_pad8_th0_reg_t touch_pad8_th0;
volatile lp_analog_peri_touch_pad8_th1_reg_t touch_pad8_th1;
volatile lp_analog_peri_touch_pad8_th2_reg_t touch_pad8_th2;
volatile lp_analog_peri_touch_pad9_th0_reg_t touch_pad9_th0;
volatile lp_analog_peri_touch_pad9_th1_reg_t touch_pad9_th1;
volatile lp_analog_peri_touch_pad9_th2_reg_t touch_pad9_th2;
volatile lp_analog_peri_touch_pad10_th0_reg_t touch_pad10_th0;
volatile lp_analog_peri_touch_pad10_th1_reg_t touch_pad10_th1;
volatile lp_analog_peri_touch_pad10_th2_reg_t touch_pad10_th2;
volatile lp_analog_peri_touch_pad11_th0_reg_t touch_pad11_th0;
volatile lp_analog_peri_touch_pad11_th1_reg_t touch_pad11_th1;
volatile lp_analog_peri_touch_pad11_th2_reg_t touch_pad11_th2;
volatile lp_analog_peri_touch_pad12_th0_reg_t touch_pad12_th0;
volatile lp_analog_peri_touch_pad12_th1_reg_t touch_pad12_th1;
volatile lp_analog_peri_touch_pad12_th2_reg_t touch_pad12_th2;
volatile lp_analog_peri_touch_pad13_th0_reg_t touch_pad13_th0;
volatile lp_analog_peri_touch_pad13_th1_reg_t touch_pad13_th1;
volatile lp_analog_peri_touch_pad13_th2_reg_t touch_pad13_th2;
volatile lp_analog_peri_touch_pad14_th0_reg_t touch_pad14_th0;
volatile lp_analog_peri_touch_pad14_th1_reg_t touch_pad14_th1;
volatile lp_analog_peri_touch_pad14_th2_reg_t touch_pad14_th2;
volatile lp_analog_peri_touch_padx_thn_reg_t touch_padx_thn[15];
uint32_t reserved_1f8[129];
volatile lp_analog_peri_date_reg_t date;
} lp_analog_peri_dev_t;
extern lp_analog_peri_dev_t LP_ANA_PERI;
#ifndef __cplusplus
_Static_assert(sizeof(lp_analog_peri_dev_t) == 0x400, "Invalid size of lp_analog_peri_dev_t structure");

View File

@ -83,6 +83,7 @@
// #define SOC_ASSIST_DEBUG_SUPPORTED 1 //TODO: IDF-7565
#define SOC_WDT_SUPPORTED 1
#define SOC_SPI_FLASH_SUPPORTED 1
// #define SOC_TOUCH_SENSOR_SUPPORTED 1 //TODO: IDF-7477
/*-------------------------- XTAL CAPS ---------------------------------------*/
#define SOC_XTAL_SUPPORT_40M 1
@ -467,6 +468,13 @@
/*--------------------------- WATCHDOG CAPS ---------------------------------------*/
#define SOC_MWDT_SUPPORT_XTAL (1)
/*-------------------------- TOUCH SENSOR CAPS -------------------------------*/
#define SOC_TOUCH_SENSOR_VERSION (3) // Hardware version of touch sensor
#define SOC_TOUCH_SENSOR_NUM (14) // Touch available channel number. Actually there are 15 Touch channels, but channel 14 is not pinned out, limit to 14 channels
#define SOC_TOUCH_PROXIMITY_CHANNEL_NUM (3) // Sopport touch proximity channel number.
#define SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED (1) // Sopport touch proximity channel measure done interrupt type.
#define SOC_TOUCH_SAMPLER_NUM (3) // The sampler number in total, each sampler can be used to sample on one frequency
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 3
#define SOC_TWAI_CLK_SUPPORT_XTAL 1

View File

@ -0,0 +1,53 @@
/*
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
//Touch channels
/* Note: T14 is an internal channel that does not have a corresponding external GPIO. */
#define TOUCH_PAD_GPIO2_CHANNEL TOUCH_PAD_NUM0
#define TOUCH_PAD_NUM0_GPIO_NUM 2
#define TOUCH_PAD_GPIO3_CHANNEL TOUCH_PAD_NUM1
#define TOUCH_PAD_NUM1_GPIO_NUM 3
#define TOUCH_PAD_GPIO4_CHANNEL TOUCH_PAD_NUM2
#define TOUCH_PAD_NUM2_GPIO_NUM 4
#define TOUCH_PAD_GPIO5_CHANNEL TOUCH_PAD_NUM3
#define TOUCH_PAD_NUM3_GPIO_NUM 5
#define TOUCH_PAD_GPIO6_CHANNEL TOUCH_PAD_NUM4
#define TOUCH_PAD_NUM4_GPIO_NUM 6
#define TOUCH_PAD_GPIO7_CHANNEL TOUCH_PAD_NUM5
#define TOUCH_PAD_NUM5_GPIO_NUM 7
#define TOUCH_PAD_GPIO8_CHANNEL TOUCH_PAD_NUM6
#define TOUCH_PAD_NUM6_GPIO_NUM 8
#define TOUCH_PAD_GPIO9_CHANNEL TOUCH_PAD_NUM7
#define TOUCH_PAD_NUM7_GPIO_NUM 9
#define TOUCH_PAD_GPIO10_CHANNEL TOUCH_PAD_NUM8
#define TOUCH_PAD_NUM8_GPIO_NUM 10
#define TOUCH_PAD_GPIO11_CHANNEL TOUCH_PAD_NUM9
#define TOUCH_PAD_NUM9_GPIO_NUM 11
#define TOUCH_PAD_GPIO12_CHANNEL TOUCH_PAD_NUM10
#define TOUCH_PAD_NUM10_GPIO_NUM 12
#define TOUCH_PAD_GPIO13_CHANNEL TOUCH_PAD_NUM11
#define TOUCH_PAD_NUM11_GPIO_NUM 13
#define TOUCH_PAD_GPIO14_CHANNEL TOUCH_PAD_NUM12
#define TOUCH_PAD_NUM12_GPIO_NUM 14
#define TOUCH_PAD_GPIO15_CHANNEL TOUCH_PAD_NUM13
#define TOUCH_PAD_NUM13_GPIO_NUM 15

View File

@ -148,7 +148,7 @@ typedef union {
} rtc_touch_int_clr_reg_t;
/** Type of chn_status register
* need_des
* Latched channel status
*/
typedef union {
struct {
@ -169,337 +169,29 @@ typedef union {
uint32_t val;
} rtc_touch_chn_status_reg_t;
/** Type of status_0 register
/** Type of chn_data register
* need_des
*/
typedef union {
struct {
/** pad0_data : RO; bitpos: [15:0]; default: 0;
/** pad_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad0_data:16;
/** pad0_debounce_cnt : RO; bitpos: [18:16]; default: 0;
uint32_t pad_data:16;
/** pad_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad0_debounce_cnt:3;
/** pad0_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
uint32_t pad_debounce_cnt:3;
/** pad_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad0_neg_noise_cnt:4;
uint32_t pad_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_0_reg_t;
} rtc_touch_chn_data_reg_t;
/** Type of status_1 register
* need_des
*/
typedef union {
struct {
/** pad1_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad1_data:16;
/** pad1_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad1_debounce_cnt:3;
/** pad1_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad1_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_1_reg_t;
/** Type of status_2 register
* need_des
*/
typedef union {
struct {
/** pad2_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad2_data:16;
/** pad2_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad2_debounce_cnt:3;
/** pad2_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad2_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_2_reg_t;
/** Type of status_3 register
* need_des
*/
typedef union {
struct {
/** pad3_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad3_data:16;
/** pad3_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad3_debounce_cnt:3;
/** pad3_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad3_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_3_reg_t;
/** Type of status_4 register
* need_des
*/
typedef union {
struct {
/** pad4_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad4_data:16;
/** pad4_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad4_debounce_cnt:3;
/** pad4_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad4_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_4_reg_t;
/** Type of status_5 register
* need_des
*/
typedef union {
struct {
/** pad5_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad5_data:16;
/** pad5_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad5_debounce_cnt:3;
/** pad5_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad5_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_5_reg_t;
/** Type of status_6 register
* need_des
*/
typedef union {
struct {
/** pad6_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad6_data:16;
/** pad6_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad6_debounce_cnt:3;
/** pad6_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad6_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_6_reg_t;
/** Type of status_7 register
* need_des
*/
typedef union {
struct {
/** pad7_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad7_data:16;
/** pad7_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad7_debounce_cnt:3;
/** pad7_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad7_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_7_reg_t;
/** Type of status_8 register
* need_des
*/
typedef union {
struct {
/** pad8_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad8_data:16;
/** pad8_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad8_debounce_cnt:3;
/** pad8_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad8_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_8_reg_t;
/** Type of status_9 register
* need_des
*/
typedef union {
struct {
/** pad9_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad9_data:16;
/** pad9_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad9_debounce_cnt:3;
/** pad9_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad9_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_9_reg_t;
/** Type of status_10 register
* need_des
*/
typedef union {
struct {
/** pad10_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad10_data:16;
/** pad10_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad10_debounce_cnt:3;
/** pad10_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad10_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_10_reg_t;
/** Type of status_11 register
* need_des
*/
typedef union {
struct {
/** pad11_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad11_data:16;
/** pad11_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad11_debounce_cnt:3;
/** pad11_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad11_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_11_reg_t;
/** Type of status_12 register
* need_des
*/
typedef union {
struct {
/** pad12_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad12_data:16;
/** pad12_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad12_debounce_cnt:3;
/** pad12_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad12_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_12_reg_t;
/** Type of status_13 register
* need_des
*/
typedef union {
struct {
/** pad13_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad13_data:16;
/** pad13_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad13_debounce_cnt:3;
/** pad13_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad13_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_13_reg_t;
/** Type of status_14 register
* need_des
*/
typedef union {
struct {
/** pad14_data : RO; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t pad14_data:16;
/** pad14_debounce_cnt : RO; bitpos: [18:16]; default: 0;
* need_des
*/
uint32_t pad14_debounce_cnt:3;
/** pad14_neg_noise_cnt : RO; bitpos: [22:19]; default: 0;
* need_des
*/
uint32_t pad14_neg_noise_cnt:4;
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_14_reg_t;
/** Type of status_15 register
/** Type of slp_ch_data register
* need_des
*/
typedef union {
@ -519,9 +211,9 @@ typedef union {
uint32_t reserved_23:9;
};
uint32_t val;
} rtc_touch_status_15_reg_t;
} rtc_touch_slp_ch_data_reg_t;
/** Type of status_16 register
/** Type of aprch_ch_data register
* need_des
*/
typedef union {
@ -544,9 +236,9 @@ typedef union {
uint32_t slp_approach_cnt:8;
};
uint32_t val;
} rtc_touch_status_16_reg_t;
} rtc_touch_aprch_ch_data_reg_t;
/** Type of status_17 register
/** Type of config register
* need_des
*/
typedef union {
@ -578,10 +270,10 @@ typedef union {
uint32_t reserved_25:7;
};
uint32_t val;
} rtc_touch_status_17_reg_t;
} rtc_touch_sampler_status_reg_t;
/** Type of chn_tmp_status register
* need_des
* Realtime channel status
*/
typedef union {
struct {
@ -625,29 +317,16 @@ typedef struct {
volatile rtc_touch_int_ena_reg_t int_ena;
volatile rtc_touch_int_clr_reg_t int_clr;
volatile rtc_touch_chn_status_reg_t chn_status;
volatile rtc_touch_status_0_reg_t status_0;
volatile rtc_touch_status_1_reg_t status_1;
volatile rtc_touch_status_2_reg_t status_2;
volatile rtc_touch_status_3_reg_t status_3;
volatile rtc_touch_status_4_reg_t status_4;
volatile rtc_touch_status_5_reg_t status_5;
volatile rtc_touch_status_6_reg_t status_6;
volatile rtc_touch_status_7_reg_t status_7;
volatile rtc_touch_status_8_reg_t status_8;
volatile rtc_touch_status_9_reg_t status_9;
volatile rtc_touch_status_10_reg_t status_10;
volatile rtc_touch_status_11_reg_t status_11;
volatile rtc_touch_status_12_reg_t status_12;
volatile rtc_touch_status_13_reg_t status_13;
volatile rtc_touch_status_14_reg_t status_14;
volatile rtc_touch_status_15_reg_t status_15;
volatile rtc_touch_status_16_reg_t status_16;
volatile rtc_touch_status_17_reg_t status_17;
volatile rtc_touch_chn_data_reg_t chn_data[15];
volatile rtc_touch_slp_ch_data_reg_t slp_ch_data;
volatile rtc_touch_aprch_ch_data_reg_t aprch_ch_data;
volatile rtc_touch_sampler_status_reg_t sampler_status;
volatile rtc_touch_chn_tmp_status_reg_t chn_tmp_status;
uint32_t reserved_060[40];
volatile rtc_touch_date_reg_t date;
} rtc_touch_dev_t;
extern rtc_touch_dev_t LP_TOUCH;
#ifndef __cplusplus
_Static_assert(sizeof(rtc_touch_dev_t) == 0x104, "Invalid size of rtc_touch_dev_t structure");

View File

@ -76,6 +76,7 @@ PROVIDE ( LP_I2C = 0x50122000 );
PROVIDE ( LP_SPI = 0x50123000 );
PROVIDE ( LP_WDT = 0x50116000 );
PROVIDE ( LP_I2S = 0x50125000 );
PROVIDE ( LP_TOUCH = 0x50128000 );
PROVIDE ( LP_GPIO = 0x5012A000 );
PROVIDE ( LP_I2C_ANA_MST = 0x50124000 );
PROVIDE ( LP_ANA_PERI = 0x50113000 );

View File

@ -0,0 +1,27 @@
/*
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include "soc/touch_sensor_periph.h"
/* Store IO number corresponding to the Touch Sensor channel number. */
/* Note: T14 is an internal channel that does not have a corresponding external GPIO. */
const int touch_sensor_channel_io_map[] = {
TOUCH_PAD_NUM0_GPIO_NUM,
TOUCH_PAD_NUM1_GPIO_NUM,
TOUCH_PAD_NUM2_GPIO_NUM,
TOUCH_PAD_NUM3_GPIO_NUM,
TOUCH_PAD_NUM4_GPIO_NUM,
TOUCH_PAD_NUM5_GPIO_NUM,
TOUCH_PAD_NUM6_GPIO_NUM,
TOUCH_PAD_NUM7_GPIO_NUM,
TOUCH_PAD_NUM8_GPIO_NUM,
TOUCH_PAD_NUM9_GPIO_NUM,
TOUCH_PAD_NUM10_GPIO_NUM,
TOUCH_PAD_NUM11_GPIO_NUM,
TOUCH_PAD_NUM12_GPIO_NUM,
TOUCH_PAD_NUM13_GPIO_NUM,
-1,
};

View File

@ -747,9 +747,9 @@ config SOC_TIMER_GROUP_TOTAL_TIMERS
int
default 4
config SOC_TOUCH_VERSION_2
bool
default y
config SOC_TOUCH_SENSOR_VERSION
int
default 2
config SOC_TOUCH_SENSOR_NUM
int
@ -759,13 +759,9 @@ config SOC_TOUCH_PROXIMITY_CHANNEL_NUM
int
default 3
config SOC_TOUCH_PAD_THRESHOLD_MAX
hex
default 0x1FFFFF
config SOC_TOUCH_PAD_MEASURE_WAIT_MAX
hex
default 0xFF
config SOC_TOUCH_SAMPLER_NUM
int
default 1
config SOC_TWAI_CONTROLLER_NUM
int

View File

@ -323,12 +323,11 @@
#define SOC_TIMER_GROUP_TOTAL_TIMERS (4)
/*-------------------------- TOUCH SENSOR CAPS -------------------------------*/
#define SOC_TOUCH_VERSION_2 (1) /*!<Hardware version of touch sensor */
#define SOC_TOUCH_SENSOR_VERSION (2) /*!<Hardware version of touch sensor */
#define SOC_TOUCH_SENSOR_NUM (15) /*!<15 Touch channels */
#define SOC_TOUCH_PROXIMITY_CHANNEL_NUM (3) /*!<Support touch proximity channel number. */
#define SOC_TOUCH_PAD_THRESHOLD_MAX (0x1FFFFF) /*!<If set touch threshold max value, The touch sensor can't be in touched status */
#define SOC_TOUCH_PAD_MEASURE_WAIT_MAX (0xFF) /*!<The timer frequency is 8Mhz, the max value is 0xff */
#define SOC_TOUCH_SAMPLER_NUM (1U) /*!< The sampler number in total, each sampler can be used to sample on one frequency */
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL

View File

@ -895,9 +895,9 @@ config SOC_TIMER_GROUP_TOTAL_TIMERS
int
default 4
config SOC_TOUCH_VERSION_2
bool
default y
config SOC_TOUCH_SENSOR_VERSION
int
default 2
config SOC_TOUCH_SENSOR_NUM
int
@ -911,13 +911,9 @@ config SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED
bool
default y
config SOC_TOUCH_PAD_THRESHOLD_MAX
hex
default 0x1FFFFF
config SOC_TOUCH_PAD_MEASURE_WAIT_MAX
hex
default 0xFF
config SOC_TOUCH_SAMPLER_NUM
int
default 1
config SOC_TWAI_CONTROLLER_NUM
int

View File

@ -357,13 +357,12 @@
#define SOC_TIMER_GROUP_TOTAL_TIMERS (4)
/*-------------------------- TOUCH SENSOR CAPS -------------------------------*/
#define SOC_TOUCH_VERSION_2 (1) // Hardware version of touch sensor
#define SOC_TOUCH_SENSOR_VERSION (2) // Hardware version of touch sensor
#define SOC_TOUCH_SENSOR_NUM (15) /*! 15 Touch channels */
#define SOC_TOUCH_PROXIMITY_CHANNEL_NUM (3) /* Sopport touch proximity channel number. */
#define SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED (1) /*Sopport touch proximity channel measure done interrupt type. */
#define SOC_TOUCH_PAD_THRESHOLD_MAX (0x1FFFFF) /*!<If set touch threshold max value, The touch sensor can't be in touched status */
#define SOC_TOUCH_PAD_MEASURE_WAIT_MAX (0xFF) /*!<The timer frequency is 8Mhz, the max value is 0xff */
#define SOC_TOUCH_SAMPLER_NUM (1U) /*!< The sampler number in total, each sampler can be used to sample on one frequency */
/*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL

View File

@ -16,7 +16,7 @@ For design, operation, and control registers of a touch sensor, see **{IDF_TARGE
In-depth design details of touch sensors and firmware development guidelines for {IDF_TARGET_NAME} are available in `Touch Sensor Application Note <https://github.com/espressif/esp-iot-solution/blob/release/v1.0/documents/touch_pad_solution/touch_sensor_design_en.md>`_.
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
For more information about testing touch sensors in various configurations, please check the `Guide for ESP32-Sense-Kit <https://docs.espressif.com/projects/espressif-esp-dev-kits/en/latest/esp32/esp32-sense-kit/user_guide.html>`_.
@ -118,14 +118,14 @@ Configuration
* - T13
- GPIO13
* - T14
- GPIO14
- GPIO14
Use the function :cpp:func:`touch_pad_set_fsm_mode` to select if touch pad measurement (operated by FSM) should be started automatically by a hardware timer, or by software. If software mode is selected, use :cpp:func:`touch_pad_sw_start` to start the FSM.
Touch State Measurements
^^^^^^^^^^^^^^^^^^^^^^^^
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
The following two functions come in handy to read raw or filtered measurements from the sensor:
@ -138,7 +138,7 @@ Touch State Measurements
Before using :cpp:func:`touch_pad_read_filtered`, you need to initialize and configure the filter by calling specific filter functions described in Section `Filtering of Measurements`_.
.. only:: SOC_TOUCH_VERSION_2
.. only:: esp32s2 or esp32s3
The following function come in handy to read raw measurements from the sensor:
@ -151,7 +151,7 @@ For the demonstration of how to read the touch pad data, check the application e
Method of Measurements
^^^^^^^^^^^^^^^^^^^^^^
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
The touch sensor counts the number of charge/discharge cycles over a fixed period of time (specified by :cpp:func:`touch_pad_set_measurement_clock_cycles`). The count result is the raw data that read from :cpp:func:`touch_pad_read_raw_data`. After finishing one measurement, the touch sensor sleeps until the next measurement start, this interval between two measurements can be set by :cpp:func:`touch_pad_set_measurement_interval`.
@ -159,7 +159,7 @@ Method of Measurements
If the specified clock cycles for measurement is too samll, the result may be inaccurate, but increasing clock cycles will increase the power consumption as well. Additionally, the response of the touch sensor will slow down if the total time of the inverval and measurement is too long.
.. only:: SOC_TOUCH_VERSION_2
.. only:: esp32s2 or esp32s3
The touch sensor records the period of time (i.e., the number of clock cycles) over a fixed charge/discharge cycles (specified by :cpp:func:`touch_pad_set_charge_discharge_times`). The count result is the raw data that read from :cpp:func:`touch_pad_read_raw_data`. After finishing one measurement, the touch sensor sleeps until the next measurement start, this interval between two measurements can be set by :cpp:func:`touch_pad_set_measurement_interval`.
@ -172,11 +172,11 @@ Optimization of Measurements
A touch sensor has several configurable parameters to match the characteristics of a particular touch pad design. For instance, to sense smaller capacity changes, it is possible to narrow down the reference voltage range within which the touch pads are charged/discharged. The high and low reference voltages are set using the function :cpp:func:`touch_pad_set_voltage`.
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
Besides the ability to discern smaller capacity changes, a positive side effect is reduction of power consumption for low power applications. A likely negative effect is an increase in measurement noise. If the dynamic range of obtained readings is still satisfactory, then further reduction of power consumption might be done by reducing the measurement time with :cpp:func:`touch_pad_set_measurement_clock_cycles`.
.. only:: SOC_TOUCH_VERSION_2
.. only:: esp32s2 or esp32s3
Besides the ability to discern smaller capacity changes, a positive side effect is reduction of power consumption for low power applications. A likely negative effect is an increase in measurement noise. If the dynamic range of obtained readings is still satisfactory, then further reduction of power consumption might be done by reducing the measurement time with :cpp:func:`touch_pad_set_charge_discharge_times`.
@ -187,17 +187,17 @@ The following list summarizes available measurement parameters and corresponding
* voltage range: :cpp:func:`touch_pad_set_voltage`
* speed (slope): :cpp:func:`touch_pad_set_cnt_mode`
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
* Clock cycles of one measurement: :cpp:func:`touch_pad_set_measurement_clock_cycles`
.. only:: SOC_TOUCH_VERSION_2
.. only:: esp32s2 or esp32s3
* Charge and discharge times of one measurement: :cpp:func:`touch_pad_set_charge_discharge_times`
Relationship between the voltage range (high/low reference voltages), speed (slope), and measurement time is shown in the figure below.
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
.. figure:: ../../../_static/touch_pad-measurement-parameters.jpg
:align: center
@ -208,7 +208,7 @@ Relationship between the voltage range (high/low reference voltages), speed (slo
The last chart **Output** represents the touch sensor reading, i.e., the count of pulses collected within the measurement time.
.. only:: SOC_TOUCH_VERSION_2
.. only:: esp32s2 or esp32s3
.. figure:: ../../../_static/touch_pad-measurement-parameters-version2.png
:align: center
@ -225,7 +225,7 @@ All functions are provided in pairs to **set** a specific parameter and to **get
Filtering of Measurements
^^^^^^^^^^^^^^^^^^^^^^^^^
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
If measurements are noisy, you can filter them with provided API functions. Before using the filter, please start it by calling :cpp:func:`touch_pad_filter_start`.
@ -233,7 +233,7 @@ Filtering of Measurements
You can stop the filter with :cpp:func:`touch_pad_filter_stop`. If not required anymore, the filter can be deleted by invoking :cpp:func:`touch_pad_filter_delete`.
.. only:: SOC_TOUCH_VERSION_2
.. only:: esp32s2 or esp32s3
If measurements are noisy, you can filter them with provided API functions. The {IDF_TARGET_NAME}'s touch functionality provide two sets of APIs for doing this.
@ -259,7 +259,7 @@ Before enabling an interrupt on a touch detection, you should establish a touch
Once a detection threshold is established, it can be set during initialization with :cpp:func:`touch_pad_config` or at the runtime with :cpp:func:`touch_pad_set_thresh`.
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
In the next step, configure how interrupts are triggered. They can be triggered below or above the threshold, which is set with the function :cpp:func:`touch_pad_set_trigger_mode`.
@ -270,13 +270,13 @@ Finally, configure and manage interrupt calls using the following functions:
When interrupts are operational, you can obtain the information from which particular pad an interrupt came by invoking :cpp:func:`touch_pad_get_status` and clear the pad status with :cpp:func:`touch_pad_clear_status`.
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
.. note::
Interrupts on touch detection operate on raw/unfiltered measurements checked against user established threshold and are implemented in hardware. Enabling the software filtering API (see :ref:`touch_pad-api-filtering-of-measurements`) does not affect this process.
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
Wakeup from Sleep Mode
^^^^^^^^^^^^^^^^^^^^^^

View File

@ -16,7 +16,7 @@
请参考 `触摸传感器应用方案简介 <https://github.com/espressif/esp-iot-solution/blob/release/v1.0/documents/touch_pad_solution/touch_sensor_design_en.md>`_,查看触摸传感器设计详情和固件开发指南。
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
如果想评估触摸传感器的多种应用场景,请查看 `ESP32 触摸功能开发套件 <https://docs.espressif.com/projects/espressif-esp-dev-kits/en/latest/esp32/esp32-sense-kit/user_guide.html>`_
@ -125,7 +125,7 @@
触摸状态测量
^^^^^^^^^^^^^^^^^^^^^^^^
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
借助以下两个函数从传感器读取原始数据和滤波后的数据:
@ -138,7 +138,7 @@
使用 :cpp:func:`touch_pad_read_filtered` 之前,需要先调用 `滤波采样`_ 中特定的滤波器函数来初始化并配置该滤波器。
.. only:: SOC_TOUCH_VERSION_2
.. only:: esp32s2 or esp32s3
借助以下函数从传感器读取原始数据:
@ -151,7 +151,7 @@
测量方式
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
触摸传感器会统计固定时间内的充放电次数,其计数结果即为原始数据,可由 :cpp:func:`touch_pad_read_raw_data` 读出。上述固定时间可通过 :cpp:func:`touch_pad_set_measurement_clock_cycles` 设置。完成一次测量后,触摸传感器会在下次测量开始前保持睡眠状态。两次测量之前的间隔时间可由 :cpp:func:`touch_pad_set_measurement_interval` 进行设置。
@ -159,7 +159,7 @@
若设置的计数时间太短(即测量持续的时钟周期数太小),则可能导致结果不准确,但是过大的计数时间也会造成功耗上升。另外,若睡眠时间加测量时间的总时间过长,则会造成触摸传感器响应变慢。
.. only:: SOC_TOUCH_VERSION_2
.. only:: esp32s2 or esp32s3
触摸传感器会统计固定充放电次数所需的时间(即所需时钟周期数),其结果即为原始数据,可由 :cpp:func:`touch_pad_read_raw_data` 读出。上述固定的充放电次数可通过 :cpp:func:`touch_pad_set_charge_discharge_times` 设置。完成一次测量后,触摸传感器会在下次测量开始前保持睡眠状态。两次测量之前的间隔时间可由 :cpp:func:`touch_pad_set_measurement_interval` 进行设置。
@ -172,11 +172,11 @@
触摸传感器设有数个可配置参数,以适应触摸传感器设计特点。例如,如果需要感知较细微的电容变化,则可以缩小触摸传感器充放电的参考电压范围。使用 :cpp:func:`touch_pad_set_voltage` 函数,可以设置电压参考低值和参考高值。
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
优化测量除了可以识别细微的电容变化之外,还可以降低应用程序功耗,但可能会增加测量噪声干扰。如果得到的动态读数范围结果比较理想,则可以调用 :cpp:func:`touch_pad_set_measurement_clock_cycles` 函数来减少测量时间,从而进一步降低功耗。
.. only:: SOC_TOUCH_VERSION_2
.. only:: esp32s2 or esp32s3
优化测量除了可以识别细微的电容变化之外,还可以降低应用程序功耗,但可能会增加测量噪声干扰。如果得到的动态读数范围结果比较理想,则可以调用 :cpp:func:`touch_pad_set_charge_discharge_times` 函数来减少测量时间,从而进一步降低功耗。
@ -187,17 +187,17 @@
* 电压门限::cpp:func:`touch_pad_set_voltage`
* 速率(斜率)::cpp:func:`touch_pad_set_cnt_mode`
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
* 单次测量所用的时钟周期::cpp:func:`touch_pad_set_measurement_clock_cycles`
.. only:: SOC_TOUCH_VERSION_2
.. only:: esp32s2 or esp32s3
* 单次测量所需充放电次数::cpp:func:`touch_pad_set_charge_discharge_times`
电压门限(参考低值/参考高值)、速率(斜率)与测量时间的关系如下图所示:
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
.. figure:: ../../../_static/touch_pad-measurement-parameters.jpg
:align: center
@ -208,7 +208,7 @@
上图中的 **Output** 代表触摸传感器读值,即一个测量周期内测得的脉冲计数值。
.. only:: SOC_TOUCH_VERSION_2
.. only:: esp32s2 or esp32s3
.. figure:: ../../../_static/touch_pad-measurement-parameters-version2.png
:align: center
@ -225,7 +225,7 @@
滤波采样
^^^^^^^^^^^^^^^^^^^^^^^^^
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
如果测量中存在噪声,可以使用提供的 API 函数对采样进行滤波。使用滤波器之前,请先调用 :cpp:func:`touch_pad_filter_start` 启动该滤波器。
@ -233,7 +233,7 @@
如需停止滤波器,请调用 :cpp:func:`touch_pad_filter_stop` 函数。如果不再使用该滤波器,请调用 :cpp:func:`touch_pad_filter_delete` 删除此滤波器。
.. only:: SOC_TOUCH_VERSION_2
.. only:: esp32s2 or esp32s3
如果测量中存在噪声,可以使用提供的 API 函数对采样进行滤波。{IDF_TARGET_NAME} 的触摸功能提供了两套 API 可实现此功能。
@ -259,7 +259,7 @@
确定监测阈值后就可以在初始化时调用 :cpp:func:`touch_pad_config` 设置此阈值,或在运行时调用 :cpp:func:`touch_pad_set_thresh` 设置此阈值。
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
下一步就是设置如何触发中断。可以设置在阈值以下或以上触发中断,具体触发模式由函数 :cpp:func:`touch_pad_set_trigger_mode` 设置。
@ -270,13 +270,13 @@
中断配置完成后,可以调用 :cpp:func:`touch_pad_get_status` 查看中断信号来自哪个触摸传感器,也可以调用 :cpp:func:`touch_pad_clear_status` 清除触摸传感器状态信息。
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
.. note::
触摸监测中的中断信号基于原始/未经滤波的采样(对比设置的阈值),并在硬件中实现。启用软件滤波 API请参考 :ref:`touch_pad-api-filtering-of-measurements`)并不会影响这一过程。
.. only:: SOC_TOUCH_VERSION_1
.. only:: esp32
从睡眠模式唤醒
^^^^^^^^^^^^^^^^^^^^^^

View File

@ -324,11 +324,11 @@ examples/peripherals/touch_sensor/touch_element:
examples/peripherals/touch_sensor/touch_sensor_v1:
disable:
- if: SOC_TOUCH_VERSION_1 != 1
- if: SOC_TOUCH_SENSOR_VERSION != 1
examples/peripherals/touch_sensor/touch_sensor_v2:
disable:
- if: SOC_TOUCH_VERSION_2 != 1
- if: SOC_TOUCH_SENSOR_VERSION != 2
examples/peripherals/twai/twai_alert_and_recovery:
disable:

View File

@ -196,7 +196,7 @@ void app_main(void)
/* Filter setting */
touchsensor_filter_set(TOUCH_PAD_FILTER_IIR_16);
touch_pad_timeout_set(true, SOC_TOUCH_PAD_THRESHOLD_MAX);
touch_pad_timeout_set(true, TOUCH_PAD_THRESHOLD_MAX);
/* Register touch interrupt ISR, enable intr type. */
touch_pad_isr_register(touchsensor_interrupt_cb, NULL, TOUCH_PAD_INTR_MASK_ALL);
/* If you have other touch algorithm, you can get the measured value after the `TOUCH_PAD_INTR_MASK_SCAN_DONE` interrupt is generated. */