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
commit 86bcea64b9
81 changed files with 4288 additions and 402 deletions

View File

@ -73,10 +73,12 @@ endif()
# Touch Sensor related source files # Touch Sensor related source files
if(CONFIG_SOC_TOUCH_SENSOR_SUPPORTED) if(CONFIG_SOC_TOUCH_SENSOR_SUPPORTED)
if(CONFIG_SOC_TOUCH_SENSOR_VERSION LESS 3)
list(APPEND srcs "touch_sensor/touch_sensor_common.c" list(APPEND srcs "touch_sensor/touch_sensor_common.c"
"touch_sensor/${target}/touch_sensor.c") "touch_sensor/${target}/touch_sensor.c")
list(APPEND includes "touch_sensor/${target}/include") list(APPEND includes "touch_sensor/${target}/include")
endif() endif()
endif()
# TWAI related source files # TWAI related source files
if(CONFIG_SOC_TWAI_SUPPORTED) if(CONFIG_SOC_TWAI_SUPPORTED)

View File

@ -10,6 +10,7 @@
#include "esp_log.h" #include "esp_log.h"
#include "sys/lock.h" #include "sys/lock.h"
#include "soc/soc_pins.h" #include "soc/soc_pins.h"
#include "soc/rtc_cntl_reg.h"
#include "freertos/FreeRTOS.h" #include "freertos/FreeRTOS.h"
#include "freertos/semphr.h" #include "freertos/semphr.h"
#include "freertos/timers.h" #include "freertos/timers.h"

View File

@ -10,6 +10,7 @@
#include "esp_log.h" #include "esp_log.h"
#include "sys/lock.h" #include "sys/lock.h"
#include "soc/soc_pins.h" #include "soc/soc_pins.h"
#include "soc/rtc_cntl_reg.h"
#include "freertos/FreeRTOS.h" #include "freertos/FreeRTOS.h"
#include "freertos/semphr.h" #include "freertos/semphr.h"
#include "freertos/timers.h" #include "freertos/timers.h"

View File

@ -8,6 +8,6 @@
#include "soc/soc_caps.h" #include "soc/soc_caps.h"
#if SOC_TOUCH_SENSOR_SUPPORTED #if SOC_TOUCH_SENSOR_SUPPORTED && SOC_TOUCH_SENSOR_VERSION < 3
#include "driver/touch_sensor.h" #include "driver/touch_sensor.h"
#endif #endif

View File

@ -0,0 +1,21 @@
idf_build_get_property(target IDF_TARGET)
if(${target} STREQUAL "linux")
return() # This component is not supported by the POSIX/Linux simulator
endif()
set(srcs)
set(public_inc)
if(CONFIG_SOC_TOUCH_SENSOR_SUPPORTED)
if(CONFIG_SOC_TOUCH_SENSOR_VERSION EQUAL 3)
list(APPEND srcs "hw_ver3/touch_version_specific.c"
"common/touch_sens_common.c")
list(APPEND public_inc "include" "hw_ver3/include")
endif()
endif()
idf_component_register(SRCS ${srcs}
PRIV_REQUIRES esp_driver_gpio
INCLUDE_DIRS ${public_inc}
)

View File

@ -0,0 +1,25 @@
menu "ESP-Driver:Touch Sensor Configurations"
depends on SOC_TOUCH_SENSOR_SUPPORTED
config TOUCH_CTRL_FUNC_IN_IRAM
bool "Place touch sensor control functions into IRAM"
default n
help
Place touch sensor oneshot scanning and continuous scanning functions into IRAM,
so that these function can be IRAM-safe and able to be called when the flash cache is disabled.
Enabling this option can improve driver performance as well.
config TOUCH_ISR_IRAM_SAFE
bool "Touch sensor ISR IRAM-Safe"
default n
help
Ensure the touch sensor interrupt is IRAM-Safe by allowing the interrupt handler to be
executable when the cache is disabled (e.g. SPI Flash write).
config TOUCH_ENABLE_DEBUG_LOG
bool "Enable debug log"
default n
help
Whether to enable the debug log message for touch driver.
Note that, this option only controls the touch driver log, won't affect other drivers.
endmenu # Touch Sensor Configuration

View File

@ -0,0 +1,428 @@
/*
* SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <inttypes.h>
#include <string.h>
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "soc/soc_caps.h"
#include "soc/rtc.h"
#include "soc/clk_tree_defs.h"
#include "soc/touch_sensor_periph.h"
#include "driver/rtc_io.h"
#include "driver/touch_sens.h"
#if SOC_TOUCH_SENSOR_VERSION <= 2
#include "esp_private/rtc_ctrl.h"
#else
#include "soc/interrupts.h"
#include "esp_intr_alloc.h"
#endif
#if CONFIG_TOUCH_ENABLE_DEBUG_LOG
// The local log level must be defined before including esp_log.h
// Set the maximum log level for this source file
#define LOG_LOCAL_LEVEL ESP_LOG_DEBUG
#endif
#include "esp_check.h"
#include "touch_sens_private.h"
#define TOUCH_CHANNEL_CHECK(num) ESP_RETURN_ON_FALSE(num >= TOUCH_MIN_CHAN_ID && num <= TOUCH_MAX_CHAN_ID, \
ESP_ERR_INVALID_ARG, TAG, "The channel number is out of supported range");
static const char *TAG = "touch";
touch_sensor_handle_t g_touch = NULL;
static void touch_channel_pin_init(int id)
{
gpio_num_t pin = touch_sensor_channel_io_map[id];
rtc_gpio_init(pin);
rtc_gpio_set_direction(pin, RTC_GPIO_MODE_DISABLED);
rtc_gpio_pulldown_dis(pin);
rtc_gpio_pullup_dis(pin);
}
static void s_touch_free_resource(touch_sensor_handle_t sens_handle)
{
if (!sens_handle) {
return;
}
if (sens_handle->mutex) {
vSemaphoreDeleteWithCaps(sens_handle->mutex);
sens_handle->mutex = NULL;
}
free(g_touch);
g_touch = NULL;
}
esp_err_t touch_sensor_new_controller(const touch_sensor_config_t *sens_cfg, touch_sensor_handle_t *ret_sens_handle)
{
#if CONFIG_TOUCH_ENABLE_DEBUG_LOG
esp_log_level_set(TAG, ESP_LOG_DEBUG);
#endif
esp_err_t ret = ESP_OK;
TOUCH_NULL_POINTER_CHECK(sens_cfg);
TOUCH_NULL_POINTER_CHECK(ret_sens_handle);
ESP_RETURN_ON_FALSE(!g_touch, ESP_ERR_INVALID_STATE, TAG, "Touch sensor has been allocated");
g_touch = (touch_sensor_handle_t)heap_caps_calloc(1, sizeof(struct touch_sensor_s), TOUCH_MEM_ALLOC_CAPS);
ESP_RETURN_ON_FALSE(g_touch, ESP_ERR_NO_MEM, TAG, "No memory for touch sensor struct");
g_touch->mutex = xSemaphoreCreateMutexWithCaps(TOUCH_MEM_ALLOC_CAPS);
ESP_GOTO_ON_FALSE(g_touch->mutex, ESP_ERR_NO_MEM, err, TAG, "No memory for mutex semaphore");
touch_priv_enable_module(true);
ESP_GOTO_ON_ERROR(touch_priv_config_controller(g_touch, sens_cfg), err, TAG, "Failed to configure the touch controller");
#if SOC_TOUCH_SENSOR_VERSION <= 2
ESP_GOTO_ON_ERROR(rtc_isr_register(touch_priv_default_intr_handler, NULL, TOUCH_LL_INTR_MASK_ALL, 0), err, TAG, "Failed to register interrupt handler");
#else
ESP_GOTO_ON_ERROR(esp_intr_alloc(ETS_LP_TOUCH_INTR_SOURCE, TOUCH_INTR_ALLOC_FLAGS, touch_priv_default_intr_handler, NULL, &(g_touch->intr_handle)),
err, TAG, "Failed to register interrupt handler");
#endif
*ret_sens_handle = g_touch;
return ret;
err:
touch_priv_enable_module(false);
s_touch_free_resource(g_touch);
return ret;
}
esp_err_t touch_sensor_del_controller(touch_sensor_handle_t sens_handle)
{
TOUCH_NULL_POINTER_CHECK(sens_handle);
ESP_RETURN_ON_FALSE(g_touch == sens_handle, ESP_ERR_INVALID_ARG, TAG, "The input touch sensor handle is unmatched");
esp_err_t ret = ESP_OK;
// Take the semaphore to make sure the touch has stopped
xSemaphoreTake(sens_handle->mutex, portMAX_DELAY);
ESP_GOTO_ON_FALSE(!sens_handle->is_enabled, ESP_ERR_INVALID_STATE, err, TAG, "Touch sensor has not disabled");
FOR_EACH_TOUCH_CHANNEL(i) {
ESP_GOTO_ON_FALSE(!sens_handle->ch[i], ESP_ERR_INVALID_STATE, err, TAG, "There are still some touch channels not deleted");
}
ESP_GOTO_ON_ERROR(touch_priv_deinit_controller(sens_handle), err, TAG, "Failed to deinitialize the controller");
#if SOC_TOUCH_SENSOR_VERSION <= 2
ESP_GOTO_ON_ERROR(rtc_isr_deregister(touch_priv_default_intr_handler, NULL), err, TAG, "Failed to deregister the interrupt handler");
#else
ESP_GOTO_ON_ERROR(esp_intr_free(sens_handle->intr_handle), err, TAG, "Failed to deregister the interrupt handler");
#endif
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
touch_ll_intr_disable(TOUCH_LL_INTR_MASK_ALL);
touch_ll_clear_active_channel_status();
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
touch_priv_enable_module(false);
s_touch_free_resource(sens_handle);
err:
if (g_touch && g_touch->mutex) {
xSemaphoreGive(g_touch->mutex);
}
return ret;
}
esp_err_t touch_sensor_new_channel(touch_sensor_handle_t sens_handle, int chan_id,
const touch_channel_config_t *chan_cfg,
touch_channel_handle_t *ret_chan_handle)
{
TOUCH_NULL_POINTER_CHECK(sens_handle);
TOUCH_NULL_POINTER_CHECK(chan_cfg);
TOUCH_NULL_POINTER_CHECK(ret_chan_handle);
TOUCH_CHANNEL_CHECK(chan_id);
ESP_RETURN_ON_FALSE(g_touch == sens_handle, ESP_ERR_INVALID_ARG, TAG, "The input touch sensor handle is unmatched");
esp_err_t ret = ESP_OK;
xSemaphoreTake(sens_handle->mutex, portMAX_DELAY);
ESP_GOTO_ON_FALSE(!sens_handle->is_enabled, ESP_ERR_INVALID_STATE, err2, TAG, "Please disable the touch sensor first");
ESP_GOTO_ON_FALSE(!sens_handle->ch[chan_id], ESP_ERR_INVALID_STATE, err2, TAG, "The channel %d has been registered", chan_id);
sens_handle->ch[chan_id] = (touch_channel_handle_t)heap_caps_calloc(1, sizeof(struct touch_channel_s), TOUCH_MEM_ALLOC_CAPS);
ESP_GOTO_ON_FALSE(sens_handle->ch[chan_id], ESP_ERR_NO_MEM, err2, TAG, "No memory for touch channel");
sens_handle->ch[chan_id]->id = chan_id;
sens_handle->ch[chan_id]->base = sens_handle;
sens_handle->ch[chan_id]->is_prox_chan = false;
/* Init the channel */
ESP_GOTO_ON_ERROR(touch_priv_config_channel(sens_handle->ch[chan_id], chan_cfg),
err1, TAG, "Failed to configure the touch channel %d", chan_id);
touch_channel_pin_init(chan_id);
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
#if SOC_TOUCH_SENSOR_VERSION == 2
touch_ll_reset_chan_benchmark(1 << chan_id);
#endif
sens_handle->chan_mask |= 1 << chan_id;
touch_ll_set_channel_mask(sens_handle->chan_mask);
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
*ret_chan_handle = sens_handle->ch[chan_id];
xSemaphoreGive(sens_handle->mutex);
return ret;
err1:
free(sens_handle->ch[chan_id]);
sens_handle->ch[chan_id] = NULL;
err2:
xSemaphoreGive(sens_handle->mutex);
return ret;
}
esp_err_t touch_sensor_del_channel(touch_channel_handle_t chan_handle)
{
TOUCH_NULL_POINTER_CHECK(chan_handle);
esp_err_t ret = ESP_OK;
touch_sensor_handle_t sens_handle = chan_handle->base;
xSemaphoreTake(sens_handle->mutex, portMAX_DELAY);
ESP_GOTO_ON_FALSE(!sens_handle->is_enabled, ESP_ERR_INVALID_STATE, err, TAG, "Please disable the touch sensor first");
#if SOC_TOUCH_SENSOR_VERSION == 2
if (sens_handle->guard_chan == chan_handle || (BIT(chan_handle->id) & sens_handle->shield_chan_mask)) {
ESP_GOTO_ON_ERROR(touch_sensor_config_waterproof(sens_handle, NULL), err, TAG, "Failed to disable waterproof on this channel");
}
if (sens_handle->sleep_chan == chan_handle) {
ESP_GOTO_ON_ERROR(touch_sensor_config_sleep_channel(sens_handle, NULL), err, TAG, "Failed to disable sleep function on this channel");
}
#endif
int id = chan_handle->id;
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
sens_handle->chan_mask &= ~(1UL << id);
touch_ll_set_channel_mask(sens_handle->chan_mask);
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
free(g_touch->ch[id]);
g_touch->ch[id] = NULL;
err:
xSemaphoreGive(sens_handle->mutex);
return ret;
}
esp_err_t touch_sensor_reconfig_controller(touch_sensor_handle_t sens_handle, const touch_sensor_config_t *sens_cfg)
{
TOUCH_NULL_POINTER_CHECK(sens_handle);
TOUCH_NULL_POINTER_CHECK(sens_cfg);
ESP_RETURN_ON_FALSE(sens_cfg->meas_interval_us >= 0, ESP_ERR_INVALID_ARG, TAG, "interval_us should be a positive value");
esp_err_t ret = ESP_OK;
xSemaphoreTake(sens_handle->mutex, portMAX_DELAY);
ESP_GOTO_ON_FALSE(!sens_handle->is_enabled, ESP_ERR_INVALID_STATE, err, TAG, "Please disable the touch sensor first");
ESP_GOTO_ON_ERROR(touch_priv_config_controller(sens_handle, sens_cfg), err, TAG, "Configure touch controller failed");
err:
xSemaphoreGive(sens_handle->mutex);
return ret;
}
esp_err_t touch_sensor_enable(touch_sensor_handle_t sens_handle)
{
TOUCH_NULL_POINTER_CHECK(sens_handle);
esp_err_t ret = ESP_OK;
xSemaphoreTakeRecursive(sens_handle->mutex, portMAX_DELAY);
ESP_GOTO_ON_FALSE(!sens_handle->is_enabled, ESP_ERR_INVALID_STATE, err, TAG, "Touch sensor has already enabled");
ESP_GOTO_ON_FALSE(sens_handle->sample_cfg_num, ESP_ERR_INVALID_STATE, err, TAG, "No sample configuration was added to the touch controller");
sens_handle->is_enabled = true;
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
touch_ll_intr_clear(TOUCH_LL_INTR_MASK_ALL);
touch_ll_intr_enable(TOUCH_LL_INTR_MASK_ALL);
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
#if SOC_TOUCH_SUPPORT_PROX_SENSING
/* Reset the cached data of proximity channel */
FOR_EACH_TOUCH_CHANNEL(i) {
if (sens_handle->ch[i] && sens_handle->ch[i]->is_prox_chan) {
sens_handle->ch[i]->prox_cnt = 0;
memset(sens_handle->ch[i]->prox_val, 0, sizeof(sens_handle->ch[i]->prox_val[0]) * TOUCH_SAMPLE_CFG_NUM);
}
}
#endif
err:
xSemaphoreGiveRecursive(sens_handle->mutex);
return ret;
}
esp_err_t touch_sensor_disable(touch_sensor_handle_t sens_handle)
{
TOUCH_NULL_POINTER_CHECK(sens_handle);
esp_err_t ret = ESP_OK;
xSemaphoreTake(sens_handle->mutex, portMAX_DELAY);
ESP_GOTO_ON_FALSE(sens_handle->is_enabled, ESP_ERR_INVALID_STATE, err, TAG, "Touch sensor has not enabled");
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
touch_ll_intr_disable(TOUCH_LL_INTR_MASK_ALL);
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
sens_handle->is_enabled = false;
err:
xSemaphoreGive(sens_handle->mutex);
return ret;
}
esp_err_t touch_sensor_reconfig_channel(touch_channel_handle_t chan_handle, const touch_channel_config_t *chan_cfg)
{
TOUCH_NULL_POINTER_CHECK(chan_handle);
TOUCH_NULL_POINTER_CHECK(chan_cfg);
esp_err_t ret = ESP_OK;
touch_sensor_handle_t sens_handle = chan_handle->base;
xSemaphoreTake(sens_handle->mutex, portMAX_DELAY);
ESP_GOTO_ON_FALSE(!sens_handle->is_enabled, ESP_ERR_INVALID_STATE, err, TAG, "Please disable the touch sensor first");
ESP_GOTO_ON_ERROR(touch_priv_config_channel(chan_handle, chan_cfg), err, TAG, "Configure touch channel failed");
err:
xSemaphoreGive(sens_handle->mutex);
return ret;
}
esp_err_t touch_sensor_start_continuous_scanning(touch_sensor_handle_t sens_handle)
{
TOUCH_NULL_POINTER_CHECK_ISR(sens_handle);
esp_err_t ret = ESP_OK;
ESP_GOTO_ON_FALSE_ISR(sens_handle->is_enabled, ESP_ERR_INVALID_STATE, err, TAG, "Please enable the touch sensor first");
ESP_GOTO_ON_FALSE_ISR(!sens_handle->is_started, ESP_ERR_INVALID_STATE, err, TAG, "Continuous scanning has started already");
TOUCH_ENTER_CRITICAL_SAFE(TOUCH_PERIPH_LOCK);
sens_handle->is_started = true;
#if SOC_TOUCH_SENSOR_VERSION <= 2
touch_ll_set_fsm_mode(TOUCH_FSM_MODE_TIMER);
touch_ll_start_fsm();
#else
touch_ll_enable_fsm_timer(true);
touch_ll_start_fsm_repeated_timer(false);
#endif
TOUCH_EXIT_CRITICAL_SAFE(TOUCH_PERIPH_LOCK);
err:
return ret;
}
esp_err_t touch_sensor_stop_continuous_scanning(touch_sensor_handle_t sens_handle)
{
TOUCH_NULL_POINTER_CHECK_ISR(sens_handle);
esp_err_t ret = ESP_OK;
ESP_GOTO_ON_FALSE_ISR(sens_handle->is_started, ESP_ERR_INVALID_STATE, err, TAG, "Continuous scanning not started yet");
TOUCH_ENTER_CRITICAL_SAFE(TOUCH_PERIPH_LOCK);
#if SOC_TOUCH_SENSOR_VERSION <= 2
touch_ll_stop_fsm();
touch_ll_set_fsm_mode(TOUCH_FSM_MODE_SW);
#else
touch_ll_stop_fsm_repeated_timer(false);
touch_ll_enable_fsm_timer(false);
#endif
sens_handle->is_started = false;
TOUCH_EXIT_CRITICAL_SAFE(TOUCH_PERIPH_LOCK);
err:
return ret;
}
esp_err_t touch_sensor_trigger_oneshot_scanning(touch_sensor_handle_t sens_handle, int timeout_ms)
{
TOUCH_NULL_POINTER_CHECK(sens_handle);
esp_err_t ret = ESP_OK;
ESP_GOTO_ON_FALSE(sens_handle->is_enabled, ESP_ERR_INVALID_STATE, err, TAG, "Please enable the touch sensor first");
ESP_GOTO_ON_FALSE(!sens_handle->is_started, ESP_ERR_INVALID_STATE, err, TAG, "Failed to trigger oneshot scanning because scanning has started");
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
sens_handle->is_started = true;
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
TickType_t ticks = 0;
if (timeout_ms > 0) {
ticks = pdMS_TO_TICKS(timeout_ms);
if (!ticks) {
ESP_LOGW(TAG, "The timeout is too small, use the minimum tick resolution as default: %"PRIu32" ms", portTICK_PERIOD_MS);
ticks = 1;
}
}
xSemaphoreTake(sens_handle->mutex, ticks);
TickType_t end_tick = xTaskGetTickCount() + ticks;
// TODO: extract the following implementation into version specific source file when supporting other targets
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
touch_ll_enable_fsm_timer(false);
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
FOR_EACH_TOUCH_CHANNEL(i) {
if (sens_handle->ch[i]) {
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
touch_ll_channel_sw_measure_mask(BIT(i));
touch_ll_trigger_oneshot_measurement();
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
while (!touch_ll_is_measure_done()) {
if (g_touch->is_meas_timeout) {
g_touch->is_meas_timeout = false;
ESP_LOGW(TAG, "The measurement time on channel %d exceed the limitation", i);
break;
}
if (timeout_ms >= 0) {
ESP_GOTO_ON_FALSE(xTaskGetTickCount() <= end_tick, ESP_ERR_TIMEOUT, err, TAG, "Wait for measurement done timeout");
}
vTaskDelay(1);
}
}
}
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
touch_ll_channel_sw_measure_mask(0);
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
err:
xSemaphoreGive(sens_handle->mutex);
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
sens_handle->is_started = false;
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
return ret;
}
esp_err_t touch_sensor_register_callbacks(touch_sensor_handle_t sens_handle, const touch_event_callbacks_t *callbacks, void *user_ctx)
{
TOUCH_NULL_POINTER_CHECK(sens_handle);
TOUCH_NULL_POINTER_CHECK(callbacks);
#if CONFIG_TOUCH_ISR_IRAM_SAFE
const uint32_t **ptr = (const uint32_t **)callbacks;
for (int i = 0; i < sizeof(touch_event_callbacks_t) / sizeof(uint32_t *); i++) {
ESP_RETURN_ON_FALSE(TOUCH_IRAM_CHECK(ptr[i]), ESP_ERR_INVALID_ARG, TAG, "callback not in IRAM");
}
ESP_RETURN_ON_FALSE(!user_ctx || esp_ptr_internal(user_ctx), ESP_ERR_INVALID_ARG, TAG, "user context not in internal RAM");
#endif
esp_err_t ret = ESP_OK;
xSemaphoreTake(sens_handle->mutex, portMAX_DELAY);
ESP_GOTO_ON_FALSE(!sens_handle->is_enabled, ESP_ERR_INVALID_STATE, err, TAG, "Please disable the touch sensor first");
memcpy(&sens_handle->cbs, callbacks, sizeof(touch_event_callbacks_t));
sens_handle->user_ctx = user_ctx;
err:
xSemaphoreGive(sens_handle->mutex);
return ret;
}
esp_err_t touch_channel_read_data(touch_channel_handle_t chan_handle, touch_chan_data_type_t type, uint32_t *data)
{
TOUCH_NULL_POINTER_CHECK_ISR(chan_handle);
TOUCH_NULL_POINTER_CHECK_ISR(data);
return touch_priv_channel_read_data(chan_handle, type, data);
}
esp_err_t touch_channel_config_benchmark(touch_channel_handle_t chan_handle, const touch_chan_benchmark_config_t *benchmark_cfg)
{
TOUCH_NULL_POINTER_CHECK_ISR(chan_handle);
TOUCH_NULL_POINTER_CHECK_ISR(benchmark_cfg);
touch_priv_config_benchmark(chan_handle, benchmark_cfg);
return ESP_OK;
}

View File

