Merge branch 'feature/touch_driver_ng_on_p4_v5.3' into 'release/v5.3'

feat(touch_sensor): touch driver ng on p4 (v5.3)

See merge request espressif/esp-idf!31624
This commit is contained in:
Jiang Jiang Jian
2024-07-26 11:42:27 +08:00
81 changed files with 4288 additions and 402 deletions

View File

@@ -0,0 +1,79 @@
/*
* SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use in application code.
* See readme.md in hal/include/hal/readme.md
******************************************************************************/
// The HAL layer for touch sensor (ESP32-P4 specific part)
#pragma once
#include "hal/touch_sensor_ll.h"
#include "hal/touch_sensor_types.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Sample configurations of the touch sensor
*
*/
typedef struct {
uint32_t div_num; /*!< The division from the source clock to the sampling frequency */
uint32_t charge_times; /*!< The charge and discharge times of the sample configuration, the read data are positive correlation to the charge_times */
uint8_t rc_filter_res; /*!< The resistance of the RC filter of the sample configuration, range [0, 3], while 0 = 0K, 1 = 1.5K, 2 = 3K, 3 = 4.5K */
uint8_t rc_filter_cap; /*!< The capacitance of the RC filter of the sample configuration, range [0, 127], while 0 = 0pF, 1 = 20fF, ..., 127 = 2.54pF */
uint8_t low_drv; /*!< Low speed touch driver, only effective when high speed driver is disabled */
uint8_t high_drv; /*!< High speed touch driver */
uint8_t bias_volt; /*!< The Internal LDO voltage, which decide the bias voltage of the sample wave, range [0,15] */
bool bypass_shield_output; /*!< Whether to bypass the shield output */
} touch_hal_sample_config_t;
/**
* @brief Configurations of the touch sensor controller
*
*/
typedef struct {
uint32_t power_on_wait_ticks; /*!< The waiting time between the channels power on and able to measure, to ensure the data stability */
uint32_t meas_interval_ticks; /*!< Measurement interval of each channels */ // TODO: Test the supported range
uint32_t timeout_ticks; /*!< The maximum time of measuring one channel, if the time exceeds this value, the timeout interrupt will be triggered.
* Set to '0' to ignore the measurement time limitation, otherwise please set a proper time considering the configurations
* of the sample configurations below.
*/
touch_out_mode_t output_mode; /*!< Touch channel counting mode of the binarized touch output */
uint32_t sample_cfg_num; /*!< The sample configuration number that used for sampling */
touch_hal_sample_config_t *sample_cfg; /*!< The array of the sample configuration configurations, the length should be specified in `touch_hal_sample_config_t::sample_cfg_num` */
} touch_hal_config_t;
/**
* @brief Configure the touch sensor hardware with the configuration
*
* @param[in] cfg Touch sensor hardware configuration
*/
void touch_hal_config_controller(const touch_hal_config_t *cfg);
/**
* @brief Save the touch sensor hardware configuration
* @note The saved configurations will be applied before entering deep sleep
*
* @param[in] deep_slp_chan The touch sensor channel that can wake-up the chip from deep sleep
* @param[in] deep_slp_cfg The hardware configuration that takes effect during the deep sleep
*/
void touch_hal_save_sleep_config(int deep_slp_chan, const touch_hal_config_t *deep_slp_cfg);
/**
* @brief Prepare for the deep sleep
* @note Including apply the deep sleep configuration, clear interrupts, resetting benchmark
*/
void touch_hal_prepare_deep_sleep(void);
#ifdef __cplusplus
}
#endif

View File

