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

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

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

View File

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

View File

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

View File

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

View File

@@ -8,6 +8,6 @@
#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"
#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
#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
#if SOC_LP_CORE_SUPPORTED
@@ -117,6 +123,7 @@ typedef enum {
RTC_UART1_TRIG_EN | \
RTC_BT_TRIG_EN | \
RTC_LP_CORE_TRIG_EN | \
RTC_TOUCH_TRIG_EN | \
RTC_XTAL32K_DEAD_TRIG_EN | \
RTC_USB_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);
#endif
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);
#endif
#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);
#if CONFIG_IDF_TARGET_ESP32S2 || CONFIG_IDF_TARGET_ESP32S3
#if SOC_TOUCH_SENSOR_VERSION >= 2
if (deep_sleep) {
if (s_config.wakeup_triggers & RTC_TOUCH_TRIG_EN) {
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),
* 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;
}
}
@@ -1602,7 +1607,7 @@ static esp_err_t timer_wakeup_prepare(int64_t sleep_duration)
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. */
static void touch_wakeup_prepare(void)
{
@@ -1621,6 +1626,11 @@ static void touch_wakeup_prepare(void)
touch_ll_start_fsm();
}
}
#elif SOC_TOUCH_SENSOR_VERSION == 3
static void touch_wakeup_prepare(void)
{
touch_hal_prepare_deep_sleep();
}
#endif
#if SOC_TOUCH_SENSOR_SUPPORTED
@@ -1648,7 +1658,11 @@ touch_pad_t esp_sleep_get_touchpad_wakeup_status(void)
return TOUCH_PAD_MAX;
}
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);
#endif
return pad_num;
}

View File