@ -0,0 +1,192 @@
/*
* SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @brief This header file is private for the internal use of the touch driver
* DO NOT use any APIs or types in this file outside of the touch driver
*/
#pragma once
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "soc/soc_caps.h"
#include "hal/touch_sensor_hal.h"
#include "driver/touch_sens_types.h"
#include "esp_memory_utils.h"
#include "esp_check.h"
#include "sdkconfig.h"
#ifdef __cplusplus
extern "C" {
#endif
/* Helper macros */
#define TOUCH_NULL_POINTER_CHECK(p) ESP_RETURN_ON_FALSE((p), ESP_ERR_INVALID_ARG, TAG, "input parameter '"#p"' is NULL")
#define TOUCH_NULL_POINTER_CHECK_ISR(p) ESP_RETURN_ON_FALSE_ISR((p), ESP_ERR_INVALID_ARG, TAG, "input parameter '"#p"' is NULL")
#define FOR_EACH_TOUCH_CHANNEL(i) for (int i = 0; i < SOC_TOUCH_SENSOR_NUM; i++)
#define TOUCH_IRAM_CHECK(cb) (!(cb) || esp_ptr_in_iram(cb))
/* IRAM safe caps */
#if CONFIG_TOUCH_ISR_IRAM_SAFE || CONFIG_TOUCH_CTRL_FUNC_IN_IRAM
#define TOUCH_INTR_ALLOC_FLAGS (ESP_INTR_FLAG_IRAM | ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_LOWMED)
#define TOUCH_MEM_ALLOC_CAPS (MALLOC_CAP_INTERNAL | MALLOC_CAP_8BIT)
#else
#define TOUCH_INTR_ALLOC_FLAGS (ESP_INTR_FLAG_SHARED | ESP_INTR_FLAG_LOWMED)
#define TOUCH_MEM_ALLOC_CAPS MALLOC_CAP_DEFAULT
#endif //CONFIG_TOUCH_ISR_IRAM_SAFE
/* DMA caps */
#define TOUCH_DMA_ALLOC_CAPS (MALLOC_CAP_INTERNAL | MALLOC_CAP_DMA)
/* RTC peripheral spin lock */
extern portMUX_TYPE rtc_spinlock;
#define TOUCH_RTC_LOCK (&rtc_spinlock)
#if SOC_TOUCH_SENSOR_VERSION <= 2
#define TOUCH_PERIPH_LOCK (&rtc_spinlock)
#else
extern portMUX_TYPE g_touch_spinlock;
#define TOUCH_PERIPH_LOCK (&g_touch_spinlock)
#endif
#define TOUCH_ENTER_CRITICAL(spinlock) portENTER_CRITICAL(spinlock)
#define TOUCH_EXIT_CRITICAL(spinlock) portEXIT_CRITICAL(spinlock)
#define TOUCH_ENTER_CRITICAL_SAFE(spinlock) portENTER_CRITICAL_SAFE(spinlock)
#define TOUCH_EXIT_CRITICAL_SAFE(spinlock) portEXIT_CRITICAL_SAFE(spinlock)
/**
* @brief The touch sensor controller instance structure
* @note A touch sensor controller includes multiple channels and sample configurations
*
*/
struct touch_sensor_s {
touch_channel_handle_t ch[SOC_TOUCH_SENSOR_NUM]; /*!< Touch sensor channel handles, will be NULL if the channel is not registered */
uint32_t chan_mask; /*!< Enabled channel mask, corresponding bit will be set if the channel is registered */
uint32_t src_freq_hz; /*!< Source clock frequency */
intr_handle_t intr_handle; /*!< Interrupt handle */
touch_event_callbacks_t cbs; /*!< Event callbacks */
touch_channel_handle_t deep_slp_chan; /*!< The configured channel for depp sleep, will be NULL if not enable the deep sleep */
touch_channel_handle_t guard_chan; /*!< The configured channel for the guard ring, will be NULL if not set */
touch_channel_handle_t shield_chan; /*!< The configured channel for the shield pad, will be NULL if not set */
SemaphoreHandle_t mutex; /*!< Mutex lock to ensure thread safety */
uint8_t sample_cfg_num; /*!< The number of sample configurations that in used */
void *user_ctx; /*!< User context that will pass to the callback function */
bool is_enabled; /*!< Flag to indicate whether the scanning is enabled */
bool is_started; /*!< Flag to indicate whether the scanning has started */
bool is_meas_timeout; /*!< Flag to indicate whether the measurement timeout, will force to stop the current measurement if the timeout is triggered */
bool sleep_en; /*!< Flag to indicate whether the sleep wake-up feature is enabled */
bool waterproof_en; /*!< Flag to indicate whether the water proof feature is enabled */
bool immersion_proof; /*!< Flag to indicate whether to disable scanning when the guard ring is triggered */
bool proximity_en; /*!< Flag to indicate whether the proximity sensing feature is enabled */
bool timeout_en; /*!< Flag to indicate whether the measurement timeout feature (hardware timeout) is enabled */
};
/**
* @brief The touch sensor channel instance structure
*
*/
struct touch_channel_s {
touch_sensor_handle_t base; /*!< The touch sensor controller handle */
int id; /*!< Touch channel id, the range is target-specific */
bool is_prox_chan; /*!< Flag to indicate whether this is a proximity channel */
uint32_t prox_cnt; /*!< Cache the proximity measurement count, only takes effect when the channel is a proximity channel.
* When this count reaches `touch_proximity_config_t::scan_times`,
* this field will be cleared and call the `on_proximity_meas_done` callback.
*/
uint32_t prox_val[TOUCH_SAMPLE_CFG_NUM]; /*!< The accumulated proximity value of each sample config.
* The value will accumulate for each scanning until it reaches `touch_proximity_config_t::scan_times`.
* This accumulated proximity value can be read via `touch_channel_read_data` when all scanning finished.
*/
};
extern touch_sensor_handle_t g_touch; /*!< Global touch sensor controller handle for `esp_driver_touch_sens` use only */
/**
* @brief Touch sensor module enable interface
* @note This is a private interface of `esp_driver_touch_sens`
* It should be implemented by each hardware version
*
* @param[in] enable Set true to enable touch sensor module clock
*/
void touch_priv_enable_module(bool enable);
/**
* @brief Touch sensor default interrupt handler
* @note This is a private interface of `esp_driver_touch_sens`
* It should be implemented by each hardware version
*
* @param[in] arg The input argument
*/
void touch_priv_default_intr_handler(void *arg);
/**
* @brief Touch sensor controller configuration interface
* @note This is a private interface of `esp_driver_touch_sens`
* It should be implemented by each hardware version
*
* @param[in] sens_handle The touch sensor controller handle
* @param[in] sens_cfg The touch sensor controller configuration pointer
* @return
* - ESP_OK On success
* - Others Version-specific failure code
*/
esp_err_t touch_priv_config_controller(touch_sensor_handle_t sens_handle, const touch_sensor_config_t *sens_cfg);
/**
* @brief Touch sensor channel configuration interface
* @note This is a private interface of `esp_driver_touch_sens`
* It should be implemented by each hardware version
*
* @param[in] chan_handle The touch sensor channel handle
* @param[in] chan_cfg The touch sensor channel configuration pointer
* @return
* - ESP_OK On success
* - Others Version-specific failure code
*/
esp_err_t touch_priv_config_channel(touch_channel_handle_t chan_handle, const touch_channel_config_t *chan_cfg);
/**
* @brief Touch sensor controller de-initialize interface
* @note This is a private interface of `esp_driver_touch_sens`
* It should be implemented by each hardware version
*
* @param[in] sens_handle The touch sensor handle
* @return
* - ESP_OK On success
* - Others Version-specific failure code
*/
esp_err_t touch_priv_deinit_controller(touch_sensor_handle_t sens_handle);
/**
* @brief Touch sensor channel data read interface
* @note This is a private interface of `esp_driver_touch_sens`
* It should be implemented by each hardware version
*
* @param[in] chan_handle The touch sensor channel handle
* @param[in] type The read data type
* @param[out] data The output data pointer
* @return
* - ESP_OK On success
* - Others Version-specific failure code
*/
esp_err_t touch_priv_channel_read_data(touch_channel_handle_t chan_handle, touch_chan_data_type_t type, uint32_t *data);
/**
* @brief Touch sensor channel benchmark set interface
* @note This is a private interface of `esp_driver_touch_sens`
* It should be implemented by each hardware version
*
* @param[in] chan_handle The channel handle
* @param[in] benchmark_cfg The benchmark operation
*/
void touch_priv_config_benchmark(touch_channel_handle_t chan_handle, const touch_chan_benchmark_config_t *benchmark_cfg);
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,12 @@
/*
* SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @brief This file is only applicable to the touch hardware version1
* Version 1 includes ESP32
*/
#error "'esp_driver_touch_sens' does not support for ESP32 yet"

View File

@ -0,0 +1,12 @@
/*
* SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @brief This file is only applicable to the touch hardware version2
* Version 2 includes ESP32-S2 and ESP32-S3
*/
#error "'esp_driver_touch_sens' does not support for ESP32-S2 and ESP32-S3 yet"

View File

@ -0,0 +1,424 @@
/*
* SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @brief This file is only applicable to the touch hardware version3
* Version 3 includes ESP32-P4
*/
#pragma once
#include "soc/soc_caps.h"
#include "driver/touch_sens_types.h"
#include "esp_err.h"
#ifdef __cplusplus
extern "C" {
#endif
#define TOUCH_MIN_CHAN_ID 0 /*!< The minimum available channel id of the touch pad */
#define TOUCH_MAX_CHAN_ID 13 /*!< The maximum available channel id of the touch pad */
/**
* @brief Helper macro to the default configurations of the touch sensor controller
*
*/
#define TOUCH_SENSOR_DEFAULT_BASIC_CONFIG(sample_cfg_number, sample_cfg_array) { \
.power_on_wait_us = 256, \
.meas_interval_us = 32.0, \
.max_meas_time_us = 0, \
.output_mode = TOUCH_PAD_OUT_AS_CLOCK, \
.sample_cfg_num = sample_cfg_number, \
.sample_cfg = sample_cfg_array, \
}
/**
* @brief Helper macro to the default sample configurations
* @note This default configuration uses `sample frequency = clock frequency / 1`
*
*/
#define TOUCH_SENSOR_V3_DEFAULT_SAMPLE_CONFIG(_div_num, coarse_freq_tune, fine_freq_tune) { \
.div_num = _div_num, \
.charge_times = 500, \
.rc_filter_res = 1, \
.rc_filter_cap = 1, \
.low_drv = fine_freq_tune, \
.high_drv = coarse_freq_tune, \
.bias_volt = 5, \
.bypass_shield_output = false, \
}
#define TOUCH_SENSOR_DEFAULT_FILTER_CONFIG() { \
.benchmark = { \
.filter_mode = TOUCH_BM_IIR_FILTER_4, \
.jitter_step = 4, \
.denoise_lvl = 1, \
}, \
.data = { \
.smooth_filter = TOUCH_SMOOTH_IIR_FILTER_2, \
.active_hysteresis = 2, \
}, \
}
/**
* @brief The data type of the touch channel
*
*/
typedef enum {
TOUCH_CHAN_DATA_TYPE_SMOOTH, /*!< The smooth data of the touch channel */
TOUCH_CHAN_DATA_TYPE_BENCHMARK, /*!< The benchmark of the touch channel */
TOUCH_CHAN_DATA_TYPE_PROXIMITY, /*!< The proximity data of the proximity channel */
} touch_chan_data_type_t;
/**
* @brief The chip sleep level that allows the touch sensor to wake-up
*
*/
typedef enum {
TOUCH_LIGHT_SLEEP_WAKEUP, /*!< Only enable the touch sensor to wake up the chip from light sleep */
TOUCH_DEEP_SLEEP_WAKEUP, /*!< Enable the touch sensor to wake up the chip from deep sleep or light sleep */
} touch_sleep_wakeup_level_t;
/**
* @brief Touch sensor shield channel drive capability level
*
*/
typedef enum {
TOUCH_SHIELD_CAP_40PF, /*!< The max equivalent capacitance in shield channel is 40pf */
TOUCH_SHIELD_CAP_80PF, /*!< The max equivalent capacitance in shield channel is 80pf */
TOUCH_SHIELD_CAP_120PF, /*!< The max equivalent capacitance in shield channel is 120pf */
TOUCH_SHIELD_CAP_160PF, /*!< The max equivalent capacitance in shield channel is 160pf */
TOUCH_SHIELD_CAP_200PF, /*!< The max equivalent capacitance in shield channel is 200pf */
TOUCH_SHIELD_CAP_240PF, /*!< The max equivalent capacitance in shield channel is 240pf */
TOUCH_SHIELD_CAP_280PF, /*!< The max equivalent capacitance in shield channel is 280pf */
TOUCH_SHIELD_CAP_320PF, /*!< The max equivalent capacitance in shield channel is 320pf */
} touch_chan_shield_cap_t;
/**
* @brief Touch channel Infinite Impulse Response (IIR) filter or Jitter filter for benchmark
* @note Recommended filter coefficient selection is `IIR_16`.
*/
typedef enum {
TOUCH_BM_IIR_FILTER_4, /*!< IIR Filter for benchmark, 1/4 raw_value + 3/4 benchmark */
TOUCH_BM_IIR_FILTER_8, /*!< IIR Filter for benchmark, 1/8 raw_value + 7/8 benchmark */
TOUCH_BM_IIR_FILTER_16, /*!< IIR Filter for benchmark, 1/16 raw_value + 15/16 benchmark (typical) */
TOUCH_BM_IIR_FILTER_32, /*!< IIR Filter for benchmark, 1/32 raw_value + 31/32 benchmark */
TOUCH_BM_IIR_FILTER_64, /*!< IIR Filter for benchmark, 1/64 raw_value + 63/64 benchmark */
TOUCH_BM_IIR_FILTER_128, /*!< IIR Filter for benchmark, 1/128 raw_value + 127/128 benchmark */
TOUCH_BM_JITTER_FILTER, /*!< Jitter Filter for benchmark, raw value +/- jitter_step */
} touch_benchmark_filter_mode_t;
/**
* @brief Touch channel Infinite Impulse Response (IIR) filter for smooth data
*
*/
typedef enum {
TOUCH_SMOOTH_NO_FILTER, /*!< No filter adopted for smooth data, smooth data equals raw data */
TOUCH_SMOOTH_IIR_FILTER_2, /*!< IIR filter adopted for smooth data, smooth data equals 1/2 raw data + 1/2 last smooth data (typical) */
TOUCH_SMOOTH_IIR_FILTER_4, /*!< IIR filter adopted for smooth data, smooth data equals 1/4 raw data + 3/4 last smooth data */
TOUCH_SMOOTH_IIR_FILTER_8, /*!< IIR filter adopted for smooth data, smooth data equals 1/8 raw data + 7/8 last smooth data */
} touch_smooth_filter_mode_t;
/**
* @brief Interrupt events
*
*/
typedef enum {
TOUCH_INTR_EVENT_ACTIVE, /*!< Touch channel active event */
TOUCH_INTR_EVENT_INACTIVE, /*!< Touch channel inactive event */
TOUCH_INTR_EVENT_MEASURE_DONE, /*!< Touch channel measure done event */
TOUCH_INTR_EVENT_SCAN_DONE, /*!< All touch channels scan done event */
TOUCH_INTR_EVENT_TIMEOUT, /*!< Touch channel measurement timeout event */
TOUCH_INTR_EVENT_PROXIMITY_DONE, /*!< Proximity channel measurement done event */
} touch_intr_event_t;
/**
* @brief Sample configurations of the touch sensor
*
*/
typedef struct {
uint32_t div_num; /*!< Division of the touch output pulse, `touch_out_pulse / div_num = charge_times` */
uint32_t charge_times; /*!< The charge and discharge times of this sample configuration, the read data are positive correlation to the charge_times */
uint8_t rc_filter_res; /*!< The resistance of the RC filter of this 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 this 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, enable when the charging/discharging rate greater than 10MHz */
} touch_sensor_sample_config_t;
/**
* @brief Configurations of the touch sensor controller
*
*/
typedef struct {
uint32_t power_on_wait_us; /*!< The waiting time between the channels power on and able to measure, to ensure the data stability */
float meas_interval_us; /*!< Measurement interval of each channels */
uint32_t max_meas_time_us; /*!< 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 this 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_sensor_sample_config_t *sample_cfg; /*!< The array of this sample configuration configurations, the length should be specified in `touch_sensor_config_t::sample_cfg_num` */
} touch_sensor_config_t;
/**
* @brief Configurations of the touch sensor channel
*
*/
typedef struct {
uint32_t active_thresh[TOUCH_SAMPLE_CFG_NUM]; /*!< The active threshold of each sample configuration,
* while the touch channel smooth value minus benchmark value exceed this threshold,
* will be regarded as activated
*/
} touch_channel_config_t;
/**
* @brief Configurations of the touch sensor filter
*
*/
typedef struct {
/**
* @brief Benchmark configuration
*/
struct {
touch_benchmark_filter_mode_t filter_mode; /*!< Benchmark filter mode. IIR filter and Jitter filter can be selected,
* TOUCH_BM_IIR_FILTER_16 is recommended
*/
uint32_t jitter_step; /*!< Jitter filter step size, only takes effect when the `filter_mode` is TOUCH_BM_JITTER_FILTER. Range: [0 ~ 15] */
int denoise_lvl; /*!< The denoise level, which determines the noise bouncing range that won't trigger benchmark update.
* Range: [0 ~ 4]. The greater the denoise_lvl is, more noise resistance will be. Specially, `0` stands for no denoise
* Typically, recommend to set this field to 1.
*/
} benchmark; /*!< Benchmark filter */
/**
* @brief Data configuration
*/
struct {
touch_smooth_filter_mode_t smooth_filter; /*!< Smooth data IIR filter mode */
uint32_t active_hysteresis; /*!< The hysteresis threshold to judge whether the touch channel is active
* If the channel data exceed the 'touch_channel_config_t::active_thresh + active_hysteresis'
* The channel will be activated. If the channel data is below to
* 'touch_channel_config_t::active_thresh - active_hysteresis' the channel will be inactivated.
*/
uint32_t debounce_cnt; /*!< The debounce count of the touch channel.
* Only when the channel data exceed the `touch_channel_config_t::active_thresh + active_hysteresis` for `debounce_cnt` times
* The channel will be activated. And only if the channel data is below to the `touch_channel_config_t::active_thresh - active_hysteresis`
* for `debounce_cnt` times, the channel will be inactivated.
* (The unit of `debounce_cnt` is the tick of the slow clock source)
*/
} data; /*!< Channel data filter */
} touch_sensor_filter_config_t;
/**
* @brief Touch sensor configuration during the deep sleep
* @note Currently it is the same as the normal controller configuration.
* The deep sleep configuration only takes effect when the chip entered sleep,
* so that to update a more power efficient configuration.
*
*/
typedef touch_sensor_config_t touch_sensor_config_dslp_t;
/**
* @brief Configure the touch sensor sleep function
*
*/
typedef struct {
touch_sleep_wakeup_level_t slp_wakeup_lvl; /*!< The sleep level that can be woke up by touch sensor. */
touch_channel_handle_t deep_slp_chan; /*!< The touch channel handle that supposed to work in the deep sleep. It can wake up the chip
* from deep sleep when this channel is activated.
* Only effective when the `touch_sleep_config_t::slp_wakeup_lvl` is `TOUCH_DEEP_SLEEP_WAKEUP`
*/
uint32_t deep_slp_thresh[TOUCH_SAMPLE_CFG_NUM]; /*!< The active threshold of the deep sleep channel during deep sleep,
* while the sleep channel exceed this threshold, it will be regarded as activated
* Only effective when the `touch_sleep_config_t::slp_wakeup_lvl` is `TOUCH_DEEP_SLEEP_WAKEUP`
*/
touch_sensor_config_dslp_t *deep_slp_sens_cfg; /*!< Specify the touch sensor configuration during the deep sleep.
* Note that these configurations will no take effect immediately,
* they will be set automatically while the chip prepare to enter sleep.
* Set NULL to not change the configurations before entering sleep.
* The sleep configuration mainly aims at lower down the charging and measuring times,
* so that to save power consumption during the sleep.
* Only effective when the `touch_sleep_config_t::slp_wakeup_lvl` is `TOUCH_DEEP_SLEEP_WAKEUP`
*/
} touch_sleep_config_t;
/**
* @brief Configure the touch sensor waterproof function
*
*/
typedef struct {
touch_channel_handle_t guard_chan; /*!< The guard channel of that used for immersion detect. Set NULL if you don't need the guard channel.
* Typically, the guard channel is a ring that surrounds the touch panels,
* it is used to detect the large area that covered by water.
* While large area of water covers the touch panel, the guard channel will be activated.
*/
touch_channel_handle_t shield_chan; /*!< The shield channel that used for water droplets shield, can't be NULL.
* Typically, the shield channel uses grid layout which covers the touch area,
* it is used to shield the influence of water droplets covering both the touch panel and the shield channel.
* The shield channel will be paralleled to the current measuring channel (except the guard channel) to reduce the influence of water droplets.
*/
uint32_t shield_drv; /*!< The shield channel driver, which controls the drive capability of shield channel, range: 0 ~ 7
* The larger the parasitic capacitance on the shielding channel, the higher the drive capability needs to be set.
*/
struct {
uint32_t immersion_proof: 1; /*!< Enable to protect the touch sensor pad when immersion detected.
* It will temporary disable the touch scanning if the guard channel triggered, and enable again if guard channel released.
* So that to avoid the fake touch when the touch panel is immersed in water.
*/
} flags; /*!< Flags of the water proof function */
} touch_waterproof_config_t;
/**
* @brief Configure the touch sensor proximity function
*
*/
typedef struct {
touch_channel_handle_t proximity_chan[TOUCH_PROXIMITY_CHAN_NUM]; /*!< The touch channel handles that will be configured as proximity sensing channels */
uint32_t scan_times; /*!< The total scan times of EACH sample configuration, all sample configurations share a same `scan_times`.
* The measurement result of each scanning will be accumulated together to get the final result.
*/
uint32_t charge_times[TOUCH_SAMPLE_CFG_NUM]; /*!< The charge times of EACH scanning, different sample configurations can set different `charge_times`.
* The measurement result of each scanning is positive correlation to the `charge_times`,
* please set a proper value in case of the final accumulated result overflow.
*/
} touch_proximity_config_t;
/**
* @brief Base event structure used in touch event queue
*/
typedef struct {
touch_channel_handle_t chan; /*!< the current triggered touch channel handle */
int chan_id; /*!< the current triggered touch channel number */
uint32_t status_mask; /*!< the current channel triggered status.
* For the bits in the status mask,
* if the bit is set, the corresponding channel is active
* if the bit is cleared, the corresponding channel is inactive
*/
} touch_base_event_data_t;
/**
* @brief Measure done event data
* @note Currently same as base event data
*
*/
typedef touch_base_event_data_t touch_meas_done_event_data_t;
/**
* @brief Scan done event data
* @note Currently same as base event data
*
*/
typedef touch_base_event_data_t touch_scan_done_event_data_t;
/**
* @brief Active event data
* @note Currently same as base event data
*
*/
typedef touch_base_event_data_t touch_active_event_data_t;
/**
* @brief Inactive event data
* @note Currently same as base event data
*
*/
typedef touch_base_event_data_t touch_inactive_event_data_t;
/**
* @brief Proximity sensing measure done event data
* @note Currently same as base event data
*
*/
typedef touch_base_event_data_t touch_prox_done_event_data_t;
/**
* @brief Timeout event data
* @note Currently same as base event data
*
*/
typedef touch_base_event_data_t touch_timeout_event_data_t;
/**
* @brief Touch sensor callbacks
* @note Set NULL for the used callbacks.
*
*/
typedef struct {
/**
* @brief Touch sensor on active event callback.
* Callback when any touch channel is activated.
* @param[in] sens_handle Touch sensor controller handle, created from `touch_sensor_new_controller()`
* @param[in] event Touch sensor active event data
* @param[in] user_ctx User registered context, passed from `touch_sensor_register_callbacks()`
*
* @return Whether a high priority task has been waken up by this callback function
*/
bool (*on_active)(touch_sensor_handle_t sens_handle, const touch_active_event_data_t *event, void *user_ctx);
/**
* @brief Touch sensor on inactive event callback.
* Callback when any touch channel is inactivated.
* @param[in] sens_handle Touch sensor controller handle, created from `touch_sensor_new_controller()`
* @param[in] event Touch sensor inactive event data
* @param[in] user_ctx User registered context, passed from `touch_sensor_register_callbacks()`
*
* @return Whether a high priority task has been waken up by this callback function
*/
bool (*on_inactive)(touch_sensor_handle_t sens_handle, const touch_inactive_event_data_t *event, void *user_ctx);
/**
* @brief Touch sensor on measure done event callback.
* Callback when the measurement of all the sample configurations on the current touch channel is done.
* @param[in] sens_handle Touch sensor controller handle, created from `touch_sensor_new_controller()`
* @param[in] event Touch sensor measure done event data
* @param[in] user_ctx User registered context, passed from `touch_sensor_register_callbacks()`
*
* @return Whether a high priority task has been waken up by this callback function
*/
bool (*on_measure_done)(touch_sensor_handle_t sens_handle, const touch_meas_done_event_data_t *event, void *user_ctx);
/**
* @brief Touch sensor on scan done event callback.
* Callback when finished scanning all the registered touch channels.
* @param[in] sens_handle Touch sensor controller handle, created from `touch_sensor_new_controller()`
* @param[in] event Touch sensor scan done event data
* @param[in] user_ctx User registered context, passed from `touch_sensor_register_callbacks()`
*
* @return Whether a high priority task has been waken up by this callback function
*/
bool (*on_scan_done)(touch_sensor_handle_t sens_handle, const touch_scan_done_event_data_t *event, void *user_ctx);
/**
* @brief Touch sensor on measurement timeout event callback.
* Callback when measure the current touch channel timeout.
* @param[in] sens_handle Touch sensor controller handle, created from `touch_sensor_new_controller()`
* @param[in] event Touch sensor timeout event data
* @param[in] user_ctx User registered context, passed from `touch_sensor_register_callbacks()`
*
* @return Whether a high priority task has been waken up by this callback function
*/
bool (*on_timeout)(touch_sensor_handle_t sens_handle, const touch_timeout_event_data_t *event, void *user_ctx);
/**
* @brief Touch sensor on proximity sensing measurement done event callback.
* Callback when proximity sensing measurement of the current channel is done.
* @param[in] sens_handle Touch sensor controller handle, created from `touch_sensor_new_controller()`
* @param[in] event Touch sensor proximity sensing measure done event data
* @param[in] user_ctx User registered context, passed from `touch_sensor_register_callbacks()`
*
* @return Whether a high priority task has been waken up by this callback function
*/
bool (*on_proximity_meas_done)(touch_sensor_handle_t sens_handle, const touch_prox_done_event_data_t *event, void *user_ctx);
} touch_event_callbacks_t;
/**
* @brief Touch sensor benchmark configurations, to set or reset the benchmark of the channel
*
*/
typedef struct {
bool do_reset; /*!< Whether to reset the benchmark to the channel's latest smooth data */
} touch_chan_benchmark_config_t;
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,473 @@
/*
* SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
/**
* @brief This file is only applicable to the touch hardware version3
* Version 3 includes ESP32-P4
*/
#include <inttypes.h>
#include <string.h>
#include "freertos/FreeRTOS.h"
#include "freertos/semphr.h"
#include "soc/soc_caps.h"
#include "soc/clk_tree_defs.h"
#include "soc/touch_sensor_periph.h"
#include "soc/rtc.h"
#include "hal/hal_utils.h"
#include "driver/touch_sens.h"
#include "esp_private/rtc_ctrl.h"
#include "esp_private/periph_ctrl.h"
#include "esp_clk_tree.h"
#include "esp_sleep.h"
#include "../../common/touch_sens_private.h"
#if CONFIG_TOUCH_ENABLE_DEBUG_LOG
// The local log level must be defined before including esp_log.h
// Set the maximum log level for this source file
#define LOG_LOCAL_LEVEL ESP_LOG_DEBUG
#endif
#include "esp_check.h"
static const char *TAG = "touch";
portMUX_TYPE g_touch_spinlock = portMUX_INITIALIZER_UNLOCKED;
/******************************************************************************
* Scope: touch driver private *
******************************************************************************/
void touch_priv_enable_module(bool enable)
{
TOUCH_ENTER_CRITICAL(TOUCH_RTC_LOCK);
touch_ll_enable_module_clock(enable);
touch_ll_enable_out_gate(enable);
#if SOC_TOUCH_SENSOR_VERSION >= 2
// Reset the benchmark after finished the scanning
touch_ll_reset_chan_benchmark(TOUCH_LL_FULL_CHANNEL_MASK);
#endif
TOUCH_EXIT_CRITICAL(TOUCH_RTC_LOCK);
}
void IRAM_ATTR touch_priv_default_intr_handler(void *arg)
{
/* If the touch controller object has not been allocated, return directly */
if (!g_touch) {
return;
}
bool need_yield = false;
uint32_t status = touch_ll_get_intr_status_mask();
g_touch->is_meas_timeout = false;
touch_ll_intr_clear(status);
touch_base_event_data_t data;
touch_ll_get_active_channel_mask(&data.status_mask);
data.chan = g_touch->ch[touch_ll_get_current_meas_channel()];
/* If the channel is not registered, return directly */
if (!data.chan) {
return;
}
data.chan_id = data.chan->id;
if (status & TOUCH_LL_INTR_MASK_DONE) {
if (g_touch->cbs.on_measure_done) {
need_yield |= g_touch->cbs.on_measure_done(g_touch, &data, g_touch->user_ctx);
}
}
if (status & TOUCH_LL_INTR_MASK_SCAN_DONE) {
if (g_touch->cbs.on_scan_done) {
need_yield |= g_touch->cbs.on_scan_done(g_touch, &data, g_touch->user_ctx);
}
}
if (status & TOUCH_LL_INTR_MASK_PROX_DONE) {
data.chan->prox_cnt++;
/* The proximity sensing result only accurate when the scanning times equal to the sample_cfg_num */
if (data.chan->prox_cnt == g_touch->sample_cfg_num) {
data.chan->prox_cnt = 0;
for (uint32_t i = 0; i < g_touch->sample_cfg_num; i++) {
touch_ll_read_chan_data(data.chan_id, i, TOUCH_LL_READ_BENCHMARK, &data.chan->prox_val[i]);
}
if (g_touch->cbs.on_proximity_meas_done) {
need_yield |= g_touch->cbs.on_proximity_meas_done(g_touch, &data, g_touch->user_ctx);
}
}
}
if (status & TOUCH_LL_INTR_MASK_ACTIVE) {
/* When the guard ring activated, disable the scanning of other channels to avoid fake touch */
TOUCH_ENTER_CRITICAL_SAFE(TOUCH_PERIPH_LOCK);
if (g_touch->immersion_proof && data.chan == g_touch->guard_chan) {
touch_ll_enable_scan_mask(~BIT(data.chan->id), false);
}
TOUCH_EXIT_CRITICAL_SAFE(TOUCH_PERIPH_LOCK);
if (g_touch->cbs.on_active) {
need_yield |= g_touch->cbs.on_active(g_touch, &data, g_touch->user_ctx);
}
}
if (status & TOUCH_LL_INTR_MASK_INACTIVE) {
/* When the guard ring inactivated, enable the scanning of other channels again */
TOUCH_ENTER_CRITICAL_SAFE(TOUCH_PERIPH_LOCK);
if (g_touch->immersion_proof && data.chan == g_touch->guard_chan) {
touch_ll_enable_scan_mask(g_touch->chan_mask & (~BIT(g_touch->shield_chan->id)), true);
}
TOUCH_EXIT_CRITICAL_SAFE(TOUCH_PERIPH_LOCK);
if (g_touch->cbs.on_inactive) {
need_yield |= g_touch->cbs.on_inactive(g_touch, &data, g_touch->user_ctx);
}
}
if (status & TOUCH_LL_INTR_MASK_TIMEOUT) {
g_touch->is_meas_timeout = true;
touch_ll_force_done_curr_measurement();
if (g_touch->cbs.on_timeout) {
need_yield |= g_touch->cbs.on_timeout(g_touch, &data, g_touch->user_ctx);
}
}
if (need_yield) {
portYIELD_FROM_ISR();
}
}
static esp_err_t s_touch_convert_to_hal_config(touch_sensor_handle_t sens_handle, const touch_sensor_config_t *sens_cfg, touch_hal_config_t *hal_cfg)
{
TOUCH_NULL_POINTER_CHECK(sens_cfg);
TOUCH_NULL_POINTER_CHECK(hal_cfg);
TOUCH_NULL_POINTER_CHECK(hal_cfg->sample_cfg);
ESP_RETURN_ON_FALSE(sens_cfg->sample_cfg_num && sens_cfg->sample_cfg, ESP_ERR_INVALID_ARG, TAG,
"at least one sample configuration required");
ESP_RETURN_ON_FALSE(sens_cfg->sample_cfg_num <= TOUCH_SAMPLE_CFG_NUM, ESP_ERR_INVALID_ARG, TAG,
"at most %d sample configurations supported", (int)(TOUCH_SAMPLE_CFG_NUM));
/* Get the source clock frequency for the first time */
if (!sens_handle->src_freq_hz) {
/* Touch sensor actually uses dynamic fast clock LP_DYN_FAST_CLK, but it will only switch to the slow clock during sleep,
* This driver only designed for wakeup case (sleep case should use ULP driver), so we only need to consider RTC_FAST here */
ESP_RETURN_ON_ERROR(esp_clk_tree_src_get_freq_hz(SOC_MOD_CLK_RTC_FAST, ESP_CLK_TREE_SRC_FREQ_PRECISION_CACHED, &sens_handle->src_freq_hz),
TAG, "get clock frequency failed");
ESP_LOGD(TAG, "touch rtc clock source: RTC_FAST, frequency: %"PRIu32" Hz", sens_handle->src_freq_hz);
}
uint32_t src_freq_hz = sens_handle->src_freq_hz;
uint32_t src_freq_mhz = src_freq_hz / 1000000;
hal_cfg->power_on_wait_ticks = (uint32_t)sens_cfg->power_on_wait_us * src_freq_mhz;
hal_cfg->meas_interval_ticks = (uint32_t)(sens_cfg->meas_interval_us * src_freq_mhz);
hal_cfg->timeout_ticks = (uint32_t)sens_cfg->max_meas_time_us * src_freq_mhz;
ESP_RETURN_ON_FALSE(hal_cfg->timeout_ticks <= TOUCH_LL_TIMEOUT_MAX, ESP_ERR_INVALID_ARG, TAG,
"max_meas_time_ms should within %"PRIu32, TOUCH_LL_TIMEOUT_MAX / src_freq_mhz);
hal_cfg->sample_cfg_num = sens_cfg->sample_cfg_num;
hal_cfg->output_mode = sens_cfg->output_mode;
for (uint32_t smp_cfg_id = 0; smp_cfg_id < sens_cfg->sample_cfg_num; smp_cfg_id++) {
const touch_sensor_sample_config_t *sample_cfg = &(sens_cfg->sample_cfg[smp_cfg_id]);
ESP_RETURN_ON_FALSE(sample_cfg->div_num > 0, ESP_ERR_INVALID_ARG, TAG,
"div_num can't be 0");
/* Assign the hal configurations */
hal_cfg->sample_cfg[smp_cfg_id].div_num = sample_cfg->div_num;
hal_cfg->sample_cfg[smp_cfg_id].charge_times = sample_cfg->charge_times;
hal_cfg->sample_cfg[smp_cfg_id].rc_filter_res = sample_cfg->rc_filter_res;
hal_cfg->sample_cfg[smp_cfg_id].rc_filter_cap = sample_cfg->rc_filter_cap;
hal_cfg->sample_cfg[smp_cfg_id].low_drv = sample_cfg->low_drv;
hal_cfg->sample_cfg[smp_cfg_id].high_drv = sample_cfg->high_drv;
hal_cfg->sample_cfg[smp_cfg_id].bias_volt = sample_cfg->bias_volt;
}
return ESP_OK;
}
esp_err_t touch_priv_config_controller(touch_sensor_handle_t sens_handle, const touch_sensor_config_t *sens_cfg)
{
#if CONFIG_TOUCH_ENABLE_DEBUG_LOG
esp_log_level_set(TAG, ESP_LOG_DEBUG);
#endif
/* Check and convert the configuration to hal configurations */
touch_hal_sample_config_t sample_cfg[TOUCH_SAMPLE_CFG_NUM] = {};
touch_hal_config_t hal_cfg = {
.sample_cfg = sample_cfg,
};
ESP_RETURN_ON_ERROR(s_touch_convert_to_hal_config(sens_handle, sens_cfg, &hal_cfg),
TAG, "parse the configuration failed due to the invalid configuration");
sens_handle->sample_cfg_num = sens_cfg->sample_cfg_num;
/* Configure the hardware */
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
touch_hal_config_controller(&hal_cfg);
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
return ESP_OK;
}
esp_err_t touch_priv_config_channel(touch_channel_handle_t chan_handle, const touch_channel_config_t *chan_cfg)
{
uint8_t sample_cfg_num = chan_handle->base->sample_cfg_num;
// Check the validation of the channel active threshold
for (uint8_t smp_cfg_id = 0; smp_cfg_id < sample_cfg_num; smp_cfg_id++) {
ESP_RETURN_ON_FALSE(chan_cfg->active_thresh[smp_cfg_id] <= TOUCH_LL_ACTIVE_THRESH_MAX, ESP_ERR_INVALID_ARG,
TAG, "the active threshold out of range 0~%d", TOUCH_LL_ACTIVE_THRESH_MAX);
}
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
for (uint8_t smp_cfg_id = 0; smp_cfg_id < sample_cfg_num; smp_cfg_id++) {
touch_ll_set_chan_active_threshold(chan_handle->id, smp_cfg_id, chan_cfg->active_thresh[smp_cfg_id]);
}
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
return ESP_OK;
}
esp_err_t touch_priv_deinit_controller(touch_sensor_handle_t sens_handle)
{
/* Disable the additional functions */
if (sens_handle->proximity_en) {
touch_sensor_config_proximity_sensing(sens_handle, NULL);
}
if (sens_handle->sleep_en) {
touch_sensor_config_sleep_wakeup(sens_handle, NULL);
}
if (sens_handle->waterproof_en) {
touch_sensor_config_waterproof(sens_handle, NULL);
}
return ESP_OK;
}
esp_err_t touch_priv_channel_read_data(touch_channel_handle_t chan_handle, touch_chan_data_type_t type, uint32_t *data)
{
ESP_RETURN_ON_FALSE_ISR(type >= TOUCH_CHAN_DATA_TYPE_SMOOTH && type <= TOUCH_CHAN_DATA_TYPE_PROXIMITY,
ESP_ERR_INVALID_ARG, TAG, "The channel data type is invalid");
#if CONFIG_TOUCH_CTRL_FUNC_IN_IRAM
ESP_RETURN_ON_FALSE_ISR(esp_ptr_internal(data), ESP_ERR_INVALID_ARG, TAG, "user context not in internal RAM");
#endif
uint8_t sample_cfg_num = chan_handle->base->sample_cfg_num;
if (type < TOUCH_CHAN_DATA_TYPE_PROXIMITY) {
uint32_t internal_type = 0;
switch (type) {
default: // fall through
case TOUCH_CHAN_DATA_TYPE_SMOOTH:
internal_type = TOUCH_LL_READ_SMOOTH;
break;
case TOUCH_CHAN_DATA_TYPE_BENCHMARK:
internal_type = TOUCH_LL_READ_BENCHMARK;
break;
}
if (type <= TOUCH_CHAN_DATA_TYPE_BENCHMARK) {
TOUCH_ENTER_CRITICAL_SAFE(TOUCH_PERIPH_LOCK);
for (int i = 0; i < sample_cfg_num; i++) {
touch_ll_read_chan_data(chan_handle->id, i, internal_type, &data[i]);
}
TOUCH_EXIT_CRITICAL_SAFE(TOUCH_PERIPH_LOCK);
}
} else {
if (!chan_handle->is_prox_chan) {
ESP_EARLY_LOGW(TAG, "This is not a proximity sensing channel");
}
TOUCH_ENTER_CRITICAL_SAFE(TOUCH_PERIPH_LOCK);
/* Get the proximity value from the stored data.
* The proximity value are updated in the isr when proximity scanning is done */
for (int i = 0; i < sample_cfg_num; i++) {
data[i] = chan_handle->prox_val[i];
}
TOUCH_EXIT_CRITICAL_SAFE(TOUCH_PERIPH_LOCK);
}
return ESP_OK;
}
void touch_priv_config_benchmark(touch_channel_handle_t chan_handle, const touch_chan_benchmark_config_t *benchmark_cfg)
{
if (benchmark_cfg->do_reset) {
touch_ll_reset_chan_benchmark(BIT(chan_handle->id));
}
}
/******************************************************************************
* Scope: public APIs *
******************************************************************************/
esp_err_t touch_sensor_config_filter(touch_sensor_handle_t sens_handle, const touch_sensor_filter_config_t *filter_cfg)
{
TOUCH_NULL_POINTER_CHECK(sens_handle);
if (filter_cfg) {
ESP_RETURN_ON_FALSE(filter_cfg->benchmark.denoise_lvl >= 0 && filter_cfg->benchmark.denoise_lvl <= 4,
ESP_ERR_INVALID_ARG, TAG, "denoise_lvl is out of range");
}
esp_err_t ret = ESP_OK;
xSemaphoreTake(sens_handle->mutex, portMAX_DELAY);
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
if (filter_cfg) {
touch_ll_filter_enable(true);
/* Configure the benchmark filter and update strategy */
touch_ll_filter_set_filter_mode(filter_cfg->benchmark.filter_mode);
if (filter_cfg->benchmark.filter_mode == TOUCH_BM_JITTER_FILTER) {
touch_ll_filter_set_jitter_step(filter_cfg->benchmark.jitter_step);
}
touch_ll_filter_set_denoise_level(filter_cfg->benchmark.denoise_lvl);
/* Configure the touch data filter */
touch_ll_filter_set_smooth_mode(filter_cfg->data.smooth_filter);
touch_ll_filter_set_active_hysteresis(filter_cfg->data.active_hysteresis);
touch_ll_filter_set_debounce(filter_cfg->data.debounce_cnt);
} else {
touch_ll_filter_enable(false);
}
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
xSemaphoreGive(sens_handle->mutex);
return ret;
}
esp_err_t touch_sensor_config_sleep_wakeup(touch_sensor_handle_t sens_handle, const touch_sleep_config_t *sleep_cfg)
{
TOUCH_NULL_POINTER_CHECK(sens_handle);
esp_err_t ret = ESP_OK;
int dp_slp_chan_id = -1;
touch_hal_sample_config_t sample_cfg[TOUCH_SAMPLE_CFG_NUM] = {};
touch_hal_config_t hal_cfg = {
.sample_cfg = sample_cfg,
};
touch_hal_config_t *hal_cfg_ptr = NULL;
xSemaphoreTake(sens_handle->mutex, portMAX_DELAY);
ESP_GOTO_ON_FALSE(!sens_handle->is_enabled, ESP_ERR_INVALID_STATE, err, TAG, "Please disable the touch sensor first");
if (sleep_cfg) {
ESP_GOTO_ON_FALSE(sleep_cfg->slp_wakeup_lvl == TOUCH_LIGHT_SLEEP_WAKEUP || sleep_cfg->slp_wakeup_lvl == TOUCH_DEEP_SLEEP_WAKEUP,
ESP_ERR_INVALID_ARG, err, TAG, "Invalid sleep level");
/* Enabled touch sensor as wake-up source */
ESP_GOTO_ON_ERROR(esp_sleep_enable_touchpad_wakeup(), err, TAG, "Failed to enable touch sensor wakeup");
#if SOC_PM_SUPPORT_RC_FAST_PD
ESP_GOTO_ON_ERROR(esp_sleep_pd_config(ESP_PD_DOMAIN_RC_FAST, ESP_PD_OPTION_ON), err, TAG, "Failed to keep touch sensor module clock during the sleep");
#endif
/* If set the deep sleep channel (i.e., enable deep sleep wake-up),
configure the deep sleep related settings. */
if (sleep_cfg->slp_wakeup_lvl == TOUCH_DEEP_SLEEP_WAKEUP) {
ESP_GOTO_ON_FALSE(sleep_cfg->deep_slp_chan, ESP_ERR_INVALID_ARG, err, TAG, "deep sleep waken channel can't be NULL");
dp_slp_chan_id = sleep_cfg->deep_slp_chan->id;
/* Check and convert the configuration to hal configurations */
if (sleep_cfg->deep_slp_sens_cfg) {
hal_cfg_ptr = &hal_cfg;
ESP_GOTO_ON_ERROR(s_touch_convert_to_hal_config(sens_handle, (const touch_sensor_config_t *)sleep_cfg->deep_slp_sens_cfg, hal_cfg_ptr),
err, TAG, "parse the configuration failed due to the invalid configuration");
}
sens_handle->sleep_en = true;
sens_handle->deep_slp_chan = sleep_cfg->deep_slp_chan;
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
/* Set sleep threshold */
for (uint8_t smp_cfg_id = 0; smp_cfg_id < TOUCH_SAMPLE_CFG_NUM; smp_cfg_id++) {
touch_ll_sleep_set_threshold(smp_cfg_id, sleep_cfg->deep_slp_thresh[smp_cfg_id]);
}
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
}
} else {
/* Disable the touch sensor as wake-up source */
esp_sleep_disable_wakeup_source(ESP_SLEEP_WAKEUP_TOUCHPAD);
#if SOC_PM_SUPPORT_RC_FAST_PD
esp_sleep_pd_config(ESP_PD_DOMAIN_RC_FAST, ESP_PD_OPTION_AUTO);
#endif
sens_handle->sleep_en = false;
}
/* Save or update the sleep config */
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
touch_hal_save_sleep_config(dp_slp_chan_id, hal_cfg_ptr);
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
err:
xSemaphoreGive(sens_handle->mutex);
return ret;
}
// Water proof can be enabled separately
esp_err_t touch_sensor_config_waterproof(touch_sensor_handle_t sens_handle, const touch_waterproof_config_t *wp_cfg)
{
TOUCH_NULL_POINTER_CHECK(sens_handle);
esp_err_t ret = ESP_OK;
xSemaphoreTake(sens_handle->mutex, portMAX_DELAY);
ESP_GOTO_ON_FALSE(!sens_handle->is_enabled, ESP_ERR_INVALID_STATE, err, TAG, "Please disable the touch sensor first");
if (wp_cfg) {
// Check the validation of the waterproof configuration
TOUCH_NULL_POINTER_CHECK(wp_cfg->shield_chan);
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
sens_handle->waterproof_en = true;
sens_handle->immersion_proof = wp_cfg->flags.immersion_proof;
sens_handle->guard_chan = wp_cfg->guard_chan;
sens_handle->shield_chan = wp_cfg->shield_chan;
touch_ll_waterproof_set_guard_chan(wp_cfg->guard_chan ? wp_cfg->guard_chan->id : TOUCH_LL_NULL_CHANNEL);
touch_ll_waterproof_set_shield_chan_mask(BIT(wp_cfg->shield_chan->id));
// need to disable the scanning of the shield channel
touch_ll_enable_scan_mask(BIT(wp_cfg->shield_chan->id), false);
touch_ll_waterproof_set_shield_driver(wp_cfg->shield_drv);
touch_ll_waterproof_enable(true);
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
} else {
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
touch_ll_waterproof_enable(false);
touch_ll_waterproof_set_guard_chan(TOUCH_LL_NULL_CHANNEL);
touch_ll_waterproof_set_shield_chan_mask(0);
if (sens_handle->shield_chan) {
touch_ll_enable_scan_mask(BIT(sens_handle->shield_chan->id), true);
}
touch_ll_waterproof_set_shield_driver(0);
sens_handle->guard_chan = NULL;
sens_handle->shield_chan = NULL;
sens_handle->immersion_proof = false;
sens_handle->waterproof_en = false;
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
}
err:
xSemaphoreGive(sens_handle->mutex);
return ret;
}
esp_err_t touch_sensor_config_proximity_sensing(touch_sensor_handle_t sens_handle, const touch_proximity_config_t *prox_cfg)
{
TOUCH_NULL_POINTER_CHECK(sens_handle);
esp_err_t ret = ESP_OK;
xSemaphoreTake(sens_handle->mutex, portMAX_DELAY);
ESP_GOTO_ON_FALSE(!sens_handle->is_enabled, ESP_ERR_INVALID_STATE, err, TAG, "Please disable the touch sensor first");
TOUCH_ENTER_CRITICAL(TOUCH_PERIPH_LOCK);
/* Reset proximity sensing part of all channels */
FOR_EACH_TOUCH_CHANNEL(i) {
if (sens_handle->ch[i] && sens_handle->ch[i]->is_prox_chan) {
sens_handle->ch[i]->is_prox_chan = false;
sens_handle->ch[i]->prox_cnt = 0;
for (int i = 0; i < TOUCH_SAMPLE_CFG_NUM; i++) {
sens_handle->ch[i]->prox_val[i] = 0;
}
}
}
if (prox_cfg) {
sens_handle->proximity_en = true;
uint8_t sample_cfg_num = sens_handle->sample_cfg_num;
for (int i = 0; i < TOUCH_PROXIMITY_CHAN_NUM; i++) {
if (prox_cfg->proximity_chan[i]) {
prox_cfg->proximity_chan[i]->is_prox_chan = true;
touch_ll_set_proximity_sensing_channel(i, prox_cfg->proximity_chan[i]->id);
} else {
touch_ll_set_proximity_sensing_channel(i, TOUCH_LL_NULL_CHANNEL);
}
}
touch_ll_proximity_set_total_scan_times(prox_cfg->scan_times * sample_cfg_num);
for (uint8_t smp_cfg_id = 0; smp_cfg_id < sample_cfg_num; smp_cfg_id++) {
touch_ll_proximity_set_charge_times(smp_cfg_id, prox_cfg->charge_times[smp_cfg_id]);
}
} else {
for (int i = 0; i < TOUCH_PROXIMITY_CHAN_NUM; i++) {
touch_ll_set_proximity_sensing_channel(i, TOUCH_LL_NULL_CHANNEL);
}
sens_handle->proximity_en = false;
}
TOUCH_EXIT_CRITICAL(TOUCH_PERIPH_LOCK);
err:
xSemaphoreGive(sens_handle->mutex);
return ret;
}

