Refactor the touch sensor driver

This commit is contained in:
Fu Zhi Bo 2019-11-27 20:08:44 +08:00 committed by Wang Jia Lin
parent c487df288c
commit 3a468a1ffd
37 changed files with 5347 additions and 2552 deletions

View file

@ -19,6 +19,7 @@ set(srcs
"spi_master.c"
"spi_slave.c"
"timer.c"
"touch_sensor_common.c"
"uart.c")
set(includes "include")
@ -28,12 +29,14 @@ if(IDF_TARGET STREQUAL "esp32")
list(APPEND srcs "mcpwm.c"
"sdio_slave.c"
"sdmmc_host.c"
"sdmmc_transaction.c")
"sdmmc_transaction.c"
"esp32/touch_sensor.c")
list(APPEND includes "esp32/include")
endif()
if(IDF_TARGET STREQUAL "esp32s2beta")
list(APPEND srcs "esp32s2beta/rtc_tempsensor.c"
"esp32s2beta/rtc_touchpad.c")
"esp32s2beta/touch_sensor.c")
# currently only S2 beta has its own target-specific includes
list(APPEND includes "esp32s2beta/include")
endif()

View file

@ -0,0 +1,331 @@
// Copyright 2019 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.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Configure touch pad interrupt threshold.
*
* @note If FSM mode is set to TOUCH_FSM_MODE_TIMER, this function will be blocked for one measurement cycle and wait for data to be valid.
*
* @param touch_num touch pad index
* @param threshold interrupt threshold,
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG if argument wrong
* - ESP_FAIL if touch pad not initialized
*/
esp_err_t touch_pad_config(touch_pad_t touch_num, uint16_t threshold);
/**
* @brief get touch sensor counter value.
* Each touch sensor has a counter to count the number of charge/discharge cycles.
* When the pad is not 'touched', we can get a number of the counter.
* When the pad is 'touched', the value in counter will get smaller because of the larger equivalent capacitance.
*
* @note This API requests hardware measurement once. If IIR filter mode is enabled,
* please use 'touch_pad_read_raw_data' interface instead.
*
* @param touch_num touch pad index
* @param touch_value pointer to accept touch sensor value
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Touch pad parameter error
* - ESP_ERR_INVALID_STATE This touch pad hardware connection is error, the value of "touch_value" is 0.
* - ESP_FAIL Touch pad not initialized
*/
esp_err_t touch_pad_read(touch_pad_t touch_num, uint16_t * touch_value);
/**
* @brief get filtered touch sensor counter value by IIR filter.
*
* @note touch_pad_filter_start has to be called before calling touch_pad_read_filtered.
* This function can be called from ISR
*
* @param touch_num touch pad index
* @param touch_value pointer to accept touch sensor value
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Touch pad parameter error
* - ESP_ERR_INVALID_STATE This touch pad hardware connection is error, the value of "touch_value" is 0.
* - ESP_FAIL Touch pad not initialized
*/
esp_err_t touch_pad_read_filtered(touch_pad_t touch_num, uint16_t *touch_value);
/**
* @brief get raw data (touch sensor counter value) from IIR filter process.
* Need not request hardware measurements.
*
* @note touch_pad_filter_start has to be called before calling touch_pad_read_raw_data.
* This function can be called from ISR
*
* @param touch_num touch pad index
* @param touch_value pointer to accept touch sensor value
*
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Touch pad parameter error
* - ESP_ERR_INVALID_STATE This touch pad hardware connection is error, the value of "touch_value" is 0.
* - ESP_FAIL Touch pad not initialized
*/
esp_err_t touch_pad_read_raw_data(touch_pad_t touch_num, uint16_t *touch_value);
/**
* @brief Callback function that is called after each IIR filter calculation.
* @note This callback is called in timer task in each filtering cycle.
* @note This callback should not be blocked.
* @param raw_value The latest raw data(touch sensor counter value) that
* points to all channels(raw_value[0..TOUCH_PAD_MAX-1]).
* @param filtered_value The latest IIR filtered data(calculated from raw data) that
* points to all channels(filtered_value[0..TOUCH_PAD_MAX-1]).
*
*/
typedef void (* filter_cb_t)(uint16_t *raw_value, uint16_t *filtered_value);
/**
* @brief Register the callback function that is called after each IIR filter calculation.
* @note The 'read_cb' callback is called in timer task in each filtering cycle.
* @param read_cb Pointer to filtered callback function.
* If the argument passed in is NULL, the callback will stop.
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG set error
*/
esp_err_t touch_pad_set_filter_read_cb(filter_cb_t read_cb);
/**
* @brief Register touch-pad ISR.
* The handler will be attached to the same CPU core that this function is running on.
* @param fn Pointer to ISR handler
* @param arg Parameter for ISR
* @return
* - ESP_OK Success ;
* - ESP_ERR_INVALID_ARG GPIO error
* - ESP_ERR_NO_MEM No memory
*/
esp_err_t touch_pad_isr_register(intr_handler_t fn, void* arg);
/**
* @brief Set touch sensor measurement and sleep time.
* Excessive total time will slow down the touch response.
* Too small measurement time will not be sampled enough, resulting in inaccurate measurements.
*
* @note The greater the duty cycle of the measurement time, the more system power is consumed.
* @param sleep_cycle The touch sensor will sleep after each measurement.
* sleep_cycle decide the interval between each measurement.
* t_sleep = sleep_cycle / (RTC_SLOW_CLK frequency).
* The approximate frequency value of RTC_SLOW_CLK can be obtained using rtc_clk_slow_freq_get_hz function.
* @param meas_cycle The duration of the touch sensor measurement.
* t_meas = meas_cycle / 8M, the maximum measure time is 0xffff / 8M = 8.19 ms
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_set_meas_time(uint16_t sleep_cycle, uint16_t meas_cycle);
/**
* @brief Get touch sensor measurement and sleep time
* @param sleep_cycle Pointer to accept sleep cycle number
* @param meas_cycle Pointer to accept measurement cycle count.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_meas_time(uint16_t *sleep_cycle, uint16_t *meas_cycle);
/**
* @brief Trigger a touch sensor measurement, only support in SW mode of FSM
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_sw_start(void);
/**
* @brief Set touch sensor interrupt threshold
* @param touch_num touch pad index
* @param threshold threshold of touchpad count, refer to touch_pad_set_trigger_mode to see how to set trigger mode.
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_set_thresh(touch_pad_t touch_num, uint16_t threshold);
/**
* @brief Get touch sensor interrupt threshold
* @param touch_num touch pad index
* @param threshold pointer to accept threshold
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_get_thresh(touch_pad_t touch_num, uint16_t *threshold);
/**
* @brief Set touch sensor interrupt trigger mode.
* Interrupt can be triggered either when counter result is less than
* threshold or when counter result is more than threshold.
* @param mode touch sensor interrupt trigger mode
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_set_trigger_mode(touch_trigger_mode_t mode);
/**
* @brief Get touch sensor interrupt trigger mode
* @param mode pointer to accept touch sensor interrupt trigger mode
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_trigger_mode(touch_trigger_mode_t *mode);
/**
* @brief Set touch sensor interrupt trigger source. There are two sets of touch signals.
* Set1 and set2 can be mapped to several touch signals. Either set will be triggered
* if at least one of its touch signal is 'touched'. The interrupt can be configured to be generated
* if set1 is triggered, or only if both sets are triggered.
* @param src touch sensor interrupt trigger source
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_set_trigger_source(touch_trigger_src_t src);
/**
* @brief Get touch sensor interrupt trigger source
* @param src pointer to accept touch sensor interrupt trigger source
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_trigger_source(touch_trigger_src_t *src);
/**
* @brief Set touch sensor group mask.
* Touch pad module has two sets of signals, 'Touched' signal is triggered only if
* at least one of touch pad in this group is "touched".
* This function will set the register bits according to the given bitmask.
* @param set1_mask bitmask of touch sensor signal group1, it's a 10-bit value
* @param set2_mask bitmask of touch sensor signal group2, it's a 10-bit value
* @param en_mask bitmask of touch sensor work enable, it's a 10-bit value
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_set_group_mask(uint16_t set1_mask, uint16_t set2_mask, uint16_t en_mask);
/**
* @brief Get touch sensor group mask.
* @param set1_mask pointer to accept bitmask of touch sensor signal group1, it's a 10-bit value
* @param set2_mask pointer to accept bitmask of touch sensor signal group2, it's a 10-bit value
* @param en_mask pointer to accept bitmask of touch sensor work enable, it's a 10-bit value
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_group_mask(uint16_t *set1_mask, uint16_t *set2_mask, uint16_t *en_mask);
/**
* @brief Clear touch sensor group mask.
* Touch pad module has two sets of signals, Interrupt is triggered only if
* at least one of touch pad in this group is "touched".
* This function will clear the register bits according to the given bitmask.
* @param set1_mask bitmask touch sensor signal group1, it's a 10-bit value
* @param set2_mask bitmask touch sensor signal group2, it's a 10-bit value
* @param en_mask bitmask of touch sensor work enable, it's a 10-bit value
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_clear_group_mask(uint16_t set1_mask, uint16_t set2_mask, uint16_t en_mask);
/**
* @brief To enable touch pad interrupt
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_intr_enable(void);
/**
* @brief To disable touch pad interrupt
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_intr_disable(void);
/**
* @brief set touch pad filter calibration period, in ms.
* Need to call touch_pad_filter_start before all touch filter APIs
* @param new_period_ms filter period, in ms
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_STATE driver state error
* - ESP_ERR_INVALID_ARG parameter error
*/
esp_err_t touch_pad_set_filter_period(uint32_t new_period_ms);
/**
* @brief get touch pad filter calibration period, in ms
* Need to call touch_pad_filter_start before all touch filter APIs
* @param p_period_ms pointer to accept period
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_STATE driver state error
* - ESP_ERR_INVALID_ARG parameter error
*/
esp_err_t touch_pad_get_filter_period(uint32_t* p_period_ms);
/**
* @brief start touch pad filter function
* This API will start a filter to process the noise in order to prevent false triggering
* when detecting slight change of capacitance.
* Need to call touch_pad_filter_start before all touch filter APIs
*
* @note This filter uses FreeRTOS timer, which is dispatched from a task with
* priority 1 by default on CPU 0. So if some application task with higher priority
* takes a lot of CPU0 time, then the quality of data obtained from this filter will be affected.
* You can adjust FreeRTOS timer task priority in menuconfig.
* @param filter_period_ms filter calibration period, in ms
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG parameter error
* - ESP_ERR_NO_MEM No memory for driver
* - ESP_ERR_INVALID_STATE driver state error
*/
esp_err_t touch_pad_filter_start(uint32_t filter_period_ms);
/**
* @brief stop touch pad filter function
* Need to call touch_pad_filter_start before all touch filter APIs
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_STATE driver state error
*/
esp_err_t touch_pad_filter_stop(void);
/**
* @brief delete touch pad filter driver and release the memory
* Need to call touch_pad_filter_start before all touch filter APIs
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_STATE driver state error
*/
esp_err_t touch_pad_filter_delete(void);
#ifdef __cplusplus
}
#endif

View file

