update touch sensor examples

This commit is contained in:
fuzhibo 2021-08-24 21:38:12 +08:00 committed by laokaiyao
parent 057b9d61b5
commit 3ca9da0386
53 changed files with 134 additions and 388 deletions

View File

@ -62,6 +62,7 @@ static SemaphoreHandle_t rtc_touch_mux = NULL;
Touch Pad
---------------------------------------------------------------*/
#if CONFIG_IDF_TARGET_ESP32S2
/** Workaround for scan done interrupt issue. */
static void touch_pad_workaround_isr_internal(void *arg)
{
@ -81,6 +82,7 @@ static void touch_pad_workaround_isr_internal(void *arg)
}
}
}
#endif
esp_err_t touch_pad_isr_register(intr_handler_t fn, void *arg, touch_pad_intr_mask_t intr_mask)
{
@ -104,13 +106,19 @@ esp_err_t touch_pad_isr_register(intr_handler_t fn, void *arg, touch_pad_intr_ma
if (intr_mask & TOUCH_PAD_INTR_MASK_TIMEOUT) {
en_msk |= RTC_CNTL_TOUCH_TIMEOUT_INT_ST_M;
}
#if SOC_TOUCH_PROXIMITY_MEAS_DONE_SUPPORTED
if (intr_mask & TOUCH_PAD_INTR_MASK_PROXI_MEAS_DONE) {
en_msk |= RTC_CNTL_TOUCH_APPROACH_LOOP_DONE_INT_ST_M;
}
#endif
esp_err_t ret = rtc_isr_register(fn, arg, en_msk);
#if CONFIG_IDF_TARGET_ESP32S2
/* Must ensure: After being registered, it is executed first. */
if ( (ret == ESP_OK) && (reg_flag == false) && (intr_mask & (TOUCH_PAD_INTR_MASK_SCAN_DONE | TOUCH_PAD_INTR_MASK_TIMEOUT)) ) {
rtc_isr_register(touch_pad_workaround_isr_internal, NULL, RTC_CNTL_TOUCH_SCAN_DONE_INT_ST_M | RTC_CNTL_TOUCH_TIMEOUT_INT_ST_M);
reg_flag = true;
}
#endif
return ret;
}

View File

@ -1,2 +0,0 @@
idf_component_register(SRCS "${CONFIG_IDF_TARGET}/tp_interrupt_main.c"
INCLUDE_DIRS ".")

View File

@ -1,240 +0,0 @@
/* Touch Pad Interrupt Example
This example code is in the Public Domain (or CC0 licensed, at your option.)
Unless required by applicable law or agreed to in writing, this
software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
CONDITIONS OF ANY KIND, either express or implied.
*/
#include <stdio.h>
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/queue.h"
#include "esp_log.h"
#include "driver/touch_pad.h"
#include "soc/rtc_periph.h"
#include "soc/sens_periph.h"
#include "esp_sleep.h"
static const char *TAG = "Touch pad";
static QueueHandle_t que_touch = NULL;
typedef struct touch_msg {
touch_pad_intr_mask_t intr_mask;
uint32_t pad_status_msk;
uint32_t curr_pad;
} touch_event_t;
#define TOUCH_BUTTON_NUM 4
#define TOUCH_BUTTON_WATERPROOF_ENABLE 1
#define TOUCH_BUTTON_DENOISE_ENABLE 1
#define TOUCH_CHANGE_CONFIG 0
static const touch_pad_t button[TOUCH_BUTTON_NUM] = {
TOUCH_PAD_NUM7, // 'SELECT' button.
TOUCH_PAD_NUM9, // 'MENU' button.
TOUCH_PAD_NUM11, // 'BACK' button.
TOUCH_PAD_NUM13, // Guard ring for waterproof design.
// If this pad be touched, other pads no response.
};
/*
* Touch threshold. The threshold determines the sensitivity of the touch.
* This threshold is derived by testing changes in readings from different touch channels.
* If (raw_data - benchmark) > benchmark * threshold, the pad be activated.
* If (raw_data - benchmark) < benchmark * threshold, the pad be inactivated.
*/
static const float button_threshold[TOUCH_BUTTON_NUM] = {
0.2, // 20%.
0.2, // 20%.
0.2, // 20%.
0.1, // 10%.
};
/*
Handle an interrupt triggered when a pad is touched.
Recognize what pad has been touched and save it in a table.
*/
static void touchsensor_interrupt_cb(void *arg)
{
int task_awoken = pdFALSE;
touch_event_t evt;
evt.intr_mask = touch_pad_read_intr_status_mask();
evt.pad_status_msk = touch_pad_get_status();
/* Note: Obtaining channel information in the interrupt callback function as the channel that triggers the interrupt is risky.
If the execution of the interrupt callback function is delayed by a channel measurement time,
the channel information obtained is wrong. Both light sleep and SPI FLASH reading and
writing may delay the response of the interrupt function. */
evt.curr_pad = touch_pad_get_current_meas_channel();
xQueueSendFromISR(que_touch, &evt, &task_awoken);
if (task_awoken == pdTRUE) {
portYIELD_FROM_ISR();
}
}
static void tp_example_set_thresholds(void)
{
uint32_t touch_value;
for (int i = 0; i < TOUCH_BUTTON_NUM; i++) {
//read benchmark value
touch_pad_read_benchmark(button[i], &touch_value);
//set interrupt threshold.
touch_pad_set_thresh(button[i], touch_value * button_threshold[i]);
ESP_LOGI(TAG, "touch pad [%d] base %d, thresh %d", \
button[i], touch_value, (uint32_t)(touch_value * button_threshold[i]));
}
}
static void touchsensor_filter_set(touch_filter_mode_t mode)
{
/* Filter function */
touch_filter_config_t filter_info = {
.mode = mode, // Test jitter and filter 1/4.
.debounce_cnt = 1, // 1 time count.
.noise_thr = 0, // 50%
.jitter_step = 4, // use for jitter mode.
.smh_lvl = TOUCH_PAD_SMOOTH_IIR_2,
};
touch_pad_filter_set_config(&filter_info);
touch_pad_filter_enable();
ESP_LOGI(TAG, "touch pad filter init");
}
static void tp_example_read_task(void *pvParameter)
{
uint8_t pad_num = 0;
uint32_t touch_trig_diff = 0;
touch_event_t evt = {0};
static uint8_t guard_mode_flag = 0;
/* Wait touch sensor init done */
vTaskDelay(50 / portTICK_RATE_MS);
uint32_t last_pad_status_msk = touch_pad_get_status();
tp_example_set_thresholds();
while (1) {
int ret = xQueueReceive(que_touch, &evt, (portTickType)portMAX_DELAY);
if (ret != pdTRUE) {
continue;
}
if (evt.intr_mask & (TOUCH_PAD_INTR_MASK_ACTIVE | TOUCH_PAD_INTR_MASK_INACTIVE)) {
if (last_pad_status_msk == evt.pad_status_msk) {
ESP_LOGW(TAG, "TouchSensor status no changes, pad mask 0x%x", evt.pad_status_msk);
continue;
}
pad_num = 0;
touch_trig_diff = evt.pad_status_msk ^ last_pad_status_msk; // Record changes in channel status. Each bit represents a channel
last_pad_status_msk = evt.pad_status_msk; // Update the pad active status
/* Traverse all channels and find out the channel where the state changes, and determine the state type */
while (touch_trig_diff) {
if (touch_trig_diff & BIT(pad_num)) {
if (evt.pad_status_msk & BIT(pad_num)) { // Touch channel active
/* if guard pad be touched, other pads no response. */
if (pad_num == button[3]) {
guard_mode_flag = 1;
ESP_LOGW(TAG, "TouchSensor [%d] be activated, enter guard mode", pad_num);
} else {
if (guard_mode_flag == 0) {
ESP_LOGI(TAG, "TouchSensor [%d] be activated, status mask 0x%x", pad_num, evt.pad_status_msk);
} else {
ESP_LOGW(TAG, "In guard mode. No response");
}
}
} else { // Touch channel inactive
/* if guard pad be touched, other pads no response. */
if (pad_num == button[3]) {
guard_mode_flag = 0;
ESP_LOGW(TAG, "TouchSensor [%d] be inactivated, exit guard mode", pad_num);
} else {
if (guard_mode_flag == 0) {
ESP_LOGI(TAG, "TouchSensor [%d] be inactivated, status mask 0x%x", pad_num, evt.pad_status_msk);
}
}
}
touch_trig_diff &= (~(BIT(pad_num))); // Clear the channels that have been checked
}
pad_num ++;
}
}
if (evt.intr_mask & TOUCH_PAD_INTR_MASK_SCAN_DONE) {
ESP_LOGI(TAG, "The touch sensor group measurement is done [%d].", evt.curr_pad);
}
if (evt.intr_mask & TOUCH_PAD_INTR_MASK_TIMEOUT) {
/* Add your exception handling in here. */
ESP_LOGI(TAG, "Touch sensor channel %d measure timeout. Skip this exception channel!!", evt.curr_pad);
touch_pad_timeout_resume(); // Point on the next channel to measure.
}
}
}
void app_main(void)
{
if (que_touch == NULL) {
que_touch = xQueueCreate(TOUCH_BUTTON_NUM, sizeof(touch_event_t));
}
// Initialize touch pad peripheral, it will start a timer to run a filter
ESP_LOGI(TAG, "Initializing touch pad");
/* Initialize touch pad peripheral. */
touch_pad_init();
for (int i = 0; i < TOUCH_BUTTON_NUM; i++) {
touch_pad_config(button[i]);
}
#if TOUCH_CHANGE_CONFIG
/* If you want change the touch sensor default setting, please write here(after initialize). There are examples: */
touch_pad_set_meas_time(TOUCH_PAD_SLEEP_CYCLE_DEFAULT, TOUCH_PAD_MEASURE_CYCLE_DEFAULT);
touch_pad_set_voltage(TOUCH_PAD_HIGH_VOLTAGE_THRESHOLD, TOUCH_PAD_LOW_VOLTAGE_THRESHOLD, TOUCH_PAD_ATTEN_VOLTAGE_THRESHOLD);
touch_pad_set_idle_channel_connect(TOUCH_PAD_IDLE_CH_CONNECT_DEFAULT);
for (int i = 0; i < TOUCH_BUTTON_NUM; i++) {
touch_pad_set_cnt_mode(i, TOUCH_PAD_SLOPE_DEFAULT, TOUCH_PAD_TIE_OPT_DEFAULT);
}
#endif
#if TOUCH_BUTTON_DENOISE_ENABLE
/* Denoise setting at TouchSensor 0. */
touch_pad_denoise_t denoise = {
/* The bits to be cancelled are determined according to the noise level. */
.grade = TOUCH_PAD_DENOISE_BIT4,
/* By adjusting the parameters, the reading of T0 should be approximated to the reading of the measured channel. */
.cap_level = TOUCH_PAD_DENOISE_CAP_L4,
};
touch_pad_denoise_set_config(&denoise);
touch_pad_denoise_enable();
ESP_LOGI(TAG, "Denoise function init");
#endif
#if TOUCH_BUTTON_WATERPROOF_ENABLE
/* Waterproof function */
touch_pad_waterproof_t waterproof = {
.guard_ring_pad = button[3], // If no ring pad, set 0;
/* It depends on the number of the parasitic capacitance of the shield pad.
Based on the touch readings of T14 and T0, estimate the size of the parasitic capacitance on T14
and set the parameters of the appropriate hardware. */
.shield_driver = TOUCH_PAD_SHIELD_DRV_L2,
};
touch_pad_waterproof_set_config(&waterproof);
touch_pad_waterproof_enable();
ESP_LOGI(TAG, "touch pad waterproof init");
#endif
/* Filter setting */
touchsensor_filter_set(TOUCH_PAD_FILTER_IIR_16);
touch_pad_timeout_set(true, SOC_TOUCH_PAD_THRESHOLD_MAX);
/* Register touch interrupt ISR, enable intr type. */
touch_pad_isr_register(touchsensor_interrupt_cb, NULL, TOUCH_PAD_INTR_MASK_ALL);
/* If you have other touch algorithm, you can get the measured value after the `TOUCH_PAD_INTR_MASK_SCAN_DONE` interrupt is generated. */
touch_pad_intr_enable(TOUCH_PAD_INTR_MASK_ACTIVE | TOUCH_PAD_INTR_MASK_INACTIVE | TOUCH_PAD_INTR_MASK_TIMEOUT);
/* In ESP32-S3 If the touch wakeup not enable, the touch action of the touch sensor during light sleep may be lost. */
esp_sleep_enable_touchpad_wakeup();
/* Enable touch sensor clock. Work mode is "timer trigger". */
touch_pad_set_fsm_mode(TOUCH_FSM_MODE_TIMER);
touch_pad_fsm_start();
// Start a task to show what pads have been touched
xTaskCreate(&tp_example_read_task, "touch_pad_read_task", 2048, NULL, 5, NULL);
}

View File

@ -1,2 +0,0 @@
idf_component_register(SRCS "${CONFIG_IDF_TARGET}/tp_read_main.c"
INCLUDE_DIRS ".")

View File

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

View File

@ -1,5 +1,5 @@
| Supported Targets | ESP32 | ESP32-S2 |
| ----------------- | ----- | -------- |
| Supported Targets | ESP32 |
| ----------------- | ----- |
# Touch Pad Interrupt Example
@ -35,30 +35,6 @@ I (22903) Touch pad: Waiting for any pad being touched...
Note: Sensing threshold is set up automatically at start up by performing simple calibration. Application is reading current value for each pad and assuming two thirds of this value as the sensing threshold. Do not touch pads on application start up, otherwise sensing may not work correctly.
## ESP32-S2 platform
Demonstrates how to set up ESP32-S2's capacitive touch pad peripheral to trigger interrupt when a pad is touched. It also shows how to detect the touch event by the software for sensor designs when greater touch detection sensitivity is required.
ESP32-S2 supports touch detection by configuring hardware registers. The hardware periodically detects the pulse counts. If the number of pulse counts exceeds the set threshold, a hardware interrupt will be generated to notify the application layer that a certain touch sensor channel may be triggered.
The application is cycling between the interrupt mode and the pooling mode with a filter, to compare performance of the touch sensor system in both scenarios:
```
I (304) Touch pad: Initializing touch pad
I (304) Touch pad: Denoise function init
I (304) Touch pad: touch pad waterproof init
I (304) Touch pad: touch pad filter init 2
I (414) Touch pad: test init: touch pad [7] base 7382, thresh 1476
I (414) Touch pad: test init: touch pad [9] base 7349, thresh 1469
I (414) Touch pad: test init: touch pad [11] base 8047, thresh 1609
I (414) Touch pad: test init: touch pad [13] base 8104, thresh 810
I (5954) Touch pad: TouchSensor [9] be actived, status mask 0x200
W (6034) Touch pad: TouchSensor [13] be actived, enter guard mode
W (6034) Touch pad: In guard mode. No response
W (6174) Touch pad: TouchSensor [13] be actived, exit guard mode
I (6194) Touch pad: TouchSensor [9] be inactived, status mask 0x0
```
## Reference Information
For a simpler example how to configure and read capacitive touch pads, please refer to [touch_pad_read](../touch_pad_read).

View File

@ -0,0 +1,2 @@
idf_component_register(SRCS "tp_interrupt_main.c"
INCLUDE_DIRS ".")

View File

@ -2,5 +2,3 @@
# "main" pseudo-component makefile.
#
# (Uses default behaviour of compiling all source files in directory, adding 'include' to include path.)
COMPONENT_SRCDIRS := $(IDF_TARGET)

View File

@ -16,6 +16,8 @@
#include "soc/rtc_periph.h"
#include "soc/sens_periph.h"
#if CONFIG_IDF_TARGET_ESP32
static const char *TAG = "Touch pad";
#define TOUCH_THRESH_NO_USE (0)
@ -169,3 +171,5 @@ void app_main(void)
// Start a task to show what pads have been touched
xTaskCreate(&tp_example_read_task, "touch_pad_read_task", 2048, NULL, 5, NULL);
}
#endif // CONFIG_IDF_TARGET_ESP32