View File

@ -0,0 +1,294 @@
/*
* SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include "esp_err.h"
#include "driver/touch_sens_types.h"
#include "driver/touch_version_types.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Allocate a new touch sensor controller
* @note The touch sensor driver will be in INIT state after this function is called successfully.
*
* @param[in] sens_cfg Touch sensor controller configurations
* @param[out] ret_sens_handle The return handle of the touch controller instance
* @return
* - ESP_OK On success
* - ESP_ERR_NO_MEM No memory for the touch sensor controller
* - ESP_ERR_INVALID_ARG Invalid argument or NULL pointer
* - ESP_ERR_INVALID_STATE The touch sensor controller is already allocated
*/
esp_err_t touch_sensor_new_controller(const touch_sensor_config_t *sens_cfg, touch_sensor_handle_t *ret_sens_handle);
/**
* @brief Delete the touch sensor controller
* @note This function can be called when the touch sensor controller is NOT enabled (i.e. INIT state).
*
* @param[in] sens_handle Touch sensor controller handle
* @return
* - ESP_OK On success
* - ESP_ERR_INVALID_ARG Invalid argument or NULL pointer
* - ESP_ERR_INVALID_STATE Controller not disabled or still some touch channels not deleted
*/
esp_err_t touch_sensor_del_controller(touch_sensor_handle_t sens_handle);
/**
* @brief Allocate a new touch channel from the touch sensor controller
* @note This function can be called when the touch sensor controller is NOT enabled (i.e. INIT state).
*
* @param[in] sens_handle Touch sensor controller handle
* @param[in] chan_id Touch channel index
* @param[in] chan_cfg Touch channel configurations
* @param[out] ret_chan_handle The return handle of the touch channel instance
* @return
* - ESP_OK On success
* - ESP_ERR_NO_MEM No memory for the touch sensor channel
* - ESP_ERR_INVALID_ARG Invalid argument or NULL pointer
* - ESP_ERR_INVALID_STATE The touch sensor controller has not disabled or this channel has been allocated
*/
esp_err_t touch_sensor_new_channel(touch_sensor_handle_t sens_handle, int chan_id,
const touch_channel_config_t *chan_cfg,
touch_channel_handle_t *ret_chan_handle);
/**
* @brief Delete the touch channel
* @note This function can be called when the touch sensor controller is NOT enabled (i.e. INIT state).
*
* @param[in] chan_handle Touch channel handle
* @return
* - ESP_OK On success
* - ESP_ERR_INVALID_ARG Invalid argument or NULL pointer
* - ESP_ERR_INVALID_STATE The touch sensor controller has not disabled
*/
esp_err_t touch_sensor_del_channel(touch_channel_handle_t chan_handle);
/**
* @brief Re-configure the touch sensor controller
* @note This function can be called when the touch sensor controller is NOT enabled (i.e. INIT state).
* @note The re-configuration only applies to the touch controller,
* so it requires the controller handle that allocated from ``touch_sensor_new_controller``,
* meanwhile, it won't affect the touch channels, no matter the channels are allocated or not.
*
* @param[in] sens_handle Touch sensor controller handle
* @param[in] sens_cfg Touch sensor controller configurations
* @return
* - ESP_OK On success
* - ESP_ERR_INVALID_ARG Invalid argument or NULL pointer
* - ESP_ERR_INVALID_STATE The touch sensor controller has not disabled
*/
esp_err_t touch_sensor_reconfig_controller(touch_sensor_handle_t sens_handle, const touch_sensor_config_t *sens_cfg);
/**
* @brief Re-configure the touch channel
* @note This function can be called when the touch sensor controller is NOT enabled (i.e. INIT state).
* @note The re-configuration only applies to a particular touch channel,
* so it requires the channel handle that allocated from ``touch_sensor_new_channel``
*
* @param[in] chan_handle Touch channel handle
* @param[in] chan_cfg Touch channel configurations
* @return
* - ESP_OK On success
* - ESP_ERR_INVALID_ARG Invalid argument or NULL pointer
* - ESP_ERR_INVALID_STATE The touch sensor controller has not disabled
*/
esp_err_t touch_sensor_reconfig_channel(touch_channel_handle_t chan_handle, const touch_channel_config_t *chan_cfg);
/**
* @brief Configure the touch sensor filter
* @note This function is allowed to be called after the touch sensor is enabled
*
* @param[in] sens_handle Touch sensor controller handle
* @param[in] filter_cfg Filter configurations, set NULL to disable the filter
* @return
* - ESP_OK: Configure the filter success
* - ESP_ERR_INVALID_ARG: The sensor handle is NULL
*/
esp_err_t touch_sensor_config_filter(touch_sensor_handle_t sens_handle, const touch_sensor_filter_config_t *filter_cfg);
/**
* @brief Enable the touch sensor controller
* @note This function can be called when the touch sensor controller is NOT enabled (i.e. INIT state).
* And the touch sensor driver will be in ENABLED state after this function is called successfully.
* @note Enable the touch sensor will power on the registered touch channels
*
* @param[in] sens_handle Touch sensor controller handle
* @return
* - ESP_OK On success
* - ESP_ERR_INVALID_ARG Invalid argument or NULL pointer
* - ESP_ERR_INVALID_STATE The touch sensor controller has already enabled
*/
esp_err_t touch_sensor_enable(touch_sensor_handle_t sens_handle);
/**
* @brief Disable the touch sensor controller
* @note This function can only be called after the touch sensor controller is enabled (i.e. ENABLED state).
* And the touch sensor driver will be in INIT state after this function is called successfully.
* @note Disable the touch sensor will power off the registered touch channels
*
* @param[in] sens_handle Touch sensor controller handle
* @return
* - ESP_OK On success
* - ESP_ERR_INVALID_ARG Invalid argument or NULL pointer
* - ESP_ERR_INVALID_STATE The touch sensor controller has already disabled
*/
esp_err_t touch_sensor_disable(touch_sensor_handle_t sens_handle);
/**
* @brief Start the scanning of the registered touch channels continuously
* @note This function can only be called after the touch sensor controller is enabled (i.e. ENABLED state).
* And the touch sensor driver will be in SCANNING state after this function is called successfully.
* And it can also be called in ISR/callback context.
* @note The hardware FSM (Finite-State Machine) of touch sensor will be driven by
* its hardware timer continuously and repeatedly.
* i.e., the registered channels will be scanned one by one repeatedly.
*
* @param[in] sens_handle Touch sensor controller handle
* @return
* - ESP_OK On success
* - ESP_ERR_INVALID_ARG Invalid argument or NULL pointer
* - ESP_ERR_INVALID_STATE The touch sensor controller is not enabled or the continuous scanning has started
*/
esp_err_t touch_sensor_start_continuous_scanning(touch_sensor_handle_t sens_handle);
/**
* @brief Stop the continuous scanning of the registered touch channels immediately
* @note This function can only be called after the continuous scanning started (i.e. SCANNING state).
* And the touch sensor driver will be in ENABLED state after this function is called successfully.
* And it can also be called in ISR/callback context.
* @note Stop the hardware timer and reset the FSM (Finite-State Machine) of the touch sensor controller
*
* @param[in] sens_handle Touch sensor controller handle
* @return
* - ESP_OK On success
* - ESP_ERR_INVALID_ARG Invalid argument or NULL pointer
* - ESP_ERR_INVALID_STATE The continuous scanning has stopped
*/
esp_err_t touch_sensor_stop_continuous_scanning(touch_sensor_handle_t sens_handle);
/**
* @brief Trigger an oneshot scanning for all the registered channels
* @note This function can only be called after the touch sensor controller is enabled (i.e. ENABLED state).
* And the touch sensor driver will be in SCANNING state after this function is called successfully,
* and then switch back to ENABLED state after the scanning is done or timeout.
* @note The block time of this function depends on various factors,
* In common practice, recommend to set the timeout to several seconds or wait forever,
* because oneshot scanning can't last for so long.
*
* @param[in] sens_handle Touch sensor controller handle
* @param[in] timeout_ms Set a positive value or zero means scan timeout in milliseconds
* Set a negative value means wait forever until finished scanning
* @return
* - ESP_OK On success
* - ESP_ERR_TIMEOUT Timeout to finish the oneshot scanning
* - ESP_ERR_INVALID_ARG Invalid argument
* - ESP_ERR_INVALID_STATE The touch sensor controller is not enabled or the continuous scanning has started
*/
esp_err_t touch_sensor_trigger_oneshot_scanning(touch_sensor_handle_t sens_handle, int timeout_ms);
/**
* @brief Register the touch sensor callbacks
* @note This function can be called when the touch sensor controller is NOT enabled (i.e. INIT state).
*
* @param[in] sens_handle Touch sensor controller handle
* @param[in] callbacks Callback functions
* @param[in] user_ctx User context that will be passed to the callback functions
* @return
* - ESP_OK On success
* - ESP_ERR_INVALID_ARG NULL pointer
* - ESP_ERR_INVALID_STATE Touch sensor controller has not disabled
*/
esp_err_t touch_sensor_register_callbacks(touch_sensor_handle_t sens_handle, const touch_event_callbacks_t *callbacks, void *user_ctx);
/**
* @brief Confiture the touch sensor benchmark for all the registered channels
* @note This function can be called no matter the touch sensor controller is enabled or not (i.e. ENABLED or SCANNING state).
* And it can also be called in ISR/callback context.
*
* @param[in] chan_handle Touch channel handle
* @param[in] benchmark_cfg The benchmark configurations
* @return
* - ESP_OK On success
* - ESP_ERR_INVALID_ARG NULL pointer
*/
esp_err_t touch_channel_config_benchmark(touch_channel_handle_t chan_handle, const touch_chan_benchmark_config_t *benchmark_cfg);
/**
* @brief Read the touch channel data according to the types
* @note This function can be called no matter the touch sensor controller is enabled or not (i.e. ENABLED or SCANNING state).
* And it can also be called in ISR/callback context.
* @note Specially, `TOUCH_CHAN_DATA_TYPE_PROXIMITY` data type will be read from the cached data in the driver,
* because the proximity data need to be accumulated in several scan times that specified by `touch_proximity_config_t::scan_times`.
* For other data types, the data are read from the hardware registers directly (not cached in the driver).
* The channel data in the register will be updated once the measurement of this channels is done,
* And keep locked until the next measurement is done.
*
* @param[in] chan_handle Touch channel handle
* @param[in] type Specify the data type to read
* @param[out] data The data array pointer. If the target supports multiple sample configurations (SOC_TOUCH_SAMPLE_CFG_NUM), the array length should be equal to
* the frequency hopping number that specified in `touch_sensor_config_t::sample_cfg_num`, otherwise the array length should be 1.
* @return
* - ESP_OK On success
* - ESP_ERR_INVALID_ARG Invalid argument or NULL pointer
*/
esp_err_t touch_channel_read_data(touch_channel_handle_t chan_handle, touch_chan_data_type_t type, uint32_t *data);
#if SOC_TOUCH_SUPPORT_WATERPROOF
/**
* @brief Configure the touch sensor water proof channels
* @note Once waterproof is enabled, the other touch channels won't be updated unless the shield channels is activated.
*
* @param[in] sens_handle Touch sensor controller handle
* @param[in] wp_cfg Water proof channel configurations, set NULL to disable the water proof function
* @return
* - ESP_OK: Configure the water proof success
* - ESP_ERR_INVALID_ARG: The sensor handle is NULL
* - ESP_ERR_INVALID_STATE: The touch sensor is enabled
*/
esp_err_t touch_sensor_config_waterproof(touch_sensor_handle_t sens_handle, const touch_waterproof_config_t *wp_cfg);
#endif
#if SOC_TOUCH_SUPPORT_PROX_SENSING
/**
* @brief Configure the touch sensor proximity sensing channels
*
* @param[in] sens_handle Touch sensor controller handle
* @param[in] prox_cfg Proximity channels configurations, set NULL to disable the proximity sensing
* @return
* - ESP_OK: Configure the proximity channel success
* - ESP_ERR_INVALID_ARG: The sensor handle is NULL
* - ESP_ERR_INVALID_STATE: The touch sensor is enabled
*/
esp_err_t touch_sensor_config_proximity_sensing(touch_sensor_handle_t sens_handle, const touch_proximity_config_t *prox_cfg);
#endif
#if SOC_TOUCH_SUPPORT_SLEEP_WAKEUP
/**
* @brief Configure the touch sensor to wake-up the chip from sleep
* @note Call this function to enable/disable the touch sensor wake-up the chip from deep/light sleep
* To only enable the touch sensor wake-up the chip from light sleep, set the `touch_sleep_config_t::deep_slp_chan` to NULL.
* During the light sleep, all enabled touch channels will keep working, and any one of them can wake-up the chip from light sleep.
* To enable the touch sensor wake-up the chip from both light and deep sleep, set the `touch_sleep_config_t::deep_slp_chan` to an enabled channel.
* During the deep sleep, only this specified channels can work and wake-up the chip from the deep sleep,
* and other enabled channels can only wake-up the chip from light sleep.
*
* @param[in] sens_handle Touch sensor controller handle
* @param[in] sleep_cfg Sleep wake-up configurations, set NULL to disable the touch sensor wake-up the chip from sleep
* @return
* - ESP_OK: Configure the sleep channel success
* - ESP_ERR_INVALID_ARG: The sensor handle is NULL
* - ESP_ERR_INVALID_STATE: The touch sensor is enabled
*/
esp_err_t touch_sensor_config_sleep_wakeup(touch_sensor_handle_t sens_handle, const touch_sleep_config_t *sleep_cfg);
#endif
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,30 @@
/*
* SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#pragma once
#include <stdint.h>
#include <stdbool.h>
#include <stddef.h>
#include "soc/soc_caps.h"
#include "hal/touch_sensor_types.h"
#ifdef __cplusplus
extern "C" {
#endif
#define TOUCH_TOTAL_CHAN_NUM SOC_TOUCH_SENSOR_NUM /*!< The total channel number of the touch sensor */
#define TOUCH_SAMPLE_CFG_NUM SOC_TOUCH_SAMPLE_CFG_NUM /*!< The supported max sample configuration number */
#if SOC_TOUCH_SUPPORT_PROX_SENSING
#define TOUCH_PROXIMITY_CHAN_NUM SOC_TOUCH_PROXIMITY_CHANNEL_NUM /*!< The supported proximity channel number in proximity sensing mode */
#endif
typedef struct touch_sensor_s *touch_sensor_handle_t; /*!< The handle of touch sensor controller */
typedef struct touch_channel_s *touch_channel_handle_t; /*!< The handle of touch channel */
#ifdef __cplusplus
}
#endif

View File

@ -0,0 +1,10 @@
[mapping:touch_sens_driver]
archive: libesp_driver_touch_sens.a
entries:
if TOUCH_CTRL_FUNC_IN_IRAM = y:
touch_sens_common: touch_sensor_start_continuous_scanning (noflash)
touch_sens_common: touch_sensor_stop_continuous_scanning (noflash)
touch_sens_common: touch_channel_read_data (noflash)
touch_sens_common: touch_channel_config_benchmark (noflash)
touch_sens_version_specific: touch_priv_channel_read_data (noflash)
touch_sens_version_specific: touch_priv_config_benchmark (noflash)

View File

@ -0,0 +1,10 @@
components/esp_driver_touch_sens/test_apps/touch_sens:
disable:
- if: SOC_TOUCH_SENSOR_VERSION != 3
temporary: currently driver ng only support version 3
disable_test:
- if: IDF_TARGET == "esp32p4"
temporary: true
reason: the runners do not support the pins for touch sensor
depends_components:
- esp_driver_touch_sens

View File

@ -0,0 +1,22 @@
# For more information about build system see
# https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html
# The following five lines of boilerplate have to be in your project's
# CMakeLists in this exact order for cmake to work correctly
cmake_minimum_required(VERSION 3.16)
set(COMPONENTS main)
include($ENV{IDF_PATH}/tools/cmake/project.cmake)
project(touch_sens)
if(CONFIG_COMPILER_DUMP_RTL_FILES)
add_custom_target(check_test_app_sections ALL
COMMAND ${PYTHON} $ENV{IDF_PATH}/tools/ci/check_callgraph.py
--rtl-dirs ${CMAKE_BINARY_DIR}/esp-idf/esp_driver_touch_sens/,${CMAKE_BINARY_DIR}/esp-idf/hal/
--elf-file ${CMAKE_BINARY_DIR}/touch_sens.elf
find-refs
--from-sections=.iram0.text
--to-sections=.flash.text,.flash.rodata
--exit-code
DEPENDS ${elf}
)
endif()

View File

@ -0,0 +1,3 @@
| Supported Targets | ESP32-P4 |
| ----------------- | -------- |

View File

@ -0,0 +1,6 @@
set(srcs "test_app_main.c" "test_touch_sens_common.c")
idf_component_register(SRCS ${srcs}
INCLUDE_DIRS "."
PRIV_REQUIRES unity esp_driver_touch_sens
WHOLE_ARCHIVE)

View File

@ -0,0 +1,53 @@
/*
* SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include "unity.h"
#include "unity_test_runner.h"
#include "esp_heap_caps.h"
// Some resources are lazy allocated in Touch Sensor driver, the threshold is left for that case
#define TEST_MEMORY_LEAK_THRESHOLD (-300)
static size_t before_free_8bit;
static size_t before_free_32bit;
static void check_leak(size_t before_free, size_t after_free, const char *type)
{
ssize_t delta = after_free - before_free;
printf("MALLOC_CAP_%s: Before %u bytes free, After %u bytes free (delta %d)\n", type, before_free, after_free, delta);
TEST_ASSERT_MESSAGE(delta >= TEST_MEMORY_LEAK_THRESHOLD, "memory leak");
}
void setUp(void)
{
before_free_8bit = heap_caps_get_free_size(MALLOC_CAP_8BIT);
before_free_32bit = heap_caps_get_free_size(MALLOC_CAP_32BIT);
}
void tearDown(void)
{
size_t after_free_8bit = heap_caps_get_free_size(MALLOC_CAP_8BIT);
size_t after_free_32bit = heap_caps_get_free_size(MALLOC_CAP_32BIT);
check_leak(before_free_8bit, after_free_8bit, "8BIT");
check_leak(before_free_32bit, after_free_32bit, "32BIT");
}
void app_main(void)
{
// _____ _ ____ _____ _
// |_ _|__ _ _ ___| |__ / ___| ___ _ __ ___ ___ _ __ |_ _|__ ___| |_
// | |/ _ \| | | |/ __| '_ \ \___ \ / _ \ '_ \/ __|/ _ \| '__| | |/ _ \/ __| __|
// | | (_) | |_| | (__| | | | ___) | __/ | | \__ \ (_) | | | | __/\__ \ |_
// |_|\___/ \__,_|\___|_| |_| |____/ \___|_| |_|___/\___/|_| |_|\___||___/\__|
printf(" _____ _ ____ _____ _ \n");
printf(" |_ _|__ _ _ ___| |__ / ___| ___ _ __ ___ ___ _ __ |_ _|__ ___| |_ \n");
printf(" | |/ _ \\| | | |/ __| '_ \\ \\___ \\ / _ \\ '_ \\/ __|/ _ \\| '__| | |/ _ \\/ __| __|\n");
printf(" | | (_) | |_| | (__| | | | ___) | __/ | | \\__ \\ (_) | | | | __/\\__ \\ |_ \n");
printf(" |_|\\___/ \\__,_|\\___|_| |_| |____/ \\___|_| |_|___/\\___/|_| |_|\\___||___/\\__|\n");
unity_run_menu();
}

View File

@ -0,0 +1,198 @@
/*
* SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <inttypes.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "unity.h"
#include "driver/touch_sens.h"
#include "hal/touch_sensor_ll.h"
#include "esp_log.h"
#include "esp_attr.h"
static touch_sensor_sample_config_t s_sample_cfg[TOUCH_SAMPLE_CFG_NUM] = {
TOUCH_SENSOR_V3_DEFAULT_SAMPLE_CONFIG(1, 1, 1),
#if TOUCH_SAMPLE_CFG_NUM > 1
TOUCH_SENSOR_V3_DEFAULT_SAMPLE_CONFIG(2, 1, 1),
#endif
#if TOUCH_SAMPLE_CFG_NUM > 2
TOUCH_SENSOR_V3_DEFAULT_SAMPLE_CONFIG(4, 1, 1),
#endif
};
static touch_channel_config_t s_chan_cfg = {
.active_thresh = {
5000,
#if TOUCH_SAMPLE_CFG_NUM > 1
2500,
#endif
#if TOUCH_SAMPLE_CFG_NUM > 2
1000,
#endif
},
};
TEST_CASE("touch_sens_install_uninstall_test", "[touch]")
{
touch_sensor_handle_t touch = NULL;
touch_channel_handle_t touch_chan[TOUCH_TOTAL_CHAN_NUM] = {NULL};
touch_sensor_config_t sens_cfg = TOUCH_SENSOR_DEFAULT_BASIC_CONFIG(TOUCH_SAMPLE_CFG_NUM, s_sample_cfg);
/* Allocate new controller */
TEST_ESP_OK(touch_sensor_new_controller(&sens_cfg, &touch));
TEST_ASSERT(touch_sensor_new_controller(&sens_cfg, &touch) == ESP_ERR_INVALID_STATE);
/* Configuring the filter */
touch_sensor_filter_config_t filter_cfg = TOUCH_SENSOR_DEFAULT_FILTER_CONFIG();
TEST_ESP_OK(touch_sensor_config_filter(touch, &filter_cfg));
for (int i = 0; i < TOUCH_TOTAL_CHAN_NUM; i++) {
TEST_ESP_OK(touch_sensor_new_channel(touch, i, &s_chan_cfg, &touch_chan[i]));
}
touch_channel_handle_t fault_chan = NULL;
TEST_ASSERT(touch_sensor_new_channel(touch, TOUCH_TOTAL_CHAN_NUM, &s_chan_cfg, &fault_chan) == ESP_ERR_INVALID_ARG);
TEST_ASSERT(touch_sensor_new_channel(touch, 0, &s_chan_cfg, &fault_chan) == ESP_ERR_INVALID_STATE);
TEST_ESP_OK(touch_sensor_enable(touch));
TEST_ASSERT(touch_sensor_del_channel(touch_chan[0]) == ESP_ERR_INVALID_STATE);
TEST_ESP_OK(touch_sensor_disable(touch));
TEST_ASSERT(touch_sensor_del_controller(touch) == ESP_ERR_INVALID_STATE);
for (int i = 0; i < TOUCH_TOTAL_CHAN_NUM; i++) {
TEST_ESP_OK(touch_sensor_del_channel(touch_chan[i]));
}
TEST_ESP_OK(touch_sensor_del_controller(touch));
}
typedef struct {
int active_count;
int inactive_count;
} test_touch_cb_data_t;
static touch_channel_config_t s_test_get_chan_cfg_by_benchmark(uint32_t benchmark[], uint32_t num, float coeff)
{
touch_channel_config_t chan_cfg = {};
for (int i = 0; i < num; i++) {
chan_cfg.active_thresh[i] = benchmark[i] * coeff;
printf("[Sampler %d] benchmark %5"PRIu32" thresh %4"PRIu32"\n",
i, benchmark[i], chan_cfg.active_thresh[i]);
}
return chan_cfg;
}
static void s_test_touch_do_initial_scanning(touch_sensor_handle_t touch, int scan_times)
{
/* Enable the touch sensor to do the initial scanning, so that to initialize the channel data */
TEST_ESP_OK(touch_sensor_enable(touch));
/* Scan the enabled touch channels for several times, to make sure the initial channel data is stable */
for (int i = 0; i < scan_times; i++) {
TEST_ESP_OK(touch_sensor_trigger_oneshot_scanning(touch, 2000));
}
/* Disable the touch channel to rollback the state */
TEST_ESP_OK(touch_sensor_disable(touch));
}
#if CONFIG_TOUCH_ISR_IRAM_SAFE
#define TEST_TCH_IRAM_ATTR IRAM_ATTR
#else
#define TEST_TCH_IRAM_ATTR
#endif
static bool TEST_TCH_IRAM_ATTR s_test_touch_on_active_callback(touch_sensor_handle_t sens_handle, const touch_active_event_data_t *event, void *user_ctx)
{
ESP_EARLY_LOGI("touch_callback", "[CH %d] active", (int)event->chan_id);
test_touch_cb_data_t *cb_data = (test_touch_cb_data_t *)user_ctx;
cb_data->active_count++;
return false;
}
static bool TEST_TCH_IRAM_ATTR s_test_touch_on_inactive_callback(touch_sensor_handle_t sens_handle, const touch_inactive_event_data_t *event, void *user_ctx)
{
ESP_EARLY_LOGI("touch_callback", "[CH %d] inactive", (int)event->chan_id);
test_touch_cb_data_t *cb_data = (test_touch_cb_data_t *)user_ctx;
cb_data->inactive_count++;
return false;
}
static void s_test_touch_simulate_touch(touch_sensor_handle_t touch, touch_channel_handle_t touch_chan, bool active)
{
touch_ll_set_internal_capacitor(active ? 0x7f : 0);
}
static void s_test_touch_log_data(touch_channel_handle_t touch_chan, uint32_t sample_cfg_num, const char *tag)
{
uint32_t data[sample_cfg_num];
TEST_ESP_OK(touch_channel_read_data(touch_chan, TOUCH_CHAN_DATA_TYPE_SMOOTH, data));
printf("%s:", tag);
for (int i = 0; i < sample_cfg_num; i++) {
printf(" %"PRIu32, data[i]);
}
printf("\n");
}
#define TEST_ACTIVE_THRESH_RATIO (0.01f)
TEST_CASE("touch_sens_active_inactive_test", "[touch]")
{
touch_sensor_handle_t touch = NULL;
touch_channel_handle_t touch_chan = NULL;
touch_sensor_config_t sens_cfg = TOUCH_SENSOR_DEFAULT_BASIC_CONFIG(TOUCH_SAMPLE_CFG_NUM, s_sample_cfg);
TEST_ESP_OK(touch_sensor_new_controller(&sens_cfg, &touch));
/* Configuring the filter */
touch_sensor_filter_config_t filter_cfg = TOUCH_SENSOR_DEFAULT_FILTER_CONFIG();
TEST_ESP_OK(touch_sensor_config_filter(touch, &filter_cfg));
TEST_ESP_OK(touch_sensor_new_channel(touch, 0, &s_chan_cfg, &touch_chan));
/* Connect the touch channels to the internal capacitor */
touch_ll_enable_internal_capacitor(true);
s_test_touch_do_initial_scanning(touch, 3);
/* Read benchmark */
uint32_t benchmark[TOUCH_SAMPLE_CFG_NUM] = {0};
TEST_ESP_OK(touch_channel_read_data(touch_chan, TOUCH_CHAN_DATA_TYPE_BENCHMARK, benchmark));
/* Re-configure the threshold according to the benchmark */
touch_channel_config_t chan_cfg = s_test_get_chan_cfg_by_benchmark(benchmark, TOUCH_SAMPLE_CFG_NUM, TEST_ACTIVE_THRESH_RATIO);
TEST_ESP_OK(touch_sensor_reconfig_channel(touch_chan, &chan_cfg));
touch_event_callbacks_t callbacks = {
.on_active = s_test_touch_on_active_callback,
.on_inactive = s_test_touch_on_inactive_callback,
};
test_touch_cb_data_t cb_data = {};
TEST_ESP_OK(touch_sensor_register_callbacks(touch, &callbacks, &cb_data));
TEST_ESP_OK(touch_sensor_enable(touch));
TEST_ESP_OK(touch_sensor_start_continuous_scanning(touch));
vTaskDelay(pdMS_TO_TICKS(20));
int touch_cnt = 3;
for (int i = 0; i < touch_cnt; i++) {
printf("\nSimulate Touch [%d] ->\n--------------------------\n", i + 1);
// Read data before touched
s_test_touch_log_data(touch_chan, TOUCH_SAMPLE_CFG_NUM, "Data Before");
// Simulate touch
s_test_touch_simulate_touch(touch, touch_chan, true);
vTaskDelay(pdMS_TO_TICKS(50));
// Read data after touched
s_test_touch_log_data(touch_chan, TOUCH_SAMPLE_CFG_NUM, "Data After ");
// Simulate release
s_test_touch_simulate_touch(touch, touch_chan, false);
vTaskDelay(pdMS_TO_TICKS(50));
}
printf("\n");
TEST_ESP_OK(touch_sensor_stop_continuous_scanning(touch));
TEST_ESP_OK(touch_sensor_disable(touch));
TEST_ESP_OK(touch_sensor_del_channel(touch_chan));
TEST_ESP_OK(touch_sensor_del_controller(touch));
/* Check the callback count */
TEST_ASSERT_EQUAL_INT32(touch_cnt, cb_data.active_count);
TEST_ASSERT_EQUAL_INT32(touch_cnt, cb_data.inactive_count);
}

View File

@ -0,0 +1,19 @@
# SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD
# SPDX-License-Identifier: CC0-1.0
import pytest
from pytest_embedded import Dut
@pytest.mark.esp32p4
@pytest.mark.temp_skip_ci(targets=['esp32p4'], reason='esp32p4 runners do not support touch pins')
@pytest.mark.generic
@pytest.mark.parametrize(
'config',
[
'release',
'iram_safe',
],
indirect=True,
)
def test_touch_sens(dut: Dut) -> None:
dut.run_all_single_board_cases()

View File

@ -0,0 +1,7 @@
CONFIG_COMPILER_DUMP_RTL_FILES=y
CONFIG_TOUCH_CTRL_FUNC_IN_IRAM=y
CONFIG_TOUCH_ISR_IRAM_SAFE=y
CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_DISABLE=y
CONFIG_COMPILER_OPTIMIZATION_NONE=y
# silent the error check, as the error string are stored in rodata, causing RTL check failure
CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT=y

View File

@ -0,0 +1,5 @@
CONFIG_PM_ENABLE=y
CONFIG_FREERTOS_USE_TICKLESS_IDLE=y
CONFIG_COMPILER_OPTIMIZATION_SIZE=y
CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_SIZE=y
CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT=y

View File

@ -0,0 +1,2 @@
CONFIG_FREERTOS_HZ=1000
CONFIG_ESP_TASK_WDT=n

View File

@ -94,6 +94,12 @@ typedef enum {
#define RTC_BT_TRIG_EN 0 #define RTC_BT_TRIG_EN 0
#endif #endif
#if SOC_TOUCH_SENSOR_SUPPORTED
#define RTC_TOUCH_TRIG_EN PMU_TOUCH_WAKEUP_EN //!< TOUCH wakeup
#else
#define RTC_TOUCH_TRIG_EN 0
#endif
#define RTC_USB_TRIG_EN PMU_USB_WAKEUP_EN #define RTC_USB_TRIG_EN PMU_USB_WAKEUP_EN
#if SOC_LP_CORE_SUPPORTED #if SOC_LP_CORE_SUPPORTED
@ -117,6 +123,7 @@ typedef enum {
RTC_UART1_TRIG_EN | \ RTC_UART1_TRIG_EN | \
RTC_BT_TRIG_EN | \ RTC_BT_TRIG_EN | \
RTC_LP_CORE_TRIG_EN | \ RTC_LP_CORE_TRIG_EN | \
RTC_TOUCH_TRIG_EN | \
RTC_XTAL32K_DEAD_TRIG_EN | \ RTC_XTAL32K_DEAD_TRIG_EN | \
RTC_USB_TRIG_EN | \ RTC_USB_TRIG_EN | \
RTC_BROWNOUT_DET_TRIG_EN) RTC_BROWNOUT_DET_TRIG_EN)

View File