@@ -280,26 +280,27 @@ if(NOT BOOTLOADER_BUILD)
"usb_wrap_hal.c")
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")
list(APPEND srcs
"touch_sensor_hal.c"
"esp32/touch_sensor_hal.c"
"esp32/gpio_hal_workaround.c")
endif()
if(${target} STREQUAL "esp32s2")
list(APPEND srcs
"touch_sensor_hal.c"
"xt_wdt_hal.c"
"esp32s2/cp_dma_hal.c"
"esp32s2/touch_sensor_hal.c")
"esp32s2/cp_dma_hal.c")
endif()
if(${target} STREQUAL "esp32s3")
list(APPEND srcs
"touch_sensor_hal.c"
"xt_wdt_hal.c"
"esp32s3/touch_sensor_hal.c"
"esp32s3/rtc_cntl_hal.c")
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
*/
@@ -229,6 +229,7 @@ static inline void touch_ll_get_tie_option(touch_pad_t touch_num, touch_tie_opt_
*
* @param mode FSM mode.
*/
__attribute__((always_inline))
static inline void touch_ll_set_fsm_mode(touch_fsm_mode_t mode)
{
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.
*/
__attribute__((always_inline))
static inline void touch_ll_stop_fsm(void)
{
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
* - 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;
}

View File

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

View File

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

View File

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

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
*/
@@ -26,7 +26,7 @@ extern "C" {
/**
* 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()
@@ -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)
/**
* Set max equivalent capacitance for sheild channel.
* Set max equivalent capacitance for shield channel.
* The equivalent capacitance of the shielded channel can be calculated
* 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)
/**
* Get max equivalent capacitance for sheild channel.
* Get max equivalent capacitance for shield channel.
* The equivalent capacitance of the shielded channel can be calculated
* 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.
*/
#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.
*/
#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.

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
*/
@@ -214,6 +214,7 @@ static inline void touch_ll_get_tie_option(touch_pad_t touch_num, touch_tie_opt_
*
* @param mode FSM mode.
*/
__attribute__((always_inline))
static inline void touch_ll_set_fsm_mode(touch_fsm_mode_t 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.
* 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)
{
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
* - 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;
}
@@ -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)
{
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;
if (intr_st & RTC_CNTL_TOUCH_DONE_INT_ST_M) {
if (intr_st.rtc_touch_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;
}
if (intr_st & RTC_CNTL_TOUCH_INACTIVE_INT_ST_M) {
if (intr_st.rtc_touch_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;
}
if (intr_st & RTC_CNTL_TOUCH_TIMEOUT_INT_ST_M) {
if (intr_st.rtc_touch_timeout) {
intr_msk |= TOUCH_PAD_INTR_MASK_TIMEOUT;
}
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
* 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
* 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.
*/
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;
}
@@ -1092,7 +1096,7 @@ static inline void touch_ll_sleep_enable_approach(void)
/**
* 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;
}
@@ -1100,7 +1104,7 @@ static inline void touch_ll_sleep_disable_approach(void)
/**
* 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;
}
@@ -1157,11 +1161,11 @@ static inline void touch_ll_sleep_read_debounce(uint32_t *debounce)
/**
* 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
*/
@@ -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_ll_proximity_set_channel_num((const touch_pad_t *)prox_pad);
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.
}
@@ -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)
{
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)

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
*/
@@ -26,7 +26,7 @@ extern "C" {
/**
* 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()
@@ -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)
/**
* Set max equivalent capacitance for sheild channel.
* Set max equivalent capacitance for shield channel.
* The equivalent capacitance of the shielded channel can be calculated
* 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)
/**
* Get max equivalent capacitance for sheild channel.
* Get max equivalent capacitance for shield channel.
* The equivalent capacitance of the shielded channel can be calculated
* 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.
*/
#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.
*/
#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.

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
*/
@@ -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)
{
#define PAD_SLOP_MASK(val, num) ((val) << (29 - (num) * 3))
uint32_t curr_slop = 0;
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 {
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)
{
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 {
*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.
*/
__attribute__((always_inline))
static inline void touch_ll_set_fsm_mode(touch_fsm_mode_t 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.
* 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)
{
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
* - 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;
}
@@ -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)
{
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;
if (intr_st & RTC_CNTL_TOUCH_DONE_INT_ST_M) {
if (intr_st.rtc_touch_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;
}
if (intr_st & RTC_CNTL_TOUCH_INACTIVE_INT_ST_M) {
if (intr_st.rtc_touch_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;
}
if (intr_st & RTC_CNTL_TOUCH_TIMEOUT_INT_ST_M) {
if (intr_st.rtc_touch_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;
}
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
* 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
* 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.
*/
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;
}
@@ -1112,7 +1123,7 @@ static inline void touch_ll_sleep_enable_approach(void)
/**
* 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;
}
@@ -1120,7 +1131,7 @@ static inline void touch_ll_sleep_disable_approach(void)
/**
* 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;
}
@@ -1177,11 +1188,11 @@ static inline void touch_ll_sleep_read_debounce(uint32_t *debounce)
/**
* 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
*/
@@ -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_ll_proximity_set_channel_num((const touch_pad_t *)prox_pad);
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.
}
@@ -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)
{
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)

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
*/
@@ -194,7 +194,7 @@ void touch_hal_get_meas_mode(touch_pad_t touch_num, touch_hal_meas_mode_t *meas)
* @return
* - 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.

View File

@@ -275,7 +275,7 @@ typedef enum {
TOUCH_PAD_SMOOTH_MAX,
} 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
*
@@ -283,9 +283,11 @@ typedef enum {
typedef enum {
TOUCH_PAD_OUT_AS_DATA, /*!< Counting the output of touch channel as data.
* The value will be smaller than actual value but more sensitive when the frequency of touch_out is close to the source clock
* 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.
* 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;
#endif

View File

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

View File

@@ -326,7 +326,7 @@
#define SOC_TOUCH_SENSOR_VERSION (1U) /*!<Hardware version of touch sensor */
#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 ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL

View File

@@ -4,7 +4,7 @@
* 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. */
const int touch_sensor_channel_io_map[] = {

View File

@@ -275,6 +275,10 @@ config SOC_SPI_FLASH_SUPPORTED
bool
default y
config SOC_TOUCH_SENSOR_SUPPORTED
bool
default y
config SOC_RNG_SUPPORTED
bool
default y
@@ -1395,6 +1399,18 @@ config SOC_TOUCH_SENSOR_NUM
int
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
int
default 3
@@ -1403,7 +1419,11 @@ config SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED
bool
default y
config SOC_TOUCH_SAMPLER_NUM
config SOC_TOUCH_SUPPORT_FREQ_HOP
bool
default y
config SOC_TOUCH_SAMPLE_CFG_NUM
int
default 3
@@ -1567,6 +1587,10 @@ config SOC_PM_SUPPORT_WIFI_WAKEUP
bool
default y
config SOC_PM_SUPPORT_TOUCH_SENSOR_WAKEUP
bool
default y
config SOC_PM_SUPPORT_XTAL32K_PD
bool
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
*/
@@ -619,13 +619,13 @@ extern "C" {
* need_des
*/
#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
*/
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_DISUPDATE_BASELINE_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_NEG_NOISE_DISUPDATE_BASELINE_EN_V 0x00000001U
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_DISUPDATE_BASELINE_EN_S 0
#define LP_ANALOG_PERI_TOUCH_NN_DISUPDATE_BENCHMARK_EN (BIT(0))
#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_NN_DISUPDATE_BENCHMARK_EN_V 0x00000001U
#define LP_ANALOG_PERI_TOUCH_NN_DISUPDATE_BENCHMARK_EN_S 0
/** LP_ANALOG_PERI_TOUCH_HYSTERESIS : R/W; bitpos: [2:1]; default: 0;
* 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_V 0x00000003U
#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
*/
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_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_NEG_NOISE_THRES_V 0x00000003U
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_THRES_S 3
#define LP_ANALOG_PERI_TOUCH_NN_THRES 0x00000003U
#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_NN_THRES_V 0x00000003U
#define LP_ANALOG_PERI_TOUCH_NN_THRES_S 3
/** LP_ANALOG_PERI_TOUCH_NOISE_THRES : R/W; bitpos: [6:5]; default: 0;
* 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_V 0x00000001U
#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
*/
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_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_NEG_NOISE_LIMIT_V 0x0000000FU
#define LP_ANALOG_PERI_TOUCH_NEG_NOISE_LIMIT_S 17
#define LP_ANALOG_PERI_TOUCH_NN_LIMIT 0x0000000FU
#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_NN_LIMIT_V 0x0000000FU
#define LP_ANALOG_PERI_TOUCH_NN_LIMIT_S 17
/** LP_ANALOG_PERI_TOUCH_APPROACH_LIMIT : R/W; bitpos: [28:21]; default: 80;
* 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_V 0x00000001U
#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
*/
#define LP_ANALOG_PERI_TOUCH_BYPASS_NEG_NOISE_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_NEG_NOISE_THRES_V 0x00000001U
#define LP_ANALOG_PERI_TOUCH_BYPASS_NEG_NOISE_THRES_S 31
#define LP_ANALOG_PERI_TOUCH_BYPASS_NN_THRES (BIT(31))
#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_NN_THRES_V 0x00000001U
#define LP_ANALOG_PERI_TOUCH_BYPASS_NN_THRES_S 31
/** LP_ANALOG_PERI_TOUCH_FILTER3_REG register
* need_des
*/
#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
*/
#define LP_ANALOG_PERI_TOUCH_BASELINE_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_BASELINE_SW_V 0x0000FFFFU
#define LP_ANALOG_PERI_TOUCH_BASELINE_SW_S 0
/** LP_ANALOG_PERI_TOUCH_UPDATE_BASELINE_SW : WT; bitpos: [16]; default: 0;
#define LP_ANALOG_PERI_TOUCH_BENCHMARK_SW 0x0000FFFFU
#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_BENCHMARK_SW_V 0x0000FFFFU
#define LP_ANALOG_PERI_TOUCH_BENCHMARK_SW_S 0
/** LP_ANALOG_PERI_TOUCH_UPDATE_BENCHMARK_SW : WT; bitpos: [16]; default: 0;
* need_des
*/
#define LP_ANALOG_PERI_TOUCH_UPDATE_BASELINE_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_BASELINE_SW_V 0x00000001U
#define LP_ANALOG_PERI_TOUCH_UPDATE_BASELINE_SW_S 16
#define LP_ANALOG_PERI_TOUCH_UPDATE_BENCHMARK_SW (BIT(16))
#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_BENCHMARK_SW_V 0x00000001U
#define LP_ANALOG_PERI_TOUCH_UPDATE_BENCHMARK_SW_S 16
/** LP_ANALOG_PERI_TOUCH_SLP0_REG register
* 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
*/
@@ -510,18 +510,18 @@ typedef union {
*/
typedef union {
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
*/
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;
* need_des
*/
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
*/
uint32_t touch_neg_noise_thres:2;
uint32_t touch_nn_thres:2;
/** touch_noise_thres : R/W; bitpos: [6:5]; default: 0;
* need_des
*/
@@ -542,10 +542,10 @@ typedef union {
* need_des
*/
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
*/
uint32_t touch_neg_noise_limit:4;
uint32_t touch_nn_limit:4;
/** touch_approach_limit : R/W; bitpos: [28:21]; default: 80;
* need_des
*/
@@ -572,10 +572,10 @@ typedef union {
* need_des
*/
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
*/
uint32_t touch_bypass_neg_noise_thres:1;
uint32_t touch_bypass_nn_thres:1;
};
uint32_t val;
} lp_analog_peri_touch_filter2_reg_t;
@@ -585,14 +585,14 @@ typedef union {
*/
typedef union {
struct {
/** touch_baseline_sw : R/W; bitpos: [15:0]; default: 0;
/** touch_benchmark_sw : R/W; bitpos: [15:0]; default: 0;
* need_des
*/
uint32_t touch_baseline_sw:16;
/** touch_update_baseline_sw : WT; bitpos: [16]; default: 0;
uint32_t touch_benchmark_sw:16;
/** touch_update_benchmark_sw : WT; bitpos: [16]; default: 0;
* need_des
*/
uint32_t touch_update_baseline_sw:1;
uint32_t touch_update_benchmark_sw:1;
uint32_t reserved_17:15;
};
uint32_t val;
@@ -704,10 +704,14 @@ typedef union {
* High speed touch driver
*/
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
*/
uint32_t touch_freq_dbias:5;
uint32_t touch_freq_dbias:4;
uint32_t reserved_23:9;
};
uint32_t val;
@@ -746,7 +750,7 @@ typedef union {
/** touch_data_sel : R/W; bitpos: [9:8]; default: 0;
* The type of the output data for debugging
* 0/1: raw data
* 2: baseline
* 2: benchmark
* 3: smooth data
*/
uint32_t touch_data_sel:2;
@@ -840,7 +844,7 @@ typedef union {
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;
typedef struct {

View File

@@ -87,7 +87,7 @@
#define SOC_ASSIST_DEBUG_SUPPORTED 1
#define SOC_WDT_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_GP_LDO_SUPPORTED 1 // General purpose LDO
#define SOC_PPA_SUPPORTED 1
@@ -549,11 +549,17 @@
#define SOC_MWDT_SUPPORT_XTAL (1)
/*-------------------------- TOUCH SENSOR CAPS -------------------------------*/
#define SOC_TOUCH_SENSOR_VERSION (3) // Hardware version of touch sensor
#define SOC_TOUCH_SENSOR_NUM (14) // Touch available channel number. Actually there are 15 Touch channels, but channel 14 is not pinned out, limit to 14 channels
#define SOC_TOUCH_PROXIMITY_CHANNEL_NUM (3) // Support touch proximity channel number.
#define SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED (1) // Support touch proximity channel measure done interrupt type.
#define SOC_TOUCH_SAMPLER_NUM (3) // The sampler number in total, each sampler can be used to sample on one frequency
#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 */
/* Touch Sensor Features */
#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 ---------------------------------------*/
#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_EXT1_WAKEUP_BY_PMU (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_RC32K_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
*/
@@ -14,7 +14,7 @@ extern "C" {
/** RTC_TOUCH_INT_RAW_REG register
* 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;
* need_des
*/
@@ -61,7 +61,7 @@ extern "C" {
/** RTC_TOUCH_INT_ST_REG register
* 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;
* need_des
*/
@@ -108,7 +108,7 @@ extern "C" {
/** RTC_TOUCH_INT_ENA_REG register
* 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;
* need_des
*/
@@ -155,7 +155,7 @@ extern "C" {
/** RTC_TOUCH_INT_CLR_REG register
* 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;
* need_des
*/
@@ -202,7 +202,7 @@ extern "C" {
/** RTC_TOUCH_CHN_STATUS_REG register
* 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;
* need_des
*/
@@ -228,7 +228,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_0_REG register
* 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;
* need_des
*/
@@ -254,7 +254,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_1_REG register
* 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;
* need_des
*/
@@ -280,7 +280,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_2_REG register
* 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;
* need_des
*/
@@ -306,7 +306,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_3_REG register
* 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;
* need_des
*/
@@ -332,7 +332,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_4_REG register
* 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;
* need_des
*/
@@ -358,7 +358,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_5_REG register
* 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;
* need_des
*/
@@ -384,7 +384,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_6_REG register
* 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;
* need_des
*/
@@ -410,7 +410,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_7_REG register
* 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;
* need_des
*/
@@ -436,7 +436,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_8_REG register
* 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;
* need_des
*/
@@ -462,7 +462,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_9_REG register
* 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;
* need_des
*/
@@ -488,7 +488,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_10_REG register
* 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;
* need_des
*/
@@ -514,7 +514,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_11_REG register
* 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;
* need_des
*/
@@ -540,7 +540,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_12_REG register
* 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;
* need_des
*/
@@ -566,7 +566,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_13_REG register
* 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;
* need_des
*/
@@ -592,7 +592,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_14_REG register
* 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;
* need_des
*/
@@ -618,7 +618,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_15_REG register
* 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;
* need_des
*/
@@ -644,7 +644,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_16_REG register
* 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;
* need_des
*/
@@ -677,7 +677,7 @@ extern "C" {
/** RTC_TOUCH_STATUS_17_REG register
* 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;
* Reserved
*/
@@ -724,7 +724,7 @@ extern "C" {
/** RTC_TOUCH_CHN_TMP_STATUS_REG register
* 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;
* need_des
*/
@@ -743,7 +743,7 @@ extern "C" {
/** RTC_TOUCH_DATE_REG register
* 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;
* need_des
*/

View File

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

View File

@@ -4,7 +4,7 @@
* 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. */
/* 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
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
int
default 3
config SOC_TOUCH_SAMPLER_NUM
config SOC_TOUCH_SAMPLE_CFG_NUM
int
default 1

View File

@@ -336,11 +336,14 @@
#define SOC_TIMER_GROUP_TOTAL_TIMERS (4)
/*-------------------------- TOUCH SENSOR CAPS -------------------------------*/
#define SOC_TOUCH_SENSOR_VERSION (2) /*!<Hardware version of touch sensor */
#define SOC_TOUCH_SENSOR_NUM (15) /*!<15 Touch channels */
#define SOC_TOUCH_PROXIMITY_CHANNEL_NUM (3) /*!<Support touch proximity channel number. */
#define SOC_TOUCH_SENSOR_VERSION (2) /*!< Hardware version of touch sensor */
#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_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 ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL

View File

@@ -4,7 +4,7 @@
* 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. */
/* 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
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
int
default 3
@@ -967,7 +979,7 @@ config SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED
bool
default y
config SOC_TOUCH_SAMPLER_NUM
config SOC_TOUCH_SAMPLE_CFG_NUM
int
default 1

View File

@@ -1,16 +1,8 @@
// Copyright 2017-2021 Espressif Systems (Shanghai) PTE LTD
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/*
* SPDX-FileCopyrightText: 2017-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef _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_S 18
/* 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_M ((SENS_TOUCH_DATA_SEL_V)<<(SENS_TOUCH_DATA_SEL_S))
#define SENS_TOUCH_DATA_SEL_V 0x3
@@ -1378,8 +1370,8 @@ extern "C" {
#define SENS_SAR_HALL_CTRL_REG (DR_REG_SENS_BASE + 0xFC)
/* 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
rocessor.*/
/*description: 1: HALL PHASE is controlled by SW 0: HALL PHASE is controlled by FSM in
ULP-coprocessor.*/
#define SENS_HALL_PHASE_FORCE (BIT(31))
#define SENS_HALL_PHASE_FORCE_M (BIT(31))
#define SENS_HALL_PHASE_FORCE_V 0x1

View File

@@ -217,7 +217,7 @@ typedef volatile struct sens_dev_s {
struct {
uint32_t touch_outen : 15; /*touch controller output enable*/
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_unit_end : 1; /*touch_unit_done*/
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
*/
@@ -370,12 +370,15 @@
#define SOC_TIMER_GROUP_TOTAL_TIMERS (4)
/*-------------------------- TOUCH SENSOR CAPS -------------------------------*/
#define SOC_TOUCH_SENSOR_VERSION (2) // Hardware version of touch sensor
#define SOC_TOUCH_SENSOR_NUM (15) /*! 15 Touch channels */
#define SOC_TOUCH_PROXIMITY_CHANNEL_NUM (3) /* Sopport touch proximity channel number. */
#define SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED (1) /*Sopport touch proximity channel measure done interrupt type. */
#define SOC_TOUCH_SENSOR_VERSION (2) /*!< Hardware version of touch sensor */
#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 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 ---------------------------------------*/
#define SOC_TWAI_CONTROLLER_NUM 1UL

View File

@@ -4,7 +4,7 @@
* 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. */
/* 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
*/
@@ -7,14 +7,6 @@
#pragma once
#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
extern "C" {