View File

@ -0,0 +1,31 @@
| Supported Targets | ESP32 |
| ----------------- | ----- |
# Touch Pad Read Example
## ESP32 plaform
Read and display raw values or IIR filtered values from capacitive touch pad sensors.
Once configured, ESP32 is continuously measuring capacitance of touch pad sensors. Measurement is reflected as numeric value inversely related to sensor's capacitance. The capacitance is bigger when sensor is touched with a finger and the measured value smaller. In opposite situation, when finger is released, capacitance is smaller and the measured value bigger.
To detect when a sensor is touched and when not, each particular design should be calibrated by obtaining both measurements for each individual sensor. Then a threshold between both values should be established. Using specific threshold, API is then able to distinguish whether specific sensor is touched or released.
ESP32 supports reading up to ten capacitive touch pad sensors T0 - T9, connected to specific GPIO pins. For information on available pins please refer to [Technical Reference Manual](https://espressif.com/sites/default/files/documentation/esp32_technical_reference_manual_en.pdf). Application initializes all ten sensor pads. Then in a loop reads sensors T0 - T9 and displays obtained values (after a colon) on a serial terminal:
```
Touch Sensor filter mode read, the output format is:
Touchpad num:[raw data, filtered data]
T0:[1072,1071] T1:[ 475, 475] T2:[1004,1003] T3:[1232,1231] T4:[1675,1676] T5:[1146,1146] T6:[1607,1607] T7:[1118,1118] T8:[1695,1695] T9:[1223,1222]
T0:[1072,1071] T1:[ 475, 475] T2:[1003,1003] T3:[1231,1231] T4:[1676,1676] T5:[1146,1146] T6:[1607,1607] T7:[1118,1118] T8:[1694,1694] T9:[1222,1221]
T0:[1071,1071] T1:[ 475, 475] T2:[1004,1004] T3:[1231,1231] T4:[1678,1677] T5:[1147,1146] T6:[1607,1607] T7:[1118,1118] T8:[1694,1694] T9:[1222,1221]
```
## Reference Information
For hardware and firmware design guidelines on ESP32 touch sensor system, please refer to [Touch Sensor Application Note](https://github.com/espressif/esp-iot-solution/blob/release/v1.0/documents/touch_pad_solution/touch_sensor_design_en.md), where you may find comprehensive information on how to design and implement touch sensing applications, such as linear slider, wheel slider, matrix buttons and spring buttons.
There is another similar example that demonstrates how to perform simple calibration and trigger an interrupt when a pat is touched - see [touch_pad_interrupt](../touch_pad_interrupt).
See the README.md file in the upper level 'examples' directory for more information about examples.

View File

@ -0,0 +1,2 @@
idf_component_register(SRCS "tp_read_main.c"
INCLUDE_DIRS ".")

View File

@ -2,5 +2,3 @@
# "main" pseudo-component makefile.
#
# (Uses default behaviour of compiling all source files in directory, adding 'include' to include path.)
COMPONENT_SRCDIRS := $(IDF_TARGET)

View File

@ -12,6 +12,8 @@
#include "driver/touch_pad.h"
#include "esp_log.h"
#if CONFIG_IDF_TARGET_ESP32
#define TOUCH_PAD_NO_CHANGE (-1)
#define TOUCH_THRESH_NO_USE (0)
#define TOUCH_FILTER_MODE_EN (1)
@ -70,3 +72,5 @@ void app_main(void)
// Start task to read values sensed by pads
xTaskCreate(&tp_example_read_task, "touch_pad_read_task", 2048, NULL, 5, NULL);
}
#endif // CONFIG_IDF_TARGET_ESP32

View File

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

View File

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

View File

@ -0,0 +1,36 @@
| Supported Targets | ESP32-S2 | ESP32-S3 |
| ----------------- | -------- | -------- |
# Touch Pad Interrupt Example
## ESP32-S2, ESP32-S3 platform
Demonstrates how to set up ESP32-S2's capacitive touch pad peripheral to trigger interrupt when a pad is touched. It also shows how to detect the touch event by the software for sensor designs when greater touch detection sensitivity is required.
ESP32-S2 supports touch detection by configuring hardware registers. The hardware periodically detects the pulse counts. If the number of pulse counts exceeds the set threshold, a hardware interrupt will be generated to notify the application layer that a certain touch sensor channel may be triggered.
The application is cycling between the interrupt mode and the pooling mode with a filter, to compare performance of the touch sensor system in both scenarios:
```
I (304) Touch pad: Initializing touch pad
I (304) Touch pad: Denoise function init
I (304) Touch pad: touch pad waterproof init
I (304) Touch pad: touch pad filter init 2
I (414) Touch pad: test init: touch pad [7] base 7382, thresh 1476
I (414) Touch pad: test init: touch pad [9] base 7349, thresh 1469
I (414) Touch pad: test init: touch pad [11] base 8047, thresh 1609
I (414) Touch pad: test init: touch pad [13] base 8104, thresh 810
I (5954) Touch pad: TouchSensor [9] be actived, status mask 0x200
W (6034) Touch pad: TouchSensor [13] be actived, enter guard mode
W (6034) Touch pad: In guard mode. No response
W (6174) Touch pad: TouchSensor [13] be actived, exit guard mode
I (6194) Touch pad: TouchSensor [9] be inactived, status mask 0x0
```
## Reference Information
For a simpler example how to configure and read capacitive touch pads, please refer to [touch_pad_read](../touch_pad_read).
Design and implementation of the touch sensor system is a complex process. The [Touch Sensor Application Note](https://github.com/espressif/esp-iot-solution/blob/release/v1.0/documents/touch_pad_solution/touch_sensor_design_en.md) contains several ESP32 specific notes and comments to optimize the design and get the best out of the application with sensors controlled with the ESP32.
See the README.md file in the upper level 'examples' directory for more information about examples.

View File

@ -0,0 +1,2 @@
idf_component_register(SRCS "tp_interrupt_main.c"
INCLUDE_DIRS ".")

View File

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

View File

@ -161,7 +161,7 @@ void app_main(void)
#if TOUCH_CHANGE_CONFIG
/* If you want change the touch sensor default setting, please write here(after initialize). There are examples: */
touch_pad_set_meas_time(TOUCH_PAD_SLEEP_CYCLE_DEFAULT, TOUCH_PAD_SLEEP_CYCLE_DEFAULT);
touch_pad_set_meas_time(TOUCH_PAD_SLEEP_CYCLE_DEFAULT, TOUCH_PAD_MEASURE_CYCLE_DEFAULT);
touch_pad_set_voltage(TOUCH_PAD_HIGH_VOLTAGE_THRESHOLD, TOUCH_PAD_LOW_VOLTAGE_THRESHOLD, TOUCH_PAD_ATTEN_VOLTAGE_THRESHOLD);
touch_pad_set_idle_channel_connect(TOUCH_PAD_IDLE_CH_CONNECT_DEFAULT);
for (int i = 0; i < TOUCH_BUTTON_NUM; i++) {

View File

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

View File

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

View File

@ -1,28 +1,9 @@
| Supported Targets | ESP32 | ESP32-S2 |
| ----------------- | ----- | -------- |
| Supported Targets | ESP32-S2 | ESP32-S3 |
| ----------------- | -------- | -------- |
# Touch Pad Read Example
## ESP32 plaform
Read and display raw values or IIR filtered values from capacitive touch pad sensors.
Once configured, ESP32 is continuously measuring capacitance of touch pad sensors. Measurement is reflected as numeric value inversely related to sensor's capacitance. The capacitance is bigger when sensor is touched with a finger and the measured value smaller. In opposite situation, when finger is released, capacitance is smaller and the measured value bigger.
To detect when a sensor is touched and when not, each particular design should be calibrated by obtaining both measurements for each individual sensor. Then a threshold between both values should be established. Using specific threshold, API is then able to distinguish whether specific sensor is touched or released.
ESP32 supports reading up to ten capacitive touch pad sensors T0 - T9, connected to specific GPIO pins. For information on available pins please refer to [Technical Reference Manual](https://espressif.com/sites/default/files/documentation/esp32_technical_reference_manual_en.pdf). Application initializes all ten sensor pads. Then in a loop reads sensors T0 - T9 and displays obtained values (after a colon) on a serial terminal:
```
Touch Sensor filter mode read, the output format is:
Touchpad num:[raw data, filtered data]
T0:[1072,1071] T1:[ 475, 475] T2:[1004,1003] T3:[1232,1231] T4:[1675,1676] T5:[1146,1146] T6:[1607,1607] T7:[1118,1118] T8:[1695,1695] T9:[1223,1222]
T0:[1072,1071] T1:[ 475, 475] T2:[1003,1003] T3:[1231,1231] T4:[1676,1676] T5:[1146,1146] T6:[1607,1607] T7:[1118,1118] T8:[1694,1694] T9:[1222,1221]
T0:[1071,1071] T1:[ 475, 475] T2:[1004,1004] T3:[1231,1231] T4:[1678,1677] T5:[1147,1146] T6:[1607,1607] T7:[1118,1118] T8:[1694,1694] T9:[1222,1221]
```
## ESP32-S2 platform
## ESP32-S2, ESP32-S3 platform
Read and display raw values from capacitive touch pad sensors.

View File

@ -0,0 +1,2 @@
idf_component_register(SRCS "tp_read_main.c"
INCLUDE_DIRS ".")

View File

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