@ -286,7 +286,7 @@ static void ext0_wakeup_prepare(void);
static void ext1_wakeup_prepare(void); static void ext1_wakeup_prepare(void);
#endif #endif
static esp_err_t timer_wakeup_prepare(int64_t sleep_duration); static esp_err_t timer_wakeup_prepare(int64_t sleep_duration);
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3 #if SOC_TOUCH_SENSOR_SUPPORTED && SOC_TOUCH_SENSOR_VERSION != 1
static void touch_wakeup_prepare(void); static void touch_wakeup_prepare(void);
#endif #endif
#if SOC_GPIO_SUPPORT_DEEPSLEEP_WAKEUP #if SOC_GPIO_SUPPORT_DEEPSLEEP_WAKEUP
@ -845,7 +845,7 @@ static esp_err_t IRAM_ATTR esp_sleep_start(uint32_t pd_flags, esp_sleep_mode_t m
misc_modules_sleep_prepare(deep_sleep); misc_modules_sleep_prepare(deep_sleep);
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3 #if SOC_TOUCH_SENSOR_VERSION >= 2
if (deep_sleep) { if (deep_sleep) {
if (s_config.wakeup_triggers & RTC_TOUCH_TRIG_EN) { if (s_config.wakeup_triggers & RTC_TOUCH_TRIG_EN) {
touch_wakeup_prepare(); touch_wakeup_prepare();
@ -860,7 +860,12 @@ static esp_err_t IRAM_ATTR esp_sleep_start(uint32_t pd_flags, esp_sleep_mode_t m
/* In light sleep, the RTC_PERIPH power domain should be in the power-on state (Power on the touch circuit in light sleep), /* In light sleep, the RTC_PERIPH power domain should be in the power-on state (Power on the touch circuit in light sleep),
* otherwise the touch sensor FSM will be cleared, causing touch sensor false triggering. * otherwise the touch sensor FSM will be cleared, causing touch sensor false triggering.
*/ */
if (touch_ll_get_fsm_state()) { // Check if the touch sensor is working properly. #if SOC_TOUCH_SENSOR_VERSION == 3
bool keep_rtc_power_on = touch_ll_is_fsm_repeated_timer_enabled();
#else
bool keep_rtc_power_on = touch_ll_get_fsm_state();
#endif
if (keep_rtc_power_on) { // Check if the touch sensor is working properly.
pd_flags &= ~RTC_SLEEP_PD_RTC_PERIPH; pd_flags &= ~RTC_SLEEP_PD_RTC_PERIPH;
} }
} }
@ -1602,7 +1607,7 @@ static esp_err_t timer_wakeup_prepare(int64_t sleep_duration)
return ESP_OK; return ESP_OK;
} }
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3 #if SOC_TOUCH_SENSOR_VERSION == 2
/* In deep sleep mode, only the sleep channel is supported, and other touch channels should be turned off. */ /* In deep sleep mode, only the sleep channel is supported, and other touch channels should be turned off. */
static void touch_wakeup_prepare(void) static void touch_wakeup_prepare(void)
{ {
@ -1621,6 +1626,11 @@ static void touch_wakeup_prepare(void)
touch_ll_start_fsm(); touch_ll_start_fsm();
} }
} }
#elif SOC_TOUCH_SENSOR_VERSION == 3
static void touch_wakeup_prepare(void)
{
touch_hal_prepare_deep_sleep();
}
#endif #endif
#if SOC_TOUCH_SENSOR_SUPPORTED #if SOC_TOUCH_SENSOR_SUPPORTED
@ -1648,7 +1658,11 @@ touch_pad_t esp_sleep_get_touchpad_wakeup_status(void)
return TOUCH_PAD_MAX; return TOUCH_PAD_MAX;
} }
touch_pad_t pad_num; touch_pad_t pad_num;
#if SOC_TOUCH_SENSOR_VERSION == 3
touch_ll_sleep_get_channel_num((uint32_t *)(&pad_num));
#else
touch_hal_get_wakeup_status(&pad_num); touch_hal_get_wakeup_status(&pad_num);
#endif
return pad_num; return pad_num;
} }

View File

@ -280,26 +280,27 @@ if(NOT BOOTLOADER_BUILD)
"usb_wrap_hal.c") "usb_wrap_hal.c")
endif() endif()
if(CONFIG_SOC_TOUCH_SENSOR_SUPPORTED)
list(APPEND srcs "${target}/touch_sensor_hal.c")
if(CONFIG_SOC_TOUCH_SENSOR_VERSION LESS 3)
list(APPEND srcs "touch_sensor_hal.c")
endif()
endif()
if(${target} STREQUAL "esp32") if(${target} STREQUAL "esp32")
list(APPEND srcs list(APPEND srcs
"touch_sensor_hal.c"
"esp32/touch_sensor_hal.c"
"esp32/gpio_hal_workaround.c") "esp32/gpio_hal_workaround.c")
endif() endif()
if(${target} STREQUAL "esp32s2") if(${target} STREQUAL "esp32s2")
list(APPEND srcs list(APPEND srcs
"touch_sensor_hal.c"
"xt_wdt_hal.c" "xt_wdt_hal.c"
"esp32s2/cp_dma_hal.c" "esp32s2/cp_dma_hal.c")
"esp32s2/touch_sensor_hal.c")
endif() endif()
if(${target} STREQUAL "esp32s3") if(${target} STREQUAL "esp32s3")
list(APPEND srcs list(APPEND srcs
"touch_sensor_hal.c"
"xt_wdt_hal.c" "xt_wdt_hal.c"
"esp32s3/touch_sensor_hal.c"
"esp32s3/rtc_cntl_hal.c") "esp32s3/rtc_cntl_hal.c")
endif() endif()

View File

@ -1,5 +1,5 @@
/* /*
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -229,6 +229,7 @@ static inline void touch_ll_get_tie_option(touch_pad_t touch_num, touch_tie_opt_
* *
* @param mode FSM mode. * @param mode FSM mode.
*/ */
__attribute__((always_inline))
static inline void touch_ll_set_fsm_mode(touch_fsm_mode_t mode) static inline void touch_ll_set_fsm_mode(touch_fsm_mode_t mode)
{ {
SENS.sar_touch_ctrl2.touch_start_fsm_en = 1; SENS.sar_touch_ctrl2.touch_start_fsm_en = 1;
@ -264,6 +265,7 @@ static inline void touch_ll_start_fsm(void)
* *
* @param mode FSM mode. * @param mode FSM mode.
*/ */
__attribute__((always_inline))
static inline void touch_ll_stop_fsm(void) static inline void touch_ll_stop_fsm(void)
{ {
RTCCNTL.state0.touch_slp_timer_en = 0; RTCCNTL.state0.touch_slp_timer_en = 0;
@ -497,7 +499,8 @@ static inline uint32_t touch_ll_read_raw_data(touch_pad_t touch_num)
* @return * @return
* - If touch sensors measure done. * - If touch sensors measure done.
*/ */
static inline bool touch_ll_meas_is_done(void) __attribute__((always_inline))
static inline bool touch_ll_is_measure_done(void)
{ {
return (bool)SENS.sar_touch_ctrl2.touch_meas_done; return (bool)SENS.sar_touch_ctrl2.touch_meas_done;
} }

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 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -18,6 +18,9 @@
#include "hal/assert.h" #include "hal/assert.h"
#include "soc/touch_sensor_periph.h" #include "soc/touch_sensor_periph.h"
#include "soc/lp_analog_peri_struct.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/touch_struct.h"
#include "soc/pmu_struct.h" #include "soc/pmu_struct.h"
#include "soc/soc_caps.h" #include "soc/soc_caps.h"
@ -27,7 +30,6 @@
extern "C" { extern "C" {
#endif #endif
#define TOUCH_LL_READ_RAW 0x0
#define TOUCH_LL_READ_BENCHMARK 0x2 #define TOUCH_LL_READ_BENCHMARK 0x2
#define TOUCH_LL_READ_SMOOTH 0x3 #define TOUCH_LL_READ_SMOOTH 0x3
@ -35,27 +37,41 @@ extern "C" {
#define TOUCH_LL_TIMER_DONE_BY_FSM 0x0 #define TOUCH_LL_TIMER_DONE_BY_FSM 0x0
// Interrupt mask // Interrupt mask
#define TOUCH_LL_INTR_MASK_SCAN_DONE BIT(1) #define TOUCH_LL_INTR_MASK_SCAN_DONE BIT(0)
#define TOUCH_LL_INTR_MASK_DONE BIT(2) #define TOUCH_LL_INTR_MASK_DONE BIT(1)
#define TOUCH_LL_INTR_MASK_ACTIVE BIT(3) #define TOUCH_LL_INTR_MASK_ACTIVE BIT(2)
#define TOUCH_LL_INTR_MASK_INACTIVE BIT(4) #define TOUCH_LL_INTR_MASK_INACTIVE BIT(3)
#define TOUCH_LL_INTR_MASK_TIMEOUT BIT(5) #define TOUCH_LL_INTR_MASK_TIMEOUT BIT(4)
#define TOUCH_LL_INTR_MASK_APPROACH_DONE BIT(6) #define TOUCH_LL_INTR_MASK_PROX_DONE BIT(5)
#define TOUCH_LL_INTR_MASK_ALL (0x3F) #define TOUCH_LL_INTR_MASK_ALL (0x3F)
#define TOUCH_LL_FULL_CHANNEL_MASK ((uint16_t)((1U << SOC_TOUCH_SENSOR_NUM) - 1)) #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_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. * Enable/disable clock gate of touch sensor.
* *
* @param enable true/false. * @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. * 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. * @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. //The times of charge and discharge in each measure process of touch channels.
switch (sampler_id) { switch (sample_cfg_id) {
case 0: case 0:
LP_ANA_PERI.touch_work_meas_num.touch_meas_num0 = charge_times; LP_ANA_PERI.touch_work_meas_num.touch_meas_num0 = charge_times;
break; 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. * @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: case 0:
*charge_times = LP_ANA_PERI.touch_work_meas_num.touch_meas_num0; *charge_times = LP_ANA_PERI.touch_work_meas_num.touch_meas_num0;
break; break;
@ -140,21 +156,21 @@ static inline void touch_ll_get_measure_interval_ticks(uint16_t *interval_ticks)
} }
/** /**
* Set touch sensor FSM mode. * Enable touch sensor FSM timer trigger (continuous) mode or software trigger (oneshot) mode.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
* *
* @param mode FSM mode. * @param enable Enable FSM timer mode.
* TOUCH_FSM_MODE_TIMER: the FSM will trigger scanning repeatedly under the control of the hardware timer * True: the FSM will trigger scanning repeatedly under the control of the hardware timer (continuous mode)
* TOUCH_FSM_MODE_SW: the FSM will trigger scanning once under the control of the software * 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 // FSM controlled by timer or software
LP_ANA_PERI.touch_mux0.touch_fsm_en = mode; LP_ANA_PERI.touch_mux0.touch_fsm_en = enable;
// Start by timer or software // Set 0 to stop by timer, otherwise by software
LP_ANA_PERI.touch_mux0.touch_start_force = mode; LP_ANA_PERI.touch_mux0.touch_done_force = !enable;
// Stop by timer or software // Set 0 to start by timer, otherwise by software
LP_ANA_PERI.touch_mux0.touch_done_force = mode; 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. * 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. * 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) static inline void touch_ll_force_done_curr_measurement(void)
{ {
if (touch_ll_is_fsm_using_timer()) { // Enable event tick first
LP_ANA_PERI.touch_mux0.touch_done_force = TOUCH_LL_TIMER_FORCE_DONE_BY_SW; LP_AON_CLKRST.lp_clk_en.etm_event_tick_en = 1;
LP_ANA_PERI.touch_mux0.touch_done_en = 1; // Set `force done` signal
LP_ANA_PERI.touch_mux0.touch_done_en = 0; PMU.touch_pwr_cntl.force_done = 1;
LP_ANA_PERI.touch_mux0.touch_done_force = TOUCH_LL_TIMER_DONE_BY_FSM; // Force done signal should last at least one slow clock tick, wait until tick interrupt triggers
} else { LP_SYS.int_clr.slow_clk_tick_int_clr = 1;
LP_ANA_PERI.touch_mux0.touch_done_en = 1; while(LP_SYS.int_clr.slow_clk_tick_int_clr);
LP_ANA_PERI.touch_mux0.touch_done_en = 0; 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 * The timer should be triggered
* @param is_sleep Whether in sleep state * @param is_sleep Whether in sleep state
*/ */
__attribute__((always_inline))
static inline void touch_ll_start_fsm_repeated_timer(bool is_sleep) 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. * Force done for touch timer ensures that the timer always can get the measurement done signal.
*/ */
touch_ll_force_done_curr_measurement(); touch_ll_force_done_curr_measurement();
if (is_sleep) {
PMU.touch_pwr_cntl.sleep_timer_en = 1; PMU.touch_pwr_cntl.sleep_timer_en = 1;
} else {
LP_ANA_PERI.touch_mux0.touch_start_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. * The measurement action can be triggered by the hardware timer, as well as by the software instruction.
* @param is_sleep Whether in sleep state * @param is_sleep Whether in sleep state
*/ */
__attribute__((always_inline))
static inline void touch_ll_stop_fsm_repeated_timer(bool is_sleep) static inline void touch_ll_stop_fsm_repeated_timer(bool is_sleep)
{ {
if (is_sleep) {
PMU.touch_pwr_cntl.sleep_timer_en = 0; PMU.touch_pwr_cntl.sleep_timer_en = 0;
} else {
LP_ANA_PERI.touch_mux0.touch_start_en = 0;
}
touch_ll_force_done_curr_measurement(); touch_ll_force_done_curr_measurement();
} }
/** /**
* Start touch sensor FSM once by software * Is the FSM repeated timer enabled.
* @note Every trigger means measuring one channel, not scanning all enabled channels * @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 */ /* Trigger once measurement */
LP_ANA_PERI.touch_mux0.touch_start_en = 1; 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) 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. * @note If set "TOUCH_PAD_THRESHOLD_MAX", the touch is never be triggered.
* @param touch_num The touch pad id * @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 * @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_ASSERT(sample_cfg_id < SOC_TOUCH_SAMPLE_CFG_NUM);
HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_padx_thn[touch_num].thn[sampler_id], threshold, thresh); // 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) 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_scan_ctrl1.touch_scan_pad_map = mask;
LP_ANA_PERI.touch_filter2.touch_outen = 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 * @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; // Channel shift workaround
LP_ANA_PERI.touch_mux1.touch_xpd = chan_mask | curr_mask; 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) static inline void touch_ll_channel_power_off(uint16_t chan_mask)
{ {
uint32_t curr_mask = LP_ANA_PERI.touch_mux1.touch_xpd; 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)) & 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;
} }
/** /**
@ -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)`. * @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) 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 * Get the data of the touch channel according to the types
* *
* @param touch_num touch pad index * @param touch_num touch pad index
* @param sampler_id The sampler index * @param sample_cfg_id The sample configuration index
* @param type data type * @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, * 2: TOUCH_LL_READ_BENCHMARK, benchmark value of touch channel,
* the benchmark value is the maximum during the first measurement period * 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. * 3: TOUCH_LL_READ_SMOOTH, the smoothed data that obtained by filtering the raw data.
* @param data pointer to the data * @param data pointer to the data
*/ */
__attribute__((always_inline)) __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(sample_cfg_id < SOC_TOUCH_SAMPLE_CFG_NUM);
HAL_ASSERT(type <= TOUCH_LL_READ_SMOOTH); HAL_ASSERT(type == TOUCH_LL_READ_BENCHMARK || 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;
LP_ANA_PERI.touch_mux0.touch_data_sel = type; 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 * @return
* - If touch sensors measure done. * - 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; 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 * 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; 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 * @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 * @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: case 0:
LP_ANA_PERI.touch_work.div_num0 = div_num; LP_ANA_PERI.touch_work.div_num0 = div_num - 1;
break; break;
case 1: case 1:
LP_ANA_PERI.touch_work.div_num1 = div_num; LP_ANA_PERI.touch_work.div_num1 = div_num - 1;
break; break;
case 2: case 2:
LP_ANA_PERI.touch_work.div_num2 = div_num; LP_ANA_PERI.touch_work.div_num2 = div_num - 1;
break; break;
default: default:
// invalid sampler_id // invalid sample_cfg_id
abort(); abort();
} }
} }
@ -434,7 +493,8 @@ static inline void touch_ll_set_idle_channel_connect(touch_pad_conn_type_t type)
__attribute__((always_inline)) __attribute__((always_inline))
static inline uint32_t touch_ll_get_current_meas_channel(void) 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 * @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 * @return type interrupt type
*/ */
__attribute__((always_inline))
static inline uint32_t touch_ll_get_intr_status_mask(void) static inline uint32_t touch_ll_get_intr_status_mask(void)
{ {
uint32_t intr_st = LP_TOUCH.int_st.val; 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. * @param sample_cfg_num The enabled sample configuration number, range 0~3.
* 0/1 means only one sampler enabled, which can not support frequency hopping * 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); HAL_ASSERT(sample_cfg_num <= SOC_TOUCH_SAMPLE_CFG_NUM);
LP_ANA_PERI.touch_scan_ctrl2.freq_scan_en = !!sampler_num; LP_ANA_PERI.touch_scan_ctrl2.freq_scan_en = !!sample_cfg_num;
LP_ANA_PERI.touch_scan_ctrl2.freq_scan_cnt_limit = sampler_num ? sampler_num : 1; 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. * 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 cap Capacitance of the RC filter.
* @param res Resistance 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); HAL_ASSERT(sample_cfg_id < SOC_TOUCH_SAMPLE_CFG_NUM);
LP_ANA_PERI.touch_freq_scan_para[sampler_id].touch_freq_dcap_lpf = cap; LP_ANA_PERI.touch_freq_scan_para[sample_cfg_id].touch_freq_dcap_lpf = cap;
LP_ANA_PERI.touch_freq_scan_para[sampler_id].touch_freq_dres_lpf = res; LP_ANA_PERI.touch_freq_scan_para[sample_cfg_id].touch_freq_dres_lpf = res;
} }
/** /**
* @brief Set the driver of the sampling frequency * @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 ls_drv Low speed touch driver
* @param hs_drv High 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); HAL_ASSERT(sample_cfg_id < SOC_TOUCH_SAMPLE_CFG_NUM);
LP_ANA_PERI.touch_freq_scan_para[sampler_id].touch_freq_drv_ls = ls_drv; LP_ANA_PERI.touch_freq_scan_para[sample_cfg_id].touch_freq_drv_ls = ls_drv;
LP_ANA_PERI.touch_freq_scan_para[sampler_id].touch_freq_drv_hs = hs_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 * 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 * @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); HAL_ASSERT(sample_cfg_id < SOC_TOUCH_SAMPLE_CFG_NUM);
LP_ANA_PERI.touch_freq_scan_para[sampler_id].touch_freq_dbias = bias_volt; 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. * @note If call this API, make sure enable clock gate(`touch_ll_clkgate`) first.
* @param chan_mask touch channel mask * @param chan_mask touch channel mask
*/ */
__attribute__((always_inline))
static inline void touch_ll_reset_chan_benchmark(uint32_t chan_mask) static inline void touch_ll_reset_chan_benchmark(uint32_t chan_mask)
{ {
LP_ANA_PERI.touch_clr.touch_channel_clr = 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. * Set the denoise coefficient regarding the denoise level.
* The benchmark will update to the new value if the touch data is within (benchmark + active_threshold * pos_coeff)
* *
* * @param denoise_lvl Range [0 ~ 4]. 0 = no noise resistance, otherwise higher denoise_lvl means more noise resistance.
* @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) static inline void touch_ll_filter_set_denoise_level(int denoise_lvl)
{ {
bool always_update = pos_noise_thresh < 0; HAL_ASSERT(denoise_lvl >= 0 && denoise_lvl <= 4);
LP_ANA_PERI.touch_filter2.touch_bypass_noise_thres = always_update; bool always_update = denoise_lvl == 0;
LP_ANA_PERI.touch_filter1.touch_noise_thres = always_update ? 0 : pos_noise_thresh; // Map denoise level to actual noise threshold coefficients
} uint32_t noise_thresh = denoise_lvl == 4 ? 3 : 3 - denoise_lvl;
/** LP_ANA_PERI.touch_filter2.touch_bypass_noise_thres = always_update;
* Set the negative noise threshold coefficient. Higher = More noise resistance. LP_ANA_PERI.touch_filter1.touch_noise_thres = always_update ? 0 : noise_thresh;
* The benchmark will update to the new value if the touch data is greater than (benchmark - active_threshold * neg_coeff)
* LP_ANA_PERI.touch_filter2.touch_bypass_nn_thres = always_update;
* @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; LP_ANA_PERI.touch_filter1.touch_nn_thres = always_update ? 0 : noise_thresh;
* -1: the benchmark will always update to the new touch data without considering the negative noise threshold LP_ANA_PERI.touch_filter1.touch_nn_limit = 5; // 5 is the default value
* -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
} }
/** /**
@ -696,10 +755,10 @@ static inline void touch_ll_filter_enable(bool enable)
*/ */
static inline void touch_ll_force_update_benchmark(uint32_t benchmark) 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); HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_filter3, touch_benchmark_sw, benchmark);
LP_ANA_PERI.touch_filter3.touch_update_baseline_sw = 1; LP_ANA_PERI.touch_filter3.touch_update_benchmark_sw = 1;
// waiting for update // 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 ************************/ /************************ 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) 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) 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 ************************/ /************************ Approach register setting ************************/
/** /**
* Set the approach channel to the specific touch channel * Set the proximity sensing channel to the specific touch channel
* To disable the approach channel, point this pad to `TOUCH_LL_NULL_CHANNEL` * To disable the proximity channel, point this pad to `TOUCH_LL_NULL_CHANNEL`
* *
* @param aprch_chan approach channel. * @param prox_chan proximity sensing channel.
* @param touch_num The touch channel that supposed to be used as approach 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: 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; break;
case 1: 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; break;
case 2: 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; break;
default: default:
// invalid approach channel // invalid proximity channel
abort(); 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 scan_times The total scan times of the proximity sensing channel
* @param times The cumulative number of measurement cycles.
*/ */
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: 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; break;
case 1: 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; break;
case 2: 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; break;
default: default:
// invalid sampler_id // invalid sample_cfg_id
abort(); 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. * @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: case 0:
*cnt = HAL_FORCE_READ_U32_REG_FIELD(LP_TOUCH.aprch_ch_data, approach_pad0_cnt); *cnt = HAL_FORCE_READ_U32_REG_FIELD(LP_TOUCH.aprch_ch_data, approach_pad0_cnt);
break; 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. * @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) 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_pad1 != touch_num)
&& (LP_ANA_PERI.touch_approach.touch_approach_pad2 != touch_num)) { && (LP_ANA_PERI.touch_approach.touch_approach_pad2 != touch_num)) {
return false; return false;
} else {
return true;
} }
return true;
} }
/************** sleep channel setting ***********************/ /************** 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) 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. * @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: case 0:
HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_slp0, touch_slp_th0, touch_thresh); HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_slp0, touch_slp_th0, touch_thresh);
break; 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); HAL_FORCE_MODIFY_U32_REG_FIELD(LP_ANA_PERI.touch_slp1, touch_slp_th2, touch_thresh);
break; break;
default: default:
// invalid sampler_id // invalid sample_cfg_id
abort(); 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; 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 * 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 * @param type data type
* 0/1: TOUCH_LL_READ_RAW, the raw data of the touch channel * 0/1: TOUCH_LL_READ_RAW, the raw data of the touch channel
* 2: TOUCH_LL_READ_BENCHMARK, benchmark value of 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 * @param smooth_data pointer to smoothed data
*/ */
__attribute__((always_inline)) __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); 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; LP_ANA_PERI.touch_mux0.touch_data_sel = type;
*data = HAL_FORCE_READ_U32_REG_FIELD(LP_TOUCH.slp_ch_data, slp_data); *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. * Read proximity count of touch sensor for sleep channel.
* @param approach_cnt Pointer to accept touch sensor approach count value. * @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 #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);
}

View File