@ -0,0 +1,471 @@
// Copyright 2016-2019 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.
#include <esp_types.h>
#include <stdlib.h>
#include <ctype.h>
#include "esp_log.h"
#include "sys/lock.h"
#include "soc/rtc.h"
#include "soc/periph_defs.h"
#include "freertos/FreeRTOS.h"
#include "freertos/xtensa_api.h"
#include "freertos/semphr.h"
#include "freertos/timers.h"
#include "esp_intr_alloc.h"
#include "driver/rtc_io.h"
#include "driver/touch_pad.h"
#include "driver/rtc_cntl.h"
#include "driver/gpio.h"
#include "sdkconfig.h"
#include "esp32/rom/ets_sys.h"
#ifndef NDEBUG
// Enable built-in checks in queue.h in debug builds
#define INVARIANTS
#endif
#include "sys/queue.h"
#include "hal/touch_sensor_types.h"
#include "hal/touch_sensor_hal.h"
typedef struct {
TimerHandle_t timer;
uint16_t filtered_val[TOUCH_PAD_MAX];
uint16_t raw_val[TOUCH_PAD_MAX];
uint32_t filter_period;
uint32_t period;
bool enable;
} touch_pad_filter_t;
static touch_pad_filter_t *s_touch_pad_filter = NULL;
// check if touch pad be inited.
static uint16_t s_touch_pad_init_bit = 0x0000;
static filter_cb_t s_filter_cb = NULL;
static SemaphoreHandle_t rtc_touch_mux = NULL;
#define TOUCH_PAD_FILTER_FACTOR_DEFAULT (4) // IIR filter coefficient.
#define TOUCH_PAD_SHIFT_DEFAULT (4) // Increase computing accuracy.
#define TOUCH_PAD_SHIFT_ROUND_DEFAULT (8) // ROUND = 2^(n-1); rounding off for fractional.
static const char *TOUCH_TAG = "TOUCH_SENSOR";
#define TOUCH_CHECK(a, str, ret_val) ({ \
if (!(a)) { \
ESP_LOGE(TOUCH_TAG,"%s:%d (%s):%s", __FILE__, __LINE__, __FUNCTION__, str); \
return (ret_val); \
} \
})
#define TOUCH_CHANNEL_CHECK(channel) TOUCH_CHECK(channel < SOC_TOUCH_SENSOR_NUM, "Touch channel error", ESP_ERR_INVALID_ARG)
#define TOUCH_PARAM_CHECK_STR(s) ""s" parameter error"
extern portMUX_TYPE rtc_spinlock; //TODO: Will be placed in the appropriate position after the rtc module is finished.
#define TOUCH_ENTER_CRITICAL() portENTER_CRITICAL(&rtc_spinlock)
#define TOUCH_EXIT_CRITICAL() portEXIT_CRITICAL(&rtc_spinlock)
/*---------------------------------------------------------------
Touch Pad
---------------------------------------------------------------*/
//Some register bits of touch sensor 8 and 9 are mismatched, we need to swap the bits.
#define BITSWAP(data, n, m) (((data >> n) & 0x1) == ((data >> m) & 0x1) ? (data) : ((data) ^ ((0x1 <<n) | (0x1 << m))))
#define TOUCH_BITS_SWAP(v) BITSWAP(v, TOUCH_PAD_NUM8, TOUCH_PAD_NUM9)
static esp_err_t _touch_pad_read(touch_pad_t touch_num, uint16_t *touch_value, touch_fsm_mode_t mode);
esp_err_t touch_pad_isr_handler_register(void (*fn)(void *), void *arg, int no_use, intr_handle_t *handle_no_use)
{
TOUCH_CHECK(fn, "Touch_Pad ISR null", ESP_ERR_INVALID_ARG);
return rtc_isr_register(fn, arg, RTC_CNTL_TOUCH_INT_ST_M);
}
esp_err_t touch_pad_isr_register(intr_handler_t fn, void *arg)
{
TOUCH_CHECK(fn, "Touch_Pad ISR null", ESP_ERR_INVALID_ARG);
return rtc_isr_register(fn, arg, RTC_CNTL_TOUCH_INT_ST_M);
}
static uint32_t _touch_filter_iir(uint32_t in_now, uint32_t out_last, uint32_t k)
{
if (k == 0) {
return in_now;
} else {
uint32_t out_now = (in_now + (k - 1) * out_last) / k;
return out_now;
}
}
esp_err_t touch_pad_set_filter_read_cb(filter_cb_t read_cb)
{
s_filter_cb = read_cb;
return ESP_OK;
}
static void touch_pad_filter_cb(void *arg)
{
static uint32_t s_filtered_temp[TOUCH_PAD_MAX] = {0};
if (s_touch_pad_filter == NULL || rtc_touch_mux == NULL) {
return;
}
uint16_t val = 0;
touch_fsm_mode_t mode;
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
touch_pad_get_fsm_mode(&mode);
for (int i = 0; i < TOUCH_PAD_MAX; i++) {
if ((s_touch_pad_init_bit >> i) & 0x1) {
_touch_pad_read(i, &val, mode);
s_touch_pad_filter->raw_val[i] = val;
s_filtered_temp[i] = s_filtered_temp[i] == 0 ? ((uint32_t)val << TOUCH_PAD_SHIFT_DEFAULT) : s_filtered_temp[i];
s_filtered_temp[i] = _touch_filter_iir((val << TOUCH_PAD_SHIFT_DEFAULT),
s_filtered_temp[i], TOUCH_PAD_FILTER_FACTOR_DEFAULT);
s_touch_pad_filter->filtered_val[i] = (s_filtered_temp[i] + TOUCH_PAD_SHIFT_ROUND_DEFAULT) >> TOUCH_PAD_SHIFT_DEFAULT;
}
}
xTimerReset(s_touch_pad_filter->timer, portMAX_DELAY);
xSemaphoreGive(rtc_touch_mux);
if (s_filter_cb != NULL) {
//return the raw data and filtered data.
s_filter_cb(s_touch_pad_filter->raw_val, s_touch_pad_filter->filtered_val);
}
}
esp_err_t touch_pad_set_meas_time(uint16_t sleep_cycle, uint16_t meas_cycle)
{
TOUCH_ENTER_CRITICAL();
touch_hal_set_meas_time(meas_cycle);
touch_hal_set_sleep_time(sleep_cycle);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_meas_time(uint16_t *sleep_cycle, uint16_t *meas_cycle)
{
TOUCH_ENTER_CRITICAL();
touch_hal_get_meas_time(meas_cycle);
touch_hal_get_sleep_time(sleep_cycle);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_set_trigger_mode(touch_trigger_mode_t mode)
{
TOUCH_CHECK((mode < TOUCH_TRIGGER_MAX), TOUCH_PARAM_CHECK_STR("mode"), ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_set_trigger_mode(mode);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_trigger_mode(touch_trigger_mode_t *mode)
{
touch_hal_get_trigger_mode(mode);
return ESP_OK;
}
esp_err_t touch_pad_set_trigger_source(touch_trigger_src_t src)
{
TOUCH_CHECK((src < TOUCH_TRIGGER_SOURCE_MAX), TOUCH_PARAM_CHECK_STR("src"), ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_set_trigger_source(src);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_trigger_source(touch_trigger_src_t *src)
{
touch_hal_get_trigger_source(src);
return ESP_OK;
}
esp_err_t touch_pad_set_group_mask(uint16_t set1_mask, uint16_t set2_mask, uint16_t en_mask)
{
TOUCH_CHECK((set1_mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch set1 bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((set2_mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch set2 bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((en_mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch work_en bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_set_group_mask(set1_mask, set2_mask);
touch_hal_set_channel_mask(en_mask);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_group_mask(uint16_t *set1_mask, uint16_t *set2_mask, uint16_t *en_mask)
{
TOUCH_ENTER_CRITICAL();
touch_hal_get_channel_mask(en_mask);
touch_hal_get_group_mask(set1_mask, set2_mask);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_clear_group_mask(uint16_t set1_mask, uint16_t set2_mask, uint16_t en_mask)
{
TOUCH_CHECK((set1_mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch set1 bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((set2_mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch set2 bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK((en_mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch work_en bitmask error", ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_clear_channel_mask(en_mask);
touch_hal_clear_group_mask(set1_mask, set2_mask);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_intr_enable(void)
{
TOUCH_ENTER_CRITICAL();
touch_hal_enable_interrupt();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_intr_disable(void)
{
TOUCH_ENTER_CRITICAL();
touch_hal_disable_interrupt();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_config(touch_pad_t touch_num, uint16_t threshold)
{
TOUCH_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_FAIL);
TOUCH_CHANNEL_CHECK(touch_num);
touch_fsm_mode_t mode;
touch_pad_io_init(touch_num);
TOUCH_ENTER_CRITICAL();
touch_hal_config(touch_num);
touch_hal_set_threshold(touch_num, threshold);
TOUCH_EXIT_CRITICAL();
touch_pad_get_fsm_mode(&mode);
if (TOUCH_FSM_MODE_SW == mode) {
touch_pad_clear_group_mask((1 << touch_num), (1 << touch_num), (1 << touch_num));
s_touch_pad_init_bit |= (1 << touch_num);
} else if (TOUCH_FSM_MODE_TIMER == mode) {
uint16_t sleep_time = 0;
uint16_t meas_cycle = 0;
uint32_t wait_time_ms = 0;
uint32_t wait_tick = 0;
uint32_t rtc_clk = rtc_clk_slow_freq_get_hz();
touch_pad_set_group_mask((1 << touch_num), (1 << touch_num), (1 << touch_num));
touch_pad_get_meas_time(&sleep_time, &meas_cycle);
//If the FSM mode is 'TOUCH_FSM_MODE_TIMER', The data will be ready after one measurement cycle
//after this function is executed, otherwise, the "touch_value" by "touch_pad_read" is 0.
wait_time_ms = sleep_time / (rtc_clk / 1000) + meas_cycle / (RTC_FAST_CLK_FREQ_APPROX / 1000);
wait_tick = wait_time_ms / portTICK_RATE_MS;
vTaskDelay(wait_tick ? wait_tick : 1);
s_touch_pad_init_bit |= (1 << touch_num);
} else {
return ESP_FAIL;
}
return ESP_OK;
}
esp_err_t touch_pad_init(void)
{
if (rtc_touch_mux == NULL) {
rtc_touch_mux = xSemaphoreCreateMutex();
}
if (rtc_touch_mux == NULL) {
return ESP_FAIL;
}
TOUCH_ENTER_CRITICAL();
touch_hal_init();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_deinit(void)
{
TOUCH_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_FAIL);
if (s_touch_pad_filter != NULL) {
touch_pad_filter_stop();
touch_pad_filter_delete();
}
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
s_touch_pad_init_bit = 0x0000;
TOUCH_ENTER_CRITICAL();
touch_hal_deinit();
TOUCH_EXIT_CRITICAL();
xSemaphoreGive(rtc_touch_mux);
vSemaphoreDelete(rtc_touch_mux);
rtc_touch_mux = NULL;
return ESP_OK;
}
static esp_err_t _touch_pad_read(touch_pad_t touch_num, uint16_t *touch_value, touch_fsm_mode_t mode)
{
esp_err_t res = ESP_OK;
if (TOUCH_FSM_MODE_SW == mode) {
touch_pad_set_group_mask((1 << touch_num), (1 << touch_num), (1 << touch_num));
touch_pad_sw_start();
while (!touch_hal_meas_is_done()) {};
*touch_value = touch_hal_read_raw_data(touch_num);
touch_pad_clear_group_mask((1 << touch_num), (1 << touch_num), (1 << touch_num));
} else if (TOUCH_FSM_MODE_TIMER == mode) {
while (!touch_hal_meas_is_done()) {};
*touch_value = touch_hal_read_raw_data(touch_num);
} else {
res = ESP_FAIL;
}
if (*touch_value == 0) {
res = ESP_ERR_INVALID_STATE;
}
return res;
}
esp_err_t touch_pad_read(touch_pad_t touch_num, uint16_t *touch_value)
{
TOUCH_CHANNEL_CHECK(touch_num);
TOUCH_CHECK(touch_value != NULL, "touch_value", ESP_ERR_INVALID_ARG);
TOUCH_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_FAIL);
esp_err_t res = ESP_OK;
touch_fsm_mode_t mode;
touch_pad_get_fsm_mode(&mode);
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
res = _touch_pad_read(touch_num, touch_value, mode);
xSemaphoreGive(rtc_touch_mux);
return res;
}
IRAM_ATTR esp_err_t touch_pad_read_raw_data(touch_pad_t touch_num, uint16_t *touch_value)
{
TOUCH_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_FAIL);
TOUCH_CHANNEL_CHECK(touch_num);
TOUCH_CHECK(touch_value != NULL, "touch_value", ESP_ERR_INVALID_ARG);
TOUCH_CHECK(s_touch_pad_filter != NULL, "Touch pad filter not initialized", ESP_FAIL);
*touch_value = s_touch_pad_filter->raw_val[touch_num];
if (*touch_value == 0) {
return ESP_ERR_INVALID_STATE;
}
return ESP_OK;
}
IRAM_ATTR esp_err_t touch_pad_read_filtered(touch_pad_t touch_num, uint16_t *touch_value)
{
TOUCH_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_FAIL);
TOUCH_CHANNEL_CHECK(touch_num);
TOUCH_CHECK(touch_value != NULL, "touch_value", ESP_ERR_INVALID_ARG);
TOUCH_CHECK(s_touch_pad_filter != NULL, "Touch pad filter not initialized", ESP_FAIL);
*touch_value = (s_touch_pad_filter->filtered_val[touch_num]);
if (*touch_value == 0) {
return ESP_ERR_INVALID_STATE;
}
return ESP_OK;
}
esp_err_t touch_pad_set_filter_period(uint32_t new_period_ms)
{
TOUCH_CHECK(s_touch_pad_filter != NULL, "Touch pad filter not initialized", ESP_ERR_INVALID_STATE);
TOUCH_CHECK(new_period_ms > 0, "Touch pad filter period error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_ERR_INVALID_STATE);
esp_err_t ret = ESP_OK;
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
if (s_touch_pad_filter != NULL) {
xTimerChangePeriod(s_touch_pad_filter->timer, new_period_ms / portTICK_PERIOD_MS, portMAX_DELAY);
s_touch_pad_filter->period = new_period_ms;
} else {
ESP_LOGE(TOUCH_TAG, "Touch pad filter deleted");
ret = ESP_ERR_INVALID_STATE;
}
xSemaphoreGive(rtc_touch_mux);
return ret;
}
esp_err_t touch_pad_get_filter_period(uint32_t *p_period_ms)
{
TOUCH_CHECK(s_touch_pad_filter != NULL, "Touch pad filter not initialized", ESP_ERR_INVALID_STATE);
TOUCH_CHECK(p_period_ms != NULL, "Touch pad period pointer error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_ERR_INVALID_STATE);
esp_err_t ret = ESP_OK;
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
if (s_touch_pad_filter != NULL) {
*p_period_ms = s_touch_pad_filter->period;
} else {
ESP_LOGE(TOUCH_TAG, "Touch pad filter deleted");
ret = ESP_ERR_INVALID_STATE;
}
xSemaphoreGive(rtc_touch_mux);
return ret;
}
esp_err_t touch_pad_filter_start(uint32_t filter_period_ms)
{
TOUCH_CHECK(filter_period_ms >= portTICK_PERIOD_MS, "Touch pad filter period error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_ERR_INVALID_STATE);
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
if (s_touch_pad_filter == NULL) {
s_touch_pad_filter = (touch_pad_filter_t *) calloc(1, sizeof(touch_pad_filter_t));
if (s_touch_pad_filter == NULL) {
goto err_no_mem;
}
}
if (s_touch_pad_filter->timer == NULL) {
s_touch_pad_filter->timer = xTimerCreate("filter_tmr", filter_period_ms / portTICK_PERIOD_MS, pdFALSE,
NULL, touch_pad_filter_cb);
if (s_touch_pad_filter->timer == NULL) {
free(s_touch_pad_filter);
s_touch_pad_filter = NULL;
goto err_no_mem;
}
s_touch_pad_filter->period = filter_period_ms;
}
xSemaphoreGive(rtc_touch_mux);
touch_pad_filter_cb(NULL);
return ESP_OK;
err_no_mem:
xSemaphoreGive(rtc_touch_mux);
return ESP_ERR_NO_MEM;
}
esp_err_t touch_pad_filter_stop(void)
{
TOUCH_CHECK(s_touch_pad_filter != NULL, "Touch pad filter not initialized", ESP_ERR_INVALID_STATE);
TOUCH_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_ERR_INVALID_STATE);
esp_err_t ret = ESP_OK;
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
if (s_touch_pad_filter != NULL) {
xTimerStop(s_touch_pad_filter->timer, portMAX_DELAY);
} else {
ESP_LOGE(TOUCH_TAG, "Touch pad filter deleted");
ret = ESP_ERR_INVALID_STATE;
}
xSemaphoreGive(rtc_touch_mux);
return ret;
}
esp_err_t touch_pad_filter_delete(void)
{
TOUCH_CHECK(s_touch_pad_filter != NULL, "Touch pad filter not initialized", ESP_ERR_INVALID_STATE);
TOUCH_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_ERR_INVALID_STATE);
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
if (s_touch_pad_filter != NULL) {
if (s_touch_pad_filter->timer != NULL) {
xTimerStop(s_touch_pad_filter->timer, portMAX_DELAY);
xTimerDelete(s_touch_pad_filter->timer, portMAX_DELAY);
s_touch_pad_filter->timer = NULL;
}
free(s_touch_pad_filter);
s_touch_pad_filter = NULL;
}
xSemaphoreGive(rtc_touch_mux);
return ESP_OK;
}

View file

@ -0,0 +1,465 @@
// Copyright 2019 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.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Set touch sensor FSM start
* @note Start FSM after the touch sensor FSM mode is set.
* @note Call this function will reset beseline of all touch channels.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_fsm_start(void);
/**
* @brief Stop touch sensor FSM.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_fsm_stop(void);
/**
* @brief Trigger a touch sensor measurement, only support in SW mode of FSM
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_sw_start(void);
/**
* @brief Set touch sensor times of charge and discharge and sleep time.
* Excessive total time will slow down the touch response.
* Too small measurement time will not be sampled enough, resulting in inaccurate measurements.
*
* @note The greater the duty cycle of the measurement time, the more system power is consumed.
* @param sleep_cycle The touch sensor will sleep after each measurement.
* sleep_cycle decide the interval between each measurement.
* t_sleep = sleep_cycle / (RTC_SLOW_CLK frequency).
* The approximate frequency value of RTC_SLOW_CLK can be obtained using rtc_clk_slow_freq_get_hz function.
* @param meas_timers The times of charge and discharge in each measure process of touch channels.
* The timer frequency is 8Mhz. Range: 0 ~ 0xffff.
* Recommended typical value: Modify this value to make the measurement time around 1ms.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_set_meas_time(uint16_t sleep_cycle, uint16_t meas_times);
/**
* @brief Get touch sensor times of charge and discharge and sleep time
* @param sleep_cycle Pointer to accept sleep cycle number
* @param meas_times Pointer to accept measurement times count.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_meas_time(uint16_t *sleep_cycle, uint16_t *meas_times);
/**
* @brief Set connection type of touch channel in idle status.
* When a channel is in measurement mode, other initialized channels are in idle mode.
* The touch channel is generally adjacent to the trace, so the connection state of the idle channel
* affects the stability and sensitivity of the test channel.
* The `CONN_HIGHZ`(high resistance) setting increases the sensitivity of touch channels.
* The `CONN_GND`(grounding) setting increases the stability of touch channels.
* @param type Select idle channel connect to high resistance state or ground.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_set_inactive_connect(touch_pad_conn_type_t type);
/**
* @brief Set connection type of touch channel in idle status.
* When a channel is in measurement mode, other initialized channels are in idle mode.
* The touch channel is generally adjacent to the trace, so the connection state of the idle channel
* affects the stability and sensitivity of the test channel.
* The `CONN_HIGHZ`(high resistance) setting increases the sensitivity of touch channels.
* The `CONN_GND`(grounding) setting increases the stability of touch channels.
* @param type Pointer to connection type.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_inactive_connect(touch_pad_conn_type_t *type);
/**
* @brief Set the trigger threshold of touch sensor.
* The threshold determines the sensitivity of the touch sensor.
* The threshold is the original value of the trigger state minus the baseline value.
* @note If set "TOUCH_PAD_THRESHOLD_MAX", the touch is never be trigered.
* @param touch_num touch pad index
* @param threshold threshold of touch sensor. Should be less than the max change value of touch.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_set_thresh(touch_pad_t touch_num, uint32_t threshold);
/**
* @brief Get touch sensor trigger threshold
* @param touch_num touch pad index
* @param threshold pointer to accept threshold
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_get_thresh(touch_pad_t touch_num, uint32_t *threshold);
/**
* @brief Register touch channel into touch sensor scan group.
* The working mode of the touch sensor is cyclically scanned.
* This function will set the scan bits according to the given bitmask.
* @note If set this mask, the FSM timer should be stop firsty.
* @note The touch sensor that in scan map, should be deinit GPIO function firstly by `touch_pad_io_init`.
* @param enable_mask bitmask of touch sensor scan group.
* e.g. TOUCH_PAD_NUM14 -> BIT(14)
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_set_channel_mask(uint16_t enable_mask);
/**
* @brief Get the touch sensor scan group bit mask.
* @param enable_mask Pointer to bitmask of touch sensor scan group.
* e.g. TOUCH_PAD_NUM14 -> BIT(14)
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_channel_mask(uint16_t *enable_mask);
/**
* @brief Clear touch channel from touch sensor scan group.
* The working mode of the touch sensor is cyclically scanned.
* This function will clear the scan bits according to the given bitmask.
* @note If clear all mask, the FSM timer should be stop firsty.
* @param enable_mask bitmask of touch sensor scan group.
* e.g. TOUCH_PAD_NUM14 -> BIT(14)
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_clear_channel_mask(uint16_t enable_mask);
/**
* @brief Configure parameter for each touch channel.
* @note Touch num 0 is denoise channel, please use `touch_pad_denoise_enable` to set denoise function
* @param touch_num touch pad index
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG if argument wrong
* - ESP_FAIL if touch pad not initialized
*/
esp_err_t touch_pad_config(touch_pad_t touch_num);
/**
* @brief Reset the whole of touch module.
* @note Call this funtion after `touch_pad_fsm_stop`,
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_reset(void);
/**
* @brief Check touch sensor measurement status.
* If doing measurement, the flag will be clear.
* If finish measurement. the flag will be set.
* @return
* - TRUE finish measurement
* - FALSE doing measurement
*/
bool touch_pad_meas_is_done(void);
/**
* @brief Get the current measure channel.
* Touch sensor measurement is cyclic scan mode.
* @return
* - touch channel number
*/
touch_pad_t touch_pad_get_current_meas_channel(void);
/**
* @brief Get the touch sensor interrupt status mask.
* @return
* - touch intrrupt bit
*/
uint32_t touch_pad_read_intr_status_mask(void);
/**
* @brief Enable touch sensor interrupt by bitmask.
* @param type interrupt type
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_intr_enable(touch_pad_intr_mask_t int_mask);
/**
* @brief Disable touch sensor interrupt by bitmask.
* @param type interrupt type
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_intr_disable(touch_pad_intr_mask_t int_mask);
/**
* @brief Register touch-pad ISR.
* The handler will be attached to the same CPU core that this function is running on.
* @param fn Pointer to ISR handler
* @param arg Parameter for ISR
* @return
* - ESP_OK Success ;
* - ESP_ERR_INVALID_ARG GPIO error
* - ESP_ERR_NO_MEM No memory
*/
esp_err_t touch_pad_isr_register(intr_handler_t fn, void* arg, touch_pad_intr_mask_t intr_mask);
/**
* @brief get raw data of touch sensor.
* @note After the initialization is complete, the "raw_data" is max value. You need to wait for a measurement
* cycle before you can read the correct touch value.
* @param touch_num touch pad index
* @param raw_data pointer to accept touch sensor value
* @return
* - ESP_OK Success
* - ESP_FAIL Touch channel 0 havent this parameter.
*/
esp_err_t touch_pad_read_raw_data(touch_pad_t touch_num, uint32_t *raw_data);
/**
* @brief get baseline of touch sensor.
* @note After initialization, the baseline value is the maximum during the first measurement period.
* @param touch_num touch pad index
* @param touch_value pointer to accept touch sensor value
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG Touch channel 0 havent this parameter.
*/
esp_err_t touch_pad_filter_read_baseline(touch_pad_t touch_num, uint32_t *basedata);
/**
* @brief Force reset baseline to raw data of touch sensor.
* @param touch_num touch pad index
* - TOUCH_PAD_MAX Reset basaline of all channels
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_filter_reset_baseline(touch_pad_t touch_num);
/**
* @brief set parameter of touch sensor filter and detection algorithm.
* For more details on the detection algorithm, please refer to the application documentation.
* @param filter_info select filter type and threshold of detection algorithm
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_filter_set_config(touch_filter_config_t *filter_info);
/**
* @brief get parameter of touch sensor filter and detection algorithm.
* For more details on the detection algorithm, please refer to the application documentation.
* @param filter_info select filter type and threshold of detection algorithm
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_filter_get_config(touch_filter_config_t *filter_info);
/**
* @brief enable touch sensor filter for detection algorithm.
* For more details on the detection algorithm, please refer to the application documentation.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_filter_enable(void);
/**
* @brief diaable touch sensor filter for detection algorithm.
* For more details on the detection algorithm, please refer to the application documentation.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_filter_disable(void);
/**
* @brief set parameter of denoise pad (TOUCH_PAD_NUM0).
* T0 is an internal channel that does not have a corresponding external GPIO.
* T0 will work simultaneously with the measured channel Tn. Finally, the actual
* measured value of Tn is the value after subtracting lower bits of T0.
* This denoise function filters out interference introduced on all channels,
* such as noise introduced by the power supply and external EMI.
* @param denoise parameter of denoise
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_denoise_set_config(touch_pad_denoise_t *denoise);
/**
* @brief get parameter of denoise pad (TOUCH_PAD_NUM0).
* @param denoise Pointer to parameter of denoise
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_denoise_get_config(touch_pad_denoise_t *denoise);
/**
* @brief enable denoise function.
* T0 is an internal channel that does not have a corresponding external GPIO.
* T0 will work simultaneously with the measured channel Tn. Finally, the actual
* measured value of Tn is the value after subtracting lower bits of T0.
* This denoise function filters out interference introduced on all channels,
* such as noise introduced by the power supply and external EMI.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_denoise_enable(void);
/**
* @brief disable denoise function.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_denoise_disable(void);
/**
* @brief Get denoise measure value (TOUCH_PAD_NUM0).
* @param denoise value of denoise
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_denoise_read_data(uint32_t *data);
/**
* @brief set parameter of waterproof function.
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
* @param waterproof parameter of waterproof
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_waterproof_set_config(touch_pad_waterproof_t *waterproof);
/**
* @brief get parameter of waterproof function.
* @param waterproof parameter of waterproof
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_waterproof_get_config(touch_pad_waterproof_t *waterproof);
/**
* @brief Enable parameter of waterproof function.
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_waterproof_enable(void);
/**
* @brief Enable parameter of waterproof function.
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_waterproof_disable(void);
/**
* @brief Set parameter of proximity channel. Three proximity sensing channels can be set.
* The proximity sensor measurement is the accumulation of touch channel measurements.
* @note If stop the proximity function for the channel, point this proximity channel to `TOUCH_PAD_NUM0`.
* @param proximity parameter of proximity
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_proximity_set_config(touch_pad_proximity_t *proximity);
/**
* @brief Get parameter of proximity channel. Three proximity sensing channels can be set.
* The proximity sensor measurement is the accumulation of touch channel measurements.
* @param proximity parameter of proximity
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_proximity_get_config(touch_pad_proximity_t *proximity);
/**
* @brief Get measure count of proximity channel.
* The proximity sensor measurement is the accumulation of touch channel measurements.
* @param touch_num touch pad index
* @param proximity parameter of proximity
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG parameter is NULL
*/
esp_err_t touch_pad_proximity_read_meas_cnt(touch_pad_t touch_num, uint32_t *cnt);
/**
* @brief Get the accumulated measurement of the proximity sensor.
* The proximity sensor measurement is the accumulation of touch channel measurements.
* @param touch_num touch pad index
* @param measure_out If the accumulation process does not end, the `measure_out` is the process value.
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_proximity_data_get(touch_pad_t touch_num, uint32_t *measure_out);
/**
* @brief Set parameter of touch sensor in sleep mode.
* In order to achieve low power consumption in sleep mode, other circuits except the RTC part of the register are in a power-off state.
* Only one touch channel is supported in the sleep state, which can be used as a wake-up function.
* If in non-sleep mode, the sleep parameters do not work.
* @param slp_config touch pad config
* @return
* - ESP_OK Success
*/
esp_err_t touch_pad_sleep_channel_config(touch_pad_sleep_channel_t *slp_config);
/**
* @brief Read baseline of touch sensor in sleep mode.
* @param baseline pointer to accept touch sensor baseline value
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG parameter is NULL
*/
esp_err_t touch_pad_sleep_channel_read_baseline(uint32_t *baseline);
/**
* @brief Read debounce of touch sensor in sleep mode.
* @param debounce pointer to accept touch sensor debounce value
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG parameter is NULL
*/
esp_err_t touch_pad_sleep_channel_read_debounce(uint32_t *debounce);
/**
* @brief Read proximity count of touch sensor in sleep mode.
* @param proximity_cnt pointer to accept touch sensor proximity count value
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG parameter is NULL
*/
esp_err_t touch_pad_sleep_channel_read_proximity_cnt(uint32_t *proximity_cnt);
#ifdef __cplusplus
}
#endif

View file

@ -1,674 +0,0 @@
// Copyright 2016-2018 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.
#include <esp_types.h>
#include <stdlib.h>
#include <ctype.h>
#include "esp_log.h"
#include "soc/rtc_periph.h"
#include "soc/sens_periph.h"
#include "soc/rtc_io_reg.h"
#include "soc/rtc_io_struct.h"
#include "soc/sens_reg.h"
#include "soc/sens_struct.h"
#include "soc/rtc_cntl_reg.h"
#include "soc/rtc_cntl_struct.h"
#include "soc/rtc.h"
#include "soc/periph_defs.h"
#include "rtc_io.h"
#include "touch_pad.h"
#include "freertos/FreeRTOS.h"
#include "freertos/xtensa_api.h"
#include "freertos/semphr.h"
#include "freertos/timers.h"
#include "esp_intr_alloc.h"
#include "sys/lock.h"
#include "driver/rtc_cntl.h"
#include "driver/gpio.h"
#include "sdkconfig.h"
#include "esp32s2beta/rom/ets_sys.h"
#ifndef NDEBUG
// Enable built-in checks in queue.h in debug builds
#define INVARIANTS
#endif
#include "sys/queue.h"
#define TOUCH_PAD_FILTER_FACTOR_DEFAULT (4) // IIR filter coefficient.
#define TOUCH_PAD_SHIFT_DEFAULT (4) // Increase computing accuracy.
#define TOUCH_PAD_SHIFT_ROUND_DEFAULT (8) // ROUND = 2^(n-1); rounding off for fractional.
#define TOUCH_PAD_MEASURE_WAIT_DEFAULT (0xFF) // The timer frequency is 8Mhz, the max value is 0xff
#define DAC_ERR_STR_CHANNEL_ERROR "DAC channel error"
#define RTC_MODULE_CHECK(a, str, ret_val) ({ \
if (!(a)) { \
ESP_LOGE(RTC_MODULE_TAG,"%s:%d (%s):%s", __FILE__, __LINE__, __FUNCTION__, str); \
return (ret_val); \
} \
})
#define RTC_RES_CHECK(res, ret_val) ({ \
if ( (res) != ESP_OK) { \
ESP_LOGE(RTC_MODULE_TAG,"%s:%d (%s)", __FILE__, __LINE__, __FUNCTION__);\
return (ret_val); \
} \
})
static portMUX_TYPE rtc_spinlock = portMUX_INITIALIZER_UNLOCKED;
#define RTC_TOUCH_ENTER_CRITICAL() portENTER_CRITICAL(&rtc_spinlock)
#define RTC_TOUCH_EXIT_CRITICAL() portEXIT_CRITICAL(&rtc_spinlock)
static SemaphoreHandle_t rtc_touch_mux = NULL;
static const char *RTC_MODULE_TAG = "RTC_MODULE";
/*---------------------------------------------------------------
Touch Pad
---------------------------------------------------------------*/
esp_err_t touch_pad_isr_register(intr_handler_t fn, void *arg, touch_pad_intr_mask_t intr_mask)
{
assert(fn != NULL);
return rtc_isr_register(fn, arg, TOUCH_PAD_INTR_MASK_ALL & (intr_mask << RTC_CNTL_TOUCH_DONE_INT_ENA_S));
}
esp_err_t touch_pad_isr_deregister(intr_handler_t fn, void *arg)
{
return rtc_isr_deregister(fn, arg);
}
esp_err_t touch_pad_set_meas_time(uint16_t sleep_cycle, uint16_t meas_times)
{
RTC_TOUCH_ENTER_CRITICAL();
// touch sensor sleep cycle Time = sleep_cycle / RTC_SLOW_CLK( can be 150k or 32k depending on the options)
RTCCNTL.touch_ctrl1.touch_sleep_cycles = sleep_cycle;
//The times of charge and discharge in each measure process of touch channels.
RTCCNTL.touch_ctrl1.touch_meas_num = meas_times;
//the waiting cycles (in 8MHz) between TOUCH_START and TOUCH_XPD
RTCCNTL.touch_ctrl2.touch_xpd_wait = TOUCH_PAD_MEASURE_WAIT_DEFAULT; //wait volt stable
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_meas_time(uint16_t *sleep_cycle, uint16_t *meas_times)
{
if (sleep_cycle) {
*sleep_cycle = RTCCNTL.touch_ctrl1.touch_sleep_cycles;
}
if (meas_times) {
*meas_times = RTCCNTL.touch_ctrl1.touch_meas_num;
}
return ESP_OK;
}
esp_err_t touch_pad_set_inactive_connect(touch_pad_conn_type_t type)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_inactive_connection = type;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_inactive_connect(touch_pad_conn_type_t *type)
{
RTC_MODULE_CHECK(type != NULL, "parameter is NULL", ESP_ERR_INVALID_ARG);
*type = RTCCNTL.touch_scan_ctrl.touch_inactive_connection;
return ESP_OK;
}
esp_err_t touch_pad_set_voltage(touch_high_volt_t refh, touch_low_volt_t refl, touch_volt_atten_t atten)
{
RTC_TOUCH_ENTER_CRITICAL();
if (refh > TOUCH_HVOLT_KEEP) {
RTCCNTL.touch_ctrl2.touch_drefh = refh;
}
if (refl > TOUCH_LVOLT_KEEP) {
RTCCNTL.touch_ctrl2.touch_drefl = refl;
}
if (atten > TOUCH_HVOLT_ATTEN_KEEP) {
RTCCNTL.touch_ctrl2.touch_drange = atten;
}
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_voltage(touch_high_volt_t *refh, touch_low_volt_t *refl, touch_volt_atten_t *atten)
{
if (refh) {
*refh = RTCCNTL.touch_ctrl2.touch_drefh;
}
if (refl) {
*refl = RTCCNTL.touch_ctrl2.touch_drefl;
}
if (atten) {
*atten = RTCCNTL.touch_ctrl2.touch_drange;
}
return ESP_OK;
}
esp_err_t touch_pad_set_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t slope, touch_tie_opt_t opt)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCIO.touch_pad[touch_num].tie_opt = opt;
RTCIO.touch_pad[touch_num].dac = slope;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t *slope, touch_tie_opt_t *opt)
{
if (slope) {
*slope = RTCIO.touch_pad[touch_num].dac;
}
if (opt) {
*opt = RTCIO.touch_pad[touch_num].tie_opt;
}
return ESP_OK;
}
esp_err_t touch_pad_io_init(touch_pad_t touch_num)
{
RTC_MODULE_CHECK(touch_num != TOUCH_DENOISE_CHANNEL,
"please use `touch_pad_denoise_enable` to set denoise channel", ESP_ERR_INVALID_ARG);
rtc_gpio_init(touch_num);
rtc_gpio_set_direction(touch_num, RTC_GPIO_MODE_DISABLED);
rtc_gpio_pulldown_dis(touch_num);
rtc_gpio_pullup_dis(touch_num);
return ESP_OK;
}
esp_err_t touch_pad_wait_init_done(void)
{
// TODO
return ESP_FAIL;
}
esp_err_t touch_pad_fsm_start(void)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_ctrl2.touch_clkgate_en = 1; //enable touch clock for FSM. or force enable.
SENS.sar_touch_chn_st.touch_channel_clr = TOUCH_PAD_BIT_MASK_MAX; // clear SENS_TOUCH_SLP_BASELINE
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_fsm_stop(void)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_ctrl2.touch_start_en = 0; //stop touch fsm
RTCCNTL.touch_ctrl2.touch_slp_timer_en = 0;
RTCCNTL.touch_ctrl2.touch_clkgate_en = 0; //enable touch clock for FSM. or force enable.
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_set_fsm_mode(touch_fsm_mode_t mode)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_ctrl2.touch_start_en = 0; //stop touch fsm
RTCCNTL.touch_ctrl2.touch_start_force = mode;
RTCCNTL.touch_ctrl2.touch_slp_timer_en = (mode == TOUCH_FSM_MODE_TIMER ? 1 : 0);
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_fsm_mode(touch_fsm_mode_t *mode)
{
assert(mode != NULL);
*mode = RTCCNTL.touch_ctrl2.touch_start_force;
return ESP_OK;
}
bool touch_pad_meas_is_done(void)
{
return SENS.sar_touch_chn_st.touch_meas_done;
}
esp_err_t touch_pad_sw_start(void)
{
RTC_MODULE_CHECK((RTCCNTL.touch_ctrl2.touch_start_force == TOUCH_FSM_MODE_SW),
"touch fsm mode error", ESP_ERR_INVALID_STATE);
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_ctrl2.touch_start_en = 0;
RTCCNTL.touch_ctrl2.touch_start_en = 1;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_set_thresh(touch_pad_t touch_num, uint32_t threshold)
{
RTC_MODULE_CHECK((touch_num < TOUCH_PAD_MAX) && (touch_num != TOUCH_DENOISE_CHANNEL), "touch num error", ESP_ERR_INVALID_ARG);
RTC_TOUCH_ENTER_CRITICAL();
SENS.touch_thresh[touch_num - 1].thresh = threshold;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_thresh(touch_pad_t touch_num, uint32_t *threshold)
{
if (threshold) {
*threshold = SENS.touch_thresh[touch_num - 1].thresh;
}
return ESP_OK;
}
esp_err_t touch_pad_set_group_mask(uint16_t enable_mask)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map |= (enable_mask & TOUCH_PAD_BIT_MASK_MAX);
SENS.sar_touch_conf.touch_outen |= (enable_mask & TOUCH_PAD_BIT_MASK_MAX);
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_group_mask(uint16_t *enable_mask)
{
RTC_TOUCH_ENTER_CRITICAL();
*enable_mask = SENS.sar_touch_conf.touch_outen \
& RTCCNTL.touch_scan_ctrl.touch_scan_pad_map \
& TOUCH_PAD_BIT_MASK_MAX;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_clear_group_mask(uint16_t enable_mask)
{
RTC_TOUCH_ENTER_CRITICAL();
SENS.sar_touch_conf.touch_outen &= ~(enable_mask & TOUCH_PAD_BIT_MASK_MAX);
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map &= ~(enable_mask & TOUCH_PAD_BIT_MASK_MAX);
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
uint32_t IRAM_ATTR touch_pad_get_status(void)
{
return (SENS.sar_touch_chn_st.touch_pad_active & TOUCH_PAD_BIT_MASK_MAX);
}
static esp_err_t touch_pad_clear_status(void)
{
SENS.sar_touch_conf.touch_status_clr = 1;
return ESP_OK;
}
touch_pad_t IRAM_ATTR touch_pad_get_scan_curr(void)
{
return (touch_pad_t)(SENS.sar_touch_status0.touch_scan_curr);
}
esp_err_t touch_pad_intr_enable(touch_pad_intr_mask_t int_mask)
{
RTC_TOUCH_ENTER_CRITICAL();
if (int_mask & TOUCH_PAD_INTR_MASK_DONE) {
RTCCNTL.int_ena.rtc_touch_done = 1;
}
if (int_mask & TOUCH_PAD_INTR_MASK_ACTIVE) {
RTCCNTL.int_ena.rtc_touch_active = 1;
}
if (int_mask & TOUCH_PAD_INTR_MASK_INACTIVE) {
RTCCNTL.int_ena.rtc_touch_inactive = 1;
}
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_intr_disable(touch_pad_intr_mask_t int_mask)
{
RTC_TOUCH_ENTER_CRITICAL();
if (int_mask & TOUCH_PAD_INTR_MASK_DONE) {
RTCCNTL.int_ena.rtc_touch_done = 0;
}
if (int_mask & TOUCH_PAD_INTR_MASK_ACTIVE) {
RTCCNTL.int_ena.rtc_touch_active = 0;
}
if (int_mask & TOUCH_PAD_INTR_MASK_INACTIVE) {
RTCCNTL.int_ena.rtc_touch_inactive = 0;
}
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
uint32_t touch_pad_intr_status_get_mask(void)
{
return ((REG_READ(RTC_CNTL_INT_ST_REG) >> (RTC_CNTL_TOUCH_DONE_INT_ST_S)) & TOUCH_PAD_INTR_MASK_ALL);
}
esp_err_t touch_pad_config(touch_pad_t touch_num)
{
RTC_MODULE_CHECK(touch_num != TOUCH_DENOISE_CHANNEL, \
"please use `touch_pad_denoise_enable` to set denoise channel", ESP_ERR_INVALID_ARG);
touch_pad_io_init(touch_num);
touch_pad_set_cnt_mode(touch_num, TOUCH_PAD_SLOPE_7, TOUCH_PAD_TIE_OPT_LOW);
touch_pad_set_thresh(touch_num, TOUCH_PAD_THRESHOLD_MAX);
touch_pad_set_group_mask(BIT(touch_num));
return ESP_OK;
}
esp_err_t touch_pad_init(void)
{
if (rtc_touch_mux == NULL) {
rtc_touch_mux = xSemaphoreCreateMutex();
}
if (rtc_touch_mux == NULL) {
return ESP_ERR_NO_MEM;
}
touch_pad_intr_disable(TOUCH_PAD_INTR_ALL);
touch_pad_clear_group_mask(TOUCH_PAD_BIT_MASK_MAX);
touch_pad_clear_status();
touch_pad_set_meas_time(TOUCH_PAD_SLEEP_CYCLE_DEFAULT, TOUCH_PAD_MEASURE_CYCLE_DEFAULT);
// Set reference voltage for charging/discharging
touch_pad_set_voltage(TOUCH_HVOLT_2V7, TOUCH_LVOLT_0V5, TOUCH_HVOLT_ATTEN_0V5);
touch_pad_set_inactive_connect(TOUCH_PAD_CONN_GND);
return ESP_OK;
}
esp_err_t touch_pad_deinit(void)
{
RTC_MODULE_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_FAIL);
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
touch_pad_fsm_stop();
touch_pad_clear_status();
touch_pad_intr_disable(TOUCH_PAD_INTR_ALL);
xSemaphoreGive(rtc_touch_mux);
vSemaphoreDelete(rtc_touch_mux);
rtc_touch_mux = NULL;
return ESP_OK;
}
esp_err_t IRAM_ATTR touch_pad_read_raw_data(touch_pad_t touch_num, uint32_t *raw_data)
{
if (raw_data) {
*raw_data = SENS.touch_meas[touch_num].meas_out;
}
return ESP_OK;
}
esp_err_t IRAM_ATTR touch_pad_filter_baseline_read(touch_pad_t touch_num, uint32_t *basedata)
{
RTC_MODULE_CHECK(touch_num != TOUCH_DENOISE_CHANNEL, "denoise channel don't support", ESP_ERR_INVALID_ARG);
if (basedata) {
*basedata = SENS.sar_touch_status[touch_num - 1].touch_pad_baseline;
}
return ESP_OK;
}
esp_err_t touch_pad_filter_debounce_read(touch_pad_t touch_num, uint32_t *debounce)
{
RTC_MODULE_CHECK(touch_num != TOUCH_DENOISE_CHANNEL, "denoise channel don't support", ESP_ERR_INVALID_ARG);
if (debounce) {
*debounce = SENS.sar_touch_status[touch_num - 1].touch_pad_debounce;
}
return ESP_OK;
}
/* Should be call after clk enable and filter enable. */
esp_err_t touch_pad_filter_baseline_reset(touch_pad_t touch_num)
{
RTC_TOUCH_ENTER_CRITICAL();
if (touch_num == TOUCH_PAD_MAX) {
SENS.sar_touch_chn_st.touch_channel_clr = TOUCH_PAD_BIT_MASK_MAX;
} else {
SENS.sar_touch_chn_st.touch_channel_clr = BIT(touch_num);
}
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_filter_set_config(touch_filter_config_t *filter_info)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_filter_ctrl.touch_filter_mode = filter_info->mode;
RTCCNTL.touch_filter_ctrl.touch_debounce = filter_info->debounce_cnt;
RTCCNTL.touch_filter_ctrl.touch_hysteresis = filter_info->hysteresis_thr;
RTCCNTL.touch_filter_ctrl.touch_noise_thres = filter_info->noise_thr;
RTCCNTL.touch_filter_ctrl.touch_neg_noise_thres = filter_info->noise_neg_thr;
RTCCNTL.touch_filter_ctrl.touch_neg_noise_limit = filter_info->neg_noise_limit;
RTCCNTL.touch_filter_ctrl.touch_jitter_step = filter_info->jitter_step;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_filter_get_config(touch_filter_config_t *filter_info)
{
RTC_TOUCH_ENTER_CRITICAL();
filter_info->mode = RTCCNTL.touch_filter_ctrl.touch_filter_mode;
filter_info->debounce_cnt = RTCCNTL.touch_filter_ctrl.touch_debounce;
filter_info->hysteresis_thr = RTCCNTL.touch_filter_ctrl.touch_hysteresis;
filter_info->noise_thr = RTCCNTL.touch_filter_ctrl.touch_noise_thres;
filter_info->noise_neg_thr = RTCCNTL.touch_filter_ctrl.touch_neg_noise_thres;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_filter_enable(void)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_filter_ctrl.touch_filter_en = 1;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_filter_disable(void)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_filter_ctrl.touch_filter_en = 0;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_enable(void)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map &= ~(BIT(TOUCH_DENOISE_CHANNEL));
RTCCNTL.touch_scan_ctrl.touch_denoise_en = 1;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_disable(void)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_denoise_en = 0;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_set_config(touch_pad_denoise_t denoise)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCIO.touch_pad[TOUCH_DENOISE_CHANNEL].tie_opt = TOUCH_PAD_TIE_OPT_LOW;
RTCIO.touch_pad[TOUCH_DENOISE_CHANNEL].dac = TOUCH_PAD_SLOPE_7;
RTCCNTL.touch_ctrl2.touch_refc = denoise.cap_level;
RTCCNTL.touch_scan_ctrl.touch_denoise_res = denoise.grade;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_get_config(touch_pad_denoise_t *denoise)
{
RTC_TOUCH_ENTER_CRITICAL();
denoise->grade = RTCCNTL.touch_scan_ctrl.touch_denoise_res;
denoise->cap_level = RTCCNTL.touch_ctrl2.touch_refc;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_data_get(uint32_t *data)
{
if (data) {
*data = SENS.sar_touch_status0.touch_denoise_data;
}
return ESP_OK;
}
esp_err_t touch_pad_waterproof_set_config(touch_pad_waterproof_t waterproof)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_out_ring = waterproof.guard_ring_pad;
RTCCNTL.touch_scan_ctrl.touch_bufdrv = waterproof.shield_driver;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_waterproof_get_config(touch_pad_waterproof_t *waterproof)
{
if (waterproof) {
RTC_TOUCH_ENTER_CRITICAL();
waterproof->guard_ring_pad = RTCCNTL.touch_scan_ctrl.touch_out_ring;
waterproof->shield_driver = RTCCNTL.touch_scan_ctrl.touch_bufdrv;
RTC_TOUCH_EXIT_CRITICAL();
}
return ESP_OK;
}
esp_err_t touch_pad_waterproof_enable(void)
{
touch_pad_io_init(TOUCH_SHIELD_CHANNEL);
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_scan_pad_map &= ~(BIT(TOUCH_SHIELD_CHANNEL));
RTCCNTL.touch_scan_ctrl.touch_shield_pad_en = 1;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_waterproof_disable(void)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_scan_ctrl.touch_shield_pad_en = 0;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_proximity_set_config(touch_pad_proximity_t proximity)
{
RTC_TOUCH_ENTER_CRITICAL();
if (proximity.select_pad0) {
SENS.sar_touch_conf.touch_approach_pad0 = proximity.select_pad0;
}
if (proximity.select_pad1) {
SENS.sar_touch_conf.touch_approach_pad1 = proximity.select_pad1;
}
if (proximity.select_pad2) {
SENS.sar_touch_conf.touch_approach_pad2 = proximity.select_pad2;
}
RTCCNTL.touch_approach.touch_approach_meas_time = proximity.meas_num;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_proximity_get_config(touch_pad_proximity_t *proximity)
{
if (proximity) {
RTC_TOUCH_ENTER_CRITICAL();
proximity->select_pad0 = SENS.sar_touch_conf.touch_approach_pad0;
proximity->select_pad1 = SENS.sar_touch_conf.touch_approach_pad1;
proximity->select_pad2 = SENS.sar_touch_conf.touch_approach_pad2;
proximity->meas_num = RTCCNTL.touch_approach.touch_approach_meas_time;
RTC_TOUCH_EXIT_CRITICAL();
} else {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
esp_err_t touch_pad_proximity_get_meas_cnt(touch_pad_t touch_num, uint32_t *cnt)
{
if (cnt == NULL) {
return ESP_ERR_INVALID_ARG;
}
if (SENS.sar_touch_conf.touch_approach_pad0 == touch_num) {
*cnt = SENS.sar_touch_appr_status.touch_approach_pad0_cnt;
} else if (SENS.sar_touch_conf.touch_approach_pad1 == touch_num) {
*cnt = SENS.sar_touch_appr_status.touch_approach_pad1_cnt;
} else if (SENS.sar_touch_conf.touch_approach_pad2 == touch_num) {
*cnt = SENS.sar_touch_appr_status.touch_approach_pad2_cnt;
} else {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
esp_err_t touch_pad_proximity_data_get(touch_pad_t touch_num, uint32_t *measure_out)
{
if ((SENS.sar_touch_conf.touch_approach_pad0 != touch_num)
&& (SENS.sar_touch_conf.touch_approach_pad1 != touch_num)
&& (SENS.sar_touch_conf.touch_approach_pad2 != touch_num)) {
return ESP_ERR_INVALID_ARG;
}
if (ESP_OK != touch_pad_filter_baseline_read(touch_num, measure_out)) {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
esp_err_t touch_pad_reset()
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_ctrl2.touch_reset = 0;
RTCCNTL.touch_ctrl2.touch_reset = 1;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
/************** sleep pad setting ***********************/
esp_err_t touch_pad_sleep_channel_config(touch_pad_sleep_channel_t slp_config)
{
RTC_TOUCH_ENTER_CRITICAL();
RTCCNTL.touch_slp_thres.touch_slp_pad = slp_config.touch_num;
RTCCNTL.touch_slp_thres.touch_slp_th = slp_config.sleep_pad_threshold;
RTCCNTL.touch_slp_thres.touch_slp_approach_en = slp_config.en_proximity;
RTC_TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_sleep_channel_baseline_get(uint32_t *baseline)
{
if (baseline) {
*baseline = REG_GET_FIELD(SENS_SAR_TOUCH_SLP_STATUS_REG, SENS_TOUCH_SLP_BASELINE);
} else {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
esp_err_t touch_pad_sleep_channel_debounce_get(uint32_t *debounce)
{
if (debounce) {
*debounce = REG_GET_FIELD(SENS_SAR_TOUCH_SLP_STATUS_REG, SENS_TOUCH_SLP_DEBOUNCE);
} else {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
esp_err_t touch_pad_sleep_channel_proximity_cnt_get(uint32_t *approach_cnt)
{
if (approach_cnt) {
*approach_cnt = REG_GET_FIELD(SENS_SAR_TOUCH_APPR_STATUS_REG, SENS_TOUCH_SLP_APPROACH_CNT);
} else {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
esp_err_t touch_pad_get_wakeup_status(touch_pad_t *pad_num)
{
if (pad_num) {
*pad_num = (touch_pad_t)RTCCNTL.touch_slp_thres.touch_slp_pad;
} else {
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}

View file

@ -0,0 +1,445 @@
// Copyright 2016-2018 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.
#include <esp_types.h>
#include <stdlib.h>
#include <ctype.h>
#include "esp_log.h"
#include "sys/lock.h"
#include "freertos/FreeRTOS.h"
#include "freertos/xtensa_api.h"
#include "freertos/semphr.h"
#include "freertos/timers.h"
#include "esp_intr_alloc.h"
#include "driver/rtc_io.h"
#include "driver/touch_pad.h"
#include "driver/rtc_cntl.h"
#include "driver/gpio.h"
#include "sdkconfig.h"
#include "esp32s2beta/rom/ets_sys.h"
#include "hal/touch_sensor_types.h"
#include "hal/touch_sensor_hal.h"
#ifndef NDEBUG
// Enable built-in checks in queue.h in debug builds
#define INVARIANTS
#endif
#include "sys/queue.h"
#define TOUCH_PAD_FILTER_FACTOR_DEFAULT (4) // IIR filter coefficient.
#define TOUCH_PAD_SHIFT_DEFAULT (4) // Increase computing accuracy.
#define TOUCH_PAD_SHIFT_ROUND_DEFAULT (8) // ROUND = 2^(n-1); rounding off for fractional.
#define TOUCH_PAD_MEASURE_WAIT_DEFAULT (0xFF) // The timer frequency is 8Mhz, the max value is 0xff
static const char *TOUCH_TAG = "TOUCH_SENSOR";
#define TOUCH_CHECK(a, str, ret_val) ({ \
if (!(a)) { \
ESP_LOGE(TOUCH_TAG,"%s:%d (%s):%s", __FILE__, __LINE__, __FUNCTION__, str); \
return (ret_val); \
} \
})
#define TOUCH_CHANNEL_CHECK(channel) do { \
TOUCH_CHECK(channel < SOC_TOUCH_SENSOR_NUM && channel >= 0, "Touch channel error", ESP_ERR_INVALID_ARG); \
TOUCH_CHECK(channel != SOC_TOUCH_DENOISE_CHANNEL, "TOUCH0 is internal denoise channel", ESP_ERR_INVALID_ARG); \
} while (0);
#define TOUCH_CH_MASK_CHECK(mask) TOUCH_CHECK((mask <= SOC_TOUCH_SENSOR_BIT_MASK_MAX), "touch channel bitmask error", ESP_ERR_INVALID_ARG)
#define TOUCH_INTR_MASK_CHECK(mask) TOUCH_CHECK(mask & TOUCH_PAD_INTR_MASK_ALL, "intr mask error", ESP_ERR_INVALID_ARG)
#define TOUCH_PARAM_CHECK_STR(s) ""s" parameter error"
extern portMUX_TYPE rtc_spinlock; //TODO: Will be placed in the appropriate position after the rtc module is finished.
#define TOUCH_ENTER_CRITICAL() portENTER_CRITICAL(&rtc_spinlock)
#define TOUCH_EXIT_CRITICAL() portEXIT_CRITICAL(&rtc_spinlock)
static SemaphoreHandle_t rtc_touch_mux = NULL;
/*---------------------------------------------------------------
Touch Pad
---------------------------------------------------------------*/
esp_err_t touch_pad_isr_register(intr_handler_t fn, void *arg, touch_pad_intr_mask_t intr_mask)
{
TOUCH_CHECK(fn != NULL, TOUCH_PARAM_CHECK_STR("intr_mask"), ESP_ERR_INVALID_ARG);
TOUCH_INTR_MASK_CHECK(intr_mask);
uint32_t en_msk = 0;
if (intr_mask & TOUCH_PAD_INTR_MASK_DONE) {
en_msk |= RTC_CNTL_TOUCH_DONE_INT_ST_M;
}
if (intr_mask & TOUCH_PAD_INTR_MASK_ACTIVE) {
en_msk |= RTC_CNTL_TOUCH_ACTIVE_INT_ST_M;
}
if (intr_mask & TOUCH_PAD_INTR_MASK_INACTIVE) {
en_msk |= RTC_CNTL_TOUCH_INACTIVE_INT_ST_M;
}
return rtc_isr_register(fn, arg, en_msk);
}
esp_err_t touch_pad_set_meas_time(uint16_t sleep_cycle, uint16_t meas_times)
{
TOUCH_ENTER_CRITICAL();
touch_hal_set_meas_times(meas_times);
touch_hal_set_sleep_time(sleep_cycle);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_meas_time(uint16_t *sleep_cycle, uint16_t *meas_times)
{
TOUCH_ENTER_CRITICAL();
touch_hal_get_measure_times(meas_times);
touch_hal_get_sleep_time(sleep_cycle);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_set_inactive_connect(touch_pad_conn_type_t type)
{
TOUCH_CHECK(type < TOUCH_PAD_CONN_MAX, TOUCH_PARAM_CHECK_STR("type"), ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_set_inactive_connect(type);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_inactive_connect(touch_pad_conn_type_t *type)
{
touch_hal_get_inactive_connect(type);
return ESP_OK;
}
bool touch_pad_meas_is_done(void)
{
return touch_hal_meas_is_done();
}
esp_err_t touch_pad_set_channel_mask(uint16_t enable_mask)
{
TOUCH_CH_MASK_CHECK(enable_mask);
TOUCH_ENTER_CRITICAL();
touch_hal_set_channel_mask(enable_mask);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_channel_mask(uint16_t *enable_mask)
{
TOUCH_ENTER_CRITICAL();
touch_hal_get_channel_mask(enable_mask);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_clear_channel_mask(uint16_t enable_mask)
{
TOUCH_CH_MASK_CHECK(enable_mask);
TOUCH_ENTER_CRITICAL();
touch_hal_clear_channel_mask(enable_mask);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
touch_pad_t IRAM_ATTR touch_pad_get_current_meas_channel(void)
{
return (touch_pad_t)touch_hal_get_current_meas_channel();
}
esp_err_t touch_pad_intr_enable(touch_pad_intr_mask_t int_mask)
{
TOUCH_INTR_MASK_CHECK(int_mask);
TOUCH_ENTER_CRITICAL();
touch_hal_intr_enable(int_mask);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_intr_disable(touch_pad_intr_mask_t int_mask)
{
TOUCH_INTR_MASK_CHECK(int_mask);
TOUCH_ENTER_CRITICAL();
touch_hal_intr_disable(int_mask);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
uint32_t touch_pad_read_intr_status_mask(void)
{
return touch_hal_read_intr_status_mask();
}
esp_err_t touch_pad_config(touch_pad_t touch_num)
{
TOUCH_CHANNEL_CHECK(touch_num);
touch_pad_io_init(touch_num);
TOUCH_ENTER_CRITICAL();
touch_hal_config(touch_num);
touch_hal_set_channel_mask(BIT(touch_num));
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_init(void)
{
if (rtc_touch_mux == NULL) {
rtc_touch_mux = xSemaphoreCreateMutex();
}
if (rtc_touch_mux == NULL) {
return ESP_ERR_NO_MEM;
}
TOUCH_ENTER_CRITICAL();
touch_hal_init();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_deinit(void)
{
TOUCH_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_FAIL);
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
TOUCH_ENTER_CRITICAL();
touch_hal_deinit();
TOUCH_EXIT_CRITICAL();
xSemaphoreGive(rtc_touch_mux);
vSemaphoreDelete(rtc_touch_mux);
rtc_touch_mux = NULL;
return ESP_OK;
}
esp_err_t touch_pad_reset(void)
{
TOUCH_ENTER_CRITICAL();
touch_hal_reset();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t IRAM_ATTR touch_pad_read_raw_data(touch_pad_t touch_num, uint32_t *raw_data)
{
TOUCH_CHANNEL_CHECK(touch_num);
*raw_data = touch_hal_read_raw_data(touch_num);
return ESP_OK;
}
esp_err_t IRAM_ATTR touch_pad_filter_read_baseline(touch_pad_t touch_num, uint32_t *basedata)
{
TOUCH_CHANNEL_CHECK(touch_num);
touch_hal_filter_read_baseline(touch_num, basedata);
return ESP_OK;
}
/* Should be call after clk enable and filter enable. */
esp_err_t touch_pad_filter_reset_baseline(touch_pad_t touch_num)
{
TOUCH_CHECK(touch_num <= TOUCH_PAD_MAX && touch_num >= 0, "Touch channel error", ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_filter_reset_baseline(touch_num);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_filter_set_config(touch_filter_config_t *filter_info)
{
TOUCH_CHECK(filter_info->mode < TOUCH_PAD_FILTER_MAX, TOUCH_PARAM_CHECK_STR("mode"), ESP_ERR_INVALID_ARG);
TOUCH_CHECK(filter_info->debounce_cnt <= TOUCH_DEBOUNCE_CNT_MAX, TOUCH_PARAM_CHECK_STR("debounce"), ESP_ERR_INVALID_ARG);
TOUCH_CHECK(filter_info->hysteresis_thr <= TOUCH_HYSTERESIS_THR_MAX, TOUCH_PARAM_CHECK_STR("hysteresis"), ESP_ERR_INVALID_ARG);
TOUCH_CHECK(filter_info->noise_thr <= TOUCH_NOISE_THR_MAX, TOUCH_PARAM_CHECK_STR("noise"), ESP_ERR_INVALID_ARG);
TOUCH_CHECK(filter_info->noise_neg_thr <= TOUCH_NOISE_NEG_THR_MAX, TOUCH_PARAM_CHECK_STR("noise"), ESP_ERR_INVALID_ARG);
TOUCH_CHECK(filter_info->neg_noise_limit <= TOUCH_NEG_NOISE_CNT_LIMIT, TOUCH_PARAM_CHECK_STR("noise_limit"), ESP_ERR_INVALID_ARG);
TOUCH_CHECK(filter_info->jitter_step <= TOUCH_JITTER_STEP_MAX, TOUCH_PARAM_CHECK_STR("jitter_step"), ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_filter_set_config(filter_info);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_filter_get_config(touch_filter_config_t *filter_info)
{
TOUCH_ENTER_CRITICAL();
touch_hal_filter_get_config(filter_info);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_filter_enable(void)
{
TOUCH_ENTER_CRITICAL();
touch_hal_filter_enable();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_filter_disable(void)
{
TOUCH_ENTER_CRITICAL();
touch_hal_filter_disable();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_enable(void)
{
TOUCH_ENTER_CRITICAL();
touch_hal_clear_channel_mask(BIT(SOC_TOUCH_DENOISE_CHANNEL));
touch_hal_denoise_enable();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_disable(void)
{
TOUCH_ENTER_CRITICAL();
touch_hal_denoise_disable();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_set_config(touch_pad_denoise_t *denoise)
{
TOUCH_CHECK(denoise->grade < TOUCH_PAD_DENOISE_MAX, TOUCH_PARAM_CHECK_STR("grade"), ESP_ERR_INVALID_ARG);
TOUCH_CHECK(denoise->cap_level < TOUCH_PAD_DENOISE_CAP_MAX, TOUCH_PARAM_CHECK_STR("cap_level"), ESP_ERR_INVALID_ARG);
const touch_hal_meas_mode_t meas = {
.slope = TOUCH_PAD_SLOPE_DEFAULT,
.tie_opt = TOUCH_PAD_TIE_OPT_DEFAULT,
};
TOUCH_ENTER_CRITICAL();
touch_hal_set_meas_mode(SOC_TOUCH_DENOISE_CHANNEL, &meas);
touch_hal_denoise_set_config(denoise);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_get_config(touch_pad_denoise_t *denoise)
{
TOUCH_ENTER_CRITICAL();
touch_hal_denoise_get_config(denoise);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_denoise_read_data(uint32_t *data)
{
touch_hal_denoise_read_data(data);
return ESP_OK;
}
esp_err_t touch_pad_waterproof_set_config(touch_pad_waterproof_t *waterproof)
{
TOUCH_CHECK(waterproof->guard_ring_pad < SOC_TOUCH_SENSOR_NUM, TOUCH_PARAM_CHECK_STR("pad"), ESP_ERR_INVALID_ARG);
TOUCH_CHECK(waterproof->shield_driver < TOUCH_PAD_SHIELD_DRV_MAX, TOUCH_PARAM_CHECK_STR("shield_driver"), ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_waterproof_set_config(waterproof);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_waterproof_get_config(touch_pad_waterproof_t *waterproof)
{
TOUCH_ENTER_CRITICAL();
touch_hal_waterproof_get_config(waterproof);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_waterproof_enable(void)
{
touch_pad_io_init(SOC_TOUCH_SHIELD_CHANNEL);
TOUCH_ENTER_CRITICAL();
touch_hal_waterproof_enable();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_waterproof_disable(void)
{
TOUCH_ENTER_CRITICAL();
touch_hal_waterproof_disable();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_proximity_set_config(touch_pad_proximity_t *proximity)
{
for (int i=0; i<SOC_TOUCH_PROXIMITY_CHANNEL_NUM; i++) {
TOUCH_CHECK(proximity->select_pad[i] < SOC_TOUCH_SENSOR_NUM, TOUCH_PARAM_CHECK_STR("pad"), ESP_ERR_INVALID_ARG);
}
TOUCH_CHECK(proximity->meas_num <= TOUCH_PROXIMITY_MEAS_NUM_MAX, TOUCH_PARAM_CHECK_STR("meas_num"), ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_proximity_set_config(proximity);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_proximity_get_config(touch_pad_proximity_t *proximity)
{
TOUCH_ENTER_CRITICAL();
touch_hal_proximity_get_config(proximity);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_proximity_read_meas_cnt(touch_pad_t touch_num, uint32_t *cnt)
{
TOUCH_CHECK(touch_hal_proximity_pad_check(touch_num), "touch_num is not proximity", ESP_ERR_INVALID_ARG);
touch_hal_proximity_read_meas_cnt(touch_num, cnt);
return ESP_OK;
}
esp_err_t touch_pad_proximity_data_get(touch_pad_t touch_num, uint32_t *measure_out)
{
TOUCH_CHECK(touch_hal_proximity_pad_check(touch_num), "touch_num is not proximity", ESP_ERR_INVALID_ARG);
touch_hal_filter_read_baseline(touch_num, measure_out);
return ESP_OK;
}
/************** sleep pad setting ***********************/
esp_err_t touch_pad_sleep_channel_config(touch_pad_sleep_channel_t *slp_config)
{
TOUCH_CHECK(slp_config->touch_num < SOC_TOUCH_SENSOR_NUM, TOUCH_PARAM_CHECK_STR("pad"), ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_sleep_channel_config(slp_config);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_sleep_channel_read_baseline(uint32_t *baseline)
{
touch_hal_sleep_read_baseline(baseline);
return ESP_OK;
}
esp_err_t touch_pad_sleep_channel_read_debounce(uint32_t *debounce)
{
touch_hal_sleep_read_debounce(debounce);
return ESP_OK;
}
esp_err_t touch_pad_sleep_channel_read_proximity_cnt(uint32_t *approach_cnt)
{
touch_hal_sleep_read_proximity_cnt(approach_cnt);
return ESP_OK;
}

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,162 @@
// Copyright 2015-2016 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.
#pragma once
#include "esp_err.h"
#include "esp_intr_alloc.h"
#include "soc/touch_sensor_periph.h"
#include "hal/touch_sensor_types.h"
#include "touch_sensor.h"
#ifdef __cplusplus
extern "C" {
#endif
/**
* @brief Initialize touch module.
* @note If default parameter don't match the usage scenario, it can be changed after this function.
* @return
* - ESP_OK Success
* - ESP_ERR_NO_MEM Touch pad init error
*/
esp_err_t touch_pad_init(void);
/**
* @brief Un-install touch pad driver.
* @note After this function is called, other touch functions are prohibited from being called.
* @return
* - ESP_OK Success
* - ESP_FAIL Touch pad driver not initialized
*/
esp_err_t touch_pad_deinit(void);
/**
* @brief Initialize touch pad GPIO
* @param touch_num touch pad index
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_io_init(touch_pad_t touch_num);
/**
* @brief Set touch sensor high voltage threshold of chanrge.
* The touch sensor measures the channel capacitance value by charging and discharging the channel.
* So the high threshold should be less than the supply voltage.
* @param refh the value of DREFH
* @param refl the value of DREFL
* @param atten the attenuation on DREFH
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_set_voltage(touch_high_volt_t refh, touch_low_volt_t refl, touch_volt_atten_t atten);
/**
* @brief Get touch sensor reference voltage,
* @param refh pointer to accept DREFH value
* @param refl pointer to accept DREFL value
* @param atten pointer to accept the attenuation on DREFH
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_voltage(touch_high_volt_t *refh, touch_low_volt_t *refl, touch_volt_atten_t *atten);
/**
* @brief Set touch sensor charge/discharge speed for each pad.
* If the slope is 0, the counter would always be zero.
* If the slope is 1, the charging and discharging would be slow, accordingly.
* If the slope is set 7, which is the maximum value, the charging and discharging would be fast.
* @note The higher the charge and discharge current, the greater the immunity of the touch channel,
* but it will increase the system power consumption.
* @param touch_num touch pad index
* @param slope touch pad charge/discharge speed
* @param opt the initial voltage
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_set_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t slope, touch_tie_opt_t opt);
/**
* @brief Get touch sensor charge/discharge speed for each pad
* @param touch_num touch pad index
* @param slope pointer to accept touch pad charge/discharge slope
* @param opt pointer to accept the initial voltage
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_get_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t *slope, touch_tie_opt_t *opt);
/**
* @brief Deregister the handler previously registered using touch_pad_isr_handler_register
* @param fn handler function to call (as passed to touch_pad_isr_handler_register)
* @param arg argument of the handler (as passed to touch_pad_isr_handler_register)
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_STATE if a handler matching both fn and
* arg isn't registered
*/
esp_err_t touch_pad_isr_deregister(void(*fn)(void *), void *arg);
/**
* @brief Get the touch pad which caused wakeup from deep sleep.
* @param pad_num pointer to touch pad which caused wakeup
* @return
* - ESP_OK Success
* - ESP_ERR_INVALID_ARG parameter is NULL
*/
esp_err_t touch_pad_get_wakeup_status(touch_pad_t *pad_num);
/**
* @brief Set touch sensor FSM mode, the test action can be triggered by the timer,
* as well as by the software.
* @param mode FSM mode
* @return
* - ESP_OK on success
* - ESP_ERR_INVALID_ARG if argument is wrong
*/
esp_err_t touch_pad_set_fsm_mode(touch_fsm_mode_t mode);
/**
* @brief Get touch sensor FSM mode
* @param mode pointer to accept FSM mode
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_get_fsm_mode(touch_fsm_mode_t *mode);
/**
* @brief To clear the touch status register, usually use this function in touch ISR to clear status.
*
* @note Generally no manual removal is required.
* @return
* - ESP_OK on success
*/
esp_err_t touch_pad_clear_status(void);
/**
* @brief Get the touch sensor status, usually used in ISR to decide which pads are 'touched'.
*
* @return
* - The touch sensor status. e.g. Touch1 trigger status is `status_mask & (BIT1)`.
*/
uint32_t touch_pad_get_status(void);
#ifdef __cplusplus
}
#endif

View file

@ -21,10 +21,6 @@
#include "soc/syscon_periph.h"
#include "soc/rtc.h"
#include "soc/periph_defs.h"
#include "rtc_io.h"
#include "touch_pad.h"
#include "adc.h"
#include "dac.h"
#include "freertos/FreeRTOS.h"
#include "freertos/xtensa_api.h"
#include "freertos/semphr.h"
@ -32,9 +28,6 @@
#include "esp_intr_alloc.h"
#include "sys/lock.h"
#include "driver/rtc_cntl.h"
#include "driver/gpio.h"
#include "driver/rtc_io.h"
#include "adc1_i2s_private.h"
#include "sdkconfig.h"
#if CONFIG_IDF_TARGET_ESP32
#include "esp32/rom/ets_sys.h"
@ -48,693 +41,7 @@
#endif
#include "sys/queue.h"
#define TOUCH_PAD_FILTER_FACTOR_DEFAULT (4) // IIR filter coefficient.
#define TOUCH_PAD_SHIFT_DEFAULT (4) // Increase computing accuracy.
#define TOUCH_PAD_SHIFT_ROUND_DEFAULT (8) // ROUND = 2^(n-1); rounding off for fractional.
portMUX_TYPE rtc_spinlock = portMUX_INITIALIZER_UNLOCKED;
#if CONFIG_IDF_TARGET_ESP32
static SemaphoreHandle_t rtc_touch_mux = NULL;
#endif
#if CONFIG_IDF_TARGET_ESP32
typedef struct {
TimerHandle_t timer;
uint16_t filtered_val[TOUCH_PAD_MAX];
uint16_t raw_val[TOUCH_PAD_MAX];
uint32_t filter_period;
uint32_t period;
bool enable;
} touch_pad_filter_t;
static touch_pad_filter_t *s_touch_pad_filter = NULL;
// check if touch pad be inited.
static uint16_t s_touch_pad_init_bit = 0x0000;
static filter_cb_t s_filter_cb = NULL;
#endif
#if CONFIG_IDF_TARGET_ESP32
static const char *RTC_MODULE_TAG = "RTC_MODULE";
#define RTC_MODULE_CHECK(a, str, ret_val) if (!(a)) { \
ESP_LOGE(RTC_MODULE_TAG,"%s:%d (%s):%s", __FILE__, __LINE__, __FUNCTION__, str); \
return (ret_val); \
}
#define RTC_RES_CHECK(res, ret_val) if ( (a) != ESP_OK) { \
ESP_LOGE(RTC_MODULE_TAG,"%s:%d (%s)", __FILE__, __LINE__, __FUNCTION__); \
return (ret_val); \
}
/*---------------------------------------------------------------
Touch Pad
---------------------------------------------------------------*/
//Some register bits of touch sensor 8 and 9 are mismatched, we need to swap the bits.
#define BITSWAP(data, n, m) (((data >> n) & 0x1) == ((data >> m) & 0x1) ? (data) : ((data) ^ ((0x1 <<n) | (0x1 << m))))
#define TOUCH_BITS_SWAP(v) BITSWAP(v, TOUCH_PAD_NUM8, TOUCH_PAD_NUM9)
static esp_err_t _touch_pad_read(touch_pad_t touch_num, uint16_t *touch_value, touch_fsm_mode_t mode);
//Some registers of touch sensor 8 and 9 are mismatched, we need to swap register index
inline static touch_pad_t touch_pad_num_wrap(touch_pad_t touch_num)
{
if (touch_num == TOUCH_PAD_NUM8) {
return TOUCH_PAD_NUM9;
} else if (touch_num == TOUCH_PAD_NUM9) {
return TOUCH_PAD_NUM8;
}
return touch_num;
}
esp_err_t touch_pad_isr_handler_register(void (*fn)(void *), void *arg, int no_use, intr_handle_t *handle_no_use)
{
RTC_MODULE_CHECK(fn, "Touch_Pad ISR null", ESP_ERR_INVALID_ARG);
#if CONFIG_IDF_TARGET_ESP32
return rtc_isr_register(fn, arg, RTC_CNTL_TOUCH_INT_ST_M);
#else
return ESP_FAIL;
#endif
}
esp_err_t touch_pad_isr_register(intr_handler_t fn, void* arg)
{
RTC_MODULE_CHECK(fn, "Touch_Pad ISR null", ESP_ERR_INVALID_ARG);
#if CONFIG_IDF_TARGET_ESP32
return rtc_isr_register(fn, arg, RTC_CNTL_TOUCH_INT_ST_M);
#else
return ESP_FAIL;
#endif
}
esp_err_t touch_pad_isr_deregister(intr_handler_t fn, void *arg)
{
return rtc_isr_deregister(fn, arg);
}
static esp_err_t touch_pad_get_io_num(touch_pad_t touch_num, gpio_num_t *gpio_num)
{
switch (touch_num) {
case TOUCH_PAD_NUM0:
*gpio_num = TOUCH_PAD_NUM0_GPIO_NUM;
break;
case TOUCH_PAD_NUM1:
*gpio_num = TOUCH_PAD_NUM1_GPIO_NUM;
break;
case TOUCH_PAD_NUM2:
*gpio_num = TOUCH_PAD_NUM2_GPIO_NUM;
break;
case TOUCH_PAD_NUM3:
*gpio_num = TOUCH_PAD_NUM3_GPIO_NUM;
break;
case TOUCH_PAD_NUM4:
*gpio_num = TOUCH_PAD_NUM4_GPIO_NUM;
break;
case TOUCH_PAD_NUM5:
*gpio_num = TOUCH_PAD_NUM5_GPIO_NUM;
break;
case TOUCH_PAD_NUM6:
*gpio_num = TOUCH_PAD_NUM6_GPIO_NUM;
break;
case TOUCH_PAD_NUM7:
*gpio_num = TOUCH_PAD_NUM7_GPIO_NUM;
break;
case TOUCH_PAD_NUM8:
*gpio_num = TOUCH_PAD_NUM8_GPIO_NUM;
break;
case TOUCH_PAD_NUM9:
*gpio_num = TOUCH_PAD_NUM9_GPIO_NUM;
break;
default:
return ESP_ERR_INVALID_ARG;
}
return ESP_OK;
}
static uint32_t _touch_filter_iir(uint32_t in_now, uint32_t out_last, uint32_t k)
{
if (k == 0) {
return in_now;
} else {
uint32_t out_now = (in_now + (k - 1) * out_last) / k;
return out_now;
}
}
esp_err_t touch_pad_set_filter_read_cb(filter_cb_t read_cb)
{
s_filter_cb = read_cb;
return ESP_OK;
}
static void touch_pad_filter_cb(void *arg)
{
static uint32_t s_filtered_temp[TOUCH_PAD_MAX] = {0};
if (s_touch_pad_filter == NULL || rtc_touch_mux == NULL) {
return;
}
uint16_t val = 0;
touch_fsm_mode_t mode;
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
touch_pad_get_fsm_mode(&mode);
for (int i = 0; i < TOUCH_PAD_MAX; i++) {
if ((s_touch_pad_init_bit >> i) & 0x1) {
_touch_pad_read(i, &val, mode);
s_touch_pad_filter->raw_val[i] = val;
s_filtered_temp[i] = s_filtered_temp[i] == 0 ? ((uint32_t)val << TOUCH_PAD_SHIFT_DEFAULT) : s_filtered_temp[i];
s_filtered_temp[i] = _touch_filter_iir((val << TOUCH_PAD_SHIFT_DEFAULT),
s_filtered_temp[i], TOUCH_PAD_FILTER_FACTOR_DEFAULT);
s_touch_pad_filter->filtered_val[i] = (s_filtered_temp[i] + TOUCH_PAD_SHIFT_ROUND_DEFAULT) >> TOUCH_PAD_SHIFT_DEFAULT;
}
}
xTimerReset(s_touch_pad_filter->timer, portMAX_DELAY);
xSemaphoreGive(rtc_touch_mux);
if(s_filter_cb != NULL) {
//return the raw data and filtered data.
s_filter_cb(s_touch_pad_filter->raw_val, s_touch_pad_filter->filtered_val);
}
}
esp_err_t touch_pad_set_meas_time(uint16_t sleep_cycle, uint16_t meas_cycle)
{
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
portENTER_CRITICAL(&rtc_spinlock);
//touch sensor sleep cycle Time = sleep_cycle / RTC_SLOW_CLK( can be 150k or 32k depending on the options)
SENS.sar_touch_ctrl2.touch_sleep_cycles = sleep_cycle;
//touch sensor measure time= meas_cycle / 8Mhz
SENS.sar_touch_ctrl1.touch_meas_delay = meas_cycle;
//the waiting cycles (in 8MHz) between TOUCH_START and TOUCH_XPD
SENS.sar_touch_ctrl1.touch_xpd_wait = TOUCH_PAD_MEASURE_WAIT_DEFAULT;
portEXIT_CRITICAL(&rtc_spinlock);
xSemaphoreGive(rtc_touch_mux);
return ESP_OK;
}
esp_err_t touch_pad_get_meas_time(uint16_t *sleep_cycle, uint16_t *meas_cycle)
{
portENTER_CRITICAL(&rtc_spinlock);
if (sleep_cycle) {
*sleep_cycle = SENS.sar_touch_ctrl2.touch_sleep_cycles;
}
if (meas_cycle) {
*meas_cycle = SENS.sar_touch_ctrl1.touch_meas_delay;
}
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
esp_err_t touch_pad_set_voltage(touch_high_volt_t refh, touch_low_volt_t refl, touch_volt_atten_t atten)
{
RTC_MODULE_CHECK(((refh < TOUCH_HVOLT_MAX) && (refh >= (int )TOUCH_HVOLT_KEEP)), "touch refh error",
ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK(((refl < TOUCH_LVOLT_MAX) && (refh >= (int )TOUCH_LVOLT_KEEP)), "touch refl error",
ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK(((atten < TOUCH_HVOLT_ATTEN_MAX) && (refh >= (int )TOUCH_HVOLT_ATTEN_KEEP)), "touch atten error",
ESP_ERR_INVALID_ARG);
#if CONFIG_IDF_TARGET_ESP32
portENTER_CRITICAL(&rtc_spinlock);
if (refh > TOUCH_HVOLT_KEEP) {
RTCIO.touch_cfg.drefh = refh;
}
if (refl > TOUCH_LVOLT_KEEP) {
RTCIO.touch_cfg.drefl = refl;
}
if (atten > TOUCH_HVOLT_ATTEN_KEEP) {
RTCIO.touch_cfg.drange = atten;
}
portEXIT_CRITICAL(&rtc_spinlock);
#endif
return ESP_OK;
}
esp_err_t touch_pad_get_voltage(touch_high_volt_t *refh, touch_low_volt_t *refl, touch_volt_atten_t *atten)
{
#if CONFIG_IDF_TARGET_ESP32
portENTER_CRITICAL(&rtc_spinlock);
if (refh) {
*refh = RTCIO.touch_cfg.drefh;
}
if (refl) {
*refl = RTCIO.touch_cfg.drefl;
}
if (atten) {
*atten = RTCIO.touch_cfg.drange;
}
portEXIT_CRITICAL(&rtc_spinlock);
#endif
return ESP_OK;
}
esp_err_t touch_pad_set_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t slope, touch_tie_opt_t opt)
{
RTC_MODULE_CHECK((slope < TOUCH_PAD_SLOPE_MAX), "touch slope error", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK((opt < TOUCH_PAD_TIE_OPT_MAX), "touch opt error", ESP_ERR_INVALID_ARG);
touch_pad_t touch_pad_wrap = touch_pad_num_wrap(touch_num);
portENTER_CRITICAL(&rtc_spinlock);
RTCIO.touch_pad[touch_pad_wrap].tie_opt = opt;
RTCIO.touch_pad[touch_num].dac = slope;
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
esp_err_t touch_pad_get_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t *slope, touch_tie_opt_t *opt)
{
RTC_MODULE_CHECK((touch_num < TOUCH_PAD_MAX), "touch IO error", ESP_ERR_INVALID_ARG);
touch_pad_t touch_pad_wrap = touch_pad_num_wrap(touch_num);
portENTER_CRITICAL(&rtc_spinlock);
if(opt) {
*opt = RTCIO.touch_pad[touch_pad_wrap].tie_opt;
}
if(slope) {
*slope = RTCIO.touch_pad[touch_num].dac;
}
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
esp_err_t touch_pad_io_init(touch_pad_t touch_num)
{
RTC_MODULE_CHECK((touch_num < TOUCH_PAD_MAX), "touch IO error", ESP_ERR_INVALID_ARG);
gpio_num_t gpio_num = GPIO_NUM_0;
touch_pad_get_io_num(touch_num, &gpio_num);
rtc_gpio_init(gpio_num);
rtc_gpio_set_direction(gpio_num, RTC_GPIO_MODE_DISABLED);
rtc_gpio_pulldown_dis(gpio_num);
rtc_gpio_pullup_dis(gpio_num);
return ESP_OK;
}
esp_err_t touch_pad_set_fsm_mode(touch_fsm_mode_t mode)
{
RTC_MODULE_CHECK((mode < TOUCH_FSM_MODE_MAX), "touch fsm mode error", ESP_ERR_INVALID_ARG);
portENTER_CRITICAL(&rtc_spinlock);
SENS.sar_touch_ctrl2.touch_start_en = 0;
SENS.sar_touch_ctrl2.touch_start_force = mode;
RTCCNTL.state0.touch_slp_timer_en = (mode == TOUCH_FSM_MODE_TIMER ? 1 : 0);
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
esp_err_t touch_pad_get_fsm_mode(touch_fsm_mode_t *mode)
{
if (mode) {
*mode = SENS.sar_touch_ctrl2.touch_start_force;
}
return ESP_OK;
}
esp_err_t touch_pad_sw_start(void)
{
portENTER_CRITICAL(&rtc_spinlock);
SENS.sar_touch_ctrl2.touch_start_en = 0;
SENS.sar_touch_ctrl2.touch_start_en = 1;
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
esp_err_t touch_pad_set_thresh(touch_pad_t touch_num, uint16_t threshold)
{
RTC_MODULE_CHECK((touch_num < TOUCH_PAD_MAX), "touch IO error", ESP_ERR_INVALID_ARG);
touch_pad_t tp_wrap = touch_pad_num_wrap(touch_num);
portENTER_CRITICAL(&rtc_spinlock);
if (tp_wrap & 0x1) {
SENS.touch_thresh[tp_wrap / 2].l_thresh = threshold;
} else {
SENS.touch_thresh[tp_wrap / 2].h_thresh = threshold;
}
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
esp_err_t touch_pad_get_thresh(touch_pad_t touch_num, uint16_t *threshold)
{
RTC_MODULE_CHECK((touch_num < TOUCH_PAD_MAX), "touch IO error", ESP_ERR_INVALID_ARG);
touch_pad_t tp_wrap = touch_pad_num_wrap(touch_num);
if (threshold) {
*threshold = (tp_wrap & 0x1 )? \
SENS.touch_thresh[tp_wrap / 2].l_thresh : \
SENS.touch_thresh[tp_wrap / 2].h_thresh;
}
return ESP_OK;
}
esp_err_t touch_pad_set_trigger_mode(touch_trigger_mode_t mode)
{
RTC_MODULE_CHECK((mode < TOUCH_TRIGGER_MAX), "touch trigger mode error", ESP_ERR_INVALID_ARG);
portENTER_CRITICAL(&rtc_spinlock);
SENS.sar_touch_ctrl1.touch_out_sel = mode;
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
esp_err_t touch_pad_get_trigger_mode(touch_trigger_mode_t *mode)
{
if (mode) {
*mode = SENS.sar_touch_ctrl1.touch_out_sel;
}
return ESP_OK;
}
esp_err_t touch_pad_set_trigger_source(touch_trigger_src_t src)
{
RTC_MODULE_CHECK((src < TOUCH_TRIGGER_SOURCE_MAX), "touch trigger source error", ESP_ERR_INVALID_ARG);
portENTER_CRITICAL(&rtc_spinlock);
SENS.sar_touch_ctrl1.touch_out_1en = src;
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
esp_err_t touch_pad_get_trigger_source(touch_trigger_src_t *src)
{
if (src) {
*src = SENS.sar_touch_ctrl1.touch_out_1en;
}
return ESP_OK;
}
esp_err_t touch_pad_set_group_mask(uint16_t set1_mask, uint16_t set2_mask, uint16_t en_mask)
{
RTC_MODULE_CHECK((set1_mask <= TOUCH_PAD_BIT_MASK_MAX), "touch set1 bitmask error", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK((set2_mask <= TOUCH_PAD_BIT_MASK_MAX), "touch set2 bitmask error", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK((en_mask <= TOUCH_PAD_BIT_MASK_MAX), "touch work_en bitmask error", ESP_ERR_INVALID_ARG);
portENTER_CRITICAL(&rtc_spinlock);
SENS.sar_touch_enable.touch_pad_outen1 |= TOUCH_BITS_SWAP(set1_mask);
SENS.sar_touch_enable.touch_pad_outen2 |= TOUCH_BITS_SWAP(set2_mask);
SENS.sar_touch_enable.touch_pad_worken |= TOUCH_BITS_SWAP(en_mask);
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
esp_err_t touch_pad_get_group_mask(uint16_t *set1_mask, uint16_t *set2_mask, uint16_t *en_mask)
{
portENTER_CRITICAL(&rtc_spinlock);
if (set1_mask) {
*set1_mask = TOUCH_BITS_SWAP(SENS.sar_touch_enable.touch_pad_outen1);
}
if (set2_mask) {
*set2_mask = TOUCH_BITS_SWAP(SENS.sar_touch_enable.touch_pad_outen2);
}
if (en_mask) {
*en_mask = TOUCH_BITS_SWAP(SENS.sar_touch_enable.touch_pad_worken);
}
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
esp_err_t touch_pad_clear_group_mask(uint16_t set1_mask, uint16_t set2_mask, uint16_t en_mask)
{
RTC_MODULE_CHECK((set1_mask <= TOUCH_PAD_BIT_MASK_MAX), "touch set1 bitmask error", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK((set2_mask <= TOUCH_PAD_BIT_MASK_MAX), "touch set2 bitmask error", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK((en_mask <= TOUCH_PAD_BIT_MASK_MAX), "touch work_en bitmask error", ESP_ERR_INVALID_ARG);
portENTER_CRITICAL(&rtc_spinlock);
SENS.sar_touch_enable.touch_pad_outen1 &= TOUCH_BITS_SWAP(~set1_mask);
SENS.sar_touch_enable.touch_pad_outen2 &= TOUCH_BITS_SWAP(~set2_mask);
SENS.sar_touch_enable.touch_pad_worken &= TOUCH_BITS_SWAP(~en_mask);
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
uint32_t IRAM_ATTR touch_pad_get_status(void)
{
uint32_t status = SENS.sar_touch_ctrl2.touch_meas_en;
return TOUCH_BITS_SWAP(status);
}
esp_err_t IRAM_ATTR touch_pad_clear_status(void)
{
SENS.sar_touch_ctrl2.touch_meas_en_clr = 1;
return ESP_OK;
}
esp_err_t touch_pad_intr_enable(void)
{
portENTER_CRITICAL(&rtc_spinlock);
RTCCNTL.int_ena.rtc_touch = 1;
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
esp_err_t touch_pad_intr_disable(void)
{
portENTER_CRITICAL(&rtc_spinlock);
RTCCNTL.int_ena.rtc_touch = 0;
portEXIT_CRITICAL(&rtc_spinlock);
return ESP_OK;
}
esp_err_t touch_pad_config(touch_pad_t touch_num, uint16_t threshold)
{
RTC_MODULE_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_FAIL);
RTC_MODULE_CHECK(touch_num < TOUCH_PAD_MAX, "Touch_Pad Num Err", ESP_ERR_INVALID_ARG);
touch_fsm_mode_t mode;
touch_pad_set_thresh(touch_num, threshold);
touch_pad_io_init(touch_num);
touch_pad_set_cnt_mode(touch_num, TOUCH_PAD_SLOPE_7, TOUCH_PAD_TIE_OPT_LOW);
touch_pad_get_fsm_mode(&mode);
if (TOUCH_FSM_MODE_SW == mode) {
touch_pad_clear_group_mask((1 << touch_num), (1 << touch_num), (1 << touch_num));
s_touch_pad_init_bit |= (1 << touch_num);
} else if (TOUCH_FSM_MODE_TIMER == mode){
uint16_t sleep_time = 0;
uint16_t meas_cycle = 0;
uint32_t wait_time_ms = 0;
uint32_t wait_tick = 0;
uint32_t rtc_clk = rtc_clk_slow_freq_get_hz();
touch_pad_set_group_mask((1 << touch_num), (1 << touch_num), (1 << touch_num));
touch_pad_get_meas_time(&sleep_time, &meas_cycle);
//If the FSM mode is 'TOUCH_FSM_MODE_TIMER', The data will be ready after one measurement cycle
//after this function is executed, otherwise, the "touch_value" by "touch_pad_read" is 0.
wait_time_ms = sleep_time/(rtc_clk/1000) + meas_cycle/(RTC_FAST_CLK_FREQ_APPROX/1000);
wait_tick = wait_time_ms/portTICK_RATE_MS;
vTaskDelay(wait_tick ? wait_tick : 1);
s_touch_pad_init_bit |= (1 << touch_num);
} else {
return ESP_FAIL;
}
return ESP_OK;
}
esp_err_t touch_pad_init(void)
{
if (rtc_touch_mux == NULL) {
rtc_touch_mux = xSemaphoreCreateMutex();
}
if (rtc_touch_mux == NULL) {
return ESP_FAIL;
}
touch_pad_intr_disable();
touch_pad_clear_group_mask(TOUCH_PAD_BIT_MASK_MAX, TOUCH_PAD_BIT_MASK_MAX, TOUCH_PAD_BIT_MASK_MAX);
touch_pad_set_trigger_mode(TOUCH_TRIGGER_MODE_DEFAULT);
touch_pad_set_trigger_source(TOUCH_TRIGGER_SOURCE_DEFAULT);
touch_pad_clear_status();
touch_pad_set_meas_time(TOUCH_PAD_SLEEP_CYCLE_DEFAULT, TOUCH_PAD_MEASURE_CYCLE_DEFAULT);
touch_pad_set_fsm_mode(TOUCH_FSM_MODE_DEFAULT);
return ESP_OK;
}
esp_err_t touch_pad_deinit(void)
{
RTC_MODULE_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_FAIL);
if (s_touch_pad_filter != NULL) {
touch_pad_filter_stop();
touch_pad_filter_delete();
}
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
s_touch_pad_init_bit = 0x0000;
touch_pad_set_fsm_mode(TOUCH_FSM_MODE_SW);
touch_pad_clear_status();
touch_pad_intr_disable();
xSemaphoreGive(rtc_touch_mux);
vSemaphoreDelete(rtc_touch_mux);
rtc_touch_mux = NULL;
return ESP_OK;
}
static esp_err_t _touch_pad_read(touch_pad_t touch_num, uint16_t *touch_value, touch_fsm_mode_t mode)
{
esp_err_t res = ESP_OK;
touch_pad_t tp_wrap = touch_pad_num_wrap(touch_num);
if (TOUCH_FSM_MODE_SW == mode) {
touch_pad_set_group_mask((1 << touch_num), (1 << touch_num), (1 << touch_num));
touch_pad_sw_start();
while (SENS.sar_touch_ctrl2.touch_meas_done == 0) {};
*touch_value = (tp_wrap & 0x1) ? \
SENS.touch_meas[tp_wrap / 2].l_val: \
SENS.touch_meas[tp_wrap / 2].h_val;
touch_pad_clear_group_mask((1 << touch_num), (1 << touch_num), (1 << touch_num));
} else if (TOUCH_FSM_MODE_TIMER == mode) {
while (SENS.sar_touch_ctrl2.touch_meas_done == 0) {};
*touch_value = (tp_wrap & 0x1) ? \
SENS.touch_meas[tp_wrap / 2].l_val: \
SENS.touch_meas[tp_wrap / 2].h_val;
} else {
res = ESP_FAIL;
}
if (*touch_value == 0) {
res = ESP_ERR_INVALID_STATE;
}
return res;
}
esp_err_t touch_pad_read(touch_pad_t touch_num, uint16_t *touch_value)
{
RTC_MODULE_CHECK(touch_num < TOUCH_PAD_MAX, "Touch_Pad Num Err", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK(touch_value != NULL, "touch_value", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_FAIL);
esp_err_t res = ESP_OK;
touch_fsm_mode_t mode;
touch_pad_get_fsm_mode(&mode);
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
res = _touch_pad_read(touch_num, touch_value, mode);
xSemaphoreGive(rtc_touch_mux);
return res;
}
IRAM_ATTR esp_err_t touch_pad_read_raw_data(touch_pad_t touch_num, uint16_t *touch_value)
{
RTC_MODULE_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_FAIL);
RTC_MODULE_CHECK(touch_num < TOUCH_PAD_MAX, "Touch_Pad Num Err", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK(touch_value != NULL, "touch_value", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK(s_touch_pad_filter != NULL, "Touch pad filter not initialized", ESP_FAIL);
*touch_value = s_touch_pad_filter->raw_val[touch_num];
if (*touch_value == 0) {
return ESP_ERR_INVALID_STATE;
}
return ESP_OK;
}
IRAM_ATTR esp_err_t touch_pad_read_filtered(touch_pad_t touch_num, uint16_t *touch_value)
{
RTC_MODULE_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_FAIL);
RTC_MODULE_CHECK(touch_num < TOUCH_PAD_MAX, "Touch_Pad Num Err", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK(touch_value != NULL, "touch_value", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK(s_touch_pad_filter != NULL, "Touch pad filter not initialized", ESP_FAIL);
*touch_value = (s_touch_pad_filter->filtered_val[touch_num]);
if (*touch_value == 0) {
return ESP_ERR_INVALID_STATE;
}
return ESP_OK;
}
esp_err_t touch_pad_set_filter_period(uint32_t new_period_ms)
{
RTC_MODULE_CHECK(s_touch_pad_filter != NULL, "Touch pad filter not initialized", ESP_ERR_INVALID_STATE);
RTC_MODULE_CHECK(new_period_ms > 0, "Touch pad filter period error", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_ERR_INVALID_STATE);
esp_err_t ret = ESP_OK;
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
if (s_touch_pad_filter != NULL) {
xTimerChangePeriod(s_touch_pad_filter->timer, new_period_ms / portTICK_PERIOD_MS, portMAX_DELAY);
s_touch_pad_filter->period = new_period_ms;
} else {
ESP_LOGE(RTC_MODULE_TAG, "Touch pad filter deleted");
ret = ESP_ERR_INVALID_STATE;
}
xSemaphoreGive(rtc_touch_mux);
return ret;
}
esp_err_t touch_pad_get_filter_period(uint32_t* p_period_ms)
{
RTC_MODULE_CHECK(s_touch_pad_filter != NULL, "Touch pad filter not initialized", ESP_ERR_INVALID_STATE);
RTC_MODULE_CHECK(p_period_ms != NULL, "Touch pad period pointer error", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_ERR_INVALID_STATE);
esp_err_t ret = ESP_OK;
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
if (s_touch_pad_filter != NULL) {
*p_period_ms = s_touch_pad_filter->period;
} else {
ESP_LOGE(RTC_MODULE_TAG, "Touch pad filter deleted");
ret = ESP_ERR_INVALID_STATE;
}
xSemaphoreGive(rtc_touch_mux);
return ret;
}
esp_err_t touch_pad_filter_start(uint32_t filter_period_ms)
{
RTC_MODULE_CHECK(filter_period_ms >= portTICK_PERIOD_MS, "Touch pad filter period error", ESP_ERR_INVALID_ARG);
RTC_MODULE_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_ERR_INVALID_STATE);
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
if (s_touch_pad_filter == NULL) {
s_touch_pad_filter = (touch_pad_filter_t *) calloc(1, sizeof(touch_pad_filter_t));
if (s_touch_pad_filter == NULL) {
goto err_no_mem;
}
}
if (s_touch_pad_filter->timer == NULL) {
s_touch_pad_filter->timer = xTimerCreate("filter_tmr", filter_period_ms / portTICK_PERIOD_MS, pdFALSE,
NULL, (void(*)(TimerHandle_t))touch_pad_filter_cb);
if (s_touch_pad_filter->timer == NULL) {
free(s_touch_pad_filter);
s_touch_pad_filter = NULL;
goto err_no_mem;
}
s_touch_pad_filter->period = filter_period_ms;
}
xSemaphoreGive(rtc_touch_mux);
touch_pad_filter_cb(NULL);
return ESP_OK;
err_no_mem:
xSemaphoreGive(rtc_touch_mux);
return ESP_ERR_NO_MEM;
}
esp_err_t touch_pad_filter_stop(void)
{
RTC_MODULE_CHECK(s_touch_pad_filter != NULL, "Touch pad filter not initialized", ESP_ERR_INVALID_STATE);
RTC_MODULE_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_ERR_INVALID_STATE);
esp_err_t ret = ESP_OK;
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
if (s_touch_pad_filter != NULL) {
xTimerStop(s_touch_pad_filter->timer, portMAX_DELAY);
} else {
ESP_LOGE(RTC_MODULE_TAG, "Touch pad filter deleted");
ret = ESP_ERR_INVALID_STATE;
}
xSemaphoreGive(rtc_touch_mux);
return ret;
}
esp_err_t touch_pad_filter_delete(void)
{
RTC_MODULE_CHECK(s_touch_pad_filter != NULL, "Touch pad filter not initialized", ESP_ERR_INVALID_STATE);
RTC_MODULE_CHECK(rtc_touch_mux != NULL, "Touch pad not initialized", ESP_ERR_INVALID_STATE);
xSemaphoreTake(rtc_touch_mux, portMAX_DELAY);
if (s_touch_pad_filter != NULL) {
if (s_touch_pad_filter->timer != NULL) {
xTimerStop(s_touch_pad_filter->timer, portMAX_DELAY);
xTimerDelete(s_touch_pad_filter->timer, portMAX_DELAY);
s_touch_pad_filter->timer = NULL;
}
free(s_touch_pad_filter);
s_touch_pad_filter = NULL;
}
xSemaphoreGive(rtc_touch_mux);
return ESP_OK;
}
esp_err_t touch_pad_get_wakeup_status(touch_pad_t *pad_num)
{
uint32_t touch_mask = SENS.sar_touch_ctrl2.touch_meas_en;
if(touch_mask == 0) {
return ESP_FAIL;
}
*pad_num = touch_pad_num_wrap((touch_pad_t)(__builtin_ffs(touch_mask) - 1));
return ESP_OK;
}
#endif
/*---------------------------------------------------------------
INTERRUPT HANDLER

View file

@ -0,0 +1,251 @@
// Copyright 2016-2018 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.
#include <esp_types.h>
#include <stdlib.h>
#include <ctype.h>
#include "esp_log.h"
#include "sys/lock.h"
#include "freertos/FreeRTOS.h"
#include "freertos/xtensa_api.h"
#include "freertos/semphr.h"
#include "freertos/timers.h"
#include "esp_intr_alloc.h"
#include "driver/rtc_io.h"
#include "driver/touch_pad.h"
#include "driver/rtc_cntl.h"
#include "driver/gpio.h"
#include "sdkconfig.h"
#if CONFIG_IDF_TARGET_ESP32
#include "esp32/rom/ets_sys.h"
#elif CONFIG_IDF_TARGET_ESP32S2BETA
#include "esp32s2beta/rom/ets_sys.h"
#endif
#include "hal/touch_sensor_types.h"
#include "hal/touch_sensor_hal.h"
static const char *TOUCH_TAG = "TOUCH_SENSOR";
#define TOUCH_CHECK(a, str, ret_val) ({ \
if (!(a)) { \
ESP_LOGE(TOUCH_TAG,"%s:%d (%s):%s", __FILE__, __LINE__, __FUNCTION__, str); \
return (ret_val); \
} \
})
#ifdef CONFIG_IDF_TARGET_ESP32
#define TOUCH_CHANNEL_CHECK(channel) do { \
TOUCH_CHECK(channel < SOC_TOUCH_SENSOR_NUM && channel >= 0, "Touch channel error", ESP_ERR_INVALID_ARG); \
} while (0);
#elif defined CONFIG_IDF_TARGET_ESP32S2BETA
#define TOUCH_CHANNEL_CHECK(channel) do { \
TOUCH_CHECK(channel < SOC_TOUCH_SENSOR_NUM && channel >= 0, "Touch channel error", ESP_ERR_INVALID_ARG); \
TOUCH_CHECK(channel != SOC_TOUCH_DENOISE_CHANNEL, "TOUCH0 is internal denoise channel", ESP_ERR_INVALID_ARG); \
} while (0);
#endif
#define TOUCH_GET_IO_NUM(channel) (touch_sensor_channel_io_map[channel])
_Static_assert(TOUCH_PAD_MAX == SOC_TOUCH_SENSOR_NUM, "Touch sensor channel number not equal to chip capabilities");
extern portMUX_TYPE rtc_spinlock; //TODO: Will be placed in the appropriate position after the rtc module is finished.
#define TOUCH_ENTER_CRITICAL() portENTER_CRITICAL(&rtc_spinlock)
#define TOUCH_EXIT_CRITICAL() portEXIT_CRITICAL(&rtc_spinlock)
esp_err_t touch_pad_isr_deregister(intr_handler_t fn, void *arg)
{
return rtc_isr_deregister(fn, arg);
}
esp_err_t touch_pad_set_voltage(touch_high_volt_t refh, touch_low_volt_t refl, touch_volt_atten_t atten)
{
TOUCH_CHECK(((refh < TOUCH_HVOLT_MAX) && (refh >= (int )TOUCH_HVOLT_KEEP)), "touch refh error",
ESP_ERR_INVALID_ARG);
TOUCH_CHECK(((refl < TOUCH_LVOLT_MAX) && (refh >= (int )TOUCH_LVOLT_KEEP)), "touch refl error",
ESP_ERR_INVALID_ARG);
TOUCH_CHECK(((atten < TOUCH_HVOLT_ATTEN_MAX) && (refh >= (int )TOUCH_HVOLT_ATTEN_KEEP)), "touch atten error",
ESP_ERR_INVALID_ARG);
const touch_hal_volt_t volt = {
.refh = refh,
.refl = refl,
.atten = atten,
};
TOUCH_ENTER_CRITICAL();
touch_hal_set_voltage(&volt);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_voltage(touch_high_volt_t *refh, touch_low_volt_t *refl, touch_volt_atten_t *atten)
{
touch_hal_volt_t volt = {0};
TOUCH_ENTER_CRITICAL();
touch_hal_get_voltage(&volt);
TOUCH_EXIT_CRITICAL();
*refh = volt.refh;
*refl = volt.refl;
*atten = volt.atten;
return ESP_OK;
}
esp_err_t touch_pad_set_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t slope, touch_tie_opt_t opt)
{
TOUCH_CHECK(touch_num < SOC_TOUCH_SENSOR_NUM, "Touch channel error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK(slope < TOUCH_PAD_SLOPE_MAX, "touch slope error", ESP_ERR_INVALID_ARG);
TOUCH_CHECK(opt < TOUCH_PAD_TIE_OPT_MAX, "touch opt error", ESP_ERR_INVALID_ARG);
const touch_hal_meas_mode_t meas = {
.slope = slope,
.tie_opt = opt,
};
TOUCH_ENTER_CRITICAL();
touch_hal_set_meas_mode(touch_num, &meas);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_get_cnt_mode(touch_pad_t touch_num, touch_cnt_slope_t *slope, touch_tie_opt_t *opt)
{
TOUCH_CHECK(touch_num < SOC_TOUCH_SENSOR_NUM, "Touch channel error", ESP_ERR_INVALID_ARG);
touch_hal_meas_mode_t meas = {0};
TOUCH_ENTER_CRITICAL();
touch_hal_get_meas_mode(touch_num, &meas);
TOUCH_EXIT_CRITICAL();
*slope = meas.slope;
*opt = meas.tie_opt;
return ESP_OK;
}
esp_err_t touch_pad_io_init(touch_pad_t touch_num)
{
TOUCH_CHANNEL_CHECK(touch_num);
gpio_num_t gpio_num = TOUCH_GET_IO_NUM(touch_num);
rtc_gpio_init(gpio_num);
rtc_gpio_set_direction(gpio_num, RTC_GPIO_MODE_DISABLED);
rtc_gpio_pulldown_dis(gpio_num);
rtc_gpio_pullup_dis(gpio_num);
return ESP_OK;
}
esp_err_t touch_pad_fsm_start(void)
{
TOUCH_ENTER_CRITICAL();
touch_hal_start_fsm();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_fsm_stop(void)
{
TOUCH_ENTER_CRITICAL();
touch_hal_stop_fsm();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
esp_err_t touch_pad_set_fsm_mode(touch_fsm_mode_t mode)
{
TOUCH_CHECK((mode < TOUCH_FSM_MODE_MAX), "touch fsm mode error", ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_set_fsm_mode(mode);
TOUCH_EXIT_CRITICAL();
#ifdef CONFIG_IDF_TARGET_ESP32
if (mode == TOUCH_FSM_MODE_TIMER) {
touch_pad_fsm_start();
} else {
touch_pad_fsm_stop();
}
#endif
return ESP_OK;
}
esp_err_t touch_pad_get_fsm_mode(touch_fsm_mode_t *mode)
{
touch_hal_get_fsm_mode(mode);
return ESP_OK;
}
esp_err_t touch_pad_sw_start(void)
{
TOUCH_ENTER_CRITICAL();
touch_hal_start_sw_meas();
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
#ifdef CONFIG_IDF_TARGET_ESP32
esp_err_t touch_pad_set_thresh(touch_pad_t touch_num, uint16_t threshold)
{
TOUCH_CHANNEL_CHECK(touch_num);
TOUCH_ENTER_CRITICAL();
touch_hal_set_threshold(touch_num, threshold);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
#elif defined CONFIG_IDF_TARGET_ESP32S2BETA
esp_err_t touch_pad_set_thresh(touch_pad_t touch_num, uint32_t threshold)
{
TOUCH_CHANNEL_CHECK(touch_num);
TOUCH_CHECK(touch_num != SOC_TOUCH_DENOISE_CHANNEL,
"TOUCH0 is internal denoise channel", ESP_ERR_INVALID_ARG);
TOUCH_ENTER_CRITICAL();
touch_hal_set_threshold(touch_num, threshold);
TOUCH_EXIT_CRITICAL();
return ESP_OK;
}
#endif
#ifdef CONFIG_IDF_TARGET_ESP32
esp_err_t touch_pad_get_thresh(touch_pad_t touch_num, uint16_t *threshold)
{
TOUCH_CHANNEL_CHECK(touch_num);
touch_hal_get_threshold(touch_num, threshold);
return ESP_OK;
}
#elif defined CONFIG_IDF_TARGET_ESP32S2BETA
esp_err_t touch_pad_get_thresh(touch_pad_t touch_num, uint32_t *threshold)
{
TOUCH_CHANNEL_CHECK(touch_num);
TOUCH_CHECK(touch_num != SOC_TOUCH_DENOISE_CHANNEL,
"TOUCH0 is internal denoise channel", ESP_ERR_INVALID_ARG);
touch_hal_get_threshold(touch_num, threshold);
return ESP_OK;
}
#endif
esp_err_t touch_pad_get_wakeup_status(touch_pad_t *pad_num)
{
touch_hal_get_wakeup_status(pad_num);
TOUCH_CHANNEL_CHECK(*pad_num);
return ESP_OK;
}
uint32_t IRAM_ATTR touch_pad_get_status(void)
{
uint32_t status = 0;
touch_hal_read_trigger_status_mask(&status);
return status;
}
esp_err_t IRAM_ATTR touch_pad_clear_status(void)
{
touch_hal_clear_trigger_status_mask();
return ESP_OK;
}

View file

@ -20,6 +20,7 @@ list(APPEND srcs
"src/hal/spi_hal_iram.c"
"src/hal/spi_slave_hal.c"
"src/hal/spi_slave_hal_iram.c"
"src/hal/touch_sensor_hal.c"
"src/soc_include_legacy_warn.c"
"src/hal/pcnt_hal.c"
"src/hal/i2s_hal.c"

View file

@ -0,0 +1,120 @@
// Copyright 2019 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.
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
// The HAL layer for touch sensor (esp32 specific part)
#pragma once
#include "hal/touch_sensor_ll.h"
#include "hal/touch_sensor_types.h"
/**
* Set touch sensor measurement time.
*
* @param meas_time The duration of the touch sensor measurement.
* t_meas = meas_time / (8MHz), the maximum measure time is 0xffff / 8M = 8.19 ms.
*/
#define touch_hal_set_meas_time(meas_time) touch_ll_set_meas_time(meas_time)
/**
* Get touch sensor measurement time.
*
* @param meas_time Pointer to accept measurement cycle count.
*/
#define touch_hal_get_meas_time(meas_time) touch_ll_get_meas_time(meas_time)
/**
* Set touch sensor interrupt trigger mode.
* Interrupt can be triggered either when touch value is less than
* threshold or when touch value is more than threshold.
*
* @param mode Touch sensor interrupt trigger mode.
*/
#define touch_hal_set_trigger_mode(mode) touch_ll_set_trigger_mode(mode)
/**
* Get touch sensor interrupt trigger mode.
* Interrupt can be triggered either when touch value is less than
* threshold or when touch value is more than threshold.
*
* @param mode Touch sensor interrupt trigger mode.
*/
#define touch_hal_get_trigger_mode(mode) touch_ll_get_trigger_mode(mode)
/**
* Set touch sensor interrupt trigger source. There are two sets of touch signals.
* Set1 and set2 can be mapped to several touch signals. Either set will be triggered
* if at least one of its touch signal is 'touched'. The interrupt can be configured to be generated
* if set1 is triggered, or only if both sets are triggered.
*
* @param src Touch sensor interrupt trigger source.
*/
#define touch_hal_set_trigger_source(src) touch_ll_set_trigger_source(src)
/**
* Get touch sensor interrupt trigger source.
*
* @param src Pointer to accept touch sensor interrupt trigger source.
*/
#define touch_hal_get_trigger_source(src) touch_ll_get_trigger_source(src)
/**
* Set touch sensor group mask.
* Touch pad module has two sets of signals, 'Touched' signal is triggered only if
* at least one of touch pad in this group is "touched".
* This function will set the register bits according to the given bitmask.
*
* @param set1_mask bitmask of touch sensor signal group1, it's a 10-bit value
* @param set2_mask bitmask of touch sensor signal group2, it's a 10-bit value
*/
#define touch_hal_set_group_mask(group1_mask, group2_mask) touch_ll_set_group_mask(group1_mask, group2_mask)
/**
* Get touch sensor group mask.
*
* @param set1_mask pointer to accept bitmask of touch sensor signal group1, it's a 10-bit value
* @param set2_mask pointer to accept bitmask of touch sensor signal group2, it's a 10-bit value
*/
#define touch_hal_get_group_mask(group1_mask, group2_mask) touch_ll_get_group_mask(group1_mask, group2_mask)
/**
* Clear touch sensor group mask.
*
* @param set1_mask pointer to accept bitmask of touch sensor signal group1, it's a 10-bit value
* @param set2_mask pointer to accept bitmask of touch sensor signal group2, it's a 10-bit value
*/
#define touch_hal_clear_group_mask(group1_mask, group2_mask) touch_ll_clear_group_mask(group1_mask, group2_mask)
/**
* To enable touch pad interrupt.
*/
#define touch_hal_enable_interrupt() touch_ll_enable_interrupt()
/**
* To disable touch pad interrupt.
*/
#define touch_hal_disable_interrupt() touch_ll_disable_interrupt()
/**
* Get the touch pad which caused wakeup from deep sleep.
*
* @param pad_num pointer to touch pad which caused wakeup.
*/
void touch_hal_get_wakeup_status(touch_pad_t *pad_num);

View file

@ -0,0 +1,490 @@
// Copyright 2015-2019 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.
/*******************************************************************************
* NOTICE
* The ll is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
// The Lowlevel layer for Touch Sensor
#pragma once
#include <stdlib.h>
#include <stdbool.h>
#include "soc/touch_sensor_periph.h"
#include "hal/touch_sensor_types.h"
//Some register bits of touch sensor 8 and 9 are mismatched, we need to swap the bits.
#define TOUCH_LL_BIT_SWAP(data, n, m) (((data >> n) & 0x1) == ((data >> m) & 0x1) ? (data) : ((data) ^ ((0x1 <<n) | (0x1 << m))))
#define TOUCH_LL_BITS_SWAP(v) TOUCH_LL_BIT_SWAP(v, TOUCH_PAD_NUM8, TOUCH_PAD_NUM9)
/**
* Swap the number of touch8 and touch9.
*
* @touch_num Touch channel num.
*/
static inline touch_pad_t touch_ll_num_wrap(touch_pad_t touch_num)
{
if (touch_num == TOUCH_PAD_NUM8) {
return TOUCH_PAD_NUM9;
} else if (touch_num == TOUCH_PAD_NUM9) {
return TOUCH_PAD_NUM8;
}
return touch_num;
}
/**
* Set touch sensor measurement time.
*
* @param meas_time The duration of the touch sensor measurement.
* t_meas = meas_time / (8MHz), the maximum measure time is 0xffff / 8M = 8.19 ms.
*/
static inline void touch_ll_set_meas_time(uint16_t meas_time)
{
//touch sensor measure time= meas_cycle / 8Mhz
SENS.sar_touch_ctrl1.touch_meas_delay = meas_time;
//the waiting cycles (in 8MHz) between TOUCH_START and TOUCH_XPD
SENS.sar_touch_ctrl1.touch_xpd_wait = SOC_TOUCH_PAD_MEASURE_WAIT;
}
/**
* Get touch sensor measurement time.
*
* @param meas_time Pointer to accept measurement cycle count.
*/
static inline void touch_ll_get_meas_time(uint16_t *meas_time)
{
*meas_time = SENS.sar_touch_ctrl1.touch_meas_delay;
}
/**
* Set touch sensor sleep time (interval of measurement).
*
* @param sleep_time The touch sensor will sleep after each measurement.
* sleep_cycle decide the interval between each measurement.
* t_sleep = sleep_cycle / (RTC_SLOW_CLK frequency).
* The approximate frequency value of RTC_SLOW_CLK can be obtained using `rtc_clk_slow_freq_get_hz` function.
*/
static inline void touch_ll_set_sleep_time(uint16_t sleep_time)
{
//touch sensor sleep cycle Time = sleep_cycle / RTC_SLOW_CLK( can be 150k or 32k depending on the options)
SENS.sar_touch_ctrl2.touch_sleep_cycles = sleep_time;
}
/**
* Get touch sensor sleep time.
*
* @param sleep_time Pointer to accept sleep cycle count.
*/
static inline void touch_ll_get_sleep_time(uint16_t *sleep_time)
{
*sleep_time = SENS.sar_touch_ctrl1.touch_meas_delay;
}
/**
* Set touch sensor high voltage threshold of chanrge.
* The touch sensor measures the channel capacitance value by charging and discharging the channel.
* So the high threshold should be less than the supply voltage.
*
* @param refh The high voltage threshold of chanrge.
*/
static inline void touch_ll_set_voltage_high(touch_high_volt_t refh)
{
RTCIO.touch_cfg.drefh = refh;
}
/**
* Get touch sensor high voltage threshold of chanrge.
* The touch sensor measures the channel capacitance value by charging and discharging the channel.
* So the high threshold should be less than the supply voltage.
*
* @param refh The high voltage threshold of chanrge.
*/
static inline void touch_ll_get_voltage_high(touch_high_volt_t *refh)
{
*refh = (touch_high_volt_t)RTCIO.touch_cfg.drefh;
}
/**
* Set touch sensor low voltage threshold of discharge.
* The touch sensor measures the channel capacitance value by charging and discharging the channel.
*
* @param refl The low voltage threshold of discharge.
*/
static inline void touch_ll_set_voltage_low(touch_low_volt_t refl)
{
RTCIO.touch_cfg.drefl = refl;
}
/**
* Get touch sensor low voltage threshold of discharge.
* The touch sensor measures the channel capacitance value by charging and discharging the channel.
*
* @param refl The low voltage threshold of discharge.
*/
static inline void touch_ll_get_voltage_low(touch_low_volt_t *refl)
{
*refl = (touch_low_volt_t)RTCIO.touch_cfg.drefl;
}
/**
* Set touch sensor high voltage attenuation of chanrge. The actual charge threshold is high voltage threshold minus attenuation value.
* The touch sensor measures the channel capacitance value by charging and discharging the channel.
* So the high threshold should be less than the supply voltage.
*
* @param refh The high voltage threshold of chanrge.
*/
static inline void touch_ll_set_voltage_attenuation(touch_volt_atten_t atten)
{
RTCIO.touch_cfg.drange = atten;
}
/**
* Get touch sensor high voltage attenuation of chanrge. The actual charge threshold is high voltage threshold minus attenuation value.
* The touch sensor measures the channel capacitance value by charging and discharging the channel.
* So the high threshold should be less than the supply voltage.
*
* @param refh The high voltage threshold of chanrge.
*/
static inline void touch_ll_get_voltage_attenuation(touch_volt_atten_t *atten)
{
*atten = (touch_volt_atten_t)RTCIO.touch_cfg.drange;
}
/**
* Set touch sensor charge/discharge speed(currents) for each pad.
* If the slope is 0, the counter would always be zero.
* If the slope is 1, the charging and discharging would be slow. The measurement time becomes longer.
* If the slope is set 7, which is the maximum value, the charging and discharging would be fast.
* The measurement time becomes shorter.
*
* @note The higher the charge and discharge current, the greater the immunity of the touch channel,
* but it will increase the system power consumption.
* @param touch_num Touch pad index.
* @param slope touch pad charge/discharge speed(currents).
*/
static inline void touch_ll_set_slope(touch_pad_t touch_num, touch_cnt_slope_t slope)
{
RTCIO.touch_pad[touch_num].dac = slope;
}
/**
* Get touch sensor charge/discharge speed(currents) for each pad.
* If the slope is 0, the counter would always be zero.
* If the slope is 1, the charging and discharging would be slow. The measurement time becomes longer.
* If the slope is set 7, which is the maximum value, the charging and discharging would be fast.
* The measurement time becomes shorter.
*
* @param touch_num Touch pad index.
* @param slope touch pad charge/discharge speed(currents).
*/
static inline void touch_ll_get_slope(touch_pad_t touch_num, touch_cnt_slope_t *slope)
{
*slope = (touch_cnt_slope_t)RTCIO.touch_pad[touch_num].dac;
}
/**
* Set initial voltage state of touch channel for each measurement.
*
* @param touch_num Touch pad index.
* @param opt Initial voltage state.
*/
static inline void touch_ll_set_tie_option(touch_pad_t touch_num, touch_tie_opt_t opt)
{
touch_pad_t touch_pad_wrap = touch_ll_num_wrap(touch_num);
RTCIO.touch_pad[touch_pad_wrap].tie_opt = opt;
}
/**
* Get initial voltage state of touch channel for each measurement.
*
* @param touch_num Touch pad index.
* @param opt Initial voltage state.
*/
static inline void touch_ll_get_tie_option(touch_pad_t touch_num, touch_tie_opt_t *opt)
{
touch_pad_t touch_pad_wrap = touch_ll_num_wrap(touch_num);
*opt = (touch_tie_opt_t)RTCIO.touch_pad[touch_pad_wrap].tie_opt;
}
/**
* Set touch sensor FSM mode.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
*
* @param mode FSM mode.
*/
static inline void touch_ll_set_fsm_mode(touch_fsm_mode_t mode)
{
SENS.sar_touch_ctrl2.touch_start_en = 0;
SENS.sar_touch_ctrl2.touch_start_force = mode;
}
/**
* Get touch sensor FSM mode.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
*
* @param mode FSM mode.
*/
static inline void touch_ll_get_fsm_mode(touch_fsm_mode_t *mode)
{
*mode = (touch_fsm_mode_t)SENS.sar_touch_ctrl2.touch_start_force;
}
/**
* Start touch sensor FSM timer.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
*
* @param mode FSM mode.
*/
static inline void touch_ll_start_fsm(void)
{
RTCCNTL.state0.touch_slp_timer_en = 1;
}
/**
* Stop touch sensor FSM timer.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
*
* @param mode FSM mode.
*/
static inline void touch_ll_stop_fsm(void)
{
RTCCNTL.state0.touch_slp_timer_en = 0;
}
/**
* Trigger a touch sensor measurement, only support in SW mode of FSM.
*/
static inline void touch_ll_start_sw_meas(void)
{
SENS.sar_touch_ctrl2.touch_start_en = 0;
SENS.sar_touch_ctrl2.touch_start_en = 1;
}
/**
* Set touch sensor interrupt threshold.
*
* @note Refer to `touch_pad_set_trigger_mode` to see how to set trigger mode.
* @param touch_num touch pad index.
* @param threshold threshold of touchpad count.
*/
static inline void touch_ll_set_threshold(touch_pad_t touch_num, uint16_t threshold)
{
touch_pad_t tp_wrap = touch_ll_num_wrap(touch_num);
if (tp_wrap & 0x1) {
SENS.touch_thresh[tp_wrap / 2].l_thresh = threshold;
} else {
SENS.touch_thresh[tp_wrap / 2].h_thresh = threshold;
}
}
/**
* Get touch sensor interrupt threshold.
*
* @param touch_num touch pad index.
* @param threshold pointer to accept threshold.
*/
static inline void touch_ll_get_threshold(touch_pad_t touch_num, uint16_t *threshold)
{
touch_pad_t tp_wrap = touch_ll_num_wrap(touch_num);
if (threshold) {
*threshold = (tp_wrap & 0x1 ) ?
SENS.touch_thresh[tp_wrap / 2].l_thresh :
SENS.touch_thresh[tp_wrap / 2].h_thresh;
}
}
/**
* Set touch sensor interrupt trigger mode.
* Interrupt can be triggered either when touch value is less than
* threshold or when touch value is more than threshold.
*
* @param mode Touch sensor interrupt trigger mode.
*/
static inline void touch_ll_set_trigger_mode(touch_trigger_mode_t mode)
{
SENS.sar_touch_ctrl1.touch_out_sel = mode;
}
/**
* Get touch sensor interrupt trigger mode.
* Interrupt can be triggered either when touch value is less than
* threshold or when touch value is more than threshold.
*
* @param mode Touch sensor interrupt trigger mode.
*/
static inline void touch_ll_get_trigger_mode(touch_trigger_mode_t *mode)
{
*mode = (touch_trigger_mode_t)SENS.sar_touch_ctrl1.touch_out_sel;
}
/**
* Set touch sensor interrupt trigger source. There are two sets of touch signals.
* Set1 and set2 can be mapped to several touch signals. Either set will be triggered
* if at least one of its touch signal is 'touched'. The interrupt can be configured to be generated
* if set1 is triggered, or only if both sets are triggered.
*
* @param src Touch sensor interrupt trigger source.
*/
static inline void touch_ll_set_trigger_source(touch_trigger_src_t src)
{
SENS.sar_touch_ctrl1.touch_out_1en = src;
}
/**
* Get touch sensor interrupt trigger source.
*
* @param src Pointer to accept touch sensor interrupt trigger source.
*/
static inline void touch_ll_get_trigger_source(touch_trigger_src_t *src)
{
*src = (touch_trigger_src_t)SENS.sar_touch_ctrl1.touch_out_1en;
}
/**
* Enable touch sensor channel. Register touch channel into touch sensor measurement group.
* The working mode of the touch sensor is simultaneous measurement.
* This function will set the measure bits according to the given bitmask.
*
* @note If set this mask, the FSM timer should be stop firsty.
* @note The touch sensor that in scan map, should be deinit GPIO function firstly.
* @param enable_mask bitmask of touch sensor scan group.
* e.g. TOUCH_PAD_NUM1 -> BIT(1)
* @return
* - ESP_OK on success
*/
static inline void touch_ll_set_channel_mask(uint16_t enable_mask)
{
SENS.sar_touch_enable.touch_pad_worken |= TOUCH_LL_BITS_SWAP(enable_mask);
}
/**
* Get touch sensor channel mask.
*
* @param enable_mask bitmask of touch sensor scan group.
* e.g. TOUCH_PAD_NUM1 -> BIT(1)
*/
static inline void touch_ll_get_channel_mask(uint16_t *enable_mask)
{
*enable_mask = TOUCH_LL_BITS_SWAP(SENS.sar_touch_enable.touch_pad_worken);
}
/**
* Disable touch sensor channel by bitmask.
*
* @param enable_mask bitmask of touch sensor scan group.
* e.g. TOUCH_PAD_NUM1 -> BIT(1)
*/
static inline void touch_ll_clear_channel_mask(uint16_t disable_mask)
{
SENS.sar_touch_enable.touch_pad_worken &= TOUCH_LL_BITS_SWAP(~disable_mask);
}
/**
* Set touch sensor group mask.
* Touch pad module has two sets of signals, 'Touched' signal is triggered only if
* at least one of touch pad in this group is "touched".
* This function will set the register bits according to the given bitmask.
*
* @param set1_mask bitmask of touch sensor signal group1, it's a 10-bit value
* @param set2_mask bitmask of touch sensor signal group2, it's a 10-bit value
*/
static inline void touch_ll_set_group_mask(uint16_t group1_mask, uint16_t group2_mask)
{
SENS.sar_touch_enable.touch_pad_outen1 |= TOUCH_LL_BITS_SWAP(group1_mask);
SENS.sar_touch_enable.touch_pad_outen2 |= TOUCH_LL_BITS_SWAP(group2_mask);
}
/**
* Get touch sensor group mask.
*
* @param set1_mask pointer to accept bitmask of touch sensor signal group1, it's a 10-bit value
* @param set2_mask pointer to accept bitmask of touch sensor signal group2, it's a 10-bit value
*/
static inline void touch_ll_get_group_mask(uint16_t *group1_mask, uint16_t *group2_mask)
{
*group1_mask = TOUCH_LL_BITS_SWAP(SENS.sar_touch_enable.touch_pad_outen1);
*group2_mask = TOUCH_LL_BITS_SWAP(SENS.sar_touch_enable.touch_pad_outen2);
}
/**
* Clear touch sensor group mask.
*
* @param set1_mask pointer to accept bitmask of touch sensor signal group1, it's a 10-bit value
* @param set2_mask pointer to accept bitmask of touch sensor signal group2, it's a 10-bit value
*/
static inline void touch_ll_clear_group_mask(uint16_t group1_mask, uint16_t group2_mask)
{
SENS.sar_touch_enable.touch_pad_outen1 &= TOUCH_LL_BITS_SWAP(~group1_mask);
SENS.sar_touch_enable.touch_pad_outen2 &= TOUCH_LL_BITS_SWAP(~group2_mask);
}
/**
* Get the touch sensor status, usually used in ISR to decide which pads are 'touched'.
*
* @param status_mask The touch sensor status. e.g. Touch1 trigger status is `status_mask & (BIT1)`.
*/
static inline void touch_ll_read_trigger_status_mask(uint32_t *status_mask)
{
*status_mask = TOUCH_LL_BITS_SWAP(SENS.sar_touch_ctrl2.touch_meas_en);
}
/**
* Clear all touch sensor status.
*/
static inline void touch_ll_clear_trigger_status_mask(void)
{
SENS.sar_touch_ctrl2.touch_meas_en_clr = 1;
}
/**
* To enable touch pad interrupt.
*/
static inline void touch_ll_enable_interrupt(void)
{
RTCCNTL.int_ena.rtc_touch = 1;
}
/**
* To disable touch pad interrupt.
*/
static inline void touch_ll_disable_interrupt(void)
{
RTCCNTL.int_ena.rtc_touch = 0;
}
/**
* Get touch sensor raw data (touch sensor counter value) from register. No block.
*
* @param touch_num touch pad index.
* @return touch_value pointer to accept touch sensor value.
*/
static inline uint32_t touch_ll_read_raw_data(touch_pad_t touch_num)
{
touch_pad_t tp_wrap = touch_ll_num_wrap(touch_num);
return ((tp_wrap & 0x1) ? SENS.touch_meas[tp_wrap / 2].l_val : SENS.touch_meas[tp_wrap / 2].h_val);
}
/**
* Get touch sensor measure status. No block.
*
* @return
* - If touch sensors measure done.
*/
static inline bool touch_ll_meas_is_done(void)
{
return (bool)SENS.sar_touch_ctrl2.touch_meas_done;
}

View file

@ -0,0 +1,29 @@
// Copyright 2019 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.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#define SOC_TOUCH_SENSOR_NUM (10)
#define SOC_TOUCH_SENSOR_BIT_MASK_MAX (0x3ff)
#define SOC_TOUCH_PAD_MEASURE_WAIT (0xFF) /*!<The timer frequency is 8Mhz, the max value is 0xff */
#define SOC_TOUCH_PAD_THRESHOLD_MAX (0) /*!<If set touch threshold max value, The touch sensor can't be in touched status */
#ifdef __cplusplus
}
#endif

View file

@ -1,4 +1,4 @@
// Copyright 2010-2016 Espressif Systems (Shanghai) PTE LTD
// Copyright 2019 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.

View file

@ -20,7 +20,8 @@ set(SOC_SRCS "adc_periph.c"
"i2s_periph.c"
"i2c_periph.c"
"uart_periph.c"
)
"touch_sensor_hal.c"
"touch_sensor_periph.c")
if(NOT BOOTLOADER_BUILD AND CONFIG_ETH_USE_ESP32_EMAC)
list(APPEND SOC_SRCS "emac_hal.c")

View file

@ -0,0 +1,49 @@
// Copyright 2015-2019 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.
// The HAL layer for SPI (common part)
#include "hal/touch_sensor_hal.h"
#include "hal/touch_sensor_types.h"
void touch_hal_init(void)
{
touch_ll_disable_interrupt();
touch_ll_clear_channel_mask(SOC_TOUCH_SENSOR_BIT_MASK_MAX);
touch_ll_clear_group_mask(SOC_TOUCH_SENSOR_BIT_MASK_MAX, SOC_TOUCH_SENSOR_BIT_MASK_MAX);
touch_ll_set_trigger_mode(TOUCH_TRIGGER_MODE_DEFAULT);
touch_ll_set_trigger_source(TOUCH_TRIGGER_SOURCE_DEFAULT);
touch_ll_clear_trigger_status_mask();
touch_ll_set_meas_time(TOUCH_PAD_MEASURE_CYCLE_DEFAULT);
touch_ll_set_sleep_time(TOUCH_PAD_SLEEP_CYCLE_DEFAULT);
touch_ll_set_fsm_mode(TOUCH_FSM_MODE_DEFAULT);
touch_ll_start_fsm();
}
void touch_hal_deinit(void)
{
touch_ll_stop_fsm();
touch_ll_clear_trigger_status_mask();
touch_ll_disable_interrupt();
}
void touch_hal_get_wakeup_status(touch_pad_t *pad_num)
{
uint32_t touch_mask = 0;
touch_hal_read_trigger_status_mask(&touch_mask);
if (touch_mask == 0) {
*pad_num = -1;
}
*pad_num = (touch_pad_t)(__builtin_ffs(touch_mask) - 1);
}

View file

@ -0,0 +1,29 @@
// Copyright 2015-2019 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.
#include "soc/touch_sensor_periph.h"
/* Store IO number corresponding to the Touch Sensor channel number. */
const int touch_sensor_channel_io_map[SOC_TOUCH_SENSOR_NUM] = {
TOUCH_PAD_NUM0_GPIO_NUM,
TOUCH_PAD_NUM1_GPIO_NUM,
TOUCH_PAD_NUM2_GPIO_NUM,
TOUCH_PAD_NUM3_GPIO_NUM,
TOUCH_PAD_NUM4_GPIO_NUM,
TOUCH_PAD_NUM5_GPIO_NUM,
TOUCH_PAD_NUM6_GPIO_NUM,
TOUCH_PAD_NUM7_GPIO_NUM,
TOUCH_PAD_NUM8_GPIO_NUM,
TOUCH_PAD_NUM9_GPIO_NUM
};

View file

@ -0,0 +1,572 @@
// Copyright 2019 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.
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
// The HAL layer for touch sensor (esp32s2beta specific part)
#pragma once
#include "hal/touch_sensor_ll.h"
#include "hal/touch_sensor_types.h"
/**
* Reset the whole of touch module.
*
* @note Call this funtion after `touch_pad_fsm_stop`,
*/
#define touch_hal_reset() touch_ll_reset()
/**
* Set touch sensor measurement time.
*
* @param meas_time The duration of the touch sensor measurement.
* t_meas = meas_time / (8MHz), the maximum measure time is 0xffff / 8M = 8.19 ms.
*/
#define touch_hal_set_meas_times(meas_time) touch_ll_set_meas_times(meas_time)
/**
* Get touch sensor times of charge and discharge.
*
* @param meas_times Pointer to accept times count of charge and discharge.
*/
#define touch_hal_get_measure_times(meas_time) touch_ll_get_measure_times(meas_time)
/**
* Set connection type of touch channel in idle status.
* When a channel is in measurement mode, other initialized channels are in idle mode.
* The touch channel is generally adjacent to the trace, so the connection state of the idle channel
* affects the stability and sensitivity of the test channel.
* The `CONN_HIGHZ`(high resistance) setting increases the sensitivity of touch channels.
* The `CONN_GND`(grounding) setting increases the stability of touch channels.
*
* @param type Select idle channel connect to high resistance state or ground.
*/
#define touch_hal_set_inactive_connect(type) touch_ll_set_inactive_connect(type)
/**
* Set connection type of touch channel in idle status.
* When a channel is in measurement mode, other initialized channels are in idle mode.
* The touch channel is generally adjacent to the trace, so the connection state of the idle channel
* affects the stability and sensitivity of the test channel.
* The `CONN_HIGHZ`(high resistance) setting increases the sensitivity of touch channels.
* The `CONN_GND`(grounding) setting increases the stability of touch channels.
*
* @param type Select idle channel connect to high resistance state or ground.
*/
#define touch_hal_get_inactive_connect(type) touch_ll_get_inactive_connect(type)
/**
* Get the current measure channel. Touch sensor measurement is cyclic scan mode.
*
* @return
* - touch channel number
*/
#define touch_hal_get_current_meas_channel() touch_ll_get_current_meas_channel()
/**
* Enable touch sensor interrupt by bitmask.
*
* @param type interrupt type
*/
#define touch_hal_intr_enable(int_mask) touch_ll_intr_enable(int_mask)
/**
* Disable touch sensor interrupt by bitmask.
*
* @param type interrupt type
*/
#define touch_hal_intr_disable(int_mask) touch_ll_intr_disable(int_mask)
/**
* Get the bitmask of touch sensor interrupt status.
*
* @return type interrupt type
*/
#define touch_hal_read_intr_status_mask() touch_ll_read_intr_status_mask()
/************************ Filter register setting ************************/
/**
* Set parameter of touch sensor filter and detection algorithm.
* For more details on the detection algorithm, please refer to the application documentation.
*
* @param filter_info select filter type and threshold of detection algorithm
*/
void touch_hal_filter_set_config(const touch_filter_config_t *filter_info);
/**
* Get parameter of touch sensor filter and detection algorithm.
* For more details on the detection algorithm, please refer to the application documentation.
*
* @param filter_info select filter type and threshold of detection algorithm
*/
void touch_hal_filter_get_config(touch_filter_config_t *filter_info);
/**
* Get baseline value of touch sensor.
*
* @note After initialization, the baseline value is the maximum during the first measurement period.
* @param touch_num touch pad index
* @param touch_value pointer to accept touch sensor value
*/
#define touch_hal_filter_read_baseline(touch_num, basedata) touch_ll_filter_read_baseline(touch_num, basedata)
/**
* Force reset baseline to raw data of touch sensor.
*
* @param touch_num touch pad index
* - TOUCH_PAD_MAX Reset basaline of all channels.
*/
#define touch_hal_filter_reset_baseline(touch_num) touch_ll_filter_reset_baseline(touch_num)
/**
* Set filter mode. The input to the filter is raw data and the output is the baseline value.
* Larger filter coefficients increase the stability of the baseline.
*
* @param mode Filter mode type. Refer to `touch_filter_mode_t`.
*/
#define touch_hal_filter_set_filter_mode(mode) touch_ll_filter_set_filter_mode(mode)
/**
* Get filter mode. The input to the filter is raw data and the output is the baseline value.
*
* @param mode Filter mode type. Refer to `touch_filter_mode_t`.
*/
#define touch_hal_filter_get_filter_mode(mode) touch_ll_filter_get_filter_mode(mode)
/**
* Set debounce count, such as `n`. If the measured values continue to exceed
* the threshold for `n` times, it is determined that the touch sensor state changes.
*
* @param dbc_cnt Debounce count value.
*/
#define touch_hal_filter_set_debounce(dbc_cnt) touch_ll_filter_set_debounce(dbc_cnt)
/**
* Get debounce count.
*
* @param dbc_cnt Debounce count value.
*/
#define touch_hal_filter_get_debounce(dbc_cnt) touch_ll_filter_get_debounce(dbc_cnt)
/**
* Set hysteresis threshold coefficient. hysteresis = hysteresis_thr * touch_threshold.
* If (raw data - baseline) > (touch threshold + hysteresis), the touch channel be touched.
* If (raw data - baseline) < (touch threshold - hysteresis), the touch channel be released.
* Range: 0 ~ 3. The coefficient is 0: 1/8; 1: 3/32; 2: 1/16; 3: 1/32
*
* @param hys_thr hysteresis coefficient.
*/
#define touch_hal_filter_set_hysteresis(hys_thr) touch_ll_filter_set_hysteresis(hys_thr)
/**
* Get hysteresis threshold coefficient. hysteresis = hysteresis_thr * touch_threshold.
* If (raw data - baseline) > (touch threshold + hysteresis), the touch channel be touched.
* If (raw data - baseline) < (touch threshold - hysteresis), the touch channel be released.
* Range: 0 ~ 3. The coefficient is 0: 1/8; 1: 3/32; 2: 1/16; 3: 1/32
*
* @param hys_thr hysteresis coefficient.
*/
#define touch_hal_filter_get_hysteresis(hys_thr) touch_ll_filter_get_hysteresis(hys_thr)
/**
* Set noise threshold coefficient. noise = noise_thr * touch threshold.
* If (raw data - baseline) > (noise), the baseline stop updating.
* If (raw data - baseline) < (noise), the baseline start updating.
* Range: 0 ~ 3. The coefficient is 0: 1/2; 1: 3/8; 2: 1/4; 3: 1/8;
*
* @param hys_thr Noise threshold coefficient.
*/
#define touch_hal_filter_set_noise_thres(noise_thr) touch_ll_filter_set_noise_thres(noise_thr)
/**
* Get noise threshold coefficient. noise = noise_thr * touch threshold.
* If (raw data - baseline) > (noise), the baseline stop updating.
* If (raw data - baseline) < (noise), the baseline start updating.
* Range: 0 ~ 3. The coefficient is 0: 1/2; 1: 3/8; 2: 1/4; 3: 1/8;
*
* @param noise_thr Noise threshold coefficient.
*/
#define touch_hal_filter_get_noise_thres(noise_thr) touch_ll_filter_get_noise_thres(noise_thr)
/**
* Set negative noise threshold coefficient. negative noise = noise_neg_thr * touch threshold.
* If (baseline - raw data) > (negative noise), the baseline restart reset process(refer to `baseline_reset`).
* If (baseline - raw data) < (negative noise), the baseline stop reset process(refer to `baseline_reset`).
* Range: 0 ~ 3. The coefficient is 0: 1/2; 1: 3/8; 2: 1/4; 3: 1/8;
*
* @param noise_thr Negative threshold coefficient.
*/
#define touch_hal_filter_set_neg_noise_thres(noise_thr) touch_ll_filter_set_neg_noise_thres(noise_thr)
/**
* Get negative noise threshold coefficient. negative noise = noise_neg_thr * touch threshold.
* If (baseline - raw data) > (negative noise), the baseline restart reset process(refer to `baseline_reset`).
* If (baseline - raw data) < (negative noise), the baseline stop reset process(refer to `baseline_reset`).
* Range: 0 ~ 3. The coefficient is 0: 1/2; 1: 3/8; 2: 1/4; 3: 1/8;
*
* @param noise_thr Negative noise threshold coefficient.
*/
#define touch_hal_filter_get_neg_noise_thres(noise_thr) touch_ll_filter_get_neg_noise_thres(noise_thr)
/**
* Set the cumulative number of baseline reset processes. such as `n`. If the measured values continue to exceed
* the negative noise threshold for `n` times, the baseline reset to raw data.
* Range: 0 ~ 15
*
* @param reset_cnt The cumulative number of baseline reset processes.
*/
#define touch_hal_filter_set_baseline_reset(reset_cnt) touch_ll_filter_set_baseline_reset(reset_cnt)
/**
* Get the cumulative number of baseline reset processes. such as `n`. If the measured values continue to exceed
* the negative noise threshold for `n` times, the baseline reset to raw data.
* Range: 0 ~ 15
*
* @param reset_cnt The cumulative number of baseline reset processes.
*/
#define touch_hal_filter_get_baseline_reset(reset_cnt) touch_ll_filter_get_baseline_reset(reset_cnt)
/**
* Set jitter filter step size.
* If filter mode is jitter, should set filter step for jitter.
* Range: 0 ~ 15
*
* @param step The step size of the data change when the baseline is updated.
*/
#define touch_hal_filter_set_jitter_step(step) touch_ll_filter_set_jitter_step(step)
/**
* Get jitter filter step size.
* If filter mode is jitter, should set filter step for jitter.
* Range: 0 ~ 15
*
* @param step The step size of the data change when the baseline is updated.
*/
#define touch_hal_filter_get_jitter_step(step) touch_ll_filter_get_jitter_step(step)
/**
* Enable touch sensor filter and detection algorithm.
* For more details on the detection algorithm, please refer to the application documentation.
*/
#define touch_hal_filter_enable() touch_ll_filter_enable()
/**
* Disable touch sensor filter and detection algorithm.
* For more details on the detection algorithm, please refer to the application documentation.
*/
#define touch_hal_filter_disable() touch_ll_filter_disable()
/************************ Denoise register setting ************************/
/**
* set parameter of denoise pad (TOUCH_PAD_NUM0).
* T0 is an internal channel that does not have a corresponding external GPIO.
* T0 will work simultaneously with the measured channel Tn. Finally, the actual
* measured value of Tn is the value after subtracting lower bits of T0.
* This denoise function filters out interference introduced on all channels,
* such as noise introduced by the power supply and external EMI.
*
* @param denoise parameter of denoise
*/
void touch_hal_denoise_set_config(const touch_pad_denoise_t *denoise);
/**
* @brief get parameter of denoise pad (TOUCH_PAD_NUM0).
*
* @param denoise Pointer to parameter of denoise
*/
void touch_hal_denoise_get_config(touch_pad_denoise_t *denoise);
/**
* Enable denoise function.
* T0 is an internal channel that does not have a corresponding external GPIO.
* T0 will work simultaneously with the measured channel Tn. Finally, the actual
* measured value of Tn is the value after subtracting lower bits of T0.
* This denoise function filters out interference introduced on all channels,
* such as noise introduced by the power supply and external EMI.
*/
void touch_hal_denoise_enable(void);
/**
* Enable denoise function.
* T0 is an internal channel that does not have a corresponding external GPIO.
* T0 will work simultaneously with the measured channel Tn. Finally, the actual
* measured value of Tn is the value after subtracting lower bits of T0.
* This denoise function filters out interference introduced on all channels,
* such as noise introduced by the power supply and external EMI.
*/
#define touch_hal_denoise_disable() touch_ll_denoise_disable()
/**
* Set internal reference capacitance of denoise channel.
* Select the appropriate internal reference capacitance value so that
* the reading of denoise channel is closest to the reading of the channel being measured.
*
* @param cap_level Capacitance level.
*/
#define touch_hal_denoise_set_cap_level(cap_level) touch_ll_denoise_set_cap_level(cap_level)
/**
* Get internal reference capacitance of denoise channel.
* Select the appropriate internal reference capacitance value so that
* the reading of denoise channel is closest to the reading of the channel being measured.
*
* @param cap_level Capacitance level.
*/
#define touch_hal_denoise_get_cap_level(cap_level) touch_ll_denoise_get_cap_level(cap_level)
/**
* Set denoise range of denoise channel.
* Determined by measuring the noise amplitude of the denoise channel.
*
* @param grade Denoise range of denoise channel.
*/
#define touch_hal_denoise_set_grade(grade) touch_ll_denoise_set_grade(grade)
/**
* Set denoise range of denoise channel.
* Determined by measuring the noise amplitude of the denoise channel.
*
* @param grade Denoise range of denoise channel.
*/
#define touch_hal_denoise_get_grade(grade) touch_ll_denoise_get_grade(grade)
/**
* Read denoise measure value (TOUCH_PAD_NUM0).
*
* @param denoise value of denoise.
*/
#define touch_hal_denoise_read_data(data) touch_ll_denoise_read_data(data)
/************************ Waterproof register setting ************************/
/**
* Set touch channel use for guard pad.
*
* @param pad_num Touch sensor channel number.
*/
#define touch_hal_waterproof_set_guard_pad(pad_num) touch_ll_waterproof_set_guard_pad(pad_num)
/**
* Get touch channel use for guard pad.
*
* @param pad_num Touch sensor channel number.
*/
#define touch_hal_waterproof_get_guard_pad(pad_num) touch_ll_waterproof_get_guard_pad(pad_num)
/**
* Set max equivalent capacitance for sheild channel.
* The equivalent capacitance of the shielded channel can be calculated
* from the reading of denoise channel.
*
* @param pad_num Touch sensor channel number.
*/
#define touch_hal_waterproof_set_sheild_driver(driver_level) touch_ll_waterproof_set_sheild_driver(driver_level)
/**
* Get max equivalent capacitance for sheild channel.
* The equivalent capacitance of the shielded channel can be calculated
* from the reading of denoise channel.
*
* @param pad_num Touch sensor channel number.
*/
#define touch_hal_waterproof_get_sheild_driver(driver_level) touch_ll_waterproof_get_sheild_driver(driver_level)
/**
* Set parameter of waterproof function.
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
*
* @param waterproof parameter of waterproof
*/
void touch_hal_waterproof_set_config(const touch_pad_waterproof_t *waterproof);
/**
* Get parameter of waterproof function.
*
* @param waterproof parameter of waterproof.
*/
void touch_hal_waterproof_get_config(touch_pad_waterproof_t *waterproof);
/**
* Enable parameter of waterproof function.
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
*/
void touch_hal_waterproof_enable(void);
/**
* Disable parameter of waterproof function.
* The waterproof function includes a shielded channel (TOUCH_PAD_NUM14) and a guard channel.
* The shielded channel outputs the same signal as the channel being measured.
* It is generally designed as a grid and is placed around the touch buttons.
* The shielded channel does not follow the measurement signal of the protection channel.
* So that the guard channel can detect a large area of water.
*/
#define touch_hal_waterproof_disable() touch_ll_waterproof_disable()
/************************ Proximity register setting ************************/
/**
* Set parameter of proximity channel. Three proximity sensing channels can be set.
* The proximity sensor measurement is the accumulation of touch channel measurements.
*
* @note If stop the proximity function for the channel, point this proximity channel to `TOUCH_PAD_NUM0`.
* @param proximity parameter of proximity
*/
void touch_hal_proximity_set_config(const touch_pad_proximity_t *proximity);
/**
* Get parameter of proximity channel. Three proximity sensing channels can be set.
* The proximity sensor measurement is the accumulation of touch channel measurements.
*
* @param proximity parameter of proximity.
*/
void touch_hal_proximity_get_config(touch_pad_proximity_t *proximity);
/**
* Set touch channel number for proximity pad.
* If disable the proximity pad, point this pad to `TOUCH_PAD_NUM0`
*
* @param prox_pad The array of three proximity pads.
*/
#define touch_hal_proximity_set_channel_num(prox_pad) touch_ll_proximity_set_channel_num(prox_pad)
/**
* Get touch channel number for proximity pad.
* If disable the proximity pad, point this pad to `TOUCH_PAD_NUM0`
*
* @param prox_pad The array of three proximity pads.
*/
#define touch_hal_proximity_get_channel_num(prox_pad) touch_ll_proximity_get_channel_num(prox_pad)
/**
* Set cumulative measurement times for proximity pad.
*
* @param times The cumulative number of measurement cycles.
*/
#define touch_hal_proximity_set_meas_times(times) touch_ll_proximity_set_meas_times(times)
/**
* Get cumulative measurement times for proximity pad.
*
* @param times The cumulative number of measurement cycles.
*/
#define touch_hal_proximity_get_meas_times(times) touch_ll_proximity_get_meas_times(times)
/**
* Read current cumulative measurement times for proximity pad.
*
* @param times The cumulative number of measurement cycles.
*/
#define touch_hal_proximity_read_meas_cnt(touch_num, cnt) touch_ll_proximity_read_meas_cnt(touch_num, cnt)
/**
* Check if the touch sensor channel is the proximity pad.
*
* @param touch_num The touch sensor channel number.
*/
#define touch_hal_proximity_pad_check(touch_num) touch_ll_proximity_pad_check(touch_num)
/************** sleep pad setting ***********************/
/**
* Set parameter of touch sensor in sleep mode.
* In order to achieve low power consumption in sleep mode, other circuits except the RTC part of the register are in a power-off state.
* Only one touch channel is supported in the sleep state, which can be used as a wake-up function.
* If in non-sleep mode, the sleep parameters do not work.
*
* @param slp_config touch pad config.
*/
void touch_hal_sleep_channel_config(const touch_pad_sleep_channel_t *slp_config);
/**
* Set touch channel number for sleep pad.
*
* @note Only one touch sensor channel is supported in deep sleep mode.
* @param touch_num Touch sensor channel number.
*/
#define touch_hal_sleep_set_channel_num(touch_num) touch_ll_sleep_set_channel_num(touch_num)
/**
* Get touch channel number for sleep pad.
*
* @note Only one touch sensor channel is supported in deep sleep mode.
* @param touch_num Touch sensor channel number.
*/
#define touch_hal_sleep_get_channel_num(touch_num) touch_ll_sleep_get_channel_num(touch_num)
/**
* Set the trigger threshold of touch sensor in deep sleep.
* The threshold determines the sensitivity of the touch sensor.
* The threshold is the original value of the trigger state minus the baseline value.
*
* @note The threshold at sleep is the same as the threshold before sleep.
*/
#define touch_hal_sleep_set_threshold(touch_thres) touch_ll_sleep_set_threshold(touch_thres)
/**
* Get the trigger threshold of touch sensor in deep sleep.
* The threshold determines the sensitivity of the touch sensor.
* The threshold is the original value of the trigger state minus the baseline value.
*
* @note The threshold at sleep is the same as the threshold before sleep.
*/
#define touch_hal_sleep_get_threshold(touch_thres) touch_ll_sleep_get_threshold(touch_thres)
/**
* Enable proximity function for sleep pad.
*/
#define touch_hal_sleep_enable_approach() touch_ll_sleep_enable_approach()
/**
* Disable proximity function for sleep pad.
*/
#define touch_hal_sleep_disable_approach() touch_ll_sleep_disable_approach()
/**
* Read baseline of touch sensor for sleep pad.
*
* @param baseline Pointer to accept touch sensor baseline value.
*/
#define touch_hal_sleep_read_baseline(baseline) touch_ll_sleep_read_baseline(baseline)
/**
* Read debounce of touch sensor for sleep pad.
*
* @param debounce Pointer to accept touch sensor debounce value.
*/
#define touch_hal_sleep_read_debounce(debounce) touch_ll_sleep_read_debounce(debounce)
/**
* Read proximity count of touch sensor for sleep pad.
* @param proximity_cnt Pointer to accept touch sensor proximity count value.
*/
#define touch_hal_sleep_read_proximity_cnt(approach_cnt) touch_ll_sleep_read_proximity_cnt(approach_cnt)
/**
* Get the touch pad which caused wakeup from deep sleep.
*
* @param pad_num pointer to touch pad which caused wakeup.
*/
#define touch_hal_get_wakeup_status(pad_num) touch_ll_get_wakeup_status(pad_num)

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,37 @@
// Copyright 2019 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.
#pragma once
#ifdef __cplusplus
extern "C" {
#endif
#define SOC_TOUCH_SENSOR_NUM (15) /*! 15 Touch channels */
#define SOC_TOUCH_SENSOR_BIT_MASK_MAX (0x7fff)/*! 15 Touch channels */
#define SOC_TOUCH_PAD_MEASURE_WAIT (0xFF) /*!<The timer frequency is 8Mhz, the max value is 0xff */
#define SOC_TOUCH_PAD_THRESHOLD_MAX (0x1FFFFF) /*!<If set touch threshold max value, The touch sensor can't be in touched status */
#define SOC_TOUCH_SHIELD_CHANNEL (14) /*!< The waterproof function includes a shielded channel (TOUCH_PAD_NUM14)
The shielded channel outputs the same signal as the channel being measured.
It is generally designed as a grid and is placed around the touch buttons. */
#define SOC_TOUCH_DENOISE_CHANNEL (0) /*!< T0 is an internal channel that does not have a corresponding external GPIO.
T0 will work simultaneously with the measured channel Tn. Finally, the actual
measured value of Tn is the value after subtracting lower bits of T0. */
#define SOC_TOUCH_PROXIMITY_CHANNEL_NUM (3) /* Sopport touch proximity channel number. */
#ifdef __cplusplus
}
#endif

View file

@ -16,6 +16,9 @@
#define _SOC_TOUCH_CHANNEL_H
//Touch channels
/* Note: T0 is an internal channel that does not have a corresponding external GPIO. */
#define TOUCH_PAD_GPIO1_CHANNEL TOUCH_PAD_NUM1
#define TOUCH_PAD_NUM1_GPIO_NUM 1

View file

@ -17,7 +17,8 @@ set(SOC_SRCS "adc_periph.c"
"i2s_periph.c"
"i2c_periph.c"
"uart_periph.c"
)
"touch_sensor_hal.c"
"touch_sensor_periph.c")
if(NOT CMAKE_BUILD_EARLY_EXPANSION)
set_source_files_properties("esp32s2beta/rtc_clk.c" PROPERTIES

View file

@ -0,0 +1,119 @@
// Copyright 2015-2019 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.
// The HAL layer for Touch Sensor (common part)
#include "hal/touch_sensor_hal.h"
#include "hal/touch_sensor_types.h"
void touch_hal_init(void)
{
touch_ll_intr_disable(TOUCH_PAD_INTR_ALL);
touch_ll_clear_channel_mask(SOC_TOUCH_SENSOR_BIT_MASK_MAX);
touch_ll_clear_trigger_status_mask();
touch_ll_set_meas_times(TOUCH_PAD_MEASURE_CYCLE_DEFAULT);
touch_ll_set_sleep_time(TOUCH_PAD_SLEEP_CYCLE_DEFAULT);
touch_ll_set_voltage_high(TOUCH_PAD_HIGH_VOLTAGE_THRESHOLD);
touch_ll_set_voltage_low(TOUCH_PAD_LOW_VOLTAGE_THRESHOLD);
touch_ll_set_voltage_attenuation(TOUCH_PAD_ATTEN_VOLTAGE_THRESHOLD);
touch_ll_set_inactive_connect(TOUCH_PAD_INACTIVE_CONNECT_DEFAULT);
}
void touch_hal_deinit(void)
{
touch_hal_stop_fsm();
touch_hal_clear_trigger_status_mask();
touch_ll_intr_disable(TOUCH_PAD_INTR_ALL);
}
void touch_hal_filter_set_config(const touch_filter_config_t *filter_info)
{
touch_ll_filter_set_filter_mode(filter_info->mode);
touch_ll_filter_set_debounce(filter_info->debounce_cnt);
touch_ll_filter_set_hysteresis(filter_info->hysteresis_thr);
touch_ll_filter_set_noise_thres(filter_info->noise_thr);
touch_ll_filter_set_neg_noise_thres(filter_info->noise_neg_thr);
touch_ll_filter_set_baseline_reset(filter_info->neg_noise_limit);
touch_ll_filter_set_jitter_step(filter_info->jitter_step);
}
void touch_hal_filter_get_config(touch_filter_config_t *filter_info)
{
touch_ll_filter_get_filter_mode(&filter_info->mode);
touch_ll_filter_get_debounce(&filter_info->debounce_cnt);
touch_ll_filter_get_hysteresis(&filter_info->hysteresis_thr);
touch_ll_filter_get_noise_thres(&filter_info->noise_thr);
touch_ll_filter_get_neg_noise_thres(&filter_info->noise_neg_thr);
touch_ll_filter_get_baseline_reset(&filter_info->neg_noise_limit);
touch_ll_filter_get_jitter_step(&filter_info->jitter_step);
}
void touch_hal_denoise_set_config(const touch_pad_denoise_t *denoise)
{
touch_ll_denoise_set_cap_level(denoise->cap_level);
touch_ll_denoise_set_grade(denoise->grade);
}
void touch_hal_denoise_get_config(touch_pad_denoise_t *denoise)
{
touch_ll_denoise_get_cap_level(&denoise->cap_level);
touch_ll_denoise_get_grade(&denoise->grade);
}
void touch_hal_denoise_enable(void)
{
touch_ll_clear_channel_mask(1U << SOC_TOUCH_DENOISE_CHANNEL);
touch_ll_denoise_enable();
}
void touch_hal_waterproof_set_config(const touch_pad_waterproof_t *waterproof)
{
touch_ll_waterproof_set_guard_pad(waterproof->guard_ring_pad);
touch_ll_waterproof_set_sheild_driver(waterproof->shield_driver);
}
void touch_hal_waterproof_get_config(touch_pad_waterproof_t *waterproof)
{
touch_ll_waterproof_get_guard_pad(&waterproof->guard_ring_pad);
touch_ll_waterproof_get_sheild_driver(&waterproof->shield_driver);
}
void touch_hal_waterproof_enable(void)
{
touch_ll_clear_channel_mask(1U << SOC_TOUCH_SHIELD_CHANNEL);
touch_ll_waterproof_enable();
}
void touch_hal_proximity_set_config(const touch_pad_proximity_t *proximity)
{
touch_ll_proximity_set_channel_num(proximity->select_pad);
touch_ll_proximity_set_meas_times(proximity->meas_num);
}
void touch_hal_proximity_get_config(touch_pad_proximity_t *proximity)
{
touch_ll_proximity_get_channel_num(proximity->select_pad);
touch_ll_proximity_get_meas_times(&proximity->meas_num);
}
void touch_hal_sleep_channel_config(const touch_pad_sleep_channel_t *slp_config)
{
touch_ll_sleep_set_channel_num(slp_config->touch_num);
touch_ll_sleep_set_threshold(slp_config->sleep_pad_threshold);
if (slp_config->en_proximity) {
touch_ll_sleep_enable_approach();
} else {
touch_ll_sleep_disable_approach();
}
}

View file

@ -0,0 +1,35 @@
// Copyright 2015-2019 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.
#include "soc/touch_sensor_periph.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. */
const int touch_sensor_channel_io_map[SOC_TOUCH_SENSOR_NUM] = {
-1,
TOUCH_PAD_NUM1_GPIO_NUM,
TOUCH_PAD_NUM2_GPIO_NUM,
TOUCH_PAD_NUM3_GPIO_NUM,
TOUCH_PAD_NUM4_GPIO_NUM,
TOUCH_PAD_NUM5_GPIO_NUM,
TOUCH_PAD_NUM6_GPIO_NUM,
TOUCH_PAD_NUM7_GPIO_NUM,
TOUCH_PAD_NUM8_GPIO_NUM,
TOUCH_PAD_NUM9_GPIO_NUM,
TOUCH_PAD_NUM10_GPIO_NUM,
TOUCH_PAD_NUM11_GPIO_NUM,
TOUCH_PAD_NUM12_GPIO_NUM,
TOUCH_PAD_NUM13_GPIO_NUM,
TOUCH_PAD_NUM14_GPIO_NUM
};

View file

@ -0,0 +1,227 @@
// Copyright 2019 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.
/*******************************************************************************
* NOTICE
* The hal is not public api, don't use in application code.
* See readme.md in soc/include/hal/readme.md
******************************************************************************/
// The HAL layer for touch sensor (common part)
#pragma once
#include "hal/touch_sensor_ll.h"
#include "hal/touch_sensor_types.h"
#ifdef CONFIG_IDF_TARGET_ESP32
#include "hal/touch_sensor_hal_esp32.h"
#elif CONFIG_IDF_TARGET_ESP32S2BETA
#include "hal/touch_sensor_hal_esp32s2beta.h"
#endif
typedef struct {
touch_high_volt_t refh;
touch_low_volt_t refl;
touch_volt_atten_t atten;
}touch_hal_volt_t;
typedef struct {
touch_cnt_slope_t slope; /*!<Set touch sensor charge/discharge speed(currents) for each pad.*/
touch_tie_opt_t tie_opt; /*!<Set initial voltage state of touch channel for each measurement.*/
} touch_hal_meas_mode_t;
/**
* Set touch sensor sleep time (interval of measurement).
*
* @param sleep_time The touch sensor will sleep after each measurement.
* sleep_cycle decide the interval between each measurement.
* t_sleep = sleep_cycle / (RTC_SLOW_CLK frequency).
* The approximate frequency value of RTC_SLOW_CLK can be obtained using `rtc_clk_slow_freq_get_hz` function.
*/
#define touch_hal_set_sleep_time(sleep_time) touch_ll_set_sleep_time(sleep_time)
/**
* Get touch sensor sleep time.
*
* @param sleep_time Pointer to accept sleep cycle count.
*/
#define touch_hal_get_sleep_time(sleep_time) touch_ll_get_sleep_time(sleep_time)
/**
* Set touch sensor high / low voltage threshold of chanrge.
* The touch sensor measures the channel capacitance value by charging and discharging the channel.
* So charge threshold should be less than the supply voltage.
* The actual charge threshold is high voltage threshold minus attenuation value.
*
* @param refh The high voltage threshold of chanrge.
*/
void touch_hal_set_voltage(const touch_hal_volt_t *volt);
/**
* Get touch sensor high / low voltage threshold of chanrge.
* The touch sensor measures the channel capacitance value by charging and discharging the channel.
* So charge threshold should be less than the supply voltage.
* The actual charge threshold is high voltage threshold minus attenuation value.
*
* @param refh The voltage threshold of chanrge / discharge.
*/
void touch_hal_get_voltage(touch_hal_volt_t *volt);
/**
* Set touch sensor charge/discharge speed(currents) and initial voltage state for each pad measurement.
*
* @param touch_num Touch pad index.
* @param meas Touch pad measurement config.
*/
void touch_hal_set_meas_mode(touch_pad_t touch_num, const touch_hal_meas_mode_t *meas);
/**
* Get touch sensor charge/discharge speed(currents) and initial voltage state for each pad measurement.
*
* @param touch_num Touch pad index.
* @param meas Touch pad measurement config.
*/
void touch_hal_get_meas_mode(touch_pad_t touch_num, touch_hal_meas_mode_t *meas);
/**
* Set touch sensor FSM mode.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
*
* @param mode FSM mode.
*/
#define touch_hal_set_fsm_mode(mode) touch_ll_set_fsm_mode(mode)
/**
* Get touch sensor FSM mode.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
*
* @param mode FSM mode.
*/
#define touch_hal_get_fsm_mode(mode) touch_ll_get_fsm_mode(mode)
/**
* Start touch sensor FSM timer.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
*
* @param mode FSM mode.
*/
#define touch_hal_start_fsm() touch_ll_start_fsm()
/**
* Stop touch sensor FSM timer.
* The measurement action can be triggered by the hardware timer, as well as by the software instruction.
*
* @param mode FSM mode.
*/
#define touch_hal_stop_fsm() touch_ll_stop_fsm()
/**
* Trigger a touch sensor measurement, only support in SW mode of FSM.
*/
#define touch_hal_start_sw_meas() touch_ll_start_sw_meas()
/**
* Set touch sensor interrupt threshold.
*
* @note Refer to `touch_pad_set_trigger_mode` to see how to set trigger mode.
* @param touch_num touch pad index.
* @param threshold threshold of touchpad count.
*/
#define touch_hal_set_threshold(touch_num, threshold) touch_ll_set_threshold(touch_num, threshold)
/**
* Get touch sensor interrupt threshold.
*
* @param touch_num touch pad index.
* @param threshold pointer to accept threshold.
*/
#define touch_hal_get_threshold(touch_num, threshold) touch_ll_get_threshold(touch_num, threshold)
/**
* Enable touch sensor channel. Register touch channel into touch sensor measurement group.
* The working mode of the touch sensor is simultaneous measurement.
* This function will set the measure bits according to the given bitmask.
*
* @note If set this mask, the FSM timer should be stop firsty.
* @note The touch sensor that in scan map, should be deinit GPIO function firstly.
* @param enable_mask bitmask of touch sensor scan group.
* e.g. TOUCH_PAD_NUM1 -> BIT(1)
* @return
* - ESP_OK on success
*/
#define touch_hal_set_channel_mask(enable_mask) touch_ll_set_channel_mask(enable_mask)
/**
* Get touch sensor channel mask.
*
* @param enable_mask bitmask of touch sensor scan group.
* e.g. TOUCH_PAD_NUM1 -> BIT(1)
*/
#define touch_hal_get_channel_mask(enable_mask) touch_ll_get_channel_mask(enable_mask)
/**
* Disable touch sensor channel by bitmask.
*
* @param enable_mask bitmask of touch sensor scan group.
* e.g. TOUCH_PAD_NUM1 -> BIT(1)
*/
#define touch_hal_clear_channel_mask(disable_mask) touch_ll_clear_channel_mask(disable_mask)
/**
* Get the touch sensor status, usually used in ISR to decide which pads are 'touched'.
*
* @param status_mask The touch sensor status. e.g. Touch1 trigger status is `status_mask & (BIT1)`.
*/
#define touch_hal_read_trigger_status_mask(status_mask) touch_ll_read_trigger_status_mask(status_mask)
/**
* Clear all touch sensor status.
*/
#define touch_hal_clear_trigger_status_mask() touch_ll_clear_trigger_status_mask()
/**
* Get touch sensor raw data (touch sensor counter value) from register. No block.
*
* @param touch_num touch pad index.
* @return touch_value pointer to accept touch sensor value.
*/
#define touch_hal_read_raw_data(touch_num) touch_ll_read_raw_data(touch_num)
/**
* Get touch sensor measure status. No block.
*
* @return
* - If touch sensors measure done.
*/
#define touch_hal_meas_is_done() touch_ll_meas_is_done()
/**
* Initialize touch module.
*
* @note If default parameter don't match the usage scenario, it can be changed after this function.
*/
void touch_hal_init(void);
/**
* Un-install touch pad driver.
*
* @note After this function is called, other touch functions are prohibited from being called.
*/
void touch_hal_deinit(void);
/**
* Configure touch sensor for each channel.
*/
void touch_hal_config(touch_pad_t touch_num);

View file

@ -0,0 +1,264 @@
// Copyright 2015-2019 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.
#pragma once
#include "soc/touch_sensor_caps.h"
#include "sdkconfig.h"
typedef enum {
TOUCH_PAD_NUM0 = 0, /*!< Touch pad channel 0 is GPIO4(ESP32) */
TOUCH_PAD_NUM1, /*!< Touch pad channel 1 is GPIO0(ESP32) / GPIO1(ESP32-S2) */
TOUCH_PAD_NUM2, /*!< Touch pad channel 2 is GPIO2(ESP32) / GPIO2(ESP32-S2) */
TOUCH_PAD_NUM3, /*!< Touch pad channel 3 is GPIO15(ESP32) / GPIO3(ESP32-S2) */
TOUCH_PAD_NUM4, /*!< Touch pad channel 4 is GPIO13(ESP32) / GPIO4(ESP32-S2) */
TOUCH_PAD_NUM5, /*!< Touch pad channel 5 is GPIO12(ESP32) / GPIO5(ESP32-S2) */
TOUCH_PAD_NUM6, /*!< Touch pad channel 6 is GPIO14(ESP32) / GPIO6(ESP32-S2) */
TOUCH_PAD_NUM7, /*!< Touch pad channel 7 is GPIO27(ESP32) / GPIO7(ESP32-S2) */
TOUCH_PAD_NUM8, /*!< Touch pad channel 8 is GPIO33(ESP32) / GPIO8(ESP32-S2) */
TOUCH_PAD_NUM9, /*!< Touch pad channel 9 is GPIO32(ESP32) / GPIO9(ESP32-S2) */
#if SOC_TOUCH_SENSOR_NUM > 10
TOUCH_PAD_NUM10, /*!< Touch channel 10 is GPIO10(ESP32-S2) */
TOUCH_PAD_NUM11, /*!< Touch channel 11 is GPIO11(ESP32-S2) */
TOUCH_PAD_NUM12, /*!< Touch channel 12 is GPIO12(ESP32-S2) */
TOUCH_PAD_NUM13, /*!< Touch channel 13 is GPIO13(ESP32-S2) */
TOUCH_PAD_NUM14, /*!< Touch channel 14 is GPIO14(ESP32-S2) */
#endif
TOUCH_PAD_MAX,
} touch_pad_t;
typedef enum {
TOUCH_HVOLT_KEEP = -1, /*!<Touch sensor high reference voltage, no change */
TOUCH_HVOLT_2V4 = 0, /*!<Touch sensor high reference voltage, 2.4V */
TOUCH_HVOLT_2V5, /*!<Touch sensor high reference voltage, 2.5V */
TOUCH_HVOLT_2V6, /*!<Touch sensor high reference voltage, 2.6V */
TOUCH_HVOLT_2V7, /*!<Touch sensor high reference voltage, 2.7V */
TOUCH_HVOLT_MAX,
} touch_high_volt_t;
typedef enum {
TOUCH_LVOLT_KEEP = -1, /*!<Touch sensor low reference voltage, no change */
TOUCH_LVOLT_0V5 = 0, /*!<Touch sensor low reference voltage, 0.5V */
TOUCH_LVOLT_0V6, /*!<Touch sensor low reference voltage, 0.6V */
TOUCH_LVOLT_0V7, /*!<Touch sensor low reference voltage, 0.7V */
TOUCH_LVOLT_0V8, /*!<Touch sensor low reference voltage, 0.8V */
TOUCH_LVOLT_MAX,
} touch_low_volt_t;
typedef enum {
TOUCH_HVOLT_ATTEN_KEEP = -1, /*!<Touch sensor high reference voltage attenuation, no change */
TOUCH_HVOLT_ATTEN_1V5 = 0, /*!<Touch sensor high reference voltage attenuation, 1.5V attenuation */
TOUCH_HVOLT_ATTEN_1V, /*!<Touch sensor high reference voltage attenuation, 1.0V attenuation */
TOUCH_HVOLT_ATTEN_0V5, /*!<Touch sensor high reference voltage attenuation, 0.5V attenuation */
TOUCH_HVOLT_ATTEN_0V, /*!<Touch sensor high reference voltage attenuation, 0V attenuation */
TOUCH_HVOLT_ATTEN_MAX,
} touch_volt_atten_t;
typedef enum {
TOUCH_PAD_SLOPE_0 = 0, /*!<Touch sensor charge / discharge speed, always zero */
TOUCH_PAD_SLOPE_1 = 1, /*!<Touch sensor charge / discharge speed, slowest */
TOUCH_PAD_SLOPE_2 = 2, /*!<Touch sensor charge / discharge speed */
TOUCH_PAD_SLOPE_3 = 3, /*!<Touch sensor charge / discharge speed */
TOUCH_PAD_SLOPE_4 = 4, /*!<Touch sensor charge / discharge speed */
TOUCH_PAD_SLOPE_5 = 5, /*!<Touch sensor charge / discharge speed */
TOUCH_PAD_SLOPE_6 = 6, /*!<Touch sensor charge / discharge speed */
TOUCH_PAD_SLOPE_7 = 7, /*!<Touch sensor charge / discharge speed, fast */
TOUCH_PAD_SLOPE_MAX,
} touch_cnt_slope_t;
typedef enum {
TOUCH_PAD_TIE_OPT_LOW = 0, /*!<Initial level of charging voltage, low level */
TOUCH_PAD_TIE_OPT_HIGH = 1, /*!<Initial level of charging voltage, high level */
TOUCH_PAD_TIE_OPT_MAX,
} touch_tie_opt_t;
typedef enum {
TOUCH_FSM_MODE_TIMER = 0, /*!<To start touch FSM by timer */
TOUCH_FSM_MODE_SW, /*!<To start touch FSM by software trigger */
TOUCH_FSM_MODE_MAX,
} touch_fsm_mode_t;
/**** ESP32 Only *****/
typedef enum {
TOUCH_TRIGGER_BELOW = 0, /*!<Touch interrupt will happen if counter value is less than threshold.*/
TOUCH_TRIGGER_ABOVE = 1, /*!<Touch interrupt will happen if counter value is larger than threshold.*/
TOUCH_TRIGGER_MAX,
} touch_trigger_mode_t;
typedef enum {
TOUCH_TRIGGER_SOURCE_BOTH = 0, /*!< wakeup interrupt is generated if both SET1 and SET2 are "touched"*/
TOUCH_TRIGGER_SOURCE_SET1 = 1, /*!< wakeup interrupt is generated if SET1 is "touched"*/
TOUCH_TRIGGER_SOURCE_MAX,
} touch_trigger_src_t;
/********************************/
#define TOUCH_PAD_SLOPE_DEFAULT (TOUCH_PAD_SLOPE_7)
#define TOUCH_PAD_TIE_OPT_DEFAULT (TOUCH_PAD_TIE_OPT_LOW)
#define TOUCH_PAD_BIT_MASK_MAX (SOC_TOUCH_SENSOR_BIT_MASK_MAX)
#define TOUCH_PAD_HIGH_VOLTAGE_THRESHOLD (TOUCH_HVOLT_2V7)
#define TOUCH_PAD_LOW_VOLTAGE_THRESHOLD (TOUCH_LVOLT_0V5)
#define TOUCH_PAD_ATTEN_VOLTAGE_THRESHOLD (TOUCH_HVOLT_ATTEN_0V5)
#define TOUCH_PAD_INACTIVE_CONNECT_DEFAULT (TOUCH_PAD_CONN_GND)
#define TOUCH_PAD_THRESHOLD_MAX (SOC_TOUCH_PAD_THRESHOLD_MAX) /*!<If set touch threshold max value, The touch sensor can't be in touched status */
#ifdef CONFIG_IDF_TARGET_ESP32
#define TOUCH_PAD_SLEEP_CYCLE_DEFAULT (0x1000) /*!<The timer frequency is RTC_SLOW_CLK (can be 150k or 32k depending on the options), max value is 0xffff */
#define TOUCH_PAD_MEASURE_CYCLE_DEFAULT (0x7fff) /*!<The timer frequency is 8Mhz, the max value is 0x7fff */
#define TOUCH_FSM_MODE_DEFAULT (TOUCH_FSM_MODE_SW) /*!<The touch FSM my be started by the software or timer */
#define TOUCH_TRIGGER_MODE_DEFAULT (TOUCH_TRIGGER_BELOW) /*!<Interrupts can be triggered if sensor value gets below or above threshold */
#define TOUCH_TRIGGER_SOURCE_DEFAULT (TOUCH_TRIGGER_SOURCE_SET1) /*!<The wakeup trigger source can be SET1 or both SET1 and SET2 */
#elif CONFIG_IDF_TARGET_ESP32S2BETA
/**
* Excessive total time will slow down the touch response.
* Too small measurement time will not be sampled enough, resulting in inaccurate measurements.
*
* @note The greater the duty cycle of the measurement time, the more system power is consumed.
*/
#define TOUCH_PAD_SLEEP_CYCLE_DEFAULT (0xf) /*!<The number of sleep cycle in each measure process of touch channels.
The timer frequency is RTC_SLOW_CLK (can be 150k or 32k depending on the options).
Range: 0 ~ 0xffff */
#define TOUCH_PAD_MEASURE_CYCLE_DEFAULT (500) /*!<The times of charge and discharge in each measure process of touch channels.
The timer frequency is 8Mhz.
Recommended typical value: Modify this value to make the measurement time around 1ms.
Range: 0 ~ 0xffff */
#endif // CONFIG_IDF_TARGET_ESP32
#ifdef CONFIG_IDF_TARGET_ESP32S2BETA
typedef enum {
TOUCH_PAD_INTR_DONE = 0, /*!<Each enabled channel measure done */
TOUCH_PAD_INTR_ACTIVE = 1, /*!<Each enabled channel be touched */
TOUCH_PAD_INTR_INACTIVE = 2,/*!<Each enabled channel be released */
TOUCH_PAD_INTR_ALL, /*!<All touch interrupt measure done & touched & released */
TOUCH_PAD_INTR_MAX
} touch_pad_intr_type_t;
typedef enum {
TOUCH_PAD_INTR_MASK_DONE = BIT(0), /*!<Each enabled channel measure done */
TOUCH_PAD_INTR_MASK_ACTIVE = BIT(1), /*!<Each enabled channel be touched */
TOUCH_PAD_INTR_MASK_INACTIVE = BIT(2), /*!<Each enabled channel be released */
TOUCH_PAD_INTR_MASK_ALL = BIT(2) | BIT(1) | BIT(0), /*!<All touch interrupt measure done & touched & released */
TOUCH_PAD_INTR_MASK_MAX
} touch_pad_intr_mask_t;
typedef enum {
TOUCH_PAD_DENOISE_BIT12 = 0, /*!<Denoise range is 12bit */
TOUCH_PAD_DENOISE_BIT10 = 1, /*!<Denoise range is 10bit */
TOUCH_PAD_DENOISE_BIT8 = 2, /*!<Denoise range is 8bit */
TOUCH_PAD_DENOISE_BIT4 = 3, /*!<Denoise range is 4bit */
TOUCH_PAD_DENOISE_MAX
} touch_pad_denoise_grade_t;
typedef enum {
TOUCH_PAD_DENOISE_CAP_L0 = 0, /*!<Denoise channel internal reference capacitance is 0pf */
TOUCH_PAD_DENOISE_CAP_L1 = 4, /*!<Denoise channel internal reference capacitance is 1.4pf */
TOUCH_PAD_DENOISE_CAP_L2 = 2, /*!<Denoise channel internal reference capacitance is 2.8pf */
TOUCH_PAD_DENOISE_CAP_L3 = 6, /*!<Denoise channel internal reference capacitance is 4.2pf */
TOUCH_PAD_DENOISE_CAP_L4 = 1, /*!<Denoise channel internal reference capacitance is 5.6pf */
TOUCH_PAD_DENOISE_CAP_L5 = 5, /*!<Denoise channel internal reference capacitance is 7.0pf */
TOUCH_PAD_DENOISE_CAP_L6 = 3, /*!<Denoise channel internal reference capacitance is 8.4pf */
TOUCH_PAD_DENOISE_CAP_L7 = 7, /*!<Denoise channel internal reference capacitance is 9.8pf */
TOUCH_PAD_DENOISE_CAP_MAX
} touch_pad_denoise_cap_t;
typedef struct touch_pad_denoise {
touch_pad_denoise_grade_t grade; /*!<Select denoise range of denoise channel.
Determined by measuring the noise amplitude of the denoise channel. */
touch_pad_denoise_cap_t cap_level; /*!<Select internal reference capacitance of denoise channel.
The equivalent capacitance of the shielded channel can be calculated
from the reading of denoise channel. */
} touch_pad_denoise_t;
typedef enum {
TOUCH_PAD_SHIELD_DRV_L0 = 0,/*!<The max equivalent capacitance in shield channel is 40pf */
TOUCH_PAD_SHIELD_DRV_L1, /*!<The max equivalent capacitance in shield channel is 80pf */
TOUCH_PAD_SHIELD_DRV_L2, /*!<The max equivalent capacitance in shield channel is 120pf */
TOUCH_PAD_SHIELD_DRV_L3, /*!<The max equivalent capacitance in shield channel is 160pf */
TOUCH_PAD_SHIELD_DRV_L4, /*!<The max equivalent capacitance in shield channel is 200pf */
TOUCH_PAD_SHIELD_DRV_L5, /*!<The max equivalent capacitance in shield channel is 240pf */
TOUCH_PAD_SHIELD_DRV_L6, /*!<The max equivalent capacitance in shield channel is 280pf */
TOUCH_PAD_SHIELD_DRV_L7, /*!<The max equivalent capacitance in shield channel is 320pf */
TOUCH_PAD_SHIELD_DRV_MAX
} touch_pad_shield_driver_t;
typedef struct touch_pad_waterproof {
touch_pad_t guard_ring_pad; /*!<Waterproof. Select touch channel use for guard pad */
touch_pad_shield_driver_t shield_driver;/*!<Waterproof. Select max equivalent capacitance for sheild pad
Config the Touch14 to the touch sensor and compare the measured
reading to the Touch0 reading to estimate the equivalent capacitance.*/
} touch_pad_waterproof_t;
typedef struct touch_pad_proximity {
touch_pad_t select_pad[SOC_TOUCH_PROXIMITY_CHANNEL_NUM]; /*!<Set touch channel number for proximity pad.
If clear the proximity channel, point this pad to `TOUCH_PAD_NUM0` */
uint32_t meas_num; /*!<Set cumulative times of measurements for proximity pad */
#define TOUCH_PROXIMITY_MEAS_NUM_MAX (0xFF)
} touch_pad_proximity_t;
typedef enum {
TOUCH_PAD_CONN_HIGHZ = 0, /*!<Idel status of touch channel is high resistance state */
TOUCH_PAD_CONN_GND = 1, /*!<Idel status of touch channel is ground connection */
TOUCH_PAD_CONN_MAX
} touch_pad_conn_type_t;
typedef enum {
TOUCH_PAD_FILTER_IIR_2 = 0, /*!<The filter mode is first-order IIR filter. The coefficient is 2 */
TOUCH_PAD_FILTER_IIR_4, /*!<The filter mode is first-order IIR filter. The coefficient is 4 */
TOUCH_PAD_FILTER_IIR_8, /*!<The filter mode is first-order IIR filter. The coefficient is 8 */
TOUCH_PAD_FILTER_JITTER, /*!<The filter mode is jitter filter */
TOUCH_PAD_FILTER_MAX
} touch_filter_mode_t;
typedef struct touch_filter_config {
touch_filter_mode_t mode; /*!<Set filter mode. The input to the filter is raw data and the output is the baseline value.
Larger filter coefficients increase the stability of the baseline. */
uint32_t debounce_cnt; /*!<Set debounce count, such as `n`. If the measured values continue to exceed
the threshold for `n` times, it is determined that the touch sensor state changes.
Range: 0 ~ 7 */
uint32_t hysteresis_thr; /*!<Hysteresis threshold coefficient. hysteresis = hysteresis_thr * touch_threshold.
If (raw data - baseline) > (touch threshold + hysteresis), the touch channel be touched.
If (raw data - baseline) < (touch threshold - hysteresis), the touch channel be released.
Range: 0 ~ 3. The coefficient is 0: 1/8; 1: 3/32; 2: 1/16; 3: 1/32 */
uint32_t noise_thr; /*!<Noise threshold coefficient. noise = noise_thr * touch threshold.
If (raw data - baseline) > (noise), the baseline stop updating.
If (raw data - baseline) < (noise), the baseline start updating.
Range: 0 ~ 3. The coefficient is 0: 1/2; 1: 3/8; 2: 1/4; 3: 1/8; */
uint32_t noise_neg_thr; /*!<Negative noise threshold coefficient. negative noise = noise_neg_thr * touch threshold.
If (baseline - raw data) > (negative noise), the baseline restart reset process(refer to `baseline_reset`).
If (baseline - raw data) < (negative noise), the baseline stop reset process(refer to `baseline_reset`).
Range: 0 ~ 3. The coefficient is 0: 1/2; 1: 3/8; 2: 1/4; 3: 1/8; */
uint32_t neg_noise_limit; /*!<Set the cumulative number of baseline reset processes. such as `n`. If the measured values continue to exceed
the negative noise threshold for `n` times, the baseline reset to raw data.
Range: 0 ~ 15 */
uint32_t jitter_step; /*!<Set jitter filter step size. Range: 0 ~ 15 */
#define TOUCH_DEBOUNCE_CNT_MAX (7)
#define TOUCH_HYSTERESIS_THR_MAX (3)
#define TOUCH_NOISE_THR_MAX (3)
#define TOUCH_NOISE_NEG_THR_MAX (3)
#define TOUCH_NEG_NOISE_CNT_LIMIT (15)
#define TOUCH_JITTER_STEP_MAX (15)
} touch_filter_config_t;
typedef struct {
touch_pad_t touch_num; /*!<Set touch channel number for sleep pad.
Only one touch sensor channel is supported in deep sleep mode. */
uint32_t sleep_pad_threshold; /*!<Set the trigger threshold of touch sensor in deep sleep.
The threshold at sleep is the same as the threshold before sleep. */
bool en_proximity; /*!<enable proximity function for sleep pad */
} touch_pad_sleep_channel_t;
#endif // CONFIG_IDF_TARGET_ESP32S2BETA

View file

@ -13,4 +13,13 @@
// limitations under the License.
#pragma once
#include "soc/touch_channel.h"
#include "soc/touch_sensor_channel.h"
#include "soc/touch_sensor_caps.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"
extern const int touch_sensor_channel_io_map[SOC_TOUCH_SENSOR_NUM];

View file

@ -0,0 +1,51 @@
// Copyright 2015-2019 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.
// The HAL layer for Touch Sensor (common part)
#include "hal/touch_sensor_hal.h"
#include "hal/touch_sensor_types.h"
void touch_hal_config(touch_pad_t touch_num)
{
touch_ll_set_threshold(touch_num, SOC_TOUCH_PAD_THRESHOLD_MAX);
touch_ll_set_slope(touch_num, TOUCH_PAD_SLOPE_DEFAULT);
touch_ll_set_tie_option(touch_num, TOUCH_PAD_TIE_OPT_DEFAULT);
}
void touch_hal_set_voltage(const touch_hal_volt_t *volt)
{
touch_ll_set_voltage_high(volt->refh);
touch_ll_set_voltage_low(volt->refl);
touch_ll_set_voltage_attenuation(volt->atten);
}
void touch_hal_get_voltage(touch_hal_volt_t *volt)
{
touch_ll_get_voltage_high(&volt->refh);
touch_ll_get_voltage_low(&volt->refl);
touch_ll_get_voltage_attenuation(&volt->atten);
}
void touch_hal_set_meas_mode(touch_pad_t touch_num, const touch_hal_meas_mode_t *meas)
{
touch_ll_set_slope(touch_num, meas->slope);
touch_ll_set_tie_option(touch_num, meas->tie_opt);
}
void touch_hal_get_meas_mode(touch_pad_t touch_num, touch_hal_meas_mode_t *meas)
{
touch_ll_get_slope(touch_num, &meas->slope);
touch_ll_get_tie_option(touch_num, &meas->tie_opt);
}

View file

@ -118,9 +118,10 @@ INPUT = \
../../components/soc/include/hal/adc_types.h \
../../components/soc/include/hal/gpio_types.h \
../../components/soc/include/hal/uart_types.h \
../../components/soc/include/hal/touch_sensor_types.h \
../../components/soc/esp32/include/soc/adc_channel.h \
../../components/soc/esp32/include/soc/dac_channel.h \
../../components/soc/esp32/include/soc/touch_channel.h \
../../components/soc/esp32/include/soc/touch_sensor_channel.h \
../../components/soc/esp32/include/soc/uart_channel.h \
../../components/soc/esp32/include/soc/rtc_io_channel.h \
## esp_netif - API Reference

View file

@ -172,5 +172,5 @@ e.g.
1. ``TOUCH_PAD_NUM5_GPIO_NUM`` is the GPIO number of channel 5 (12);
2. ``TOUCH_PAD_GPIO4_CHANNEL`` is the channel number of GPIO 4 (channel 0).
.. include:: /_build/inc/touch_channel.inc
.. include:: /_build/inc/touch_sensor_channel.inc
.. include:: /_build/inc/touch_sensor_types.inc

View file

@ -165,4 +165,4 @@ GPIO 宏查找表
1. ``TOUCH_PAD_NUM5_GPIO_NUM`` 定义了通道 5 的 GPIO即 GPIO 12
2. ``TOUCH_PAD_GPIO4_CHANNEL`` 定义了 GPIO 4 的通道(即通道 0
.. include:: /_build/inc/touch_channel.inc
.. include:: /_build/inc/touch_sensor_channel.inc

View file

@ -1,4 +1,7 @@
# Touch Pad Interrupt Example
## ESP32 platform
Demonstrates how to set up ESP32'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 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.
@ -29,8 +32,34 @@ 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).
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/master/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.
See the README.md file in the upper level 'examples' directory for more information about examples.

View file

@ -60,12 +60,12 @@ static void touchsensor_interrupt_cb(void *arg)
int task_awoken = pdFALSE;
touch_event_t evt;
evt.intr_mask = touch_pad_intr_status_get_mask();
evt.intr_mask = touch_pad_read_intr_status_mask();
evt.pad_status = touch_pad_get_status();
evt.pad_num = touch_pad_get_scan_curr();
evt.pad_num = touch_pad_get_current_meas_channel();
if (evt.intr_mask & TOUCH_PAD_INTR_MASK_DONE) {
touch_pad_filter_baseline_read(evt.pad_num, &evt.pad_val);
touch_pad_filter_read_baseline(evt.pad_num, &evt.pad_val);
}
xQueueSendFromISR(que_touch, &evt, &task_awoken);
if (task_awoken == pdTRUE) {
@ -78,7 +78,7 @@ static void tp_example_set_thresholds(void)
uint32_t touch_value;
for (int i = 0; i < TOUCH_BUTTON_NUM; i++) {
//read baseline value
touch_pad_read_raw_data(button[i], &touch_value);
touch_pad_filter_read_baseline(button[i], &touch_value);
//set interrupt threshold.
touch_pad_set_thresh(button[i], touch_value * button_threshold[i]);
ESP_LOGI(TAG, "test init: touch pad [%d] base %d, thresh %d", \
@ -92,16 +92,16 @@ static void touchsensor_filter_set(touch_filter_mode_t mode)
touch_filter_config_t filter_info = {
.mode = mode, // Test jitter and filter 1/4.
.debounce_cnt = 1, // 1 time count.
.hysteresis_thr = 1, // 9.4%
.noise_thr = 1, // 37.5%
.noise_neg_thr = 1, // 37.5%
.hysteresis_thr = 3, // 3%
.noise_thr = 0, // 50%
.noise_neg_thr = 0, // 50%
.neg_noise_limit = 10, // 10 time count.
.jitter_step = 4, // use for jitter mode.
};
touch_pad_filter_set_config(&filter_info);
touch_pad_filter_enable();
touch_pad_filter_baseline_reset(TOUCH_PAD_MAX);
ESP_LOGI(TAG, "touch pad filter init %d", mode);
touch_pad_filter_reset_baseline(TOUCH_PAD_MAX);
ESP_LOGI(TAG, "touch pad filter init");
}
static void tp_example_read_task(void *pvParameter)
@ -158,9 +158,16 @@ void app_main(void)
touch_pad_init();
for (int i = 0; i < TOUCH_BUTTON_NUM; i++) {
touch_pad_config(button[i]);
touch_pad_set_thresh(button[i], TOUCH_PAD_THRESHOLD_MAX);
}
#if 0
/* 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_inactive_connect(TOUCH_PAD_INACTIVE_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 = {
@ -168,7 +175,7 @@ void app_main(void)
.grade = TOUCH_PAD_DENOISE_BIT4,
.cap_level = TOUCH_PAD_DENOISE_CAP_L7,
};
touch_pad_denoise_set_config(denoise);
touch_pad_denoise_set_config(&denoise);
touch_pad_denoise_enable();
ESP_LOGI(TAG, "Denoise function init");
#endif
@ -180,7 +187,7 @@ void app_main(void)
/* It depends on the number of the parasitic capacitance of the shield pad. */
.shield_driver = TOUCH_PAD_SHIELD_DRV_L0, //40pf
};
touch_pad_waterproof_set_config(waterproof);
touch_pad_waterproof_set_config(&waterproof);
touch_pad_waterproof_enable();
ESP_LOGI(TAG, "touch pad waterproof init");
#endif

View file

@ -1,5 +1,7 @@
# 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.
@ -16,6 +18,28 @@ T0:[1072,1071] T1:[ 475, 475] T2:[1004,1003] T3:[1232,1231] T4:[1675,1676] T5:[1
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
Read and display raw values from capacitive touch pad sensors.
Once configured, ESP32-S2 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 bigger. In opposite situation, when finger is released, capacitance is smaller and the measured value smaller.
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. For ESP32-S2, the hardware integrates the edge detection algorithm, which can achieve the purpose of detecting touch actions by configuring appropriate parameters. Please find the example in [touch_pad_interrupt](../touch_pad_interrupt).
ESP32-S2 supports reading up to 14 capacitive touch pad sensors T1 - T14, connected to specific GPIO pins. For information on available pins please refer to ESP32-S2 Technical Reference Manual. T0 is the internal denoise channel used to filter out system noise and there is no corresponding external GPIO. Application initializes 14 sensor pads. Then in a loop reads sensors T1 - T14 and displays obtained values (after a colon) on a serial terminal:
```
Touch Sensor read, the output format is:
Touchpad num:[raw data]
T1: [6473] T2: [6507] T3: [6638] T4: [8917] T5: [9053] T6: [7190] T7: [7176] T8: [7416] T9: [7145] T10: [7387] T11: [7973] T12: [7776] T13: [8151] T14: [8190]
T1: [6463] T2: [6512] T3: [6643] T4: [8920] T5: [9050] T6: [7191] T7: [7176] T8: [7416] T9: [7143] T10: [7387] T11: [7974] T12: [7778] T13: [8152] T14: [8192]
T1: [6476] T2: [6508] T3: [6641] T4: [8919] T5: [9053] T6: [7190] T7: [7177] T8: [7416] T9: [7143] T10: [7386] T11: [7974] T12: [7776] T13: [8153] T14: [8193]
```
## 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/master/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).

View file

@ -60,16 +60,23 @@ void app_main(void)
touch_pad_init();
for (int i = 0; i < TOUCH_BUTTON_NUM; i++) {
touch_pad_config(button[i]);
touch_pad_set_thresh(button[i], TOUCH_PAD_THRESHOLD_MAX);
}
#if 0
/* 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_inactive_connect(TOUCH_PAD_INACTIVE_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_L7,
};
touch_pad_denoise_set_config(denoise);
touch_pad_denoise_set_config(&denoise);
touch_pad_denoise_enable();
ESP_LOGI(TAG, "Denoise function init");

View file

@ -173,29 +173,28 @@ void app_main(void)
touch_pad_init();
/* Only support one touch channel in sleep mode. */
touch_pad_config(TOUCH_PAD_NUM9);
touch_pad_set_thresh(TOUCH_PAD_NUM9, TOUCH_PAD_THRESHOLD_MAX);
/* 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_L7,
};
touch_pad_denoise_set_config(denoise);
touch_pad_denoise_set_config(&denoise);
touch_pad_denoise_enable();
printf("Denoise function init\n");
/* Filter setting */
touch_filter_config_t filter_info = {
.mode = TOUCH_PAD_FILTER_IIR_8,
.debounce_cnt = 1, // 1 time count.
.hysteresis_thr = 1, // 9.4%
.noise_thr = 1, // 37.5%
.noise_neg_thr = 1, // 37.5%
.neg_noise_limit = 10, // 10 time count.
.jitter_step = 4, // use for jitter mode.
.mode = TOUCH_PAD_FILTER_IIR_8,
.debounce_cnt = 1, // 1 time count.
.hysteresis_thr = 3, // 3%
.noise_thr = 0, // 50%
.noise_neg_thr = 0, // 50%
.neg_noise_limit = 10, // 10 time count.
.jitter_step = 4, // use for jitter mode.
};
touch_pad_filter_set_config(&filter_info);
touch_pad_filter_enable();
touch_pad_filter_baseline_reset(TOUCH_PAD_NUM9);
touch_pad_filter_reset_baseline(TOUCH_PAD_NUM9);
printf("touch pad filter init %d\n", TOUCH_PAD_FILTER_IIR_8);
/* Set sleep touch pad. */
touch_pad_sleep_channel_t slp_config = {
@ -203,16 +202,16 @@ void app_main(void)
.sleep_pad_threshold = TOUCH_PAD_THRESHOLD_MAX,
.en_proximity = false,
};
touch_pad_sleep_channel_config(slp_config);
touch_pad_sleep_channel_config(&slp_config);
/* Enable touch sensor clock. Work mode is "timer trigger". */
touch_pad_set_fsm_mode(TOUCH_FSM_MODE_TIMER);
touch_pad_fsm_start();
vTaskDelay(100 / portTICK_RATE_MS);
/* read sleep touch pad value */
uint32_t touch_value;
touch_pad_sleep_channel_baseline_get(&touch_value);
touch_pad_sleep_channel_read_baseline(&touch_value);
slp_config.sleep_pad_threshold = touch_value * 0.1;
touch_pad_sleep_channel_config(slp_config); //10%
touch_pad_sleep_channel_config(&slp_config); //10%
printf("test init: touch pad [%d] slp %d, thresh %d\n",
TOUCH_PAD_NUM9, touch_value, (uint32_t)(touch_value * 0.1));
#endif