@@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@@ -18,6 +18,9 @@
#include "hal/assert.h"
#include "soc/touch_sensor_periph.h"
#include "soc/lp_analog_peri_struct.h"
#include "soc/lp_clkrst_struct.h"
#include "soc/lp_system_struct.h"
#include "soc/lpperi_struct.h"
#include "soc/touch_struct.h"
#include "soc/pmu_struct.h"
#include "soc/soc_caps.h"
@@ -27,7 +30,6 @@
extern "C" {
#endif
#define TOUCH_LL_READ_RAW 0x0
#define TOUCH_LL_READ_BENCHMARK 0x2
#define TOUCH_LL_READ_SMOOTH 0x3
@@ -35,27 +37,41 @@ extern "C" {
#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_SCAN_DONE BIT(0)
#define TOUCH_LL_INTR_MASK_DONE BIT(1)
#define TOUCH_LL_INTR_MASK_ACTIVE BIT(2)
#define TOUCH_LL_INTR_MASK_INACTIVE BIT(3)
#define TOUCH_LL_INTR_MASK_TIMEOUT BIT(4)
#define TOUCH_LL_INTR_MASK_PROX_DONE BIT(5)
#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_NULL_CHANNEL (15) // Null Channel id. Used for disabling some functions like sleep/proximity/waterproof
#define TOUCH_LL_PAD_MEASURE_WAIT_MAX (0x7FFF) // The timer frequency is 8Mhz, the max value is 0xff
#define TOUCH_LL_ACTIVE_THRESH_MAX (0xFFFF) // Max channel active threshold
#define TOUCH_LL_CLK_DIV_MAX (0x08) // Max clock divider value
#define TOUCH_LL_TIMEOUT_MAX (0xFFFF) // Max timeout value
/**
* Enable/disable clock gate of touch sensor.
*
* @param enable true/false.
*/
static inline void touch_ll_enable_clock(bool enable)
static inline void touch_ll_enable_module_clock(bool enable)
{
LP_ANA_PERI.date.clk_en = enable;
LPPERI.clk_en.ck_en_lp_touch = enable;
}
/**
* Enable/disable clock gate of touch sensor.
*
* @param enable true/false.
*/
static inline void touch_ll_reset_module(void)
{
LPPERI.reset_en.rst_en_lp_touch = 1;
LPPERI.reset_en.rst_en_lp_touch = 0;
}
/**
@@ -71,14 +87,14 @@ static inline void touch_ll_set_power_on_wait_cycle(uint32_t wait_cycles)
/**
* Set touch sensor touch sensor charge and discharge times of every measurement on a pad.
*
* @param sampler_id The sampler index
* @param sample_cfg_id The sample configuration 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.
* The timer frequency is RTC_FAST (about 16M). Range: 0 ~ 0xffff.
*/
static inline void touch_ll_set_charge_times(uint8_t sampler_id, uint16_t charge_times)
static inline void touch_ll_set_charge_times(uint8_t sample_cfg_id, uint16_t charge_times)
{
//The times of charge and discharge in each measure process of touch channels.
switch (sampler_id) {
switch (sample_cfg_id) {
case 0:
LP_ANA_PERI.touch_work_meas_num.touch_meas_num0 = charge_times;
break;
@@ -98,9 +114,9 @@ static inline void touch_ll_set_charge_times(uint8_t sampler_id, uint16_t charge
*
* @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)
static inline void touch_ll_get_charge_times(uint8_t sample_cfg_id, uint16_t *charge_times)
{
switch (sampler_id) {
switch (sample_cfg_id) {
case 0:
*charge_times = LP_ANA_PERI.touch_work_meas_num.touch_meas_num0;
break;
@@ -140,21 +156,21 @@ static inline void touch_ll_get_measure_interval_ticks(uint16_t *interval_ticks)
}
/**
* Set touch sensor FSM mode.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
* Enable touch sensor FSM timer trigger (continuous) mode or software trigger (oneshot) mode.
*
* @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
* @param enable Enable FSM timer mode.
* True: the FSM will trigger scanning repeatedly under the control of the hardware timer (continuous mode)
* False: the FSM will trigger scanning once under the control of the software (continuous mode)
*/
static inline void touch_ll_set_fsm_mode(touch_fsm_mode_t mode)
__attribute__((always_inline))
static inline void touch_ll_enable_fsm_timer(bool enable)
{
// 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;
LP_ANA_PERI.touch_mux0.touch_fsm_en = enable;
// Set 0 to stop by timer, otherwise by software
LP_ANA_PERI.touch_mux0.touch_done_force = !enable;
// Set 0 to start by timer, otherwise by software
LP_ANA_PERI.touch_mux0.touch_start_force = !enable;
}
/**
@@ -182,18 +198,23 @@ static inline bool touch_ll_is_fsm_using_timer(void)
/**
* 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.
* @note The `force done` signal should last as least one slow clock tick
*/
__attribute__((always_inline))
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;
}
// Enable event tick first
LP_AON_CLKRST.lp_clk_en.etm_event_tick_en = 1;
// Set `force done` signal
PMU.touch_pwr_cntl.force_done = 1;
// Force done signal should last at least one slow clock tick, wait until tick interrupt triggers
LP_SYS.int_clr.slow_clk_tick_int_clr = 1;
while(LP_SYS.int_clr.slow_clk_tick_int_clr);
while(!LP_SYS.int_raw.slow_clk_tick_int_raw);
// Clear `force done` signal
PMU.touch_pwr_cntl.force_done = 0;
// Disable event tick
LP_AON_CLKRST.lp_clk_en.etm_event_tick_en = 0;
}
/**
@@ -203,6 +224,7 @@ static inline void touch_ll_force_done_curr_measurement(void)
* The timer should be triggered
* @param is_sleep Whether in sleep state
*/
__attribute__((always_inline))
static inline void touch_ll_start_fsm_repeated_timer(bool is_sleep)
{
/**
@@ -210,11 +232,7 @@ static inline void touch_ll_start_fsm_repeated_timer(bool is_sleep)
* 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.sleep_timer_en = 1;
} else {
LP_ANA_PERI.touch_mux0.touch_start_en = 1;
}
PMU.touch_pwr_cntl.sleep_timer_en = 1;
}
/**
@@ -222,21 +240,31 @@ static inline void touch_ll_start_fsm_repeated_timer(bool is_sleep)
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
* @param is_sleep Whether in sleep state
*/
__attribute__((always_inline))
static inline void touch_ll_stop_fsm_repeated_timer(bool is_sleep)
{
if (is_sleep) {
PMU.touch_pwr_cntl.sleep_timer_en = 0;
} else {
LP_ANA_PERI.touch_mux0.touch_start_en = 0;
}
PMU.touch_pwr_cntl.sleep_timer_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
* Is the FSM repeated timer enabled.
* @note when the timer is enabled, RTC clock should not be power down
*
* @return
* - true: enabled
* - true: disabled
*/
static inline void touch_ll_start_fsm_once(void)
static inline bool touch_ll_is_fsm_repeated_timer_enabled(void)
{
return (bool)(PMU.touch_pwr_cntl.sleep_timer_en);
}
/**
* Enable the touch sensor FSM start signal from software
*/
__attribute__((always_inline))
static inline void touch_ll_trigger_oneshot_measurement(void)
{
/* Trigger once measurement */
LP_ANA_PERI.touch_mux0.touch_start_en = 1;
@@ -245,7 +273,8 @@ static inline void touch_ll_start_fsm_once(void)
static inline void touch_ll_measure_channel_once(uint16_t chan_mask)
{
LP_ANA_PERI.touch_mux1.touch_start = chan_mask;
// Channel shift workaround
LP_ANA_PERI.touch_mux1.touch_start = chan_mask << 1;
}
/**
@@ -255,13 +284,34 @@ static inline void touch_ll_measure_channel_once(uint16_t chan_mask)
*
* @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 sample_cfg_id The sample configuration 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)
static inline void touch_ll_set_chan_active_threshold(uint32_t touch_num, uint8_t sample_cfg_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);
HAL_ASSERT(sample_cfg_id < SOC_TOUCH_SAMPLE_CFG_NUM);
// Channel shift workaround
HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_padx_thn[touch_num + 1].thresh[sample_cfg_id], threshold, thresh); // codespell:ignore
}
/**
* @brief Enable or disable the channel that will be scanned.
* @note The shield channel should not be enabled to scan here
*
* @param chan_mask The channel mask to be enabled or disabled
* @param enable Enable or disable the channel mask
*/
__attribute__((always_inline))
static inline void touch_ll_enable_scan_mask(uint16_t chan_mask, bool enable)
{
// Channel shift workaround: the lowest bit takes no effect
uint16_t mask = (chan_mask << 1) & TOUCH_PAD_BIT_MASK_ALL;
uint16_t prev_mask = LP_ANA_PERI.touch_scan_ctrl1.touch_scan_pad_map;
if (enable) {
LP_ANA_PERI.touch_scan_ctrl1.touch_scan_pad_map = prev_mask | mask;
} else {
LP_ANA_PERI.touch_scan_ctrl1.touch_scan_pad_map = prev_mask & (~mask);
}
}
/**
@@ -278,7 +328,8 @@ static inline void touch_ll_set_chan_active_threshold(uint32_t touch_num, uint8_
*/
static inline void touch_ll_set_channel_mask(uint16_t enable_mask)
{
uint16_t mask = enable_mask & TOUCH_PAD_BIT_MASK_ALL;
// Channel shift workaround: the lowest bit takes no effect
uint16_t mask = (enable_mask << 1) & TOUCH_PAD_BIT_MASK_ALL;
LP_ANA_PERI.touch_scan_ctrl1.touch_scan_pad_map = mask;
LP_ANA_PERI.touch_filter2.touch_outen = mask;
}
@@ -288,10 +339,12 @@ static inline void touch_ll_set_channel_mask(uint16_t enable_mask)
*
* @param chan_mask The channel mask that needs to power on
*/
static inline void touch_ll_channel_power_on(uint16_t chan_mask)
__attribute__((always_inline))
static inline void touch_ll_channel_sw_measure_mask(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;
// Channel shift workaround
LP_ANA_PERI.touch_mux1.touch_xpd = chan_mask << 1;
LP_ANA_PERI.touch_mux1.touch_start = chan_mask << 1;
}
/**
@@ -302,20 +355,8 @@ static inline void touch_ll_channel_power_on(uint16_t chan_mask)
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;
// Channel shift workaround
LP_ANA_PERI.touch_mux1.touch_xpd = (~(chan_mask << 1)) & curr_mask;
}
/**
@@ -323,9 +364,11 @@ static inline void touch_ll_channel_start(uint16_t chan_mask)
*
* @param active_mask The touch channel status. e.g. Touch1 trigger status is `status_mask & (BIT1)`.
*/
__attribute__((always_inline))
static inline void touch_ll_get_active_channel_mask(uint32_t *active_mask)
{
*active_mask = LP_TOUCH.chn_status.pad_active;
// Channel shift workaround
*active_mask = (LP_TOUCH.chn_status.pad_active >> 1);
}
/**
@@ -342,22 +385,23 @@ static inline void touch_ll_clear_active_channel_status(void)
* Get the data of the touch channel according to the types
*
* @param touch_num touch pad index
* @param sampler_id The sampler index
* @param sample_cfg_id The sample configuration index
* @param type data type
* 0/1: TOUCH_LL_READ_RAW, the raw data of the touch channel
* 0/1: not work
* 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)
static inline void touch_ll_read_chan_data(uint32_t touch_num, uint8_t sample_cfg_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;
HAL_ASSERT(sample_cfg_id < SOC_TOUCH_SAMPLE_CFG_NUM);
HAL_ASSERT(type == TOUCH_LL_READ_BENCHMARK || type == TOUCH_LL_READ_SMOOTH);
LP_ANA_PERI.touch_mux0.touch_freq_sel = sample_cfg_id;
LP_ANA_PERI.touch_mux0.touch_data_sel = type;
*data = LP_TOUCH.chn_data[touch_num - 1].pad_data;
// Channel shift workaround
*data = LP_TOUCH.chn_data[touch_num + 1].pad_data;
}
/**
@@ -366,12 +410,17 @@ static inline void touch_ll_read_chan_data(uint32_t touch_num, uint8_t sampler_i
* @return
* - If touch sensors measure done.
*/
static inline bool touch_ll_is_measure_done(uint32_t *touch_num)
__attribute__((always_inline))
static inline bool touch_ll_is_measure_done(void)
{
*touch_num = (uint32_t)(LP_TOUCH.chn_status.scan_curr);
return (bool)LP_TOUCH.chn_status.meas_done;
}
static inline uint32_t touch_ll_get_current_measure_channel(void)
{
// Channel shift workaround
return (uint32_t)(LP_TOUCH.chn_status.scan_curr - 1);
}
/**
* Select the counting mode of the binarized touch out wave
*
@@ -384,26 +433,36 @@ static inline void touch_ll_set_out_mode(touch_out_mode_t mode)
LP_ANA_PERI.touch_work.touch_out_sel = mode;
}
/**
* @brief Enable/disable the touch sensor output gate
*
* @param enable set true to enable the output gate, false to disable it
*/
static inline void touch_ll_enable_out_gate(bool enable)
{
LP_ANA_PERI.touch_work.touch_out_gate = enable;
}
/**
* @brief Set the clock division of the sampling frequency
*
* @param sampler_id The sampler index
* @param sample_cfg_id The sample configuration index
* @param div_num Division number
*/
static inline void touch_ll_set_clock_div(uint8_t sampler_id, uint32_t div_num)
static inline void touch_ll_set_clock_div(uint8_t sample_cfg_id, uint32_t div_num)
{
switch (sampler_id) {
switch (sample_cfg_id) {
case 0:
LP_ANA_PERI.touch_work.div_num0 = div_num;
LP_ANA_PERI.touch_work.div_num0 = div_num - 1;
break;
case 1:
LP_ANA_PERI.touch_work.div_num1 = div_num;
LP_ANA_PERI.touch_work.div_num1 = div_num - 1;
break;
case 2:
LP_ANA_PERI.touch_work.div_num2 = div_num;
LP_ANA_PERI.touch_work.div_num2 = div_num - 1;
break;
default:
// invalid sampler_id
// invalid sample_cfg_id
abort();
}
}
@@ -434,7 +493,8 @@ static inline void touch_ll_set_idle_channel_connect(touch_pad_conn_type_t type)
__attribute__((always_inline))
static inline uint32_t touch_ll_get_current_meas_channel(void)
{
return (uint32_t)(LP_TOUCH.chn_status.scan_curr);
// Channel shift workaround
return (uint32_t)(LP_TOUCH.chn_status.scan_curr - 1);
}
/**
@@ -466,9 +526,10 @@ static inline void touch_ll_intr_disable(uint32_t int_mask)
*
* @param int_mask Pad mask to clear interrupts
*/
static inline void touch_ll_intr_clear_all(void)
__attribute__((always_inline))
static inline void touch_ll_intr_clear(touch_pad_intr_mask_t int_mask)
{
LP_TOUCH.int_clr.val = TOUCH_LL_INTR_MASK_ALL;
LP_TOUCH.int_clr.val = int_mask;
}
/**
@@ -476,6 +537,7 @@ static inline void touch_ll_intr_clear_all(void)
*
* @return type interrupt type
*/
__attribute__((always_inline))
static inline uint32_t touch_ll_get_intr_status_mask(void)
{
uint32_t intr_st = LP_TOUCH.int_st.val;
@@ -508,56 +570,68 @@ static inline void touch_ll_timeout_disable(void)
}
/**
* Set the engaged sampler number
* Set the engaged sample configuration number
*
* @param sampler_num The enabled sampler number, range 0~3.
* 0/1 means only one sampler enabled, which can not support frequency hopping
* @param sample_cfg_num The enabled sample configuration number, range 0~3.
* 0/1 means only one sample configuration enabled, which can not support frequency hopping
*/
static inline void touch_ll_sampler_set_engaged_num(uint8_t sampler_num)
static inline void touch_ll_sample_cfg_set_engaged_num(uint8_t sample_cfg_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;
HAL_ASSERT(sample_cfg_num <= SOC_TOUCH_SAMPLE_CFG_NUM);
LP_ANA_PERI.touch_scan_ctrl2.freq_scan_en = !!sample_cfg_num;
LP_ANA_PERI.touch_scan_ctrl2.freq_scan_cnt_limit = sample_cfg_num ? sample_cfg_num : 1;
}
/**
* Set capacitance and resistance of the RC filter of the sampling frequency.
*
* @param sampler_id The sampler index
* @param sample_cfg_id The sample configuration 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)
static inline void touch_ll_sample_cfg_set_rc_filter(uint8_t sample_cfg_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;
HAL_ASSERT(sample_cfg_id < SOC_TOUCH_SAMPLE_CFG_NUM);
LP_ANA_PERI.touch_freq_scan_para[sample_cfg_id].touch_freq_dcap_lpf = cap;
LP_ANA_PERI.touch_freq_scan_para[sample_cfg_id].touch_freq_dres_lpf = res;
}
/**
* @brief Set the driver of the sampling frequency
*
* @param sampler_id The sampler index
* @param sample_cfg_id The sample configuration 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)
static inline void touch_ll_sample_cfg_set_driver(uint8_t sample_cfg_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;
HAL_ASSERT(sample_cfg_id < SOC_TOUCH_SAMPLE_CFG_NUM);
LP_ANA_PERI.touch_freq_scan_para[sample_cfg_id].touch_freq_drv_ls = ls_drv;
LP_ANA_PERI.touch_freq_scan_para[sample_cfg_id].touch_freq_drv_hs = hs_drv;
}
/**
* Bypass the shield channel output for the specify sample configuration
*
* @param sample_cfg_id The sample configuration index
* @param enable Set true to bypass the shield channel output for the current channel
*/
static inline void touch_ll_sample_cfg_bypass_shield_output(uint8_t sample_cfg_id, bool enable)
{
HAL_ASSERT(sample_cfg_id < SOC_TOUCH_SAMPLE_CFG_NUM);
LP_ANA_PERI.touch_freq_scan_para[sample_cfg_id].touch_bypass_shield = enable;
}
/**
* Set the touch internal LDO bias voltage of the sampling frequency
*
* @param sampler_id The sampler index
* @param sample_cfg_id The sample configuration index
* @param bias_volt LDO bias voltage
*/
static inline void touch_ll_sampler_set_bias_voltage(uint8_t sampler_id, uint32_t bias_volt)
static inline void touch_ll_sample_cfg_set_bias_voltage(uint8_t sample_cfg_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;
HAL_ASSERT(sample_cfg_id < SOC_TOUCH_SAMPLE_CFG_NUM);
LP_ANA_PERI.touch_freq_scan_para[sample_cfg_id].touch_freq_dbias = bias_volt;
}
/**
@@ -581,6 +655,7 @@ static inline void touch_ll_set_internal_loop_capacitance(int cap)
* @note If call this API, make sure enable clock gate(`touch_ll_clkgate`) first.
* @param chan_mask touch channel mask
*/
__attribute__((always_inline))
static inline void touch_ll_reset_chan_benchmark(uint32_t chan_mask)
{
LP_ANA_PERI.touch_clr.touch_channel_clr = chan_mask;
@@ -620,39 +695,23 @@ static inline void touch_ll_filter_set_debounce(uint32_t 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)
* Set the denoise coefficient regarding the denoise level.
*
*
* @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
* @param denoise_lvl Range [0 ~ 4]. 0 = no noise resistance, otherwise higher denoise_lvl means more noise resistance.
*/
static inline void touch_ll_filter_set_pos_noise_thresh(int pos_noise_thresh)
static inline void touch_ll_filter_set_denoise_level(int denoise_lvl)
{
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;
}
HAL_ASSERT(denoise_lvl >= 0 && denoise_lvl <= 4);
bool always_update = denoise_lvl == 0;
// Map denoise level to actual noise threshold coefficients
uint32_t noise_thresh = denoise_lvl == 4 ? 3 : 3 - denoise_lvl;
/**
* 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
LP_ANA_PERI.touch_filter2.touch_bypass_noise_thres = always_update;
LP_ANA_PERI.touch_filter1.touch_noise_thres = always_update ? 0 : noise_thresh;
LP_ANA_PERI.touch_filter2.touch_bypass_nn_thres = always_update;
LP_ANA_PERI.touch_filter1.touch_nn_thres = always_update ? 0 : noise_thresh;
LP_ANA_PERI.touch_filter1.touch_nn_limit = 5; // 5 is the default value
}
/**
@@ -696,10 +755,10 @@ static inline void touch_ll_filter_enable(bool enable)
*/
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;
HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_filter3, touch_benchmark_sw, benchmark);
LP_ANA_PERI.touch_filter3.touch_update_benchmark_sw = 1;
// waiting for update
while (LP_ANA_PERI.touch_filter3.touch_update_baseline_sw);
while (LP_ANA_PERI.touch_filter3.touch_update_benchmark_sw);
}
/************************ Waterproof register setting ************************/
@@ -711,7 +770,8 @@ static inline void touch_ll_force_update_benchmark(uint32_t benchmark)
*/
static inline void touch_ll_waterproof_set_guard_chan(uint32_t pad_num)
{
LP_ANA_PERI.touch_scan_ctrl2.touch_out_ring = pad_num;
// Channel shift workaround
LP_ANA_PERI.touch_scan_ctrl2.touch_out_ring = pad_num == TOUCH_LL_NULL_CHANNEL ? TOUCH_LL_NULL_CHANNEL : pad_num + 1;
}
/**
@@ -734,7 +794,8 @@ static inline void touch_ll_waterproof_enable(bool enable)
*/
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);
// Channel shift workaround
LP_ANA_PERI.touch_mux0.touch_bufsel = mask << 1;
}
/**
@@ -750,63 +811,76 @@ static inline void touch_ll_waterproof_set_shield_driver(touch_pad_shield_driver
/************************ 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`
* Set the proximity sensing channel to the specific touch channel
* To disable the proximity 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
* @param prox_chan proximity sensing channel.
* @param touch_num The touch channel that supposed to be used as proximity sensing channel
*/
static inline void touch_ll_set_approach_channel(uint8_t aprch_chan, uint32_t touch_num)
static inline void touch_ll_set_proximity_sensing_channel(uint8_t prox_chan, uint32_t touch_num)
{
switch (aprch_chan) {
switch (prox_chan) {
case 0:
LP_ANA_PERI.touch_approach.touch_approach_pad0 = touch_num;
// Channel shift workaround
LP_ANA_PERI.touch_approach.touch_approach_pad0 = touch_num + 1;
break;
case 1:
LP_ANA_PERI.touch_approach.touch_approach_pad1 = touch_num;
// Channel shift workaround
LP_ANA_PERI.touch_approach.touch_approach_pad1 = touch_num + 1;
break;
case 2:
LP_ANA_PERI.touch_approach.touch_approach_pad2 = touch_num;
// Channel shift workaround
LP_ANA_PERI.touch_approach.touch_approach_pad2 = touch_num + 1;
break;
default:
// invalid approach channel
// invalid proximity channel
abort();
}
}
/**
* Set cumulative measurement times for approach channel.
* Set the total scan times of the proximity sensing channel.
*
* @param sampler_id The sampler index
* @param times The cumulative number of measurement cycles.
* @param scan_times The total scan times of the proximity sensing channel
*/
static inline void touch_ll_approach_set_measure_times(uint8_t sampler_id, uint32_t times)
static inline void touch_ll_proximity_set_total_scan_times(uint32_t scan_times)
{
switch (sampler_id) {
LP_ANA_PERI.touch_filter1.touch_approach_limit = scan_times;
}
/**
* Set charge times for each sample configuration in proximity sensing mode.
*
* @param sample_cfg_id The sample configuration index
* @param charge_times The charge and discharge times.
*/
static inline void touch_ll_proximity_set_charge_times(uint8_t sample_cfg_id, uint32_t charge_times)
{
switch (sample_cfg_id) {
case 0:
LP_ANA_PERI.touch_approach_work_meas_num.touch_approach_meas_num0 = times;
LP_ANA_PERI.touch_approach_work_meas_num.touch_approach_meas_num0 = charge_times;
break;
case 1:
LP_ANA_PERI.touch_approach_work_meas_num.touch_approach_meas_num1 = times;
LP_ANA_PERI.touch_approach_work_meas_num.touch_approach_meas_num1 = charge_times;
break;
case 2:
LP_ANA_PERI.touch_approach_work_meas_num.touch_approach_meas_num2 = times;
LP_ANA_PERI.touch_approach_work_meas_num.touch_approach_meas_num2 = charge_times;
break;
default:
// invalid sampler_id
// invalid sample_cfg_id
abort();
}
}
/**
* Read current cumulative measurement times for approach channel.
* Read current cumulative measurement times for proximity sensing channel.
*
* @param aprch_chan approach channel.
* @param prox_chan proximity sensing 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)
static inline void touch_ll_proximity_read_measure_cnt(uint8_t prox_chan, uint32_t *cnt)
{
switch (aprch_chan) {
switch (prox_chan) {
case 0:
*cnt = HAL_FORCE_READ_U32_REG_FIELD(LP_TOUCH.aprch_ch_data, approach_pad0_cnt);
break;
@@ -823,19 +897,18 @@ static inline void touch_ll_approach_read_measure_cnt(uint8_t aprch_chan, uint32
}
/**
* Check if the touch sensor channel is the approach channel.
* Check if the touch sensor channel is the proximity sensing channel.
*
* @param touch_num The touch sensor channel number.
*/
static inline bool touch_ll_is_approach_channel(uint32_t touch_num)
static inline bool touch_ll_is_proximity_sensing_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;
}
return true;
}
/************** sleep channel setting ***********************/
@@ -848,7 +921,8 @@ static inline bool touch_ll_is_approach_channel(uint32_t touch_num)
*/
static inline void touch_ll_sleep_set_channel_num(uint32_t touch_num)
{
LP_ANA_PERI.touch_slp0.touch_slp_pad = touch_num;
// Channel shift workaround
LP_ANA_PERI.touch_slp0.touch_slp_pad = touch_num + 1;
}
/**
@@ -869,9 +943,9 @@ static inline void touch_ll_sleep_get_channel_num(uint32_t *touch_num)
*
* @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)
static inline void touch_ll_sleep_set_threshold(uint8_t sample_cfg_id, uint32_t touch_thresh)
{
switch (sampler_id) {
switch (sample_cfg_id) {
case 0:
HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_slp0, touch_slp_th0, touch_thresh);
break;
@@ -882,15 +956,15 @@ static inline void touch_ll_sleep_set_threshold(uint8_t sampler_id, uint32_t tou
HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_slp1, touch_slp_th2, touch_thresh);
break;
default:
// invalid sampler_id
// invalid sample_cfg_id
abort();
}
}
/**
* Enable approach function for sleep channel.
* Enable proximity sensing function for sleep channel.
*/
static inline void touch_ll_sleep_enable_approach(bool enable)
static inline void touch_ll_sleep_enable_proximity_sensing(bool enable)
{
LP_ANA_PERI.touch_approach.touch_slp_approach_en = enable;
}
@@ -898,7 +972,7 @@ static inline void touch_ll_sleep_enable_approach(bool enable)
/**
* Get the data of the touch channel according to the types
*
* @param sampler_id The sampler index
* @param sample_cfg_id The sample configuration 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,
@@ -907,10 +981,10 @@ static inline void touch_ll_sleep_enable_approach(bool enable)
* @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)
static inline void touch_ll_sleep_read_chan_data(uint8_t type, uint8_t sample_cfg_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_freq_sel = sample_cfg_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);
}
@@ -935,12 +1009,33 @@ static inline void touch_ll_sleep_read_debounce(uint32_t *debounce)
}
/**
* Read approach count of touch sensor for sleep channel.
* @param approach_cnt Pointer to accept touch sensor approach count value.
* Read proximity count of touch sensor for sleep channel.
* @param prox_cnt Pointer to accept touch sensor proximity count value.
*/
static inline void touch_ll_sleep_read_approach_cnt(uint32_t *approach_cnt)
static inline void touch_ll_sleep_read_proximity_cnt(uint32_t *prox_cnt)
{
*approach_cnt = HAL_FORCE_READ_U32_REG_FIELD(LP_TOUCH.aprch_ch_data, slp_approach_cnt);
*prox_cnt = HAL_FORCE_READ_U32_REG_FIELD(LP_TOUCH.aprch_ch_data, slp_approach_cnt);
}
/**
* @brief Enable or disable the internal capacitor, mainly for debug
*
* @param enable enable or disable the internal capacitor
*/
static inline void touch_ll_enable_internal_capacitor(bool enable)
{
LP_ANA_PERI.touch_ana_para.touch_touch_en_cal = enable;
}
/**
* @brief Set the internal capacitor, mainly for debug
* @note Only take effect when the internal capacitor is enabled
*
* @param cap the capacitor value
*/
static inline void touch_ll_set_internal_capacitor(uint32_t cap)
{
LP_ANA_PERI.touch_ana_para.touch_touch_dcap_cal = cap;
}
#ifdef __cplusplus

View File

@@ -0,0 +1,82 @@
/*
* SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <string.h>
#include "soc/soc_pins.h"
#include "hal/touch_sensor_ll.h"
#include "hal/touch_sensor_hal.h"
#include "hal/touch_sensor_types.h"
#include "soc/soc_caps.h"
typedef struct {
int deep_slp_chan;
touch_hal_config_t slp_cfg;
bool apply_slp_cfg;
} touch_hal_deep_sleep_obj_t;
static touch_hal_deep_sleep_obj_t s_touch_slp_obj = {
.deep_slp_chan = -1,
.apply_slp_cfg = false,
};
void touch_hal_config_controller(const touch_hal_config_t *cfg)
{
HAL_ASSERT(cfg);
touch_ll_sleep_set_channel_num(TOUCH_LL_NULL_CHANNEL);
touch_ll_set_out_mode(cfg->output_mode);
touch_ll_set_power_on_wait_cycle(cfg->power_on_wait_ticks);
touch_ll_set_measure_interval_ticks(cfg->meas_interval_ticks);
if (cfg->timeout_ticks) {
touch_ll_timeout_enable(cfg->timeout_ticks);
} else {
touch_ll_timeout_disable();
}
touch_ll_sample_cfg_set_engaged_num(cfg->sample_cfg_num);
for (int i = 0; i < cfg->sample_cfg_num; i++) {
touch_ll_set_clock_div(i, cfg->sample_cfg[i].div_num);
touch_ll_set_charge_times(i, cfg->sample_cfg[i].charge_times);
touch_ll_sample_cfg_set_rc_filter(i, cfg->sample_cfg[i].rc_filter_cap, cfg->sample_cfg[i].rc_filter_res);
touch_ll_sample_cfg_set_driver(i, cfg->sample_cfg[i].low_drv, cfg->sample_cfg[i].high_drv);
touch_ll_sample_cfg_bypass_shield_output(i, cfg->sample_cfg[i].bypass_shield_output);
touch_ll_sample_cfg_set_bias_voltage(i, cfg->sample_cfg[i].bias_volt);
}
}
void touch_hal_save_sleep_config(int deep_slp_chan, const touch_hal_config_t *deep_slp_cfg)
{
s_touch_slp_obj.deep_slp_chan = deep_slp_chan;
/* If particular deep sleep configuration is given, save it and apply it before entering the deep sleep */
if (deep_slp_chan >= 0 && deep_slp_cfg) {
s_touch_slp_obj.apply_slp_cfg = true;
memcpy(&s_touch_slp_obj.slp_cfg, deep_slp_cfg, sizeof(touch_hal_config_t));
} else {
s_touch_slp_obj.apply_slp_cfg = false;
}
}
//This function will only be called when the chip is going to deep sleep.
static void s_touch_hal_apply_sleep_config(void)
{
/* Apply the particular configuration for deep sleep */
if (s_touch_slp_obj.apply_slp_cfg) {
touch_hal_config_controller(&s_touch_slp_obj.slp_cfg);
}
/* Whether to enable touch sensor wake-up the chip from deep sleep */
if (s_touch_slp_obj.deep_slp_chan >= 0) {
touch_ll_sleep_set_channel_num(s_touch_slp_obj.deep_slp_chan);
touch_ll_set_channel_mask(BIT(s_touch_slp_obj.deep_slp_chan));
} else {
touch_ll_sleep_set_channel_num(TOUCH_LL_NULL_CHANNEL);
}
}
void touch_hal_prepare_deep_sleep(void)
{
s_touch_hal_apply_sleep_config();
touch_ll_sleep_reset_benchmark();
touch_ll_intr_clear(TOUCH_LL_INTR_MASK_ALL);
}