@ -1,5 +1,5 @@
/* /*
* SPDX-FileCopyrightText: 2019-2022 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2019-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -26,7 +26,7 @@ extern "C" {
/** /**
* Reset the whole of touch module. * Reset the whole of touch module.
* *
* @note Call this funtion after `touch_pad_fsm_stop`, * @note Call this function after `touch_pad_fsm_stop`,
*/ */
#define touch_hal_reset() touch_ll_reset() #define touch_hal_reset() touch_ll_reset()
@ -385,7 +385,7 @@ void touch_hal_denoise_enable(void);
#define touch_hal_waterproof_get_guard_pad(pad_num) touch_ll_waterproof_get_guard_pad(pad_num) #define touch_hal_waterproof_get_guard_pad(pad_num) touch_ll_waterproof_get_guard_pad(pad_num)
/** /**
* Set max equivalent capacitance for sheild channel. * Set max equivalent capacitance for shield channel.
* The equivalent capacitance of the shielded channel can be calculated * The equivalent capacitance of the shielded channel can be calculated
* from the reading of denoise channel. * from the reading of denoise channel.
* *
@ -394,7 +394,7 @@ void touch_hal_denoise_enable(void);
#define touch_hal_waterproof_set_sheild_driver(driver_level) touch_ll_waterproof_set_sheild_driver(driver_level) #define touch_hal_waterproof_set_sheild_driver(driver_level) touch_ll_waterproof_set_sheild_driver(driver_level)
/** /**
* Get max equivalent capacitance for sheild channel. * Get max equivalent capacitance for shield channel.
* The equivalent capacitance of the shielded channel can be calculated * The equivalent capacitance of the shielded channel can be calculated
* from the reading of denoise channel. * from the reading of denoise channel.
* *
@ -551,12 +551,12 @@ void touch_hal_sleep_channel_enable(touch_pad_t pad_num, bool enable);
/** /**
* Enable proximity function for sleep pad. * Enable proximity function for sleep pad.
*/ */
#define touch_hal_sleep_enable_approach() touch_ll_sleep_enable_approach() #define touch_hal_sleep_enable_approach() touch_ll_sleep_enable_proximity_sensing()
/** /**
* Disable proximity function for sleep pad. * Disable proximity function for sleep pad.
*/ */
#define touch_hal_sleep_disable_approach() touch_ll_sleep_disable_approach() #define touch_hal_sleep_disable_approach() touch_ll_sleep_disable_proximity_sensing()
/** /**
* Read benchmark of touch sensor for sleep pad. * Read benchmark of touch sensor for sleep pad.

View File

@ -1,5 +1,5 @@
/* /*
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -214,6 +214,7 @@ static inline void touch_ll_get_tie_option(touch_pad_t touch_num, touch_tie_opt_
* *
* @param mode FSM mode. * @param mode FSM mode.
*/ */
__attribute__((always_inline))
static inline void touch_ll_set_fsm_mode(touch_fsm_mode_t mode) static inline void touch_ll_set_fsm_mode(touch_fsm_mode_t mode)
{ {
RTCCNTL.touch_ctrl2.touch_start_force = mode; RTCCNTL.touch_ctrl2.touch_start_force = mode;
@ -280,6 +281,7 @@ static inline void touch_ll_start_fsm(void)
* Stop touch sensor FSM timer. * Stop touch sensor FSM timer.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction. * The measurement action can be triggered by the hardware timer, as well as by the software instruction.
*/ */
__attribute__((always_inline))
static inline void touch_ll_stop_fsm(void) static inline void touch_ll_stop_fsm(void)
{ {
RTCCNTL.touch_ctrl2.touch_start_en = 0; //stop touch fsm RTCCNTL.touch_ctrl2.touch_start_en = 0; //stop touch fsm
@ -416,7 +418,8 @@ static inline uint32_t IRAM_ATTR touch_ll_read_raw_data(touch_pad_t touch_num)
* @return * @return
* - If touch sensors measure done. * - If touch sensors measure done.
*/ */
static inline bool touch_ll_meas_is_done(void) __attribute__((always_inline))
static inline bool touch_ll_is_measure_done(void)
{ {
return (bool)SENS.sar_touch_chn_st.touch_meas_done; return (bool)SENS.sar_touch_chn_st.touch_meas_done;
} }
@ -555,22 +558,23 @@ static inline void touch_ll_intr_clear(touch_pad_intr_mask_t int_mask)
*/ */
static inline uint32_t touch_ll_read_intr_status_mask(void) static inline uint32_t touch_ll_read_intr_status_mask(void)
{ {
uint32_t intr_st = RTCCNTL.int_st.val; typeof(RTCCNTL.int_st) intr_st;
intr_st.val = RTCCNTL.int_st.val;
uint32_t intr_msk = 0; uint32_t intr_msk = 0;
if (intr_st & RTC_CNTL_TOUCH_DONE_INT_ST_M) { if (intr_st.rtc_touch_done) {
intr_msk |= TOUCH_PAD_INTR_MASK_DONE; intr_msk |= TOUCH_PAD_INTR_MASK_DONE;
} }
if (intr_st & RTC_CNTL_TOUCH_ACTIVE_INT_ST_M) { if (intr_st.rtc_touch_active) {
intr_msk |= TOUCH_PAD_INTR_MASK_ACTIVE; intr_msk |= TOUCH_PAD_INTR_MASK_ACTIVE;
} }
if (intr_st & RTC_CNTL_TOUCH_INACTIVE_INT_ST_M) { if (intr_st.rtc_touch_inactive) {
intr_msk |= TOUCH_PAD_INTR_MASK_INACTIVE; intr_msk |= TOUCH_PAD_INTR_MASK_INACTIVE;
} }
if (intr_st & RTC_CNTL_TOUCH_SCAN_DONE_INT_ST_M) { if (intr_st.rtc_touch_scan_done) {
intr_msk |= TOUCH_PAD_INTR_MASK_SCAN_DONE; intr_msk |= TOUCH_PAD_INTR_MASK_SCAN_DONE;
} }
if (intr_st & RTC_CNTL_TOUCH_TIMEOUT_INT_ST_M) { if (intr_st.rtc_touch_timeout) {
intr_msk |= TOUCH_PAD_INTR_MASK_TIMEOUT; intr_msk |= TOUCH_PAD_INTR_MASK_TIMEOUT;
} }
return (intr_msk & TOUCH_PAD_INTR_MASK_ALL); return (intr_msk & TOUCH_PAD_INTR_MASK_ALL);
@ -909,7 +913,7 @@ static inline void touch_ll_waterproof_get_guard_pad(touch_pad_t *pad_num)
} }
/** /**
* Set max equivalent capacitance for sheild channel. * Set max equivalent capacitance for shield channel.
* The equivalent capacitance of the shielded channel can be calculated * The equivalent capacitance of the shielded channel can be calculated
* from the reading of denoise channel. * from the reading of denoise channel.
* *
@ -921,7 +925,7 @@ static inline void touch_ll_waterproof_set_sheild_driver(touch_pad_shield_driver
} }
/** /**
* Get max equivalent capacitance for sheild channel. * Get max equivalent capacitance for shield channel.
* The equivalent capacitance of the shielded channel can be calculated * The equivalent capacitance of the shielded channel can be calculated
* from the reading of denoise channel. * from the reading of denoise channel.
* *
@ -1084,7 +1088,7 @@ static inline void touch_ll_sleep_get_threshold(uint32_t *touch_thres)
/** /**
* Enable proximity function for sleep pad. * Enable proximity function for sleep pad.
*/ */
static inline void touch_ll_sleep_enable_approach(void) static inline void touch_ll_sleep_enable_proximity_sensing(void)
{ {
RTCCNTL.touch_slp_thres.touch_slp_approach_en = 1; RTCCNTL.touch_slp_thres.touch_slp_approach_en = 1;
} }
@ -1092,7 +1096,7 @@ static inline void touch_ll_sleep_enable_approach(void)
/** /**
* Disable proximity function for sleep pad. * Disable proximity function for sleep pad.
*/ */
static inline void touch_ll_sleep_disable_approach(void) static inline void touch_ll_sleep_disable_proximity_sensing(void)
{ {
RTCCNTL.touch_slp_thres.touch_slp_approach_en = 0; RTCCNTL.touch_slp_thres.touch_slp_approach_en = 0;
} }
@ -1100,7 +1104,7 @@ static inline void touch_ll_sleep_disable_approach(void)
/** /**
* Get proximity function status for sleep pad. * Get proximity function status for sleep pad.
*/ */
static inline bool touch_ll_sleep_get_approach_status(void) static inline bool touch_ll_sleep_is_proximity_enabled(void)
{ {
return (bool)RTCCNTL.touch_slp_thres.touch_slp_approach_en; return (bool)RTCCNTL.touch_slp_thres.touch_slp_approach_en;
} }
@ -1157,11 +1161,11 @@ static inline void touch_ll_sleep_read_debounce(uint32_t *debounce)
/** /**
* Read proximity count of touch sensor for sleep pad. * Read proximity count of touch sensor for sleep pad.
* @param proximity_cnt Pointer to accept touch sensor proximity count value. * @param prox_cnt Pointer to accept touch sensor proximity count value.
*/ */
static inline void touch_ll_sleep_read_proximity_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(SENS.sar_touch_appr_status, touch_slp_approach_cnt); *prox_cnt = HAL_FORCE_READ_U32_REG_FIELD(SENS.sar_touch_appr_status, touch_slp_approach_cnt);
} }
/** /**

View File

@ -1,5 +1,5 @@
/* /*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -53,7 +53,7 @@ void touch_hal_deinit(void)
touch_pad_t prox_pad[SOC_TOUCH_PROXIMITY_CHANNEL_NUM] = {[0 ... (SOC_TOUCH_PROXIMITY_CHANNEL_NUM - 1)] = 0}; touch_pad_t prox_pad[SOC_TOUCH_PROXIMITY_CHANNEL_NUM] = {[0 ... (SOC_TOUCH_PROXIMITY_CHANNEL_NUM - 1)] = 0};
touch_ll_proximity_set_channel_num((const touch_pad_t *)prox_pad); touch_ll_proximity_set_channel_num((const touch_pad_t *)prox_pad);
touch_ll_sleep_set_channel_num(0); touch_ll_sleep_set_channel_num(0);
touch_ll_sleep_disable_approach(); touch_ll_sleep_disable_proximity_sensing();
touch_ll_reset(); // Reset the touch sensor FSM. touch_ll_reset(); // Reset the touch sensor FSM.
} }
@ -152,7 +152,7 @@ void touch_hal_sleep_channel_enable(touch_pad_t pad_num, bool enable)
void touch_hal_sleep_channel_get_config(touch_pad_sleep_channel_t *slp_config) void touch_hal_sleep_channel_get_config(touch_pad_sleep_channel_t *slp_config)
{ {
touch_ll_sleep_get_channel_num(&slp_config->touch_num); touch_ll_sleep_get_channel_num(&slp_config->touch_num);
slp_config->en_proximity = touch_ll_sleep_get_approach_status(); slp_config->en_proximity = touch_ll_sleep_is_proximity_enabled();
} }
void touch_hal_sleep_channel_set_work_time(uint16_t sleep_cycle, uint16_t meas_times) void touch_hal_sleep_channel_set_work_time(uint16_t sleep_cycle, uint16_t meas_times)

View File

@ -1,5 +1,5 @@
/* /*
* SPDX-FileCopyrightText: 2015-2021 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -26,7 +26,7 @@ extern "C" {
/** /**
* Reset the whole of touch module. * Reset the whole of touch module.
* *
* @note Call this funtion after `touch_pad_fsm_stop`, * @note Call this function after `touch_pad_fsm_stop`,
*/ */
#define touch_hal_reset() touch_ll_reset() #define touch_hal_reset() touch_ll_reset()
@ -385,7 +385,7 @@ void touch_hal_denoise_enable(void);
#define touch_hal_waterproof_get_guard_pad(pad_num) touch_ll_waterproof_get_guard_pad(pad_num) #define touch_hal_waterproof_get_guard_pad(pad_num) touch_ll_waterproof_get_guard_pad(pad_num)
/** /**
* Set max equivalent capacitance for sheild channel. * Set max equivalent capacitance for shield channel.
* The equivalent capacitance of the shielded channel can be calculated * The equivalent capacitance of the shielded channel can be calculated
* from the reading of denoise channel. * from the reading of denoise channel.
* *
@ -394,7 +394,7 @@ void touch_hal_denoise_enable(void);
#define touch_hal_waterproof_set_sheild_driver(driver_level) touch_ll_waterproof_set_sheild_driver(driver_level) #define touch_hal_waterproof_set_sheild_driver(driver_level) touch_ll_waterproof_set_sheild_driver(driver_level)
/** /**
* Get max equivalent capacitance for sheild channel. * Get max equivalent capacitance for shield channel.
* The equivalent capacitance of the shielded channel can be calculated * The equivalent capacitance of the shielded channel can be calculated
* from the reading of denoise channel. * from the reading of denoise channel.
* *
@ -551,12 +551,12 @@ void touch_hal_sleep_channel_enable(touch_pad_t pad_num, bool enable);
/** /**
* Enable proximity function for sleep pad. * Enable proximity function for sleep pad.
*/ */
#define touch_hal_sleep_enable_approach() touch_ll_sleep_enable_approach() #define touch_hal_sleep_enable_approach() touch_ll_sleep_enable_proximity_sensing()
/** /**
* Disable proximity function for sleep pad. * Disable proximity function for sleep pad.
*/ */
#define touch_hal_sleep_disable_approach() touch_ll_sleep_disable_approach() #define touch_hal_sleep_disable_approach() touch_ll_sleep_disable_proximity_sensing()
/** /**
* Read benchmark of touch sensor for sleep pad. * Read benchmark of touch sensor for sleep pad.

View File

@ -1,5 +1,5 @@
/* /*
* SPDX-FileCopyrightText: 2015-2023 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -168,11 +168,18 @@ static inline void touch_ll_get_voltage_attenuation(touch_volt_atten_t *atten)
*/ */
static inline void touch_ll_set_slope(touch_pad_t touch_num, touch_cnt_slope_t slope) static inline void touch_ll_set_slope(touch_pad_t touch_num, touch_cnt_slope_t slope)
{ {
#define PAD_SLOP_MASK(val, num) ((val) << (29 - (num) * 3))
uint32_t curr_slop = 0;
if (touch_num < TOUCH_PAD_NUM10) { if (touch_num < TOUCH_PAD_NUM10) {
SET_PERI_REG_BITS(RTC_CNTL_TOUCH_DAC_REG, RTC_CNTL_TOUCH_PAD0_DAC_V, slope, (RTC_CNTL_TOUCH_PAD0_DAC_S - touch_num * 3)); curr_slop = RTCCNTL.touch_dac.val;
curr_slop &= ~PAD_SLOP_MASK(0x07, touch_num); // clear the old value
RTCCNTL.touch_dac.val = curr_slop | PAD_SLOP_MASK(slope, touch_num);
} else { } else {
SET_PERI_REG_BITS(RTC_CNTL_TOUCH_DAC1_REG, RTC_CNTL_TOUCH_PAD10_DAC_V, slope, (RTC_CNTL_TOUCH_PAD10_DAC_S - (touch_num - TOUCH_PAD_NUM10) * 3)); curr_slop = RTCCNTL.touch_dac1.val;
curr_slop &= ~PAD_SLOP_MASK(0x07, touch_num - TOUCH_PAD_NUM10); // clear the old value
RTCCNTL.touch_dac1.val = curr_slop | PAD_SLOP_MASK(slope, touch_num - TOUCH_PAD_NUM10);
} }
#undef PAD_SLOP_MASK
} }
/** /**
@ -188,9 +195,9 @@ static inline void touch_ll_set_slope(touch_pad_t touch_num, touch_cnt_slope_t s
static inline void touch_ll_get_slope(touch_pad_t touch_num, touch_cnt_slope_t *slope) static inline void touch_ll_get_slope(touch_pad_t touch_num, touch_cnt_slope_t *slope)
{ {
if (touch_num < TOUCH_PAD_NUM10) { if (touch_num < TOUCH_PAD_NUM10) {
*slope = (touch_cnt_slope_t)(GET_PERI_REG_BITS2(RTC_CNTL_TOUCH_DAC_REG, RTC_CNTL_TOUCH_PAD0_DAC_V, (RTC_CNTL_TOUCH_PAD0_DAC_S - touch_num * 3))); *slope = (touch_cnt_slope_t)((RTCCNTL.touch_dac.val >> (29 - touch_num * 3)) & 0x07);
} else { } else {
*slope = (touch_cnt_slope_t)(GET_PERI_REG_BITS2(RTC_CNTL_TOUCH_DAC1_REG, RTC_CNTL_TOUCH_PAD10_DAC_V, (RTC_CNTL_TOUCH_PAD10_DAC_S - (touch_num - TOUCH_PAD_NUM10) * 3))); *slope = (touch_cnt_slope_t)((RTCCNTL.touch_dac1.val >> (29 - (touch_num - TOUCH_PAD_NUM10) * 3)) & 0x07);
} }
} }
@ -222,6 +229,7 @@ static inline void touch_ll_get_tie_option(touch_pad_t touch_num, touch_tie_opt_
* *
* @param mode FSM mode. * @param mode FSM mode.
*/ */
__attribute__((always_inline))
static inline void touch_ll_set_fsm_mode(touch_fsm_mode_t mode) static inline void touch_ll_set_fsm_mode(touch_fsm_mode_t mode)
{ {
RTCCNTL.touch_ctrl2.touch_start_force = mode; RTCCNTL.touch_ctrl2.touch_start_force = mode;
@ -288,6 +296,7 @@ static inline void touch_ll_start_fsm(void)
* Stop touch sensor FSM timer. * Stop touch sensor FSM timer.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction. * The measurement action can be triggered by the hardware timer, as well as by the software instruction.
*/ */
__attribute__((always_inline))
static inline void touch_ll_stop_fsm(void) static inline void touch_ll_stop_fsm(void)
{ {
RTCCNTL.touch_ctrl2.touch_start_en = 0; //stop touch fsm RTCCNTL.touch_ctrl2.touch_start_en = 0; //stop touch fsm
@ -424,7 +433,8 @@ static inline uint32_t IRAM_ATTR touch_ll_read_raw_data(touch_pad_t touch_num)
* @return * @return
* - If touch sensors measure done. * - If touch sensors measure done.
*/ */
static inline bool touch_ll_meas_is_done(void) __attribute__((always_inline))
static inline bool touch_ll_is_measure_done(void)
{ {
return (bool)SENS.sar_touch_chn_st.touch_meas_done; return (bool)SENS.sar_touch_chn_st.touch_meas_done;
} }
@ -572,25 +582,26 @@ static inline void touch_ll_intr_clear(touch_pad_intr_mask_t int_mask)
*/ */
static inline uint32_t touch_ll_read_intr_status_mask(void) static inline uint32_t touch_ll_read_intr_status_mask(void)
{ {
uint32_t intr_st = RTCCNTL.int_st.val; typeof(RTCCNTL.int_st) intr_st;
intr_st.val = RTCCNTL.int_st.val;
uint32_t intr_msk = 0; uint32_t intr_msk = 0;
if (intr_st & RTC_CNTL_TOUCH_DONE_INT_ST_M) { if (intr_st.rtc_touch_done) {
intr_msk |= TOUCH_PAD_INTR_MASK_DONE; intr_msk |= TOUCH_PAD_INTR_MASK_DONE;
} }
if (intr_st & RTC_CNTL_TOUCH_ACTIVE_INT_ST_M) { if (intr_st.rtc_touch_active) {
intr_msk |= TOUCH_PAD_INTR_MASK_ACTIVE; intr_msk |= TOUCH_PAD_INTR_MASK_ACTIVE;
} }
if (intr_st & RTC_CNTL_TOUCH_INACTIVE_INT_ST_M) { if (intr_st.rtc_touch_inactive) {
intr_msk |= TOUCH_PAD_INTR_MASK_INACTIVE; intr_msk |= TOUCH_PAD_INTR_MASK_INACTIVE;
} }
if (intr_st & RTC_CNTL_TOUCH_SCAN_DONE_INT_ST_M) { if (intr_st.rtc_touch_scan_done) {
intr_msk |= TOUCH_PAD_INTR_MASK_SCAN_DONE; intr_msk |= TOUCH_PAD_INTR_MASK_SCAN_DONE;
} }
if (intr_st & RTC_CNTL_TOUCH_TIMEOUT_INT_ST_M) { if (intr_st.rtc_touch_timeout) {
intr_msk |= TOUCH_PAD_INTR_MASK_TIMEOUT; intr_msk |= TOUCH_PAD_INTR_MASK_TIMEOUT;
} }
if (intr_st & RTC_CNTL_TOUCH_APPROACH_LOOP_DONE_INT_ST_M) { if (intr_st.rtc_touch_approach_loop_done) {
intr_msk |= TOUCH_PAD_INTR_MASK_PROXI_MEAS_DONE; intr_msk |= TOUCH_PAD_INTR_MASK_PROXI_MEAS_DONE;
} }
return (intr_msk & TOUCH_PAD_INTR_MASK_ALL); return (intr_msk & TOUCH_PAD_INTR_MASK_ALL);
@ -929,7 +940,7 @@ static inline void touch_ll_waterproof_get_guard_pad(touch_pad_t *pad_num)
} }
/** /**
* Set max equivalent capacitance for sheild channel. * Set max equivalent capacitance for shield channel.
* The equivalent capacitance of the shielded channel can be calculated * The equivalent capacitance of the shielded channel can be calculated
* from the reading of denoise channel. * from the reading of denoise channel.
* *
@ -941,7 +952,7 @@ static inline void touch_ll_waterproof_set_sheild_driver(touch_pad_shield_driver
} }
/** /**
* Get max equivalent capacitance for sheild channel. * Get max equivalent capacitance for shield channel.
* The equivalent capacitance of the shielded channel can be calculated * The equivalent capacitance of the shielded channel can be calculated
* from the reading of denoise channel. * from the reading of denoise channel.
* *
@ -1104,7 +1115,7 @@ static inline void touch_ll_sleep_get_threshold(uint32_t *touch_thres)
/** /**
* Enable proximity function for sleep pad. * Enable proximity function for sleep pad.
*/ */
static inline void touch_ll_sleep_enable_approach(void) static inline void touch_ll_sleep_enable_proximity_sensing(void)
{ {
RTCCNTL.touch_slp_thres.touch_slp_approach_en = 1; RTCCNTL.touch_slp_thres.touch_slp_approach_en = 1;
} }
@ -1112,7 +1123,7 @@ static inline void touch_ll_sleep_enable_approach(void)
/** /**
* Disable proximity function for sleep pad. * Disable proximity function for sleep pad.
*/ */
static inline void touch_ll_sleep_disable_approach(void) static inline void touch_ll_sleep_disable_proximity_sensing(void)
{ {
RTCCNTL.touch_slp_thres.touch_slp_approach_en = 0; RTCCNTL.touch_slp_thres.touch_slp_approach_en = 0;
} }
@ -1120,7 +1131,7 @@ static inline void touch_ll_sleep_disable_approach(void)
/** /**
* Get proximity function status for sleep pad. * Get proximity function status for sleep pad.
*/ */
static inline bool touch_ll_sleep_get_approach_status(void) static inline bool touch_ll_sleep_is_proximity_enabled(void)
{ {
return (bool)RTCCNTL.touch_slp_thres.touch_slp_approach_en; return (bool)RTCCNTL.touch_slp_thres.touch_slp_approach_en;
} }
@ -1177,11 +1188,11 @@ static inline void touch_ll_sleep_read_debounce(uint32_t *debounce)
/** /**
* Read proximity count of touch sensor for sleep pad. * Read proximity count of touch sensor for sleep pad.
* @param proximity_cnt Pointer to accept touch sensor proximity count value. * @param prox_cnt Pointer to accept touch sensor proximity count value.
*/ */
static inline void touch_ll_sleep_read_proximity_cnt(uint32_t *approach_cnt) static inline void touch_ll_sleep_read_proximity_cnt(uint32_t *prox_cnt)
{ {
*approach_cnt = SENS.sar_touch_appr_status.touch_slp_approach_cnt; *prox_cnt = SENS.sar_touch_appr_status.touch_slp_approach_cnt;
} }
/** /**

View File

@ -1,5 +1,5 @@
/* /*
* SPDX-FileCopyrightText: 2015-2021 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -53,7 +53,7 @@ void touch_hal_deinit(void)
touch_pad_t prox_pad[SOC_TOUCH_PROXIMITY_CHANNEL_NUM] = {[0 ... (SOC_TOUCH_PROXIMITY_CHANNEL_NUM - 1)] = 0}; touch_pad_t prox_pad[SOC_TOUCH_PROXIMITY_CHANNEL_NUM] = {[0 ... (SOC_TOUCH_PROXIMITY_CHANNEL_NUM - 1)] = 0};
touch_ll_proximity_set_channel_num((const touch_pad_t *)prox_pad); touch_ll_proximity_set_channel_num((const touch_pad_t *)prox_pad);
touch_ll_sleep_set_channel_num(0); touch_ll_sleep_set_channel_num(0);
touch_ll_sleep_disable_approach(); touch_ll_sleep_disable_proximity_sensing();
touch_ll_reset(); // Reset the touch sensor FSM. touch_ll_reset(); // Reset the touch sensor FSM.
} }
@ -152,7 +152,7 @@ void touch_hal_sleep_channel_enable(touch_pad_t pad_num, bool enable)
void touch_hal_sleep_channel_get_config(touch_pad_sleep_channel_t *slp_config) void touch_hal_sleep_channel_get_config(touch_pad_sleep_channel_t *slp_config)
{ {
touch_ll_sleep_get_channel_num(&slp_config->touch_num); touch_ll_sleep_get_channel_num(&slp_config->touch_num);
slp_config->en_proximity = touch_ll_sleep_get_approach_status(); slp_config->en_proximity = touch_ll_sleep_is_proximity_enabled();
} }
void touch_hal_sleep_channel_set_work_time(uint16_t sleep_cycle, uint16_t meas_times) void touch_hal_sleep_channel_set_work_time(uint16_t sleep_cycle, uint16_t meas_times)

View File

@ -1,5 +1,5 @@
/* /*
* SPDX-FileCopyrightText: 2019-2022 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2019-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -194,7 +194,7 @@ void touch_hal_get_meas_mode(touch_pad_t touch_num, touch_hal_meas_mode_t *meas)
* @return * @return
* - If touch sensors measure done. * - If touch sensors measure done.
*/ */
#define touch_hal_meas_is_done() touch_ll_meas_is_done() #define touch_hal_meas_is_done() touch_ll_is_measure_done()
/** /**
* Initialize touch module. * Initialize touch module.

View File

@ -275,7 +275,7 @@ typedef enum {
TOUCH_PAD_SMOOTH_MAX, TOUCH_PAD_SMOOTH_MAX,
} touch_smooth_mode_t; } touch_smooth_mode_t;
#if CONFIG_IDF_TARGET_ESP32P4 #if SOC_TOUCH_SENSOR_VERSION == 3
/** /**
* @brief Touch channel counting mode of the binarized touch output * @brief Touch channel counting mode of the binarized touch output
* *
@ -283,9 +283,11 @@ typedef enum {
typedef enum { typedef enum {
TOUCH_PAD_OUT_AS_DATA, /*!< Counting the output of touch channel as data. 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 * The value will be smaller than actual value but more sensitive when the frequency of touch_out is close to the source clock
* Normally we treat the output as data when it is lower than the sample clock
*/ */
TOUCH_PAD_OUT_AS_CLOCK, /*!< Counting the output of touch channel as 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 * The value is accurate but less sensitive when the frequency of touch_out is close to the source clock
* Normally we treat the output as clock when it is higher than the sample clock
*/ */
} touch_out_mode_t; } touch_out_mode_t;
#endif #endif

View File

@ -703,7 +703,7 @@ config SOC_TOUCH_SENSOR_NUM
int int
default 10 default 10
config SOC_TOUCH_SAMPLER_NUM config SOC_TOUCH_SAMPLE_CFG_NUM
int int
default 1 default 1

View File

@ -326,7 +326,7 @@
#define SOC_TOUCH_SENSOR_VERSION (1U) /*!<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_SENSOR_NUM (10)
#define SOC_TOUCH_SAMPLER_NUM (1U) /*!< The sampler number in total, each sampler can be used to sample on one frequency */ #define SOC_TOUCH_SAMPLE_CFG_NUM (1U) /*!< The sample configuration number in total, each sampler can be used to sample on one frequency */
/*-------------------------- TWAI CAPS ---------------------------------------*/ /*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL #define SOC_TWAI_CONTROLLER_NUM 1UL

View File

@ -4,7 +4,7 @@
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
#include "soc/touch_sensor_periph.h" #include "soc/touch_sensor_channel.h"
/* Store IO number corresponding to the Touch Sensor channel number. */ /* Store IO number corresponding to the Touch Sensor channel number. */
const int touch_sensor_channel_io_map[] = { const int touch_sensor_channel_io_map[] = {

View File

@ -275,6 +275,10 @@ config SOC_SPI_FLASH_SUPPORTED
bool bool
default y default y
config SOC_TOUCH_SENSOR_SUPPORTED
bool
default y
config SOC_RNG_SUPPORTED config SOC_RNG_SUPPORTED
bool bool
default y default y
@ -1395,6 +1399,18 @@ config SOC_TOUCH_SENSOR_NUM
int int
default 14 default 14
config SOC_TOUCH_SUPPORT_SLEEP_WAKEUP
bool
default y
config SOC_TOUCH_SUPPORT_WATERPROOF
bool
default y
config SOC_TOUCH_SUPPORT_PROX_SENSING
bool
default y
config SOC_TOUCH_PROXIMITY_CHANNEL_NUM config SOC_TOUCH_PROXIMITY_CHANNEL_NUM
int int
default 3 default 3
@ -1403,7 +1419,11 @@ config SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED
bool bool
default y default y
config SOC_TOUCH_SAMPLER_NUM config SOC_TOUCH_SUPPORT_FREQ_HOP
bool
default y
config SOC_TOUCH_SAMPLE_CFG_NUM
int int
default 3 default 3
@ -1567,6 +1587,10 @@ config SOC_PM_SUPPORT_WIFI_WAKEUP
bool bool
default y default y
config SOC_PM_SUPPORT_TOUCH_SENSOR_WAKEUP
bool
default y
config SOC_PM_SUPPORT_XTAL32K_PD config SOC_PM_SUPPORT_XTAL32K_PD
bool bool
default y default y

View File

@ -1,5 +1,5 @@
/** /**
* SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -619,13 +619,13 @@ extern "C" {
* need_des * need_des
*/ */
#define LP_ANALOG_PERI_TOUCH_FILTER1_REG (DR_REG_LP_ANALOG_PERI_BASE + 0x110) #define LP_ANALOG_PERI_TOUCH_FILTER1_REG (DR_REG_LP_ANALOG_PERI_BASE + 0x110)
/** LP_ANALOG_PERI_TOUCH_NEG_NOISE_DISUPDATE_BASELINE_EN : R/W; bitpos: [0]; default: 0; /** LP_ANALOG_PERI_TOUCH_NN_DISUPDATE_BENCHMARK_EN : R/W; bitpos: [0]; default: 0;
* Reserved * Reserved
*/ */
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_DISUPDATE_BASELINE_EN (BIT(0)) #define LP_ANALOG_PERI_TOUCH_NN_DISUPDATE_BENCHMARK_EN (BIT(0))
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_DISUPDATE_BASELINE_EN_M (LP_ANALOG_PERI_TOUCH_NEG_NOISE_DISUPDATE_BASELINE_EN_V << LP_ANALOG_PERI_TOUCH_NEG_NOISE_DISUPDATE_BASELINE_EN_S) #define LP_ANALOG_PERI_TOUCH_NN_DISUPDATE_BENCHMARK_EN_M (LP_ANALOG_PERI_TOUCH_NN_DISUPDATE_BENCHMARK_EN_V << LP_ANALOG_PERI_TOUCH_NN_DISUPDATE_BENCHMARK_EN_S)
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_DISUPDATE_BASELINE_EN_V 0x00000001U #define LP_ANALOG_PERI_TOUCH_NN_DISUPDATE_BENCHMARK_EN_V 0x00000001U
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_DISUPDATE_BASELINE_EN_S 0 #define LP_ANALOG_PERI_TOUCH_NN_DISUPDATE_BENCHMARK_EN_S 0
/** LP_ANALOG_PERI_TOUCH_HYSTERESIS : R/W; bitpos: [2:1]; default: 0; /** LP_ANALOG_PERI_TOUCH_HYSTERESIS : R/W; bitpos: [2:1]; default: 0;
* need_des * need_des
*/ */
@ -633,13 +633,13 @@ extern "C" {
#define LP_ANALOG_PERI_TOUCH_HYSTERESIS_M (LP_ANALOG_PERI_TOUCH_HYSTERESIS_V << LP_ANALOG_PERI_TOUCH_HYSTERESIS_S) #define LP_ANALOG_PERI_TOUCH_HYSTERESIS_M (LP_ANALOG_PERI_TOUCH_HYSTERESIS_V << LP_ANALOG_PERI_TOUCH_HYSTERESIS_S)
#define LP_ANALOG_PERI_TOUCH_HYSTERESIS_V 0x00000003U #define LP_ANALOG_PERI_TOUCH_HYSTERESIS_V 0x00000003U
#define LP_ANALOG_PERI_TOUCH_HYSTERESIS_S 1 #define LP_ANALOG_PERI_TOUCH_HYSTERESIS_S 1
/** LP_ANALOG_PERI_TOUCH_NEG_NOISE_THRES : R/W; bitpos: [4:3]; default: 0; /** LP_ANALOG_PERI_TOUCH_NN_THRES : R/W; bitpos: [4:3]; default: 0;
* need_des * need_des
*/ */
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_THRES 0x00000003U #define LP_ANALOG_PERI_TOUCH_NN_THRES 0x00000003U
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_THRES_M (LP_ANALOG_PERI_TOUCH_NEG_NOISE_THRES_V << LP_ANALOG_PERI_TOUCH_NEG_NOISE_THRES_S) #define LP_ANALOG_PERI_TOUCH_NN_THRES_M (LP_ANALOG_PERI_TOUCH_NN_THRES_V << LP_ANALOG_PERI_TOUCH_NN_THRES_S)
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_THRES_V 0x00000003U #define LP_ANALOG_PERI_TOUCH_NN_THRES_V 0x00000003U
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_THRES_S 3 #define LP_ANALOG_PERI_TOUCH_NN_THRES_S 3
/** LP_ANALOG_PERI_TOUCH_NOISE_THRES : R/W; bitpos: [6:5]; default: 0; /** LP_ANALOG_PERI_TOUCH_NOISE_THRES : R/W; bitpos: [6:5]; default: 0;
* need_des * need_des
*/ */
@ -675,13 +675,13 @@ extern "C" {
#define LP_ANALOG_PERI_TOUCH_FILTER_EN_M (LP_ANALOG_PERI_TOUCH_FILTER_EN_V << LP_ANALOG_PERI_TOUCH_FILTER_EN_S) #define LP_ANALOG_PERI_TOUCH_FILTER_EN_M (LP_ANALOG_PERI_TOUCH_FILTER_EN_V << LP_ANALOG_PERI_TOUCH_FILTER_EN_S)
#define LP_ANALOG_PERI_TOUCH_FILTER_EN_V 0x00000001U #define LP_ANALOG_PERI_TOUCH_FILTER_EN_V 0x00000001U
#define LP_ANALOG_PERI_TOUCH_FILTER_EN_S 16 #define LP_ANALOG_PERI_TOUCH_FILTER_EN_S 16
/** LP_ANALOG_PERI_TOUCH_NEG_NOISE_LIMIT : R/W; bitpos: [20:17]; default: 5; /** LP_ANALOG_PERI_TOUCH_NN_LIMIT : R/W; bitpos: [20:17]; default: 5;
* need_des * need_des
*/ */
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_LIMIT 0x0000000FU #define LP_ANALOG_PERI_TOUCH_NN_LIMIT 0x0000000FU
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_LIMIT_M (LP_ANALOG_PERI_TOUCH_NEG_NOISE_LIMIT_V << LP_ANALOG_PERI_TOUCH_NEG_NOISE_LIMIT_S) #define LP_ANALOG_PERI_TOUCH_NN_LIMIT_M (LP_ANALOG_PERI_TOUCH_NN_LIMIT_V << LP_ANALOG_PERI_TOUCH_NN_LIMIT_S)
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_LIMIT_V 0x0000000FU #define LP_ANALOG_PERI_TOUCH_NN_LIMIT_V 0x0000000FU
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_LIMIT_S 17 #define LP_ANALOG_PERI_TOUCH_NN_LIMIT_S 17
/** LP_ANALOG_PERI_TOUCH_APPROACH_LIMIT : R/W; bitpos: [28:21]; default: 80; /** LP_ANALOG_PERI_TOUCH_APPROACH_LIMIT : R/W; bitpos: [28:21]; default: 80;
* need_des * need_des
*/ */
@ -715,32 +715,32 @@ extern "C" {
#define LP_ANALOG_PERI_TOUCH_BYPASS_NOISE_THRES_M (LP_ANALOG_PERI_TOUCH_BYPASS_NOISE_THRES_V << LP_ANALOG_PERI_TOUCH_BYPASS_NOISE_THRES_S) #define LP_ANALOG_PERI_TOUCH_BYPASS_NOISE_THRES_M (LP_ANALOG_PERI_TOUCH_BYPASS_NOISE_THRES_V << LP_ANALOG_PERI_TOUCH_BYPASS_NOISE_THRES_S)
#define LP_ANALOG_PERI_TOUCH_BYPASS_NOISE_THRES_V 0x00000001U #define LP_ANALOG_PERI_TOUCH_BYPASS_NOISE_THRES_V 0x00000001U
#define LP_ANALOG_PERI_TOUCH_BYPASS_NOISE_THRES_S 30 #define LP_ANALOG_PERI_TOUCH_BYPASS_NOISE_THRES_S 30
/** LP_ANALOG_PERI_TOUCH_BYPASS_NEG_NOISE_THRES : R/W; bitpos: [31]; default: 0; /** LP_ANALOG_PERI_TOUCH_BYPASS_NN_THRES : R/W; bitpos: [31]; default: 0;
* need_des * need_des
*/ */
#define LP_ANALOG_PERI_TOUCH_BYPASS_NEG_NOISE_THRES (BIT(31)) #define LP_ANALOG_PERI_TOUCH_BYPASS_NN_THRES (BIT(31))
#define LP_ANALOG_PERI_TOUCH_BYPASS_NEG_NOISE_THRES_M (LP_ANALOG_PERI_TOUCH_BYPASS_NEG_NOISE_THRES_V << LP_ANALOG_PERI_TOUCH_BYPASS_NEG_NOISE_THRES_S) #define LP_ANALOG_PERI_TOUCH_BYPASS_NN_THRES_M (LP_ANALOG_PERI_TOUCH_BYPASS_NN_THRES_V << LP_ANALOG_PERI_TOUCH_BYPASS_NN_THRES_S)
#define LP_ANALOG_PERI_TOUCH_BYPASS_NEG_NOISE_THRES_V 0x00000001U #define LP_ANALOG_PERI_TOUCH_BYPASS_NN_THRES_V 0x00000001U
#define LP_ANALOG_PERI_TOUCH_BYPASS_NEG_NOISE_THRES_S 31 #define LP_ANALOG_PERI_TOUCH_BYPASS_NN_THRES_S 31
/** LP_ANALOG_PERI_TOUCH_FILTER3_REG register /** LP_ANALOG_PERI_TOUCH_FILTER3_REG register
* need_des * need_des
*/ */
#define LP_ANALOG_PERI_TOUCH_FILTER3_REG (DR_REG_LP_ANALOG_PERI_BASE + 0x118) #define LP_ANALOG_PERI_TOUCH_FILTER3_REG (DR_REG_LP_ANALOG_PERI_BASE + 0x118)
/** LP_ANALOG_PERI_TOUCH_BASELINE_SW : R/W; bitpos: [15:0]; default: 0; /** LP_ANALOG_PERI_TOUCH_BENCHMARK_SW : R/W; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
#define LP_ANALOG_PERI_TOUCH_BASELINE_SW 0x0000FFFFU #define LP_ANALOG_PERI_TOUCH_BENCHMARK_SW 0x0000FFFFU
#define LP_ANALOG_PERI_TOUCH_BASELINE_SW_M (LP_ANALOG_PERI_TOUCH_BASELINE_SW_V << LP_ANALOG_PERI_TOUCH_BASELINE_SW_S) #define LP_ANALOG_PERI_TOUCH_BENCHMARK_SW_M (LP_ANALOG_PERI_TOUCH_BENCHMARK_SW_V << LP_ANALOG_PERI_TOUCH_BENCHMARK_SW_S)
#define LP_ANALOG_PERI_TOUCH_BASELINE_SW_V 0x0000FFFFU #define LP_ANALOG_PERI_TOUCH_BENCHMARK_SW_V 0x0000FFFFU
#define LP_ANALOG_PERI_TOUCH_BASELINE_SW_S 0 #define LP_ANALOG_PERI_TOUCH_BENCHMARK_SW_S 0
/** LP_ANALOG_PERI_TOUCH_UPDATE_BASELINE_SW : WT; bitpos: [16]; default: 0; /** LP_ANALOG_PERI_TOUCH_UPDATE_BENCHMARK_SW : WT; bitpos: [16]; default: 0;
* need_des * need_des
*/ */
#define LP_ANALOG_PERI_TOUCH_UPDATE_BASELINE_SW (BIT(16)) #define LP_ANALOG_PERI_TOUCH_UPDATE_BENCHMARK_SW (BIT(16))
#define LP_ANALOG_PERI_TOUCH_UPDATE_BASELINE_SW_M (LP_ANALOG_PERI_TOUCH_UPDATE_BASELINE_SW_V << LP_ANALOG_PERI_TOUCH_UPDATE_BASELINE_SW_S) #define LP_ANALOG_PERI_TOUCH_UPDATE_BENCHMARK_SW_M (LP_ANALOG_PERI_TOUCH_UPDATE_BENCHMARK_SW_V << LP_ANALOG_PERI_TOUCH_UPDATE_BENCHMARK_SW_S)
#define LP_ANALOG_PERI_TOUCH_UPDATE_BASELINE_SW_V 0x00000001U #define LP_ANALOG_PERI_TOUCH_UPDATE_BENCHMARK_SW_V 0x00000001U
#define LP_ANALOG_PERI_TOUCH_UPDATE_BASELINE_SW_S 16 #define LP_ANALOG_PERI_TOUCH_UPDATE_BENCHMARK_SW_S 16
/** LP_ANALOG_PERI_TOUCH_SLP0_REG register /** LP_ANALOG_PERI_TOUCH_SLP0_REG register
* need_des * need_des

View File

@ -1,5 +1,5 @@
/** /**
* SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -510,18 +510,18 @@ typedef union {
*/ */
typedef union { typedef union {
struct { struct {
/** touch_neg_noise_disupdate_baseline_en : R/W; bitpos: [0]; default: 0; /** touch_nn_disupdate_benchmark_en : R/W; bitpos: [0]; default: 0;
* Reserved * Reserved
*/ */
uint32_t touch_neg_noise_disupdate_baseline_en:1; uint32_t touch_nn_disupdate_benchmark_en:1;
/** touch_hysteresis : R/W; bitpos: [2:1]; default: 0; /** touch_hysteresis : R/W; bitpos: [2:1]; default: 0;
* need_des * need_des
*/ */
uint32_t touch_hysteresis:2; uint32_t touch_hysteresis:2;
/** touch_neg_noise_thres : R/W; bitpos: [4:3]; default: 0; /** touch_nn_thres : R/W; bitpos: [4:3]; default: 0;
* need_des * need_des
*/ */
uint32_t touch_neg_noise_thres:2; uint32_t touch_nn_thres:2;
/** touch_noise_thres : R/W; bitpos: [6:5]; default: 0; /** touch_noise_thres : R/W; bitpos: [6:5]; default: 0;
* need_des * need_des
*/ */
@ -542,10 +542,10 @@ typedef union {
* need_des * need_des
*/ */
uint32_t touch_filter_en:1; uint32_t touch_filter_en:1;
/** touch_neg_noise_limit : R/W; bitpos: [20:17]; default: 5; /** touch_nn_limit : R/W; bitpos: [20:17]; default: 5;
* need_des * need_des
*/ */
uint32_t touch_neg_noise_limit:4; uint32_t touch_nn_limit:4;
/** touch_approach_limit : R/W; bitpos: [28:21]; default: 80; /** touch_approach_limit : R/W; bitpos: [28:21]; default: 80;
* need_des * need_des
*/ */
@ -572,10 +572,10 @@ typedef union {
* need_des * need_des
*/ */
uint32_t touch_bypass_noise_thres:1; uint32_t touch_bypass_noise_thres:1;
/** touch_bypass_neg_noise_thres : R/W; bitpos: [31]; default: 0; /** touch_bypass_nn_thres : R/W; bitpos: [31]; default: 0;
* need_des * need_des
*/ */
uint32_t touch_bypass_neg_noise_thres:1; uint32_t touch_bypass_nn_thres:1;
}; };
uint32_t val; uint32_t val;
} lp_analog_peri_touch_filter2_reg_t; } lp_analog_peri_touch_filter2_reg_t;
@ -585,14 +585,14 @@ typedef union {
*/ */
typedef union { typedef union {
struct { struct {
/** touch_baseline_sw : R/W; bitpos: [15:0]; default: 0; /** touch_benchmark_sw : R/W; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
uint32_t touch_baseline_sw:16; uint32_t touch_benchmark_sw:16;
/** touch_update_baseline_sw : WT; bitpos: [16]; default: 0; /** touch_update_benchmark_sw : WT; bitpos: [16]; default: 0;
* need_des * need_des
*/ */
uint32_t touch_update_baseline_sw:1; uint32_t touch_update_benchmark_sw:1;
uint32_t reserved_17:15; uint32_t reserved_17:15;
}; };
uint32_t val; uint32_t val;
@ -704,10 +704,14 @@ typedef union {
* High speed touch driver * High speed touch driver
*/ */
uint32_t touch_freq_drv_hs:5; uint32_t touch_freq_drv_hs:5;
/** touch_freq_dbias : R/W; bitpos: [22:18]; default: 0; /** touch_bypass_shield : R/W; bitpos: [18]; default: 0;
* bypass the shield channel output (only available since ECO1)
*/
uint32_t touch_bypass_shield:1;
/** touch_freq_dbias : R/W; bitpos: [22:19]; default: 0;
* Internal LDO voltage * Internal LDO voltage
*/ */
uint32_t touch_freq_dbias:5; uint32_t touch_freq_dbias:4;
uint32_t reserved_23:9; uint32_t reserved_23:9;
}; };
uint32_t val; uint32_t val;
@ -746,7 +750,7 @@ typedef union {
/** touch_data_sel : R/W; bitpos: [9:8]; default: 0; /** touch_data_sel : R/W; bitpos: [9:8]; default: 0;
* The type of the output data for debugging * The type of the output data for debugging
* 0/1: raw data * 0/1: raw data
* 2: baseline * 2: benchmark
* 3: smooth data * 3: smooth data
*/ */
uint32_t touch_data_sel:2; uint32_t touch_data_sel:2;
@ -840,7 +844,7 @@ typedef union {
typedef struct { typedef struct {
volatile lp_analog_peri_touch_pad_thn_reg_t thn[3]; volatile lp_analog_peri_touch_pad_thn_reg_t thresh[3];
} lp_analog_peri_touch_padx_thn_reg_t; } lp_analog_peri_touch_padx_thn_reg_t;
typedef struct { typedef struct {

View File

@ -87,7 +87,7 @@
#define SOC_ASSIST_DEBUG_SUPPORTED 1 #define SOC_ASSIST_DEBUG_SUPPORTED 1
#define SOC_WDT_SUPPORTED 1 #define SOC_WDT_SUPPORTED 1
#define SOC_SPI_FLASH_SUPPORTED 1 #define SOC_SPI_FLASH_SUPPORTED 1
// #define SOC_TOUCH_SENSOR_SUPPORTED 1 //TODO: IDF-7477 #define SOC_TOUCH_SENSOR_SUPPORTED 1
#define SOC_RNG_SUPPORTED 1 #define SOC_RNG_SUPPORTED 1
#define SOC_GP_LDO_SUPPORTED 1 // General purpose LDO #define SOC_GP_LDO_SUPPORTED 1 // General purpose LDO
#define SOC_PPA_SUPPORTED 1 #define SOC_PPA_SUPPORTED 1
@ -549,11 +549,17 @@
#define SOC_MWDT_SUPPORT_XTAL (1) #define SOC_MWDT_SUPPORT_XTAL (1)
/*-------------------------- TOUCH SENSOR CAPS -------------------------------*/ /*-------------------------- TOUCH SENSOR CAPS -------------------------------*/
#define SOC_TOUCH_SENSOR_VERSION (3) // Hardware version of touch sensor #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_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) // Support touch proximity channel number.
#define SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED (1) // Support touch proximity channel measure done interrupt type. /* Touch Sensor Features */
#define SOC_TOUCH_SAMPLER_NUM (3) // The sampler number in total, each sampler can be used to sample on one frequency #define SOC_TOUCH_SUPPORT_SLEEP_WAKEUP (1) /*!< Touch sensor supports sleep awake */
#define SOC_TOUCH_SUPPORT_WATERPROOF (1) /*!< Touch sensor supports waterproof */
#define SOC_TOUCH_SUPPORT_PROX_SENSING (1) /*!< Touch sensor supports proximity sensing */
#define SOC_TOUCH_PROXIMITY_CHANNEL_NUM (3) /*!< Support touch proximity channel number. */
#define SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED (1) /*!< Support touch proximity channel measure done interrupt type. */
#define SOC_TOUCH_SUPPORT_FREQ_HOP (1) /*!< Touch sensor supports frequency hopping */
#define SOC_TOUCH_SAMPLE_CFG_NUM (3) /*!< The sample configurations number in total, each sampler can be used to sample on one frequency */
/*-------------------------- TWAI CAPS ---------------------------------------*/ /*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 3 #define SOC_TWAI_CONTROLLER_NUM 3
@ -621,6 +627,7 @@
#define SOC_PM_SUPPORT_EXT1_WAKEUP_MODE_PER_PIN (1) /*!<Supports one bit per pin to configure the EXT1 trigger level */ #define SOC_PM_SUPPORT_EXT1_WAKEUP_MODE_PER_PIN (1) /*!<Supports one bit per pin to configure the EXT1 trigger level */
#define SOC_PM_EXT1_WAKEUP_BY_PMU (1) #define SOC_PM_EXT1_WAKEUP_BY_PMU (1)
#define SOC_PM_SUPPORT_WIFI_WAKEUP (1) #define SOC_PM_SUPPORT_WIFI_WAKEUP (1)
#define SOC_PM_SUPPORT_TOUCH_SENSOR_WAKEUP (1) /*!<Supports waking up from touch pad trigger */
#define SOC_PM_SUPPORT_XTAL32K_PD (1) #define SOC_PM_SUPPORT_XTAL32K_PD (1)
#define SOC_PM_SUPPORT_RC32K_PD (1) #define SOC_PM_SUPPORT_RC32K_PD (1)
#define SOC_PM_SUPPORT_RC_FAST_PD (1) #define SOC_PM_SUPPORT_RC_FAST_PD (1)

View File

@ -1,5 +1,5 @@
/** /**
* SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -14,7 +14,7 @@ extern "C" {
/** RTC_TOUCH_INT_RAW_REG register /** RTC_TOUCH_INT_RAW_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_INT_RAW_REG (DR_REG_RTC_TOUCH_BASE + 0x0) #define RTC_TOUCH_INT_RAW_REG (DR_REG_LP_TOUCH_BASE + 0x0)
/** RTC_TOUCH_SCAN_DONE_INT_RAW : R/WTC/SS; bitpos: [0]; default: 0; /** RTC_TOUCH_SCAN_DONE_INT_RAW : R/WTC/SS; bitpos: [0]; default: 0;
* need_des * need_des
*/ */
@ -61,7 +61,7 @@ extern "C" {
/** RTC_TOUCH_INT_ST_REG register /** RTC_TOUCH_INT_ST_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_INT_ST_REG (DR_REG_RTC_TOUCH_BASE + 0x4) #define RTC_TOUCH_INT_ST_REG (DR_REG_LP_TOUCH_BASE + 0x4)
/** RTC_TOUCH_SCAN_DONE_INT_ST : RO; bitpos: [0]; default: 0; /** RTC_TOUCH_SCAN_DONE_INT_ST : RO; bitpos: [0]; default: 0;
* need_des * need_des
*/ */
@ -108,7 +108,7 @@ extern "C" {
/** RTC_TOUCH_INT_ENA_REG register /** RTC_TOUCH_INT_ENA_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_INT_ENA_REG (DR_REG_RTC_TOUCH_BASE + 0x8) #define RTC_TOUCH_INT_ENA_REG (DR_REG_LP_TOUCH_BASE + 0x8)
/** RTC_TOUCH_SCAN_DONE_INT_ENA : R/W; bitpos: [0]; default: 0; /** RTC_TOUCH_SCAN_DONE_INT_ENA : R/W; bitpos: [0]; default: 0;
* need_des * need_des
*/ */
@ -155,7 +155,7 @@ extern "C" {
/** RTC_TOUCH_INT_CLR_REG register /** RTC_TOUCH_INT_CLR_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_INT_CLR_REG (DR_REG_RTC_TOUCH_BASE + 0xc) #define RTC_TOUCH_INT_CLR_REG (DR_REG_LP_TOUCH_BASE + 0xc)
/** RTC_TOUCH_SCAN_DONE_INT_CLR : WT; bitpos: [0]; default: 0; /** RTC_TOUCH_SCAN_DONE_INT_CLR : WT; bitpos: [0]; default: 0;
* need_des * need_des
*/ */
@ -202,7 +202,7 @@ extern "C" {
/** RTC_TOUCH_CHN_STATUS_REG register /** RTC_TOUCH_CHN_STATUS_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_CHN_STATUS_REG (DR_REG_RTC_TOUCH_BASE + 0x10) #define RTC_TOUCH_CHN_STATUS_REG (DR_REG_LP_TOUCH_BASE + 0x10)
/** RTC_TOUCH_PAD_ACTIVE : RO; bitpos: [14:0]; default: 0; /** RTC_TOUCH_PAD_ACTIVE : RO; bitpos: [14:0]; default: 0;
* need_des * need_des
*/ */
@ -228,7 +228,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_0_REG register /** RTC_TOUCH_STATUS_0_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_0_REG (DR_REG_RTC_TOUCH_BASE + 0x14) #define RTC_TOUCH_STATUS_0_REG (DR_REG_LP_TOUCH_BASE + 0x14)
/** RTC_TOUCH_PAD0_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD0_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -254,7 +254,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_1_REG register /** RTC_TOUCH_STATUS_1_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_1_REG (DR_REG_RTC_TOUCH_BASE + 0x18) #define RTC_TOUCH_STATUS_1_REG (DR_REG_LP_TOUCH_BASE + 0x18)
/** RTC_TOUCH_PAD1_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD1_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -280,7 +280,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_2_REG register /** RTC_TOUCH_STATUS_2_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_2_REG (DR_REG_RTC_TOUCH_BASE + 0x1c) #define RTC_TOUCH_STATUS_2_REG (DR_REG_LP_TOUCH_BASE + 0x1c)
/** RTC_TOUCH_PAD2_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD2_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -306,7 +306,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_3_REG register /** RTC_TOUCH_STATUS_3_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_3_REG (DR_REG_RTC_TOUCH_BASE + 0x20) #define RTC_TOUCH_STATUS_3_REG (DR_REG_LP_TOUCH_BASE + 0x20)
/** RTC_TOUCH_PAD3_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD3_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -332,7 +332,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_4_REG register /** RTC_TOUCH_STATUS_4_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_4_REG (DR_REG_RTC_TOUCH_BASE + 0x24) #define RTC_TOUCH_STATUS_4_REG (DR_REG_LP_TOUCH_BASE + 0x24)
/** RTC_TOUCH_PAD4_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD4_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -358,7 +358,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_5_REG register /** RTC_TOUCH_STATUS_5_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_5_REG (DR_REG_RTC_TOUCH_BASE + 0x28) #define RTC_TOUCH_STATUS_5_REG (DR_REG_LP_TOUCH_BASE + 0x28)
/** RTC_TOUCH_PAD5_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD5_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -384,7 +384,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_6_REG register /** RTC_TOUCH_STATUS_6_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_6_REG (DR_REG_RTC_TOUCH_BASE + 0x2c) #define RTC_TOUCH_STATUS_6_REG (DR_REG_LP_TOUCH_BASE + 0x2c)
/** RTC_TOUCH_PAD6_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD6_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -410,7 +410,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_7_REG register /** RTC_TOUCH_STATUS_7_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_7_REG (DR_REG_RTC_TOUCH_BASE + 0x30) #define RTC_TOUCH_STATUS_7_REG (DR_REG_LP_TOUCH_BASE + 0x30)
/** RTC_TOUCH_PAD7_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD7_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -436,7 +436,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_8_REG register /** RTC_TOUCH_STATUS_8_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_8_REG (DR_REG_RTC_TOUCH_BASE + 0x34) #define RTC_TOUCH_STATUS_8_REG (DR_REG_LP_TOUCH_BASE + 0x34)
/** RTC_TOUCH_PAD8_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD8_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -462,7 +462,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_9_REG register /** RTC_TOUCH_STATUS_9_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_9_REG (DR_REG_RTC_TOUCH_BASE + 0x38) #define RTC_TOUCH_STATUS_9_REG (DR_REG_LP_TOUCH_BASE + 0x38)
/** RTC_TOUCH_PAD9_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD9_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -488,7 +488,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_10_REG register /** RTC_TOUCH_STATUS_10_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_10_REG (DR_REG_RTC_TOUCH_BASE + 0x3c) #define RTC_TOUCH_STATUS_10_REG (DR_REG_LP_TOUCH_BASE + 0x3c)
/** RTC_TOUCH_PAD10_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD10_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -514,7 +514,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_11_REG register /** RTC_TOUCH_STATUS_11_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_11_REG (DR_REG_RTC_TOUCH_BASE + 0x40) #define RTC_TOUCH_STATUS_11_REG (DR_REG_LP_TOUCH_BASE + 0x40)
/** RTC_TOUCH_PAD11_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD11_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -540,7 +540,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_12_REG register /** RTC_TOUCH_STATUS_12_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_12_REG (DR_REG_RTC_TOUCH_BASE + 0x44) #define RTC_TOUCH_STATUS_12_REG (DR_REG_LP_TOUCH_BASE + 0x44)
/** RTC_TOUCH_PAD12_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD12_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -566,7 +566,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_13_REG register /** RTC_TOUCH_STATUS_13_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_13_REG (DR_REG_RTC_TOUCH_BASE + 0x48) #define RTC_TOUCH_STATUS_13_REG (DR_REG_LP_TOUCH_BASE + 0x48)
/** RTC_TOUCH_PAD13_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD13_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -592,7 +592,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_14_REG register /** RTC_TOUCH_STATUS_14_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_14_REG (DR_REG_RTC_TOUCH_BASE + 0x4c) #define RTC_TOUCH_STATUS_14_REG (DR_REG_LP_TOUCH_BASE + 0x4c)
/** RTC_TOUCH_PAD14_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_PAD14_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -618,7 +618,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_15_REG register /** RTC_TOUCH_STATUS_15_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_15_REG (DR_REG_RTC_TOUCH_BASE + 0x50) #define RTC_TOUCH_STATUS_15_REG (DR_REG_LP_TOUCH_BASE + 0x50)
/** RTC_TOUCH_SLP_DATA : RO; bitpos: [15:0]; default: 0; /** RTC_TOUCH_SLP_DATA : RO; bitpos: [15:0]; default: 0;
* need_des * need_des
*/ */
@ -644,7 +644,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_16_REG register /** RTC_TOUCH_STATUS_16_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_16_REG (DR_REG_RTC_TOUCH_BASE + 0x54) #define RTC_TOUCH_STATUS_16_REG (DR_REG_LP_TOUCH_BASE + 0x54)
/** RTC_TOUCH_APPROACH_PAD2_CNT : RO; bitpos: [7:0]; default: 0; /** RTC_TOUCH_APPROACH_PAD2_CNT : RO; bitpos: [7:0]; default: 0;
* need_des * need_des
*/ */
@ -677,7 +677,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_17_REG register /** RTC_TOUCH_STATUS_17_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_STATUS_17_REG (DR_REG_RTC_TOUCH_BASE + 0x58) #define RTC_TOUCH_STATUS_17_REG (DR_REG_LP_TOUCH_BASE + 0x58)
/** RTC_TOUCH_DCAP_LPF : RO; bitpos: [6:0]; default: 0; /** RTC_TOUCH_DCAP_LPF : RO; bitpos: [6:0]; default: 0;
* Reserved * Reserved
*/ */
@ -724,7 +724,7 @@ extern "C" {
/** RTC_TOUCH_CHN_TMP_STATUS_REG register /** RTC_TOUCH_CHN_TMP_STATUS_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_CHN_TMP_STATUS_REG (DR_REG_RTC_TOUCH_BASE + 0x5c) #define RTC_TOUCH_CHN_TMP_STATUS_REG (DR_REG_LP_TOUCH_BASE + 0x5c)
/** RTC_TOUCH_PAD_INACTIVE_STATUS : RO; bitpos: [14:0]; default: 0; /** RTC_TOUCH_PAD_INACTIVE_STATUS : RO; bitpos: [14:0]; default: 0;
* need_des * need_des
*/ */
@ -743,7 +743,7 @@ extern "C" {
/** RTC_TOUCH_DATE_REG register /** RTC_TOUCH_DATE_REG register
* need_des * need_des
*/ */
#define RTC_TOUCH_DATE_REG (DR_REG_RTC_TOUCH_BASE + 0x100) #define RTC_TOUCH_DATE_REG (DR_REG_LP_TOUCH_BASE + 0x100)
/** RTC_TOUCH_DATE : R/W; bitpos: [27:0]; default: 2294548; /** RTC_TOUCH_DATE : R/W; bitpos: [27:0]; default: 2294548;
* need_des * need_des
*/ */

View File

@ -270,7 +270,7 @@ typedef union {
uint32_t reserved_25:7; uint32_t reserved_25:7;
}; };
uint32_t val; uint32_t val;
} rtc_touch_sampler_status_reg_t; } rtc_touch_sample_status_reg_t;
/** Type of chn_tmp_status register /** Type of chn_tmp_status register
* Realtime channel status * Realtime channel status
@ -320,7 +320,7 @@ typedef struct {
volatile rtc_touch_chn_data_reg_t chn_data[15]; volatile rtc_touch_chn_data_reg_t chn_data[15];
volatile rtc_touch_slp_ch_data_reg_t slp_ch_data; 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_aprch_ch_data_reg_t aprch_ch_data;
volatile rtc_touch_sampler_status_reg_t sampler_status; volatile rtc_touch_sample_status_reg_t sample_status;
volatile rtc_touch_chn_tmp_status_reg_t chn_tmp_status; volatile rtc_touch_chn_tmp_status_reg_t chn_tmp_status;
uint32_t reserved_060[40]; uint32_t reserved_060[40];
volatile rtc_touch_date_reg_t date; volatile rtc_touch_date_reg_t date;

View File

@ -4,7 +4,7 @@
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
#include "soc/touch_sensor_periph.h" #include "soc/touch_sensor_channel.h"
/* Store IO number corresponding to the Touch Sensor channel number. */ /* Store IO number corresponding to the Touch Sensor channel number. */
/* Note: T14 is an internal channel that does not have a corresponding external GPIO. */ /* Note: T14 is an internal channel that does not have a corresponding external GPIO. */

View File

@ -803,11 +803,23 @@ config SOC_TOUCH_SENSOR_NUM
int int
default 15 default 15
config SOC_TOUCH_SUPPORT_SLEEP_WAKEUP
bool
default y
config SOC_TOUCH_SUPPORT_WATERPROOF
bool
default y
config SOC_TOUCH_SUPPORT_PROX_SENSING
bool
default y
config SOC_TOUCH_PROXIMITY_CHANNEL_NUM config SOC_TOUCH_PROXIMITY_CHANNEL_NUM
int int
default 3 default 3
config SOC_TOUCH_SAMPLER_NUM config SOC_TOUCH_SAMPLE_CFG_NUM
int int
default 1 default 1

View File

@ -338,9 +338,12 @@
/*-------------------------- TOUCH SENSOR CAPS -------------------------------*/ /*-------------------------- TOUCH SENSOR CAPS -------------------------------*/
#define SOC_TOUCH_SENSOR_VERSION (2) /*!< 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_SENSOR_NUM (15) /*!< 15 Touch channels */
#define SOC_TOUCH_SUPPORT_SLEEP_WAKEUP (1) /*!< Touch sensor supports sleep awake */
#define SOC_TOUCH_SUPPORT_WATERPROOF (1) /*!< Touch sensor supports waterproof */
#define SOC_TOUCH_SUPPORT_PROX_SENSING (1) /*!< Touch sensor supports proximity sensing */
#define SOC_TOUCH_PROXIMITY_CHANNEL_NUM (3) /*!< Support touch proximity channel number. */ #define SOC_TOUCH_PROXIMITY_CHANNEL_NUM (3) /*!< Support touch proximity channel number. */
#define SOC_TOUCH_SAMPLER_NUM (1U) /*!< The sampler number in total, each sampler can be used to sample on one frequency */ #define SOC_TOUCH_SAMPLE_CFG_NUM (1U) /*!< The sample configuration number in total, each sampler can be used to sample on one frequency */
/*-------------------------- TWAI CAPS ---------------------------------------*/ /*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL #define SOC_TWAI_CONTROLLER_NUM 1UL

View File

@ -4,7 +4,7 @@
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
#include "soc/touch_sensor_periph.h" #include "soc/touch_sensor_channel.h"
/* Store IO number corresponding to the Touch Sensor channel number. */ /* Store IO number corresponding to the Touch Sensor channel number. */
/* Note: T0 is an internal channel that does not have a corresponding external GPIO. */ /* Note: T0 is an internal channel that does not have a corresponding external GPIO. */

View File

@ -959,6 +959,18 @@ config SOC_TOUCH_SENSOR_NUM
int int
default 15 default 15
config SOC_TOUCH_SUPPORT_SLEEP_WAKEUP
bool
default y
config SOC_TOUCH_SUPPORT_WATERPROOF
bool
default y
config SOC_TOUCH_SUPPORT_PROX_SENSING
bool
default y
config SOC_TOUCH_PROXIMITY_CHANNEL_NUM config SOC_TOUCH_PROXIMITY_CHANNEL_NUM
int int
default 3 default 3
@ -967,7 +979,7 @@ config SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED
bool bool
default y default y
config SOC_TOUCH_SAMPLER_NUM config SOC_TOUCH_SAMPLE_CFG_NUM
int int
default 1 default 1

View File

@ -1,16 +1,8 @@
// Copyright 2017-2021 Espressif Systems (Shanghai) PTE LTD /*
// * SPDX-FileCopyrightText: 2017-2024 Espressif Systems (Shanghai) CO LTD
// Licensed under the Apache License, Version 2.0 (the "License"); *
// you may not use this file except in compliance with the License. * SPDX-License-Identifier: Apache-2.0
// You may obtain a copy of the License at */
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef _SOC_SENS_REG_H_ #ifndef _SOC_SENS_REG_H_
#define _SOC_SENS_REG_H_ #define _SOC_SENS_REG_H_
@ -602,7 +594,7 @@ extern "C" {
#define SENS_TOUCH_DENOISE_END_V 0x1 #define SENS_TOUCH_DENOISE_END_V 0x1
#define SENS_TOUCH_DENOISE_END_S 18 #define SENS_TOUCH_DENOISE_END_S 18
/* SENS_TOUCH_DATA_SEL : R/W ;bitpos:[17:16] ;default: 2'd0 ; */ /* SENS_TOUCH_DATA_SEL : R/W ;bitpos:[17:16] ;default: 2'd0 ; */
/*description: 3: smooth data 2: baseline 1,0: raw_data.*/ /*description: 3: smooth data 2: benchmark 1,0: raw_data.*/
#define SENS_TOUCH_DATA_SEL 0x00000003 #define SENS_TOUCH_DATA_SEL 0x00000003
#define SENS_TOUCH_DATA_SEL_M ((SENS_TOUCH_DATA_SEL_V)<<(SENS_TOUCH_DATA_SEL_S)) #define SENS_TOUCH_DATA_SEL_M ((SENS_TOUCH_DATA_SEL_V)<<(SENS_TOUCH_DATA_SEL_S))
#define SENS_TOUCH_DATA_SEL_V 0x3 #define SENS_TOUCH_DATA_SEL_V 0x3
@ -1378,8 +1370,8 @@ extern "C" {
#define SENS_SAR_HALL_CTRL_REG (DR_REG_SENS_BASE + 0xFC) #define SENS_SAR_HALL_CTRL_REG (DR_REG_SENS_BASE + 0xFC)
/* SENS_HALL_PHASE_FORCE : R/W ;bitpos:[31] ;default: 1'b1 ; */ /* SENS_HALL_PHASE_FORCE : R/W ;bitpos:[31] ;default: 1'b1 ; */
/*description: 1: HALL PHASE is controlled by SW 0: HALL PHASE is controlled by FSM in ULP-cop /*description: 1: HALL PHASE is controlled by SW 0: HALL PHASE is controlled by FSM in
rocessor.*/ ULP-coprocessor.*/
#define SENS_HALL_PHASE_FORCE (BIT(31)) #define SENS_HALL_PHASE_FORCE (BIT(31))
#define SENS_HALL_PHASE_FORCE_M (BIT(31)) #define SENS_HALL_PHASE_FORCE_M (BIT(31))
#define SENS_HALL_PHASE_FORCE_V 0x1 #define SENS_HALL_PHASE_FORCE_V 0x1

View File

@ -217,7 +217,7 @@ typedef volatile struct sens_dev_s {
struct { struct {
uint32_t touch_outen : 15; /*touch controller output enable*/ uint32_t touch_outen : 15; /*touch controller output enable*/
uint32_t touch_status_clr : 1; /*clear all touch active status*/ uint32_t touch_status_clr : 1; /*clear all touch active status*/
uint32_t touch_data_sel : 2; /*3: smooth data 2: baseline 1,0: raw_data*/ uint32_t touch_data_sel : 2; /*3: smooth data 2: benchmark 1,0: raw_data*/
uint32_t touch_denoise_end : 1; /*touch_denoise_done*/ uint32_t touch_denoise_end : 1; /*touch_denoise_done*/
uint32_t touch_unit_end : 1; /*touch_unit_done*/ uint32_t touch_unit_end : 1; /*touch_unit_done*/
uint32_t touch_approach_pad2 : 4; /*indicate which pad is approach pad2*/ uint32_t touch_approach_pad2 : 4; /*indicate which pad is approach pad2*/

View File

@ -1,5 +1,5 @@
/* /*
* SPDX-FileCopyrightText: 2019-2023 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2019-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -370,12 +370,15 @@
#define SOC_TIMER_GROUP_TOTAL_TIMERS (4) #define SOC_TIMER_GROUP_TOTAL_TIMERS (4)
/*-------------------------- TOUCH SENSOR CAPS -------------------------------*/ /*-------------------------- TOUCH SENSOR CAPS -------------------------------*/
#define SOC_TOUCH_SENSOR_VERSION (2) // 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_SENSOR_NUM (15) /*!< 15 Touch channels */
#define SOC_TOUCH_PROXIMITY_CHANNEL_NUM (3) /* Sopport touch proximity channel number. */ #define SOC_TOUCH_SUPPORT_SLEEP_WAKEUP (1) /*!< Touch sensor supports sleep awake */
#define SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED (1) /*Sopport touch proximity channel measure done interrupt type. */ #define SOC_TOUCH_SUPPORT_WATERPROOF (1) /*!< Touch sensor supports waterproof */
#define SOC_TOUCH_SUPPORT_PROX_SENSING (1) /*!< Touch sensor supports proximity sensing */
#define SOC_TOUCH_PROXIMITY_CHANNEL_NUM (3) /*!< Support touch proximity sensing channel number. */
#define SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED (1) /*!< Support touch proximity sensing measure done interrupt type. */
#define SOC_TOUCH_SAMPLER_NUM (1U) /*!< The sampler number in total, each sampler can be used to sample on one frequency */ #define SOC_TOUCH_SAMPLE_CFG_NUM (1U) /*!< The sample configuration number in total, each sampler can be used to sample on one frequency */
/*-------------------------- TWAI CAPS ---------------------------------------*/ /*-------------------------- TWAI CAPS ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL #define SOC_TWAI_CONTROLLER_NUM 1UL

View File

@ -4,7 +4,7 @@
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
#include "soc/touch_sensor_periph.h" #include "soc/touch_sensor_channel.h"
/* Store IO number corresponding to the Touch Sensor channel number. */ /* Store IO number corresponding to the Touch Sensor channel number. */
/* Note: T0 is an internal channel that does not have a corresponding external GPIO. */ /* Note: T0 is an internal channel that does not have a corresponding external GPIO. */

View File

@ -1,5 +1,5 @@
/* /*
* SPDX-FileCopyrightText: 2019-2022 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2019-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Apache-2.0 * SPDX-License-Identifier: Apache-2.0
*/ */
@ -7,14 +7,6 @@
#pragma once #pragma once
#include "soc/soc_caps.h" #include "soc/soc_caps.h"
#if SOC_TOUCH_SENSOR_SUPPORTED
#include "soc/touch_sensor_channel.h"
#include "soc/rtc_cntl_reg.h"
#include "soc/rtc_cntl_struct.h"
#include "soc/sens_reg.h"
#include "soc/sens_struct.h"
#include "soc/rtc_io_struct.h"
#endif // SOC_TOUCH_SENSOR_SUPPORTED
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {

File diff suppressed because one or more lines are too long

After

Width:  |  Height:  |  Size: 31 KiB

File diff suppressed because one or more lines are too long

After

Width:  |  Height:  |  Size: 27 KiB

View File

@ -108,8 +108,6 @@ LDO_DOCS = ['api-reference/peripherals/ldo_regulator.rst']
TEMP_SENSOR_DOCS = ['api-reference/peripherals/temp_sensor.rst'] TEMP_SENSOR_DOCS = ['api-reference/peripherals/temp_sensor.rst']
TOUCH_SENSOR_DOCS = ['api-reference/peripherals/touch_pad.rst']
SPIRAM_DOCS = ['api-guides/external-ram.rst'] SPIRAM_DOCS = ['api-guides/external-ram.rst']
USB_DOCS = ['api-reference/peripherals/usb_device.rst', USB_DOCS = ['api-reference/peripherals/usb_device.rst',
@ -185,6 +183,7 @@ ESP32_DOCS = ['api-reference/system/himem.rst',
'security/secure-boot-v1.rst', 'security/secure-boot-v1.rst',
'api-reference/peripherals/dac.rst', 'api-reference/peripherals/dac.rst',
'api-reference/peripherals/sd_pullup_requirements.rst', 'api-reference/peripherals/sd_pullup_requirements.rst',
'api-reference/peripherals/touch_pad.rst',
'hw-reference/esp32/**', 'hw-reference/esp32/**',
'api-guides/RF_calibration.rst', 'api-guides/RF_calibration.rst',
'api-guides/phy.rst'] + FTDI_JTAG_DOCS + QEMU_DOCS 'api-guides/phy.rst'] + FTDI_JTAG_DOCS + QEMU_DOCS
@ -194,6 +193,7 @@ ESP32S2_DOCS = ['hw-reference/esp32s2/**',
'api-reference/peripherals/ds.rst', 'api-reference/peripherals/ds.rst',
'api-reference/peripherals/temp_sensor.rst', 'api-reference/peripherals/temp_sensor.rst',
'api-reference/system/async_memcpy.rst', 'api-reference/system/async_memcpy.rst',
'api-reference/peripherals/touch_pad.rst',
'api-reference/peripherals/touch_element.rst', 'api-reference/peripherals/touch_element.rst',
'api-guides/RF_calibration.rst', 'api-guides/RF_calibration.rst',
'api-guides/phy.rst'] + FTDI_JTAG_DOCS + USB_OTG_DFU_DOCS + USB_OTG_CONSOLE_DOCS 'api-guides/phy.rst'] + FTDI_JTAG_DOCS + USB_OTG_DFU_DOCS + USB_OTG_CONSOLE_DOCS
@ -201,6 +201,7 @@ ESP32S2_DOCS = ['hw-reference/esp32s2/**',
ESP32S3_DOCS = ['hw-reference/esp32s3/**', ESP32S3_DOCS = ['hw-reference/esp32s3/**',
'api-reference/system/ipc.rst', 'api-reference/system/ipc.rst',
'api-guides/flash_psram_config.rst', 'api-guides/flash_psram_config.rst',
'api-reference/peripherals/touch_pad.rst',
'api-reference/peripherals/sd_pullup_requirements.rst', 'api-reference/peripherals/sd_pullup_requirements.rst',
'api-guides/RF_calibration.rst', 'api-guides/RF_calibration.rst',
'api-guides/phy.rst'] + USB_OTG_DFU_DOCS + USB_OTG_CONSOLE_DOCS 'api-guides/phy.rst'] + USB_OTG_DFU_DOCS + USB_OTG_CONSOLE_DOCS
@ -223,6 +224,7 @@ ESP32H2_DOCS = ['api-guides/RF_calibration.rst',
'api-guides/phy.rst'] 'api-guides/phy.rst']
ESP32P4_DOCS = ['api-reference/system/ipc.rst', ESP32P4_DOCS = ['api-reference/system/ipc.rst',
'api-reference/peripherals/cap_touch_sens.rst',
'api-reference/peripherals/sd_pullup_requirements.rst'] 'api-reference/peripherals/sd_pullup_requirements.rst']
# format: {tag needed to include: documents to included}, tags are parsed from sdkconfig and peripheral_caps.h headers # format: {tag needed to include: documents to included}, tags are parsed from sdkconfig and peripheral_caps.h headers
@ -253,7 +255,6 @@ conditional_include_dict = {'SOC_BT_SUPPORTED':BT_DOCS,
'SOC_RMT_SUPPORTED':RMT_DOCS, 'SOC_RMT_SUPPORTED':RMT_DOCS,
'SOC_DAC_SUPPORTED':DAC_DOCS, 'SOC_DAC_SUPPORTED':DAC_DOCS,
'SOC_ETM_SUPPORTED':ETM_DOCS, 'SOC_ETM_SUPPORTED':ETM_DOCS,
'SOC_TOUCH_SENSOR_SUPPORTED':TOUCH_SENSOR_DOCS,
'SOC_ULP_FSM_SUPPORTED':ULP_FSM_DOCS, 'SOC_ULP_FSM_SUPPORTED':ULP_FSM_DOCS,
'SOC_RISCV_COPROC_SUPPORTED':RISCV_COPROC_DOCS, 'SOC_RISCV_COPROC_SUPPORTED':RISCV_COPROC_DOCS,
'SOC_LP_CORE_SUPPORTED':LP_CORE_DOCS, 'SOC_LP_CORE_SUPPORTED':LP_CORE_DOCS,

View File

@ -20,6 +20,9 @@ INPUT += \
$(PROJECT_PATH)/components/esp_driver_cam/csi/include/esp_cam_ctlr_csi.h \ $(PROJECT_PATH)/components/esp_driver_cam/csi/include/esp_cam_ctlr_csi.h \
$(PROJECT_PATH)/components/hal/include/hal/jpeg_types.h \ $(PROJECT_PATH)/components/hal/include/hal/jpeg_types.h \
$(PROJECT_PATH)/components/hal/include/hal/ppa_types.h \ $(PROJECT_PATH)/components/hal/include/hal/ppa_types.h \
$(PROJECT_PATH)/components/esp_driver_touch_sens/include/driver/touch_sens.h \
$(PROJECT_PATH)/components/esp_driver_touch_sens/include/driver/touch_sens_types.h \
$(PROJECT_PATH)/components/esp_driver_touch_sens/hw_ver3/include/driver/touch_version_types.h \
$(PROJECT_PATH)/components/esp_driver_jpeg/include/driver/jpeg_types.h \ $(PROJECT_PATH)/components/esp_driver_jpeg/include/driver/jpeg_types.h \
$(PROJECT_PATH)/components/esp_driver_isp/include/driver/isp.h \ $(PROJECT_PATH)/components/esp_driver_isp/include/driver/isp.h \
$(PROJECT_PATH)/components/esp_driver_isp/include/driver/isp_types.h \ $(PROJECT_PATH)/components/esp_driver_isp/include/driver/isp_types.h \

View File

@ -0,0 +1,416 @@
Capacitive Touch Sensor
=========================
:link_to_translation:`zh_CN:[中文]`
{IDF_TARGET_TOUCH_SENSOR_VERSION:default="NOT_UPDATED", esp32p4="v3"}
Introduction
---------------
A touch sensor system is built on a substrate which carries electrodes and relevant connections under a protective flat surface. When the surface is touched, the capacitance variation is used to evaluate if the touch was valid.
The sensing pads can be arranged in different combinations (e.g., matrix, slider), so that a larger area or more points can be detected. The touch pad sensing process is under the control of a hardware-implemented finite-state machine (FSM) which is initiated by software or a dedicated hardware timer.
For design, operation, and control registers of a touch sensor, see **{IDF_TARGET_NAME} Technical Reference Manual** > **On-Chip Sensors and Analog Signal Processing** [`PDF <{IDF_TARGET_TRM_EN_URL}#sensor>`__].
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>`_.
Overview of Capacitive Touch Sensor Versions
-----------------------------------------------
+------------------+--------------+------------------------------------------------------------------------+
| Hardware Version | Chip | Main Features |
+==================+==============+========================================================================+
| V1 | ESP32 | Version 1, the channel value decreases when it is touched |
+------------------+--------------+------------------------------------------------------------------------+
| V2 | ESP32-S2 | Version 2, the channel value increases when it is touched |
| | | Supports waterproof, proximity sensing and sleep wake-up |
| +--------------+------------------------------------------------------------------------+
| | ESP32-S3 | Version 2, support proximity measurement done interrupt |
+------------------+--------------+------------------------------------------------------------------------+
| V3 | ESP32-P4 | Version 3, support frequency hopping |
+------------------+--------------+------------------------------------------------------------------------+
Overview of Touch Sensor Channels
------------------------------------
.. only:: esp32p4
========= ===== ===== ===== ===== ===== ===== ===== ===== ====== ====== ====== ====== ====== ====== ==========
Channel CH0 CH1 CH2 CH3 CH4 CH5 CH6 CH7 CH8 CH9 CH10 CH11 CH12 CH13 CH14
--------- ----- ----- ----- ----- ----- ----- ----- ----- ------ ------ ------ ------ ------ ------ ----------
GPIO IO2 IO3 IO4 IO5 IO6 IO7 IO8 IO9 IO10 IO11 IO12 IO13 IO14 IO15 Internal
========= ===== ===== ===== ===== ===== ===== ===== ===== ====== ====== ====== ====== ====== ====== ==========
Terminology in the Driver
----------------------------
- **Touch Sensor Controller**: The controller of the touch sensor, responsible for configuring and managing the touch sensor.
- **Touch Sensor Channel**: A specific touch sensor sampling channel. A touch sensor module has multiple touch channels, which are usually connected to the touch pad for measuring the capacitance change. In the driver, sampling of **one** channel is called one ``measurement`` and the scanning of **all** registered channels is called one ``scan``.
.. only:: SOC_TOUCH_SUPPORT_FREQ_HOP
- **Touch Sensor Sampling Configuration**: Touch sensor sampling configuration refers to all the hardware configurations that related to the sampling. It can determine how the touch channels sample by setting the number of charging times, charging frequency, measurement interval, etc. {IDF_TARGET_NAME} supports multiple sets of sample configuration, which means it can support frequency hopping.
.. only:: not SOC_TOUCH_SUPPORT_FREQ_HOP
- **Touch Sensor Sampling Configuration**: Touch sensor sampling configuration refers to all the hardware configurations that related to the sampling. It can determine how the touch channels sample by setting the number of charging times, charging frequency, measurement interval, etc. {IDF_TARGET_NAME} only support one set of sample configuration, so it doesn't support frequency hopping.
File Structure
-----------------
.. figure:: ../../../_static/diagrams/cap_touch_sens/touch_file_structure.svg
:align: center
:alt: File Structure of Touch Sensor Driver
File Structure of Touch Sensor Driver
Finite-state Machine
---------------------
The following diagram shows the state machine of the touch sensor driver, which describes the driver state after calling a function, and the constraint of the state transition.
.. figure:: ../../../_static/diagrams/cap_touch_sens/touch_state_machine.svg
:align: center
:alt: Finite-state Machine of Touch Sensor Driver
Finite-state Machine of Touch Sensor Driver
The diagram above is the finite-state machine of the touch sensor driver, which describes how the state transferred by invoking different APIs. ``<other_configurations>`` in the diagram stands for the other optional configurations, like reconfigurations to the touch sensor controller or channels, callback registration, filter, and so on.
.. note::
:cpp:func:`touch_channel_read_data` can be called at any time after the channel is registered (i.e., since ``INIT`` state), but please take care of the validation of the data.
Functionality Introduction
------------------------------
Categorized by functionality, the APIs of Capacitive Touch Sensor mainly include:
.. list::
- `Touch Sensor Controller Management <#touch-ctrl>`__
- `Touch Sensor Channel Management <#touch-chan>`__
- `Filter Configuration <#touch-filter>`__
- `Callback <#touch-callback>`__
- `Enable and Disable <#touch-enable>`__
- `Continuous Scan <#touch-conti-scan>`__
- `Oneshot Scan <#touch-oneshot-scan>`__
- `Benchmark Configuration <#touch-benchmark>`__
- `Read Measurement Data <#touch-read>`__
:SOC_TOUCH_SUPPORT_WATERPROOF: - `Waterproof Configuration <#touch-waterproof>`__
:SOC_TOUCH_SUPPORT_PROX_SENSING: - `Proximity Sensing Configuration <#touch-prox-sensing>`__
:SOC_TOUCH_SUPPORT_SLEEP_WAKEUP: - `Sleep Wake-up Configuration <#touch-sleep-wakeup>`__
.. _touch-ctrl:
Touch Sensor Controller Management
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Touch Sensor is controlled by controller handle :cpp:type:`touch_sensor_handle_t`, it can be initialized and allocated by :cpp:func:`touch_sensor_new_controller`.
.. code-block:: c
// Some target has multiple sets of sample configuration can be set, here take one for example
#define SAMPLE_NUM 1
touch_sensor_handle_t sens_handle = NULL;
// sample configuration
touch_sensor_sample_config_t sample_cfg[SAMPLE_NUM] = {
// Specify sample configuration or apply the default sample configuration via `TOUCH_SENSOR_Vn_DEFAULT_SAMPLE_CONFIG`
// ...
};
// Use the default touch controller configuration
touch_sensor_config_t touch_cfg = TOUCH_SENSOR_DEFAULT_BASIC_CONFIG(SAMPLE_NUM, sample_cfg);
// Allocate a new touch sensor controller handle
ESP_ERROR_CHECK(touch_sensor_new_controller(&touch_cfg, &sens_handle));
To delete the controller handle and free the software and hardware resources, please call :cpp:func:`touch_sensor_del_controller`. But note that you need to delete the other resources that based on the controller first, like the registered touch channels, otherwise it can't be deleted directly.
.. code-block:: c
ESP_ERROR_CHECK(touch_sensor_del_controller(sens_handle));
You can also update the configurations via :cpp:func:`touch_sensor_reconfig_controller` before the controller is enabled.
.. code-block:: c
touch_sensor_config_t touch_cfg = {
// New controller configurations
// ...
};
ESP_ERROR_CHECK(touch_sensor_reconfig_controller(sens_handle, &touch_cfg));
.. _touch-chan:
Touch Sensor Channel Management
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
There are multiple touch channels in the touch sensor module, the touch sensor channel is controlled by the channel handle :cpp:type:`touch_channel_handle_t`. It can be initialized and allocated by :cpp:func:`touch_sensor_new_channel`.
.. code-block:: c
// ...
touch_channel_config_t chan_cfg = {
// Touch channel configurations
// ...
};
touch_channel_handle_t chan_handle = NULL;
int chan_id = 0;
// Allocate a new touch sensor controller handle
ESP_ERROR_CHECK(touch_sensor_new_channel(sens_handle, chan_id, &chan_cfg, &chan_handle));
To delete the touch channel handle and free the software and hardware resources, please call :cpp:func:`touch_sensor_del_channel`.
.. code-block:: c
ESP_ERROR_CHECK(touch_sensor_del_channel(chan_handle));
You can also update the configurations via :cpp:func:`touch_sensor_reconfig_channel` before the controller is enabled.
.. code-block:: c
touch_channel_config_t chan_cfg = {
// New touch channel configurations
// ...
};
ESP_ERROR_CHECK(touch_sensor_reconfig_channel(chan_handle, &chan_cfg));
.. _touch-filter:
Filter Configuration
^^^^^^^^^^^^^^^^^^^^^^
The filter can help to increase the stability in different use cases. The filter can be registered by calling :cpp:func:`touch_sensor_config_filter` and specify the configurations :cpp:type:`touch_sensor_filter_config_t`. These configurations mainly determine how to filter and update the benchmark and read data. Please note that all touch channels will share this filter.
To deregister the filter, you can call :cpp:func:`touch_sensor_config_filter` again, and set the second parameter (i.e. :cpp:type:`touch_sensor_filter_config_t` pointer) to ``NULL``.
.. code-block:: c
// ...
touch_sensor_filter_config_t filter_config = {
// Filter configurations
// ...
};
// Register the filter
ESP_ERROR_CHECK(touch_sensor_config_filter(sens_handle, &filter_config));
// ...
// Deregister the filter
ESP_ERROR_CHECK(touch_sensor_config_filter(sens_handle, NULL));
.. _touch-callback:
Callback
^^^^^^^^^^^^^
Calling :cpp:func:`touch_sensor_register_callbacks` to register the touch sensor event callbacks. Once the touch sensor events (like ``on_active``, ``on_inactive``) trigger, the corresponding callbacks will be invoked, so that to deal with the event in the upper application.
For the general example, when the measured data of the current touch channel exceed the ``benchmark`` + ``active_threshold``, this channel is activated, and the driver will call ``on_active`` callback to inform the application layer. Similar, when the active channel measured a lower data than ``benchmark`` + ``active_threshold``, then this channel will be inactivated, and ``on_inactive`` will be called to inform this channel is released.
.. note::
To ensure the stability of the triggering and releasing, ``active_hysteresis`` and ``debounce_cnt`` can be configured to avoid the frequent triggering that caused by jitter and noise.
Please refer to :cpp:type:`touch_event_callbacks_t` for the details about the supported callbacks.
.. code-block:: c
touch_event_callbacks_t callbacks = {
.on_active = example_touch_on_active_cb,
// Other callbacks
// ...
};
// Register callbacks
ESP_ERROR_CHECK(touch_sensor_register_callbacks(sens_handle, &callbacks, NULL));
// To deregister callbacks, set the corresponding callback to NULL
callbacks.on_active = NULL;
// Other callbacks to deregister
// ...
ESP_ERROR_CHECK(touch_sensor_register_callbacks(sens_handle, &callbacks, NULL));
.. _touch-enable:
Enable and Disable
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
After finished the configuration of the touch controller and touch channels, :cpp:func:`touch_sensor_enable` can be called to enable the touch sensor controller. It will enter ``READY`` status and power on the registered channels, then you can start scanning and sampling the touch data. Note that you can only do scanning and reading operation once the controller is enabled. If you want to update the controller or channel configurations, you need to call :cpp:func:`touch_sensor_disable` first.
.. code-block:: c
// Enable touch sensor
ESP_ERROR_CHECK(touch_sensor_enable(sens_handle));
// ...
// Disable touch sensor
ESP_ERROR_CHECK(touch_sensor_disable(sens_handle));
.. _touch-conti-scan:
Continuous Scan
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
With the touch controller enabled, :cpp:func:`touch_sensor_start_continuous_scanning` can be called to start the continuous scanning to all the registered touch channels. The read data of these touch channels will be updated automatically in each scan. Calling :cpp:func:`touch_sensor_stop_continuous_scanning` can stop the continuous scan.
.. code-block:: c
// Start continuous scan
ESP_ERROR_CHECK(touch_sensor_start_continuous_scanning(sens_handle));
// ...
// Stop continuous scan
ESP_ERROR_CHECK(touch_sensor_stop_continuous_scanning(sens_handle));
.. _touch-oneshot-scan:
Oneshot Scan
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
With the touch controller enabled, :cpp:func:`touch_sensor_trigger_oneshot_scanning` can be called to trigger an one-time scan to all the registered touch channels. Note that oneshot scan is a blocking function, it will keep blocking and only return when the scan is finished. Moreover, you can't trigger an oneshot scan after the continuous scan has started.
.. code-block:: c
// Trigger an oneshot scan with timeout 1000ms
ESP_ERROR_CHECK(touch_sensor_trigger_oneshot_scanning(sens_handle, 1000));
.. _touch-benchmark:
Benchmark Configuration
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Normally, you don't have to set the benchmark manually, but you can force reset the benchmark to the current smooth value by calling :cpp:func:`touch_channel_config_benchmark` when necessary
.. code-block:: c
touch_chan_benchmark_config_t benchmark_cfg = {
// Benchmark operations
// ...
};
ESP_ERROR_CHECK(touch_channel_config_benchmark(chan_handle, &benchmark_cfg));
.. _touch-read:
Read Measurement Data
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Call :cpp:func:`touch_channel_read_data` to read the data with different types. Like, benchmark, smooth data, etc. You can refer to :cpp:type:`touch_chan_data_type_t` for the supported data types.
.. only:: SOC_TOUCH_SUPPORT_FREQ_HOP
{IDF_TARGET_NAME} supports frequency hopping by configuring multiple set of sample configurations, :cpp:func:`touch_channel_read_data` can read out the data of each sample configuration in a single call, you can determine the sample configuration number by :cpp:member:`touch_sensor_config_t::sample_cfg_num`, and pass an array (which length is not smaller than the configuration number) to the third parameter ``*data``, so that all the measured data of this channel will be stored in the array.
.. code-block:: c
#define SAMPLE_NUM 1 // Take one sample configuration set for example
uint32_t smooth_data[SAMPLE_NUM] = {};
// Read the smooth data
ESP_ERROR_CHECK(touch_channel_read_data(chan_handle, TOUCH_CHAN_DATA_TYPE_SMOOTH, smooth_data));
.. _touch-waterproof:
.. only:: SOC_TOUCH_SUPPORT_WATERPROOF
Waterproof Configuration
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
{IDF_TARGET_NAME} supports waterproof. Waterproof can be registered by calling :cpp:func:`touch_sensor_config_waterproof` and specify the configurations :cpp:type:`touch_waterproof_config_t`. There are two parts of the waterproof function:
- Immersion (in-water) proof: :cpp:member:`touch_waterproof_config_t::guard_chan` can be specified for detecting immersion. It is usually designed as a ring on the PCB, which surrounds all the other touch pads. When this guard ring channel is triggered, that means the touch panel is immersed by water, all the touch channels will stop measuring to avoid falsely triggering.
- Moisture (water-drop) proof: :cpp:member:`touch_waterproof_config_t::shield_chan` can be specified for detecting moisture. It usually uses the grid layout on the PCB, which covers the whole touch panel. The shield channel will charge and discharge synchronously with the current touch channel, when there is a water droplet covers both shield channel and normal touch channel, :cpp:member:`touch_waterproof_config_t::shield_drv` can strengthen the electrical coupling caused by the water droplets, and then reconfigure the active threshold based on the disturbance to eliminate the influence that introduced by the water droplet.
To deregister the waterproof function, you can call :cpp:func:`touch_sensor_config_waterproof` again, and set the second parameter (i.e. :cpp:type:`touch_waterproof_config_t` pointer) to ``NULL``.
.. code-block:: c
touch_waterproof_config_t waterproof_cfg = {
// Waterproof configurations
// ...
};
// Register waterproof function
ESP_ERROR_CHECK(touch_sensor_config_waterproof(sens_handle, &waterproof_cfg));
// ...
// Deregister waterproof function
ESP_ERROR_CHECK(touch_sensor_config_waterproof(sens_handle, NULL));
.. _touch-prox-sensing:
.. only:: SOC_TOUCH_SUPPORT_PROX_SENSING
Proximity Sensing Configuration
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
{IDF_TARGET_NAME} supports proximity sensing. Proximity sensing can be registered by calling :cpp:func:`touch_sensor_config_proximity_sensing` and specify the configurations :cpp:type:`touch_proximity_config_t`.
Since the capacitance change caused by proximity sensing is far less than that caused by physical touch, large area of copper foil is often used on PCB to increase the sensing area. In addition, multiple rounds of scans are needed and the result of each scan will be accumulated in the driver to improve the measurement sensitivity. The scan times (rounds) can be determined by :cpp:member:`touch_proximity_config_t::scan_times` and the charging times of the proximity channel in one scan can be determined by :cpp:member:`touch_proximity_config_t::charge_times`. Generally, the larger the scan times and charging times is, the higher the sensitivity will be, however, the read data will be unstable if the sensitivity is too high. Proper parameters should be determined regarding the application.
The accumulated proximity data can be read by :cpp:func:`touch_channel_read_data` with the data type :cpp:enumerator:`TOUCH_CHAN_DATA_TYPE_PROXIMITY`
To deregister the proximity sensing, you can call :cpp:func:`touch_sensor_config_proximity_sensing` again, and set the second parameter (i.e. :cpp:type:`touch_proximity_config_t` pointer) to ``NULL``.
.. code-block:: c
touch_proximity_config_t prox_cfg = {
// Proximity sensing configuration
// ...
};
// Register the proximity sensing
ESP_ERROR_CHECK(touch_sensor_config_proximity_sensing(sens_handle, &prox_cfg));
// ...
// Deregister the proximity sensing
ESP_ERROR_CHECK(touch_sensor_config_proximity_sensing(sens_handle, NULL));
.. _touch-sleep-wakeup:
.. only:: SOC_TOUCH_SUPPORT_SLEEP_WAKEUP
Sleep Wake-up Configuration
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
{IDF_TARGET_NAME} supports waking-up the chip from light sleep or deep sleep with the touch sensor as a wake-up source. The wake-up functionality can be registered by calling :cpp:func:`touch_sensor_config_sleep_wakeup` and specifying the configurations :cpp:type:`touch_sleep_config_t`.
After registering the touch sensor sleep wake-up, the chip will continue to sample the touch channels after sleep, which will increase the power consumption during the sleep. To reduce the sleep power consumption, you can reduce the number of charging and discharging times, increase the sampling interval, etc.
Moreover, please note that the operations like sampling, wake-up are all done by hardware when the main core is sleeping. Since this driver runs on the main core, it cannot provide functions such as reading or configuring during the sleep.
.. only:: SOC_RISCV_COPROC_SUPPORTED
If you want to read or configure the touch sensor during the sleep, you can turn to the driver ``components/ulp/ulp_riscv/ulp_core/include/ulp_riscv_touch_ulp_core.h`` which based on the :doc:`Ultra Low Power (ULP) Coprocessor <../system/ulp>`.
- Light sleep wake-up: you need to set :cpp:member:`slp_wakeup_lvl` to :cpp:enumerator:`TOUCH_LIGHT_SLEEP_WAKEUP` to enable the light sleep wake-up by touch sensor. Note that any registered touch channel can wake-up the chip from light sleep.
- Deep sleep wake-up: beside setting :cpp:member:`slp_wakeup_lvl` to :cpp:enumerator:`TOUCH_DEEP_SLEEP_WAKEUP`, you need to specify :cpp:member:`deep_slp_chan` additionally. Only the specified channel can wake-up the chip from the deep sleep, in order to reduce the power consumption. And also, the driver supports to store another set of configurations for the deep sleep via :cpp:member:`deep_slp_sens_cfg`, this set of configurations only takes effect during the deep sleep, you can customize the configurations to save more power. The configurations will be reset to the previous set after waking-up from the deep sleep. Please be aware that, not only deep sleep wake-up, but also light sleep wake-up will be enabled when the :cpp:member:`slp_wakeup_lvl` is :cpp:enumerator:`TOUCH_DEEP_SLEEP_WAKEUP`.
To deregister the sleep wake-up function, you can call :cpp:func:`touch_sensor_config_sleep_wakeup` again, and set the second parameter (i.e. :cpp:type:`touch_sleep_config_t` pointer) to ``NULL``.
.. code-block:: c
touch_sleep_config_t light_slp_cfg = {
.slp_wakeup_lvl = TOUCH_LIGHT_SLEEP_WAKEUP,
};
// Register the light sleep wake-up
ESP_ERROR_CHECK(touch_sensor_config_sleep_wakeup(sens_handle, &light_slp_cfg));
// ...
// Deregister the light sleep wake-up
ESP_ERROR_CHECK(touch_sensor_config_sleep_wakeup(sens_handle, NULL));
touch_sleep_config_t deep_slp_cfg = {
.slp_wakeup_lvl = TOUCH_DEEP_SLEEP_WAKEUP,
.deep_slp_chan = dslp_chan_handle,
// Other deep sleep configurations
// ...
};
// Register the deep sleep wake-up
ESP_ERROR_CHECK(touch_sensor_config_sleep_wakeup(sens_handle, &deep_slp_cfg));
Application Examples
------------------------
.. only:: esp32p4
- Touch sensor basic example: :example:`peripherals/touch_sensor/touch_sensor_{IDF_TARGET_TOUCH_SENSOR_VERSION}`.
API 参考
-------------
.. only:: esp32p4
.. include-build-file:: inc/touch_sens.inc
.. include-build-file:: inc/touch_sens_types.inc
.. include-build-file:: inc/touch_version_types.inc

View File

@ -42,7 +42,8 @@ Peripherals API
:SOC_GPSPI_SUPPORTED: spi_slave :SOC_GPSPI_SUPPORTED: spi_slave
:SOC_SPI_SUPPORT_SLAVE_HD_VER2: spi_slave_hd :SOC_SPI_SUPPORT_SLAVE_HD_VER2: spi_slave_hd
:SOC_TEMP_SENSOR_SUPPORTED: temp_sensor :SOC_TEMP_SENSOR_SUPPORTED: temp_sensor
:SOC_TOUCH_SENSOR_SUPPORTED: touch_pad :SOC_TOUCH_SENSOR_SUPPORTED and not esp32p4: touch_pad
:esp32p4: cap_touch_sens
:esp32s2: touch_element :esp32s2: touch_element
:SOC_TWAI_SUPPORTED: twai :SOC_TWAI_SUPPORTED: twai
uart uart

View File

@ -443,7 +443,7 @@ The Touch Element Wakeup example is available in `system/light_sleep` directory.
// ESP_ERROR_CHECK(touch_element_enable_light_sleep(&sleep_config)); // ESP_ERROR_CHECK(touch_element_enable_light_sleep(&sleep_config));
ESP_ERROR_CHECK(touch_element_enable_deep_sleep(button_handle[0], &sleep_config)); ESP_ERROR_CHECK(touch_element_enable_deep_sleep(button_handle[0], &sleep_config));
// ESP_ERROR_CHECK(touch_element_sleep_enable_wakeup_calibration(button_handle[0], false)); // (optional) Disable wakeup calibration to prevent updating the baseline to a wrong value // ESP_ERROR_CHECK(touch_element_sleep_enable_wakeup_calibration(button_handle[0], false)); // (optional) Disable wakeup calibration to prevent updating the benchmark to a wrong value
touch_element_start(); touch_element_start();

View File

@ -0,0 +1,415 @@
电容式触摸传感器
===================
:link_to_translation:`en:[English]`
{IDF_TARGET_TOUCH_SENSOR_VERSION:default="NOT_UPDATED", esp32p4="v3"}
概述
------------
触摸传感器系统由保护覆盖层、触摸电极、绝缘基板和走线组成,保护覆盖层位于最上层,绝缘基板上设有电极及走线。触摸覆盖层将引起电容变化,根据电容变化,可以判断此次触摸是否为有效触摸行为。
触摸传感器可以以矩阵或滑条等方式组合使用,从而覆盖更大触感区域及更多触感点。触摸传感由软件或专用硬件计时器发起,由有限状态机 (FSM) 硬件控制。
如需了解触摸传感器设计、操作及其控制寄存器等相关信息,请参考《`{IDF_TARGET_NAME} 技术参考手册 <{IDF_TARGET_TRM_CN_URL}>`_》(PDF) 中“片上传感器与模拟信号处理”章节。
请参考 `触摸传感器应用方案简介 <https://github.com/espressif/esp-iot-solution/blob/release/v1.0/documents/touch_pad_solution/touch_sensor_design_en.md>`_,查看触摸传感器设计详情和固件开发指南。
电容式触摸传感器版本概览
-------------------------
+-----------+--------------+------------------------------------------------------------------------+
| 硬件版本 | 芯片 | 主要特征 |
+===========+==============+========================================================================+
| V1 | ESP32 | 第一代触摸传感器,触摸时读数变小 |
+-----------+--------------+------------------------------------------------------------------------+
| V2 | ESP32-S2 | 第二代触摸传感器,触摸时读数变大 |
| | | 新增防水防潮、接近感应、睡眠唤醒功能 |
| +--------------+------------------------------------------------------------------------+
| | ESP32-S3 | 第二代触摸传感器,新增接近感应测量完成中断 |
+-----------+--------------+------------------------------------------------------------------------+
| V3 | ESP32-P4 | 第三代触摸传感器,新增跳频扫描 |
+-----------+--------------+------------------------------------------------------------------------+
触摸通道概览
----------------------
.. only:: esp32p4
====== ===== ===== ===== ===== ===== ===== ===== ===== ====== ====== ====== ====== ====== ====== ==========
通道 CH0 CH1 CH2 CH3 CH4 CH5 CH6 CH7 CH8 CH9 CH10 CH11 CH12 CH13 CH14
------ ----- ----- ----- ----- ----- ----- ----- ----- ------ ------ ------ ------ ------ ------ ----------
GPIO IO2 IO3 IO4 IO5 IO6 IO7 IO8 IO9 IO10 IO11 IO12 IO13 IO14 IO15 未引出
====== ===== ===== ===== ===== ===== ===== ===== ===== ====== ====== ====== ====== ====== ====== ==========
驱动中的术语介绍
-------------------------
- **触摸传感器控制器**:触摸传感器驱动的控制器,负责触摸传感器的配置和管理。
- **触摸传感器通道**:具体的一路触摸传感器采样通道。一个触摸传感器模块具有多个通道,一般连接到触摸板上,用于测量该触摸板电容的变化。驱动中把对 **一个** 通道的采样称为 ``测量``,而对 **所有** 注册通道的 ``测量`` 称为一次 ``扫描``
.. only:: IDF_TARGET_TOUCH_SAMPLE_CFG_DESC
- **触摸传感器采样配置**:触摸传感器采样配置是驱动中对采样有关的硬件配置的统称。采样配置负责触摸传感器通道的采样,其配置决定了触摸通道的充放电次数、充放电频率、测量间隔等。{IDF_TARGET_NAME} 支持多套采样配置,支持跳频采样。
.. only:: not IDF_TARGET_TOUCH_SAMPLE_CFG_DESC
- **触摸传感器采样配置**:触摸传感器采样配置是驱动中对采样有关的硬件配置的统称。采样配置负责触摸传感器通道的采样,其配置决定了触摸通道的充放电次数、充放电频率、测量间隔等。{IDF_TARGET_NAME} 仅支持一套采样配置,不支持跳频采样。
文件结构
--------------------
.. figure:: ../../../_static/diagrams/cap_touch_sens/touch_file_structure.svg
:align: center
:alt: 触摸传感器驱动文件结构图
触摸传感器驱动文件结构图
驱动状态机
---------------------
下图为触摸传感器驱动的状态机,描述了调用不同函数后驱动的运行状态,以及状态变迁的约束。
.. figure:: ../../../_static/diagrams/cap_touch_sens/touch_state_machine.svg
:align: center
:alt: 触摸传感器驱动状态机示意图
触摸传感器驱动状态机示意图
上图为触摸传感器驱动的状态机,描述了调用不同函数后状态的变换关系。其中 ``<other_configurations>`` 部分为可选的配置项,包括对触摸驱动控制器和触摸通道的重新配置、回调函数注册等。
.. note::
:cpp:func:`touch_channel_read_data` 可在获取触摸通道句柄后(即 ``INIT`` 后)任意状态调用,但请注意读数值的有效性。
功能介绍
------------------
{IDF_TARGET_NAME} 的电容式触摸传感器驱动提供的 API 按功能主要可分为:
.. list::
- `触摸传感器控制器管理 <#touch-ctrl>`__
- `触摸传感器通道管理 <#touch-chan>`__
- `滤波器配置 <#touch-filter>`__
- `回调函数 <#touch-callback>`__
- `启用和禁用 <#touch-enable>`__
- `连续扫描 <#touch-conti-scan>`__
- `单次扫描 <#touch-oneshot-scan>`__
- `基线值配置 <#touch-benchmark>`__
- `测量值读数 <#touch-read>`__
:SOC_TOUCH_SUPPORT_WATERPROOF: - `防水防潮配置 <#touch-waterproof>`__
:SOC_TOUCH_SUPPORT_PROX_SENSING: - `接近感应配置 <#touch-prox-sensing>`__
:SOC_TOUCH_SUPPORT_SLEEP_WAKEUP: - `睡眠唤醒配置 <#touch-sleep-wakeup>`__
.. _touch-ctrl:
触摸传感器控制器管理
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
触摸传感器驱动通过触摸传感器控制器句柄 :cpp:type:`touch_sensor_handle_t` 控制。调用 :cpp:func:`touch_sensor_new_controller` 函数即可初始化触摸传感器控制器并得到控制器句柄。
.. code-block:: c
// 有些芯片支持多套采样配置,这里以一套为例
#define SAMPLE_NUM 1
touch_sensor_handle_t sens_handle = NULL;
// 采样配置
touch_sensor_sample_config_t sample_cfg[SAMPLE_NUM] = {
// 指定采样配置或通过 `TOUCH_SENSOR_Vn_DEFAULT_SAMPLE_CONFIG` 使用默认采样配置
// ...
};
// 默认控制器配置
touch_sensor_config_t touch_cfg = TOUCH_SENSOR_DEFAULT_BASIC_CONFIG(SAMPLE_NUM, sample_cfg);
// 申请一个新的触摸传感器控制器句柄
ESP_ERROR_CHECK(touch_sensor_new_controller(&touch_cfg, &sens_handle));
删除触摸传感器驱动控制器时需调用 :cpp:func:`touch_sensor_del_controller` 函数,从而释放该控制器所占用的软硬件资源。注意,需要将基于该控制器申请的其他资源销毁或释放后才能删除该控制器。如该控制器下仍有触摸通道未被删除,则无法直接删除。
.. code-block:: c
ESP_ERROR_CHECK(touch_sensor_del_controller(sens_handle));
在触摸传感器驱动控制器初始化后,且未启用触摸传感器时,可调用 :cpp:func:`touch_sensor_reconfig_controller` 函数对该控制器进行重新配置。
.. code-block:: c
touch_sensor_config_t touch_cfg = {
// 控制器的新配置
// ...
};
ESP_ERROR_CHECK(touch_sensor_reconfig_controller(sens_handle, &touch_cfg));
.. _touch-chan:
触摸传感器通道管理
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
一个触摸传感器具有多个测量通道,每个触摸传感器通道由句柄 :cpp:type:`touch_channel_handle_t` 控制。调用 :cpp:func:`touch_sensor_new_channel` 函数即可初始化触摸传感器通道并得到通道句柄。
.. code-block:: c
// ...
touch_channel_config_t chan_cfg = {
// 触摸通道配置
// ...
};
touch_channel_handle_t chan_handle = NULL;
int chan_id = 0;
// 申请一个新的触摸通道句柄
ESP_ERROR_CHECK(touch_sensor_new_channel(sens_handle, chan_id, &chan_cfg, &chan_handle));
删除触摸传感器通道时需调用 :cpp:func:`touch_sensor_del_channel` 函数,从而释放该通道所占用的软硬件资源。
.. code-block:: c
ESP_ERROR_CHECK(touch_sensor_del_channel(chan_handle));
在触摸传感器驱动通道初始化后,且未启用触摸传感器时,可调用 :cpp:func:`touch_sensor_reconfig_channel` 函数对该通道进行重新配置。
.. code-block:: c
touch_channel_config_t chan_cfg = {
// 触摸通道新配置
// ...
};
ESP_ERROR_CHECK(touch_sensor_reconfig_channel(chan_handle, &chan_cfg));
.. _touch-filter:
滤波器配置
^^^^^^^^^^^^^^
触摸传感器可以通过配置滤波器来提升不同场景下的数据稳定性。调用 :cpp:func:`touch_sensor_config_filter` 并指定 :cpp:type:`touch_sensor_filter_config_t` 来配置基线值和读数值的滤波策略和更新方式,配置后对所有启用的触摸通道都生效。
若需要注销滤波器,可再次调用 :cpp:func:`touch_sensor_config_filter` 并将第二个参数(即 :cpp:type:`touch_sensor_filter_config_t` 的配置结构体指针)设为 ``NULL`` 来注销滤波器功能。
.. code-block:: c
// ...
touch_sensor_filter_config_t filter_config = {
// 滤波器配置
// ...
};
// 注册滤波器
ESP_ERROR_CHECK(touch_sensor_config_filter(sens_handle, &filter_config));
// ...
// 注销滤波器
ESP_ERROR_CHECK(touch_sensor_config_filter(sens_handle, NULL));
.. _touch-callback:
回调函数
^^^^^^^^^^^^^
通过调用 :cpp:func:`touch_sensor_register_callbacks` 注册各类触摸传感器事件回调函数,当触摸传感器通道触发如触摸 ``on_active``、释放 ``on_inactive`` 等事件时,就会调用对应的回调函数通知上层应用,以便对触摸事件进行处理。
例如,测量值超出当前的测量通道的 ``基线值`` + ``触发阈值``,则该通道将被触发,并调用 ``on_active`` 事件的回调函数,通知应用层该触摸通道被 ``触发``。同理,若处于 ``触发`` 状态的通道测量值小于 ``基线值`` + ``触发阈值``,则该通道将回到未触发状态,并调用 ``on_inactive`` 事件的回调函数,通知应用层该触摸通道被 ``释放``
.. note::
为保证触发和释放事件的稳定性,触摸传感器可配置 ``触发阈值`` 的迟滞比较裕量和 ``去抖动计数`` 来避免短时间内由噪声和读数抖动引起的反复触发和释放
具体可注册的回调时间请参考 :cpp:type:`touch_event_callbacks_t`
.. code-block:: c
touch_event_callbacks_t callbacks = {
.on_active = example_touch_on_active_cb,
// 其他回调函数
// ...
};
// 注册回调函数
ESP_ERROR_CHECK(touch_sensor_register_callbacks(sens_handle, &callbacks, NULL));
// 通过把相应回调设为 NULL 以注销回调函数
callbacks.on_active = NULL;
// 其他需要注销的回调函数
// ...
ESP_ERROR_CHECK(touch_sensor_register_callbacks(sens_handle, &callbacks, NULL));
.. _touch-enable:
启用和禁用
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
配置完成触摸传感器控制器以及通道后,可调用 :cpp:func:`touch_sensor_enable` 函数启用该控制器,启用后控制器处于 ``就绪`` 状态,会对注册的通道上电,可以开始扫描并采集触摸数据。注意,控制器启用后无法更新配置,只能进行扫描采样和读数操作。若要更新配置,需先调用 :cpp:func:`touch_sensor_disable` 函数禁用控制器,方可重新配置控制器、通道等。
.. code-block:: c
// 启用触摸传感器
ESP_ERROR_CHECK(touch_sensor_enable(sens_handle));
// ...
// 禁用触摸传感器
ESP_ERROR_CHECK(touch_sensor_disable(sens_handle));
.. _touch-conti-scan:
连续扫描
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
在控制器启用后,调用 :cpp:func:`touch_sensor_start_continuous_scanning` 函数可开始对所有已注册的触摸通道进行连续扫描,每次扫描都会更新对应通道的测量值。调用 :cpp:func:`touch_sensor_stop_continuous_scanning` 函数后则停止扫描。
.. code-block:: c
// 开始连续扫描
ESP_ERROR_CHECK(touch_sensor_start_continuous_scanning(sens_handle));
// ...
// 停止连续扫描
ESP_ERROR_CHECK(touch_sensor_stop_continuous_scanning(sens_handle));
.. _touch-oneshot-scan:
单次扫描
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
在控制器启用后,调用 :cpp:func:`touch_sensor_trigger_oneshot_scanning` 函数可触发一次对所有已注册的触摸通道的扫描。注意,单次扫描为阻塞函数,调用后会保持阻塞直到扫描结束后返回。此外在开始连续扫描后,无法再触发单次扫描。
.. code-block:: c
// 触发单次扫描,并设置超时时间为 1000ms
ESP_ERROR_CHECK(touch_sensor_trigger_oneshot_scanning(sens_handle, 1000));
.. _touch-benchmark:
基线值配置
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
一般情况下,不需要额外设置触摸传感器的基线值,若有必要强制复位基线值到当前平滑值,可调用 :cpp:func:`touch_channel_config_benchmark`
.. code-block:: c
touch_chan_benchmark_config_t benchmark_cfg = {
// 基线操作
// ...
};
ESP_ERROR_CHECK(touch_channel_config_benchmark(chan_handle, &benchmark_cfg));
.. _touch-read:
测量值读数
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
调用 :cpp:func:`touch_channel_read_data` 可读取每个通道不同种类的数据,例如基线值、经过滤波后的平滑值等。支持的数据类型请参考 :cpp:type:`touch_chan_data_type_t`
.. only:: SOC_TOUCH_SUPPORT_FREQ_HOP
{IDF_TARGET_NAME} 支持通过配置多套采样配置来实现跳频采样,:cpp:func:`touch_channel_read_data` 可一次性读出一个通道所有采样配置的测量值。根据配置的 :cpp:member:`touch_sensor_config_t::sample_cfg_num` 采样配置数量,第三个参数 (``*data``) 数据指针传入数组长度大于等于采样配置数量的数组指针即可,该函数会将所指定通道的所有采样配置的测量值存入该数组中。
.. code-block:: c
#define SAMPLE_NUM 1 // 以一套采样配置为例
uint32_t smooth_data[SAMPLE_NUM] = {};
// 读取滤波后的平滑数据
ESP_ERROR_CHECK(touch_channel_read_data(chan_handle, TOUCH_CHAN_DATA_TYPE_SMOOTH, smooth_data));
.. _touch-waterproof:
.. only:: SOC_TOUCH_SUPPORT_WATERPROOF
防水防潮配置
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
{IDF_TARGET_NAME} 支持防水防潮功能。可通过调用 :cpp:func:`touch_sensor_config_waterproof` 并配置 :cpp:type:`touch_waterproof_config_t` 来注册防水防潮功能。防水防潮功能主要包含两部分:
- 遇水(浸没)保护功能: :cpp:member:`touch_waterproof_config_t::guard_chan` 用于指定用于遇水保护功能的触摸通道,该通道在 PCB 上一般设计成环形,其他普通触摸通道布局在该环形保护圈内,当电路板大面积浸水时,该环形保护通道会被触发,并停止其他触摸通道的扫描,由此防止其他普通通道的误触发;
- 防潮(水滴)屏蔽功能: :cpp:member:`touch_waterproof_config_t::shield_chan` 用于指定防潮屏蔽功能的触摸通道,该通道在 PCB 上一般设计成网格状铺铜。防潮屏蔽通道将与当前测量通道进行同步充放电,当有小水珠覆盖时,通过配置适当的 :cpp:member:`touch_waterproof_config_t::shield_drv` 来提高因水滴造成的电耦合强度,从而识别水滴造成的误触。在实际应用中识别到水滴造成的误触后可适当增加触摸通道触发的阈值来实现通道在水滴覆盖下的正常触发,从而实现防潮功能。
若需要注销防水防潮功能,可再次调用 :cpp:func:`touch_sensor_config_waterproof` 并将第二个参数(即 :cpp:type:`touch_waterproof_config_t` 的配置结构体指针)设为 ``NULL`` 来注销防水防潮功能。
.. code-block:: c
touch_waterproof_config_t waterproof_cfg = {
// 防水防潮配置
// ...
};
// 注册防水防潮功能
ESP_ERROR_CHECK(touch_sensor_config_waterproof(sens_handle, &waterproof_cfg));
// ...
// 注销防水防潮功能
ESP_ERROR_CHECK(touch_sensor_config_waterproof(sens_handle, NULL));
.. _touch-prox-sensing:
.. only:: SOC_TOUCH_SUPPORT_PROX_SENSING
接近感应配置
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
{IDF_TARGET_NAME} 支持接近感应功能。可通过调用 :cpp:func:`touch_sensor_config_proximity_sensing` 并配置 :cpp:type:`touch_proximity_config_t` 来注册接近感应功能。
由于接近感应引起的电容变化远小于物理触摸PCB 上常用较大面积的铺铜来增大触摸通道的感应面积,另外需要在硬件上对接近感应通道进行多轮扫描并在驱动中进行累加来提高测量灵敏度。接近感应的灵敏度由测量轮数 :cpp:member:`touch_proximity_config_t::scan_times` 以及单次测量的充放电次数 :cpp:member:`touch_proximity_config_t::charge_times` 决定。测量轮数以及充放电次数越高,灵敏度越高,但是过高的灵敏度容易导致误触发,请选择适当的灵敏度来保证触发的稳定性。
接近感应通道多次测量的累加值也可通过 :cpp:func:`touch_channel_read_data` 获取,数据类型 :cpp:type:`touch_chan_data_type_t`:cpp:enumerator:`TOUCH_CHAN_DATA_TYPE_PROXIMITY`
若需要注销接近感应功能,可再次调用 :cpp:func:`touch_sensor_config_proximity_sensing` 并将第二个参数(即 :cpp:type:`touch_proximity_config_t` 的配置结构体指针)设为 ``NULL`` 来注销接近感应功能。
.. code-block:: c
touch_proximity_config_t prox_cfg = {
// 接近感应配置
// ...
};
// 注册接近感应功能
ESP_ERROR_CHECK(touch_sensor_config_proximity_sensing(sens_handle, &prox_cfg));
// ...
// 注销接近感应功能
ESP_ERROR_CHECK(touch_sensor_config_proximity_sensing(sens_handle, NULL));
.. _touch-sleep-wakeup:
.. only:: SOC_TOUCH_SUPPORT_SLEEP_WAKEUP
睡眠唤醒配置
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
{IDF_TARGET_NAME} 支持触摸传感器将芯片从浅睡眠或深睡眠状态中唤醒。可通过调用 :cpp:func:`touch_sensor_config_sleep_wakeup` 并配置 :cpp:type:`touch_sleep_config_t` 来注册接近感应功能。
注册触摸传感器的睡眠唤醒功能后,处于睡眠状态下的芯片仍将继续保持对触摸传感器的采样,这将会导致芯片睡眠后的功耗增加,可通过减少充放电次数、增加采样间隔等方式来降低功耗。
另外,请注意在主核睡眠期间的采样、唤醒等操作均由硬件完成,本驱动由于运行在主核上,无法提供读数、配置等功能。
.. only:: SOC_RISCV_COPROC_SUPPORTED
若需要在睡眠过程中进行读数、配置等操作,可通过运行在 :doc:`超低功耗协处理器 ULP <../system/ulp>` 上的触摸传感器驱动 ``components/ulp/ulp_riscv/ulp_core/include/ulp_riscv_touch_ulp_core.h`` 实现。
- 浅睡眠状态唤醒:通过指定 :cpp:member:`slp_wakeup_lvl`:cpp:enumerator:`TOUCH_LIGHT_SLEEP_WAKEUP` 即可启用触摸传感器浅睡眠唤醒功能。注意任何已注册的触摸传感器通道都会在浅睡眠状态下保持采样并支持唤醒浅睡眠。
- 深睡眠状态唤醒:启用触摸传感器深睡眠唤醒功能除了指定 :cpp:member:`slp_wakeup_lvl`:cpp:enumerator:`TOUCH_DEEP_SLEEP_WAKEUP` 外,还需要指定深睡眠唤醒通道 :cpp:member:`deep_slp_chan`,注意只有该指定的通道才会在深睡眠状态下保持采样以及唤醒,以此降低在深睡眠状态下的功耗。此外,若需要在深度睡眠下使用另一套低功耗的配置来进一步降低功耗,可以通过 :cpp:member:`deep_slp_sens_cfg` 额外指定一套低功耗配置,在进入深睡眠前,驱动会应用这套配置,从深睡眠状态唤醒后,则会重新配置到之前的配置。请注意当 :cpp:member:`slp_wakeup_lvl` 配置为 :cpp:enumerator:`TOUCH_DEEP_SLEEP_WAKEUP` 后,触摸传感器不仅能唤醒深睡眠状态,还能唤醒浅睡眠状态。
若需要注销睡眠唤醒功能,可再次调用 :cpp:func:`touch_sensor_config_sleep_wakeup` 并将第二个参数(即 :cpp:type:`touch_sleep_config_t` 的配置结构体指针)设为 ``NULL`` 来注销睡眠唤醒功能。
.. code-block:: c
touch_sleep_config_t light_slp_cfg = {
.slp_wakeup_lvl = TOUCH_LIGHT_SLEEP_WAKEUP,
};
// 注册浅睡眠唤醒功能
ESP_ERROR_CHECK(touch_sensor_config_sleep_wakeup(sens_handle, &light_slp_cfg));
// ...
// 注销睡眠唤醒功能
ESP_ERROR_CHECK(touch_sensor_config_sleep_wakeup(sens_handle, NULL));
touch_sleep_config_t deep_slp_cfg = {
.slp_wakeup_lvl = TOUCH_DEEP_SLEEP_WAKEUP,
.deep_slp_chan = dslp_chan_handle,
// 其他深睡眠唤醒配置
// ...
};
// 注册深睡眠唤醒功能
ESP_ERROR_CHECK(touch_sensor_config_sleep_wakeup(sens_handle, &deep_slp_cfg));
应用示例
--------------------
.. only:: esp32p4
- 触摸传感器基础例程: :example:`peripherals/touch_sensor/touch_sensor_{IDF_TARGET_TOUCH_SENSOR_VERSION}`.
API 参考
-------------
.. only:: esp32p4
.. include-build-file:: inc/touch_sens.inc
.. include-build-file:: inc/touch_sens_types.inc
.. include-build-file:: inc/touch_version_types.inc

View File

@ -42,7 +42,8 @@
:SOC_SPI_SUPPORT_SLAVE_HD_VER2: spi_slave_hd :SOC_SPI_SUPPORT_SLAVE_HD_VER2: spi_slave_hd
:SOC_JPEG_CODEC_SUPPORTED: jpeg :SOC_JPEG_CODEC_SUPPORTED: jpeg
:SOC_TEMP_SENSOR_SUPPORTED: temp_sensor :SOC_TEMP_SENSOR_SUPPORTED: temp_sensor
:SOC_TOUCH_SENSOR_SUPPORTED: touch_pad :SOC_TOUCH_SENSOR_SUPPORTED and not esp32p4: touch_pad
:esp32p4: cap_touch_sens
:esp32s2: touch_element :esp32s2: touch_element
:SOC_TWAI_SUPPORTED: twai :SOC_TWAI_SUPPORTED: twai
uart uart

View File

@ -433,6 +433,16 @@ examples/peripherals/touch_sensor/touch_sensor_v2:
disable: disable:
- if: SOC_TOUCH_SENSOR_VERSION != 2 - if: SOC_TOUCH_SENSOR_VERSION != 2
examples/peripherals/touch_sensor/touch_sensor_v3:
disable:
- if: SOC_TOUCH_SENSOR_VERSION != 3
disable_test:
- if: IDF_TARGET == "esp32p4"
temporary: true
reason: the runners do not support the pins for touch sensor
depends_components:
- esp_driver_touch_sens
examples/peripherals/twai/twai_alert_and_recovery: examples/peripherals/twai/twai_alert_and_recovery:
disable: disable:
- if: SOC_TWAI_SUPPORTED != 1 - if: SOC_TWAI_SUPPORTED != 1

View File

@ -2,3 +2,4 @@
| ------- | ----------------- | | ------- | ----------------- |
| V1 | ESP32 | | V1 | ESP32 |
| V2 | ESP32S2, ESP32S3 | | V2 | ESP32S2, ESP32S3 |
| V3 | ESP32P4 |

View File

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

View File

@ -0,0 +1,125 @@
| Supported Targets | ESP32-P4 |
| ----------------- | -------- |
# Capacity Touch Sensor Example (for hardware version 3)
(See the README.md file in the upper level 'examples' directory for more information about examples.)
This example is going to demonstrate how to register the touch channels and read the data.
## How to Use Example
### Hardware Required
* A development board with any supported Espressif SOC chip (see `Supported Targets` table above)
* A USB cable for power supply and programming
* (Optional) Touch board with touch buttons on it.
- If you don't have a touch board, you can connect the touch pins with male jump wires and touch it directly for testing.
### Configure the Project
You can determine the touch channel number by ``EXAMPLE_TOUCH_CHANNEL_NUM`` in the example. And adjust the active threshold by ``s_thresh2bm_ratio``.
### Build and Flash
Build the project and flash it to the board, then run monitor tool to view serial output:
```
idf.py -p PORT build flash monitor
```
(To exit the serial monitor, type ``Ctrl-]``.)
See the Getting Started Guide for full steps to configure and use ESP-IDF to build projects.
## Example Output
You can see the following output in the monitor if the example runs successfully:
```
W (461) touch: [sample_cfg_id 0] clock precision loss, expect 4000000 hz, got 4006725 hz
W (461) touch: [sample_cfg_id 1] clock precision loss, expect 8000000 hz, got 8013450 hz
W (461) touch: [sample_cfg_id 2] clock precision loss, expect 16000000 hz, got 16026900 hz
Initial benchmark and new threshold are:
[CH 0] 0: 4114, 411 1: 2057, 205 2: 1028, 102
[CH 1] 0: 4643, 464 1: 2322, 232 2: 1160, 116
[CH 2] 0: 4848, 484 1: 2424, 242 2: 1211, 121
[CH 3] 0: 4340, 434 1: 2170, 217 2: 1085, 108
=================================
benchmark [CH 0]: 4115 2056 1028
chan_data [CH 0]: 4115 2056 1028
benchmark [CH 1]: 4644 2322 1160
chan_data [CH 1]: 4644 2322 1160
benchmark [CH 2]: 4848 2423 1211
chan_data [CH 2]: 4848 2423 1211
benchmark [CH 3]: 4337 2168 1084
chan_data [CH 3]: 4337 2168 1084
=================================
benchmark [CH 0]: 4109 2054 1027
chan_data [CH 0]: 4109 2054 1027
benchmark [CH 1]: 4638 2318 1158
chan_data [CH 1]: 4638 2318 1158
benchmark [CH 2]: 4843 2421 1210
chan_data [CH 2]: 4845 2421 1210
benchmark [CH 3]: 4334 2167 1084
chan_data [CH 3]: 4334 2167 1083
...
```
And if you touch and release a button, you will see the following output:
```
...
I (1321) touch_callback: [CH 1] active
=================================
benchmark [CH 0]: 4111 2055 1027
chan_data [CH 0]: 4111 2055 1027
benchmark [CH 1]: 4676 2339 1168
chan_data [CH 1]: 17701 8798 4399
benchmark [CH 2]: 4870 2434 1217
chan_data [CH 2]: 4867 2433 1217
benchmark [CH 3]: 4333 2165 1082
chan_data [CH 3]: 4333 2165 1082
=================================
benchmark [CH 0]: 4109 2053 1027
chan_data [CH 0]: 4108 2053 1027
benchmark [CH 1]: 4676 2339 1168
chan_data [CH 1]: 11256 8817 4363
benchmark [CH 2]: 4868 2434 1217
chan_data [CH 2]: 4862 2429 1214
benchmark [CH 3]: 4332 2165 1082
chan_data [CH 3]: 4330 2164 1081
I (1931) touch_callback: [CH 1] inactive
=================================
benchmark [CH 0]: 4106 2052 1026
chan_data [CH 0]: 4106 2052 1026
benchmark [CH 1]: 4649 2323 1161
chan_data [CH 1]: 4650 2323 1161
benchmark [CH 2]: 4847 2422 1211
chan_data [CH 2]: 4846 2422 1211
benchmark [CH 3]: 4329 2163 1082
chan_data [CH 3]: 4329 2164 1082
...
```
## Troubleshooting
For any technical queries, please open an [issue](https://github.com/espressif/esp-idf/issues) on GitHub. We will get back to you soon.

View File

@ -0,0 +1,3 @@
idf_component_register(SRCS "touch_sens_v3_example_main.c"
REQUIRES esp_driver_touch_sens
INCLUDE_DIRS ".")

View File

@ -0,0 +1,168 @@
/*
* SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: CC0-1.0
*/
#include <stdio.h>
#include <inttypes.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "driver/touch_sens.h"
#include "esp_check.h"
// Touch version 3 supports multiple sample configurations
#define EXAMPLE_TOUCH_SAMPLE_CFG_NUM 1 // Up to 'TOUCH_SAMPLE_CFG_NUM'
#define EXAMPLE_TOUCH_CHANNEL_NUM 4
#define EXAMPLE_TOUCH_CHAN_INIT_SCAN_TIMES 3
static touch_sensor_handle_t s_sens_handle = NULL;
static touch_channel_handle_t s_chan_handle[EXAMPLE_TOUCH_CHANNEL_NUM] = {};
// Active threshold to benchmark ratio. (i.e., touch will be activated when data >= benchmark * (1 + ratio))
static float s_thresh2bm_ratio[EXAMPLE_TOUCH_CHANNEL_NUM] = {
[0 ... EXAMPLE_TOUCH_CHANNEL_NUM - 1] = 0.015f, // 1.5%
};
bool example_touch_on_active_callback(touch_sensor_handle_t sens_handle, const touch_active_event_data_t *event, void *user_ctx)
{
ESP_EARLY_LOGI("touch_callback", "[CH %d] active", (int)event->chan_id);
return false;
}
bool example_touch_on_inactive_callback(touch_sensor_handle_t sens_handle, const touch_inactive_event_data_t *event, void *user_ctx)
{
ESP_EARLY_LOGI("touch_callback", "[CH %d] inactive", (int)event->chan_id);
return false;
}
static void example_touch_do_initial_scanning(void)
{
/* Enable the touch sensor to do the initial scanning, so that to initialize the channel data */
ESP_ERROR_CHECK(touch_sensor_enable(s_sens_handle));
/* Scan the enabled touch channels for several times, to make sure the initial channel data is stable */
for (int i = 0; i < EXAMPLE_TOUCH_CHAN_INIT_SCAN_TIMES; i++) {
ESP_ERROR_CHECK(touch_sensor_trigger_oneshot_scanning(s_sens_handle, 2000));
}
/* Disable the touch channel to rollback the state */
ESP_ERROR_CHECK(touch_sensor_disable(s_sens_handle));
/* (Optional) Read the initial channel benchmark and reconfig the channel active threshold accordingly */
printf("Initial benchmark and new threshold are:\n");
for (int i = 0; i < EXAMPLE_TOUCH_CHANNEL_NUM; i++) {
/* Read the initial benchmark of the touch channel */
uint32_t benchmark[EXAMPLE_TOUCH_SAMPLE_CFG_NUM] = {};
ESP_ERROR_CHECK(touch_channel_read_data(s_chan_handle[i], TOUCH_CHAN_DATA_TYPE_BENCHMARK, benchmark));
/* Calculate the proper active thresholds regarding the initial benchmark */
printf("[CH %d]", i);
touch_channel_config_t chan_cfg = {};
for (int j = 0; j < EXAMPLE_TOUCH_SAMPLE_CFG_NUM; j++) {
chan_cfg.active_thresh[j] = (uint32_t)(benchmark[j] * s_thresh2bm_ratio[i]);
printf(" %d: %"PRIu32", %"PRIu32"\t", j, benchmark[j], chan_cfg.active_thresh[j]);
}
printf("\n");
/* Update the channel configuration */
ESP_ERROR_CHECK(touch_sensor_reconfig_channel(s_chan_handle[i], &chan_cfg));
}
}
void app_main(void)
{
/* Use the default sample configurations */
touch_sensor_sample_config_t sample_cfg[EXAMPLE_TOUCH_SAMPLE_CFG_NUM] = {
TOUCH_SENSOR_V3_DEFAULT_SAMPLE_CONFIG(1, 1, 1),
#if EXAMPLE_TOUCH_SAMPLE_CFG_NUM > 1
TOUCH_SENSOR_V3_DEFAULT_SAMPLE_CONFIG(2, 1, 1),
#endif
#if EXAMPLE_TOUCH_SAMPLE_CFG_NUM > 2
TOUCH_SENSOR_V3_DEFAULT_SAMPLE_CONFIG(4, 1, 1),
#endif
};
/* Allocate new touch controller handle */
touch_sensor_config_t sens_cfg = TOUCH_SENSOR_DEFAULT_BASIC_CONFIG(EXAMPLE_TOUCH_SAMPLE_CFG_NUM, sample_cfg);
ESP_ERROR_CHECK(touch_sensor_new_controller(&sens_cfg, &s_sens_handle));
/* Configure the touch sensor filter */
touch_sensor_filter_config_t filter_cfg = TOUCH_SENSOR_DEFAULT_FILTER_CONFIG();
ESP_ERROR_CHECK(touch_sensor_config_filter(s_sens_handle, &filter_cfg));
/* Allocate new touch channel on the touch controller */
touch_channel_config_t chan_cfg = {
/** Set the touch channel active threshold of each sample configuration.
*
* @How to Determine:
* As the actual threshold is affected by various factors in real application,
* we need to run the touch app first to get the `benchmark` and the `smooth_data` that being touched.
*
* @Formula:
* threshold = benchmark * coeff, (coeff for example, 0.1%~20%)
* Please adjust the coeff to guarantee the threshold < smooth_data - benchmark
*
* @Typical Practice:
* Normally, we can't determine a fixed threshold at the beginning,
* but we can give them estimated values first and update them after an initial scanning (like this example),
* Step1: set an estimated value for each sample configuration first. (i.e., here)
* Step2: then reconfig the threshold after the initial scanning.(see `example_touch_do_initial_scanning`)
* Step3: adjust the `s_thresh2bm_ratio` to a proper value to trigger the active callback
*/
.active_thresh = {
1000, // estimated active threshold of sample configuration 0
#if EXAMPLE_TOUCH_SAMPLE_CFG_NUM > 1
2500, // estimated active threshold of sample configuration 1
#endif
#if EXAMPLE_TOUCH_SAMPLE_CFG_NUM > 2
5000, // estimated active threshold of sample configuration 2
#endif
},
};
for (int i = 0; i < EXAMPLE_TOUCH_CHANNEL_NUM; i++) {
ESP_ERROR_CHECK(touch_sensor_new_channel(s_sens_handle, i, &chan_cfg, &s_chan_handle[i]));
}
/* Do the initial scanning to initialize the touch channel data
* Without this step, the channel data in the first read will be invalid
*/
example_touch_do_initial_scanning();
/* Register the touch sensor callbacks, here only take `active` and `deactivate` event for example */
touch_event_callbacks_t callbacks = {
.on_active = example_touch_on_active_callback,
.on_inactive = example_touch_on_inactive_callback,
.on_measure_done = NULL,
.on_scan_done = NULL,
.on_timeout = NULL,
.on_proximity_meas_done = NULL,
};
ESP_ERROR_CHECK(touch_sensor_register_callbacks(s_sens_handle, &callbacks, NULL));
/* Enable the touch sensor */
ESP_ERROR_CHECK(touch_sensor_enable(s_sens_handle));
/* Start continuous scanning, you can also trigger oneshot scanning manually */
ESP_ERROR_CHECK(touch_sensor_start_continuous_scanning(s_sens_handle));
uint32_t benchmark[EXAMPLE_TOUCH_SAMPLE_CFG_NUM] = {};
uint32_t chan_data[EXAMPLE_TOUCH_SAMPLE_CFG_NUM] = {};
while (1) {
printf("=================================\n");
for (int i = 0; i < EXAMPLE_TOUCH_CHANNEL_NUM; i++) {
/* Read and print the benchmark of each sample configuration */
ESP_ERROR_CHECK(touch_channel_read_data(s_chan_handle[i], TOUCH_CHAN_DATA_TYPE_BENCHMARK, benchmark));
printf("benchmark [CH %d]:", i);
for (int j = 0; j < EXAMPLE_TOUCH_SAMPLE_CFG_NUM; j++) {
printf(" %"PRIu32, benchmark[j]);
}
printf("\n");
/* Read and print the channel data of each sample configuration */
ESP_ERROR_CHECK(touch_channel_read_data(s_chan_handle[i], TOUCH_CHAN_DATA_TYPE_SMOOTH, chan_data));
printf("chan_data [CH %d]:", i);
for (int j = 0; j < EXAMPLE_TOUCH_SAMPLE_CFG_NUM; j++) {
printf(" %"PRIu32, chan_data[j]);
}
printf("\n\n");
}
/* Read and display the data every 300 ms */
vTaskDelay(pdMS_TO_TICKS(300));
}
}

View File

@ -0,0 +1,14 @@
# SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD
# SPDX-License-Identifier: Unlicense OR CC0-1.0
import pytest
from pytest_embedded import Dut
@pytest.mark.esp32p4
@pytest.mark.temp_skip_ci(targets=['esp32p4'], reason='esp32p4 runners do not support touch pins')
@pytest.mark.generic
def test_touch_sens_v3(dut: Dut) -> None:
dut.expect_exact('Initial benchmark and new threshold are:')
dut.expect(r'\[CH [0-9]+\] 0: [0-9]+, [0-9]+')
dut.expect(r'benchmark \[CH [0-9]+\]: [0-9]+')
dut.expect(r'chan_data \[CH [0-9]+\]: [0-9]+')

View File

@ -50,7 +50,7 @@ void example_deep_sleep_register_touch_wakeup(void)
// If use touch pad wake up, should set touch sensor FSM mode at 'TOUCH_FSM_MODE_TIMER'. // If use touch pad wake up, should set touch sensor FSM mode at 'TOUCH_FSM_MODE_TIMER'.
touch_pad_set_fsm_mode(TOUCH_FSM_MODE_TIMER); touch_pad_set_fsm_mode(TOUCH_FSM_MODE_TIMER);
// Set reference voltage for charging/discharging // Set reference voltage for charging/discharging
// In this case, the high reference valtage will be 2.4V - 1V = 1.4V // In this case, the high reference voltage will be 2.4V - 1V = 1.4V
// The low reference voltage will be 0.5 // The low reference voltage will be 0.5
// The larger the range, the larger the pulse count value. // The larger the range, the larger the pulse count value.
touch_pad_set_voltage(TOUCH_HVOLT_2V4, TOUCH_LVOLT_0V5, TOUCH_HVOLT_ATTEN_1V); touch_pad_set_voltage(TOUCH_HVOLT_2V4, TOUCH_LVOLT_0V5, TOUCH_HVOLT_ATTEN_1V);
@ -104,6 +104,8 @@ void example_deep_sleep_register_touch_wakeup(void)
#endif #endif
printf("Enabling touch pad wakeup\n"); printf("Enabling touch pad wakeup\n");
ESP_ERROR_CHECK(esp_sleep_enable_touchpad_wakeup()); ESP_ERROR_CHECK(esp_sleep_enable_touchpad_wakeup());
#if SOC_PM_SUPPORT_RTC_PERIPH_PD
ESP_ERROR_CHECK(esp_sleep_pd_config(ESP_PD_DOMAIN_RTC_PERIPH, ESP_PD_OPTION_ON)); ESP_ERROR_CHECK(esp_sleep_pd_config(ESP_PD_DOMAIN_RTC_PERIPH, ESP_PD_OPTION_ON));
#endif
} }
#endif // CONFIG_EXAMPLE_TOUCH_WAKEUP #endif // CONFIG_EXAMPLE_TOUCH_WAKEUP

View File

@ -9,5 +9,9 @@ if(IDF_TARGET IN_LIST TOUCH_ELEMENT_COMPATIBLE_TARGETS)
list(APPEND srcs "touch_wakeup.c") list(APPEND srcs "touch_wakeup.c")
endif() endif()
if(IDF_TARGET STREQUAL "esp32p4")
list(APPEND srcs "touch_sens_wakeup.c")
endif()
idf_component_register(SRCS ${srcs} idf_component_register(SRCS ${srcs}
INCLUDE_DIRS ".") INCLUDE_DIRS ".")

View File

@ -1,15 +1,20 @@
/* /*
* SPDX-FileCopyrightText: 2021-2022 Espressif Systems (Shanghai) CO LTD * SPDX-FileCopyrightText: 2021-2024 Espressif Systems (Shanghai) CO LTD
* *
* SPDX-License-Identifier: Unlicense OR CC0-1.0 * SPDX-License-Identifier: Unlicense OR CC0-1.0
*/ */
#pragma once #pragma once
#include "sdkconfig.h"
#ifdef __cplusplus #ifdef __cplusplus
extern "C" { extern "C" {
#endif #endif
// TODO: [ESP32P4] add P4 when runner is ready
#define EXAMPLE_TOUCH_LSLEEP_WAKEUP_SUPPORT (CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3)
void example_wait_gpio_inactive(void); void example_wait_gpio_inactive(void);
esp_err_t example_register_gpio_wakeup(void); esp_err_t example_register_gpio_wakeup(void);
@ -18,7 +23,7 @@ esp_err_t example_register_timer_wakeup(void);
esp_err_t example_register_uart_wakeup(void); esp_err_t example_register_uart_wakeup(void);
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3 #if EXAMPLE_TOUCH_LSLEEP_WAKEUP_SUPPORT
void example_register_touch_wakeup(void); void example_register_touch_wakeup(void);
#endif #endif

View File

@ -50,7 +50,7 @@ static void light_sleep_task(void *args)
* Otherwise the chip may fall sleep again before running uart task */ * Otherwise the chip may fall sleep again before running uart task */
vTaskDelay(1); vTaskDelay(1);
break; break;
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3 #if EXAMPLE_TOUCH_LSLEEP_WAKEUP_SUPPORT
case ESP_SLEEP_WAKEUP_TOUCHPAD: case ESP_SLEEP_WAKEUP_TOUCHPAD:
wakeup_reason = "touch"; wakeup_reason = "touch";
break; break;
@ -83,7 +83,7 @@ void app_main(void)
example_register_timer_wakeup(); example_register_timer_wakeup();
/* Enable wakeup from light sleep by uart */ /* Enable wakeup from light sleep by uart */
example_register_uart_wakeup(); example_register_uart_wakeup();
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3 #if EXAMPLE_TOUCH_LSLEEP_WAKEUP_SUPPORT
/* Enable wakeup from light sleep by touch element */ /* Enable wakeup from light sleep by touch element */
example_register_touch_wakeup(); example_register_touch_wakeup();
#endif #endif

View File

@ -0,0 +1,107 @@
/*
* SPDX-FileCopyrightText: 2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Unlicense OR CC0-1.0
*/
#include "freertos/FreeRTOS.h"
#include "esp_log.h"
#include "driver/touch_sens.h"
static const char *TAG = "touch_wakeup";
#define EXAMPLE_TOUCH_SAMPLE_CFG_NUM 1
#define EXAMPLE_TOUCH_CHANNEL_NUM 5
#define EXAMPLE_TOUCH_CHAN_INIT_SCAN_TIMES 3
// Active threshold to benchmark ratio. (i.e., touch will be activated when data >= benchmark * (1 + ratio))
static float s_thresh2bm_ratio[EXAMPLE_TOUCH_CHANNEL_NUM] = {
[0 ... EXAMPLE_TOUCH_CHANNEL_NUM - 1] = 0.02f, // 2%
};
static bool example_touch_on_active_cb(touch_sensor_handle_t sens_handle, const touch_active_event_data_t *event, void *user_ctx)
{
ESP_EARLY_LOGW("isr", "ch %d active", (int)event->chan_id);
return false;
}
static bool example_touch_on_inactive_cb(touch_sensor_handle_t sens_handle, const touch_inactive_event_data_t *event, void *user_ctx)
{
ESP_EARLY_LOGW("isr", "ch %d inactive", (int)event->chan_id);
return false;
}
static void example_touch_do_initial_scanning(touch_sensor_handle_t sens_handle, touch_channel_handle_t chan_handle[])
{
/* Enable the touch sensor to do the initial scanning, so that to initialize the channel data */
ESP_ERROR_CHECK(touch_sensor_enable(sens_handle));
/* Scan the enabled touch channels for several times, to make sure the initial channel data is stable */
for (int i = 0; i < EXAMPLE_TOUCH_CHAN_INIT_SCAN_TIMES; i++) {
ESP_ERROR_CHECK(touch_sensor_trigger_oneshot_scanning(sens_handle, 2000));
}
/* Disable the touch channel to rollback the state */
ESP_ERROR_CHECK(touch_sensor_disable(sens_handle));
/* (Optional) Read the initial channel benchmark and reconfig the channel active threshold accordingly */
printf("Initial benchmark and new threshold are:\n");
for (int i = 0; i < EXAMPLE_TOUCH_CHANNEL_NUM; i++) {
/* Read the initial benchmark of the touch channel */
uint32_t benchmark[EXAMPLE_TOUCH_SAMPLE_CFG_NUM] = {};
ESP_ERROR_CHECK(touch_channel_read_data(chan_handle[i], TOUCH_CHAN_DATA_TYPE_BENCHMARK, benchmark));
/* Calculate the proper active thresholds regarding the initial benchmark */
printf("[CH %d]", i);
touch_channel_config_t chan_cfg = {};
for (int j = 0; j < EXAMPLE_TOUCH_SAMPLE_CFG_NUM; j++) {
chan_cfg.active_thresh[j] = (uint32_t)(benchmark[j] * s_thresh2bm_ratio[j]);
printf(" %d: %"PRIu32", %"PRIu32"\t", j, benchmark[j], chan_cfg.active_thresh[j]);
}
printf("\n");
/* Update the channel configuration */
ESP_ERROR_CHECK(touch_sensor_reconfig_channel(chan_handle[i], &chan_cfg));
}
}
esp_err_t example_register_touch_wakeup(void)
{
touch_sensor_handle_t sens_handle = NULL;
touch_sensor_sample_config_t sample_cfg[EXAMPLE_TOUCH_SAMPLE_CFG_NUM] = {
TOUCH_SENSOR_V3_DEFAULT_SAMPLE_CONFIG(1, 1, 1),
};
touch_sensor_config_t sens_cfg = TOUCH_SENSOR_DEFAULT_BASIC_CONFIG(EXAMPLE_TOUCH_SAMPLE_CFG_NUM, sample_cfg);
ESP_ERROR_CHECK(touch_sensor_new_controller(&sens_cfg, &sens_handle));
touch_sensor_filter_config_t filter_cfg = TOUCH_SENSOR_DEFAULT_FILTER_CONFIG();
ESP_ERROR_CHECK(touch_sensor_config_filter(sens_handle, &filter_cfg));
touch_channel_handle_t chan_handle[EXAMPLE_TOUCH_CHANNEL_NUM];
touch_channel_config_t chan_cfg = {
.active_thresh = {5000}, // Initial threshold
};
for (int i = 0; i < EXAMPLE_TOUCH_CHANNEL_NUM; i++) {
ESP_ERROR_CHECK(touch_sensor_new_channel(sens_handle, i, &chan_cfg, &chan_handle[i]));
}
/* (Optional) Do the initial scanning to initialize the touch channel data
* Without this step, the channel data in the first read will be invalid
*/
example_touch_do_initial_scanning(sens_handle, chan_handle);
touch_event_callbacks_t callbacks = {
.on_active = example_touch_on_active_cb,
.on_inactive = example_touch_on_inactive_cb,
};
ESP_ERROR_CHECK(touch_sensor_register_callbacks(sens_handle, &callbacks, NULL));
touch_sleep_config_t light_slp_cfg = {
.slp_wakeup_lvl = TOUCH_LIGHT_SLEEP_WAKEUP,
};
ESP_ERROR_CHECK(touch_sensor_config_sleep_wakeup(sens_handle, &light_slp_cfg));
ESP_ERROR_CHECK(touch_sensor_enable(sens_handle));
ESP_ERROR_CHECK(touch_sensor_start_continuous_scanning(sens_handle));
ESP_LOGI(TAG, "touch wakeup source is ready");
return ESP_OK;
}

View File

@ -692,7 +692,6 @@ components/soc/esp32s3/include/soc/rtc_io_reg.h
components/soc/esp32s3/include/soc/rtc_io_struct.h components/soc/esp32s3/include/soc/rtc_io_struct.h
components/soc/esp32s3/include/soc/sdmmc_pins.h components/soc/esp32s3/include/soc/sdmmc_pins.h
components/soc/esp32s3/include/soc/sdmmc_reg.h components/soc/esp32s3/include/soc/sdmmc_reg.h
components/soc/esp32s3/include/soc/sens_reg.h
components/soc/esp32s3/include/soc/sensitive_reg.h components/soc/esp32s3/include/soc/sensitive_reg.h
components/soc/esp32s3/include/soc/sensitive_struct.h components/soc/esp32s3/include/soc/sensitive_struct.h
components/soc/esp32s3/include/soc/soc_ulp.h components/soc/esp32s3/include/soc/soc_ulp.h