Explorar o código

driver: fix `sens_struct.h`;
driver: fix timer wakeup dsleep;
example: fix EXT1 wakeup dsleep;
example: fix touch pad wakeup dsleep;

fuzhibo %!s(int64=6) %!d(string=hai) anos
pai
achega
246242dbd5

+ 6 - 6
components/driver/esp32s2beta/rtc_touchpad.c

@@ -588,11 +588,11 @@ esp_err_t touch_pad_proximity_get_meas_cnt(touch_pad_t touch_num, uint32_t *cnt)
         return ESP_ERR_INVALID_ARG;
     }
     if (SENS.sar_touch_conf.touch_approach_pad0 == touch_num) {
-        *cnt = SENS.sar_touch_status16.touch_approach_pad0_cnt;
+        *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_status16.touch_approach_pad1_cnt;
+        *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_status16.touch_approach_pad2_cnt;
+        *cnt = SENS.sar_touch_appr_status.touch_approach_pad2_cnt;
     } else {
         return ESP_ERR_INVALID_ARG;
     }
@@ -636,7 +636,7 @@ esp_err_t touch_pad_sleep_channel_config(touch_pad_sleep_channel_t slp_config)
 esp_err_t touch_pad_sleep_channel_baseline_get(uint32_t *baseline)
 {
     if (baseline) {
-        *baseline = REG_GET_FIELD(SENS_SAR_TOUCH_STATUS15_REG, SENS_TOUCH_SLP_BASELINE);
+        *baseline = REG_GET_FIELD(SENS_SAR_TOUCH_SLP_STATUS_REG, SENS_TOUCH_SLP_BASELINE);
     } else {
         return ESP_ERR_INVALID_ARG;
     }
@@ -646,7 +646,7 @@ esp_err_t touch_pad_sleep_channel_baseline_get(uint32_t *baseline)
 esp_err_t touch_pad_sleep_channel_debounce_get(uint32_t *debounce)
 {
     if (debounce) {
-        *debounce = REG_GET_FIELD(SENS_SAR_TOUCH_STATUS15_REG, SENS_TOUCH_SLP_DEBOUNCE);
+        *debounce = REG_GET_FIELD(SENS_SAR_TOUCH_SLP_STATUS_REG, SENS_TOUCH_SLP_DEBOUNCE);
     } else {
         return ESP_ERR_INVALID_ARG;
     }
@@ -656,7 +656,7 @@ esp_err_t touch_pad_sleep_channel_debounce_get(uint32_t *debounce)
 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_STATUS16_REG, SENS_TOUCH_SLP_APPROACH_CNT);
+        *approach_cnt = REG_GET_FIELD(SENS_SAR_TOUCH_APPR_STATUS_REG, SENS_TOUCH_SLP_APPROACH_CNT);
     } else {
         return ESP_ERR_INVALID_ARG;
     }

+ 7 - 8
components/esp32s2beta/sleep_modes.c

@@ -35,6 +35,7 @@
 #include "soc/sens_reg.h"
 #include "soc/dport_reg.h"
 #include "soc/rtc_wdt.h"
+#include "soc/uart_caps.h"
 #include "driver/rtc_io.h"
 #include "freertos/FreeRTOS.h"
 #include "freertos/task.h"
@@ -136,19 +137,15 @@ void esp_deep_sleep(uint64_t time_in_us)
 
 static void IRAM_ATTR suspend_uarts(void)
 {
-    for (int i = 0; i < 2; ++i) {
-        REG_SET_BIT(UART_FLOW_CONF_REG(i), UART_FORCE_XOFF);
+    for (int i = 0; i < SOC_UART_NUM; ++i) {
         uart_tx_wait_idle(i);
+        /* Note: Set `UART_FORCE_XOFF` can't stop new Tx request. */
     }
 }
 
 static void IRAM_ATTR resume_uarts(void)
 {
-    for (int i = 0; i < 2; ++i) {
-        REG_CLR_BIT(UART_FLOW_CONF_REG(i), UART_FORCE_XOFF);
-        REG_SET_BIT(UART_FLOW_CONF_REG(i), UART_FORCE_XON);
-        REG_CLR_BIT(UART_FLOW_CONF_REG(i), UART_FORCE_XON);
-    }
+    /* Note: Set `UART_FORCE_XOFF` can't stop new Tx request. */
 }
 
 static uint32_t IRAM_ATTR esp_sleep_start(uint32_t pd_flags)
@@ -182,7 +179,7 @@ static uint32_t IRAM_ATTR esp_sleep_start(uint32_t pd_flags)
         s_config.sleep_duration > 0) {
         timer_wakeup_prepare();
     }
-    uint32_t result = rtc_sleep_start(s_config.wakeup_triggers, 0,0);
+    uint32_t result = rtc_sleep_start(s_config.wakeup_triggers, 0, 0);
 
     // Restore CPU frequency
     rtc_clk_cpu_freq_set(cpu_freq);
@@ -381,6 +378,8 @@ static void timer_wakeup_prepare(void)
     int64_t rtc_count_delta = rtc_time_us_to_slowclk(sleep_duration, period);
 
     rtc_sleep_set_wakeup_time(s_config.rtc_ticks_at_sleep_start + rtc_count_delta);
+    SET_PERI_REG_MASK(RTC_CNTL_INT_CLR_REG, RTC_CNTL_MAIN_TIMER_INT_CLR_M);
+    SET_PERI_REG_MASK(RTC_CNTL_SLP_TIMER1_REG, RTC_CNTL_MAIN_TIMER_ALARM_EN_M);
 }
 
 esp_err_t esp_sleep_enable_touchpad_wakeup(void)

+ 2 - 2
components/soc/esp32s2beta/include/soc/sens_reg.h

@@ -1143,7 +1143,7 @@ extern "C" {
 #define SENS_TOUCH_PAD14_BASELINE_V  0x3FFFFF
 #define SENS_TOUCH_PAD14_BASELINE_S  0
 
-#define SENS_SAR_TOUCH_STATUS15_REG          (DR_REG_SENS_BASE + 0x0114)
+#define SENS_SAR_TOUCH_SLP_STATUS_REG          (DR_REG_SENS_BASE + 0x0114)
 /* SENS_TOUCH_SLP_DEBOUNCE : RO ;bitpos:[31:29] ;default: 3'd0 ; */
 /*description: */
 #define SENS_TOUCH_SLP_DEBOUNCE  0x00000007
@@ -1157,7 +1157,7 @@ extern "C" {
 #define SENS_TOUCH_SLP_BASELINE_V  0x3FFFFF
 #define SENS_TOUCH_SLP_BASELINE_S  0
 
-#define SENS_SAR_TOUCH_STATUS16_REG          (DR_REG_SENS_BASE + 0x0118)
+#define SENS_SAR_TOUCH_APPR_STATUS_REG          (DR_REG_SENS_BASE + 0x0118)
 /* SENS_TOUCH_SLP_APPROACH_CNT : RO ;bitpos:[31:24] ;default: 8'd0 ; */
 /*description: */
 #define SENS_TOUCH_SLP_APPROACH_CNT  0x000000FF

+ 9 - 1
components/soc/esp32s2beta/include/soc/sens_struct.h

@@ -277,6 +277,14 @@ typedef volatile struct {
         };
         uint32_t val;
     } sar_touch_status[14];
+    union {
+        struct {
+            uint32_t touch_slp_baseline:22;
+            uint32_t reserved22:         7;
+            uint32_t touch_slp_debounce: 3;
+        };
+        uint32_t val;
+    } sar_touch_slp_status;
     union {
         struct {
             uint32_t touch_approach_pad2_cnt: 8;
@@ -285,7 +293,7 @@ typedef volatile struct {
             uint32_t touch_slp_approach_cnt:  8;
         };
         uint32_t val;
-    } sar_touch_status16;
+    } sar_touch_appr_status;
     union {
         struct {
             uint32_t sw_fstep:          16;                 /*frequency step for CW generator*/

+ 0 - 1
examples/system/deep_sleep/CMakeLists.txt

@@ -2,6 +2,5 @@
 # in this exact order for cmake to work correctly
 cmake_minimum_required(VERSION 3.5)
 
-set(SUPPORTED_TARGETS esp32)
 include($ENV{IDF_PATH}/tools/cmake/project.cmake)
 project(deep_sleep)

+ 6 - 6
examples/system/deep_sleep/README.md

@@ -7,8 +7,8 @@ The [deep sleep mode](https://docs.espressif.com/projects/esp-idf/en/latest/api-
 The following wake up sources are demonstrated in this example (refer to the [Wakeup Sources documentation](https://docs.espressif.com/projects/esp-idf/en/latest/api-reference/system/sleep_modes.html#wakeup-sources) for more details regarding wake up sources):
 
 1. **Timer:** An RTC timer that can be programmed to trigger a wake up after a preset time. This example will trigger a wake up every 20 seconds.
-2. **EXT1:** External wake up 1 which is tied to multiple RTC GPIOs. This example use GPIO25 and GPIO26 to trigger a wake up with any one of the two pins are HIGH.
-3. **Touch:** Touch pad sensor interrupt. This example uses touch pads connected to GPIO32 and GPIO33 to trigger a wake up when any of the pads are pressed.
+2. **EXT1:** External wake up 1 which is tied to multiple RTC GPIOs. This example use GPIO2 and GPIO4 to trigger a wake up with any one of the two pins are HIGH.
+3. **Touch:** Touch pad sensor interrupt. This example uses touch pads connected to GPIO32, GPIO33 in ESP32 or GPIO9 in ESP32-S2 to trigger a wake up when any of the pads are pressed.
 4. **ULP:** Ultra Low Power Coprocessor which can continue to run during deep sleep. This example utilizes the ULP and constantly sample the chip's temperature and trigger a wake up  if the chips temperature exceeds ~5 degrees Celsius.
 
 Note: Some wake up sources can be disabled via configuration (see section on [project configuration](#Configure-the-project))
@@ -21,9 +21,9 @@ In this example, the `CONFIG_BOOTLOADER_SKIP_VALIDATE_IN_DEEP_SLEEP` Kconfig opt
 
 This example should be able to run on any commonly available ESP32 development board without any extra hardware if only **Timer** and **ULP** wake up sources are used. However, the following extra connections will be required for the remaining wake up sources.
 
-- **EXT1:** GPIO25 and GPIO26 should be connected to LOW to avoid floating pins. When triggering a wake up, connect one or both of then pins to HIGH. Note that floating pins may trigger an wake up.
+- **EXT1:** GPIO2 and GPIO4 should be connected to LOW to avoid floating pins. When triggering a wake up, connect one or both of then pins to HIGH. Note that floating pins may trigger an wake up.
 
-- **Touch:** GPIO32 and GPIO33 should be connected to touch sensors (see [Touch Sensor Application Note](https://github.com/espressif/esp-iot-solution/blob/master/documents/touch_pad_solution/touch_sensor_design_en.md)).
+- **Touch:** GPIO32, GPIO33 in ESP32 or GPIO9 in ESP32-S2 should be connected to touch sensors (see [Touch Sensor Application Note](https://github.com/espressif/esp-iot-solution/blob/master/documents/touch_pad_solution/touch_sensor_design_en.md)).
 
 ### Configure the project
 
@@ -60,7 +60,7 @@ I (304) cpu_start: Starting scheduler on PRO CPU.
 I (0) cpu_start: Starting scheduler on APP CPU.
 Not a deep sleep reset
 Enabling timer wakeup, 20s
-Enabling EXT1 wakeup on pins GPIO25, GPIO26
+Enabling EXT1 wakeup on pins GPIO2, GPIO4
 Touch pad #8 average: 2148, wakeup threshold set to 2048.
 Touch pad #9 average: 2148, wakeup threshold set to 2048.
 Enabling touch pad wakeup
@@ -78,7 +78,7 @@ Wake up from timer. Time spent in deep sleep: 20313ms
 ULP did 110 temperature measurements in 20313 ms
 Initial T=87, latest T=87
 Enabling timer wakeup, 20s
-Enabling EXT1 wakeup on pins GPIO25, GPIO26
+Enabling EXT1 wakeup on pins GPIO2, GPIO4
 Touch pad #8 average: 2149, wakeup threshold set to 2049.
 Touch pad #9 average: 2146, wakeup threshold set to 2046.
 Enabling touch pad wakeup

+ 47 - 25
examples/system/deep_sleep/main/deep_sleep_example_main.c

@@ -26,6 +26,7 @@
 static RTC_DATA_ATTR struct timeval sleep_enter_time;
 
 #ifdef CONFIG_ENABLE_ULP_TEMPERATURE_WAKEUP
+#if CONFIG_IDF_TARGET_ESP32
 
 /*
  * Offset (in 32-bit words) in RTC Slow memory where the data is placed
@@ -68,13 +69,15 @@ static inline void ulp_data_write(size_t offset, uint16_t value)
 {
     RTC_SLOW_MEM[ULP_DATA_OFFSET + offset] = value;
 }
-
+#endif // CONFIG_IDF_TARGET_ESP32
 #endif // CONFIG_ENABLE_ULP_TEMPERATURE_WAKEUP
 
 #ifdef CONFIG_ENABLE_TOUCH_WAKEUP
+#if CONFIG_IDF_TARGET_ESP32
 #define TOUCH_THRESH_NO_USE 0
 static void calibrate_touch_pad(touch_pad_t pad);
 #endif
+#endif
 
 void app_main(void)
 {
@@ -104,6 +107,7 @@ void app_main(void)
         }
 #endif // CONFIG_ENABLE_TOUCH_WAKEUP
 #ifdef CONFIG_ENABLE_ULP_TEMPERATURE_WAKEUP
+#if CONFIG_IDF_TARGET_ESP32
         case ESP_SLEEP_WAKEUP_ULP: {
             printf("Wake up from ULP\n");
             int16_t diff_high = (int16_t) ulp_data_read(3);
@@ -117,6 +121,7 @@ void app_main(void)
             }
             break;
         }
+#endif // CONFIG_IDF_TARGET_ESP32
 #endif // CONFIG_ENABLE_ULP_TEMPERATURE_WAKEUP
         case ESP_SLEEP_WAKEUP_UNDEFINED:
         default:
@@ -124,10 +129,12 @@ void app_main(void)
     }
 
 #ifdef CONFIG_ENABLE_ULP_TEMPERATURE_WAKEUP
+#if CONFIG_IDF_TARGET_ESP32
     if (esp_sleep_get_wakeup_cause() != ESP_SLEEP_WAKEUP_UNDEFINED) {
         printf("ULP did %d temperature measurements in %d ms\n", ulp_data_read(1), sleep_time_ms);
         printf("Initial T=%d, latest T=%d\n", ulp_data_read(0), ulp_data_read(2));
     }
+#endif // CONFIG_IDF_TARGET_ESP32
 #endif // CONFIG_ENABLE_ULP_TEMPERATURE_WAKEUP
 
     vTaskDelay(1000 / portTICK_PERIOD_MS);
@@ -136,9 +143,9 @@ void app_main(void)
     printf("Enabling timer wakeup, %ds\n", wakeup_time_sec);
     esp_sleep_enable_timer_wakeup(wakeup_time_sec * 1000000);
 
-    const int ext_wakeup_pin_1 = 25;
+    const int ext_wakeup_pin_1 = 2;
     const uint64_t ext_wakeup_pin_1_mask = 1ULL << ext_wakeup_pin_1;
-    const int ext_wakeup_pin_2 = 26;
+    const int ext_wakeup_pin_2 = 4;
     const uint64_t ext_wakeup_pin_2_mask = 1ULL << ext_wakeup_pin_2;
 
     printf("Enabling EXT1 wakeup on pins GPIO%d, GPIO%d\n", ext_wakeup_pin_1, ext_wakeup_pin_2);
@@ -165,13 +172,17 @@ void app_main(void)
     /* Initialize touch pad peripheral. */
     touch_pad_init();
     /* Only support one touch channel in sleep mode. */
-    touch_pad_set_thresh(TOUCH_PAD_NUM8, TOUCH_PAD_THRESHOLD_MAX);
-    touch_pad_sleep_channel_t slp_config = {
-        .touch_num = TOUCH_PAD_NUM8,
-        .sleep_pad_threshold = TOUCH_PAD_THRESHOLD_MAX,
-        .en_proximity = false,
+    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_sleep_channel_config(slp_config);
+    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,
@@ -184,48 +195,57 @@ void app_main(void)
     };
     touch_pad_filter_set_config(&filter_info);
     touch_pad_filter_enable();
-    touch_pad_filter_baseline_reset(TOUCH_PAD_MAX);
-    printf("touch pad filter init %d", TOUCH_PAD_FILTER_IIR_8);
-
-    /* Enable touch sensor clock. Work mode is "timer trigger". */
-    touch_pad_fsm_start(TOUCH_FSM_MODE_TIMER);
-
-    uint32_t touch_value;
-    //read baseline value
-    touch_pad_read_raw(TOUCH_PAD_NUM8, &touch_value);
-    //set interrupt threshold.
+    touch_pad_filter_baseline_reset(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 = {
-        .touch_num = TOUCH_PAD_NUM8,
-        .sleep_pad_threshold = touch_value * 0.2,
+        .touch_num = TOUCH_PAD_NUM9,
+        .sleep_pad_threshold = TOUCH_PAD_THRESHOLD_MAX,
         .en_proximity = false,
     };
-    touch_pad_sleep_channel_config(slp_config); //20%
-    printf("test init: touch pad [%d] base %d, thresh %d", \
-        TOUCH_PAD_NUM8, touch_value, (uint32_t)(touch_value * 0.2));
+    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);
+    slp_config.sleep_pad_threshold = touch_value * 0.1;
+    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
     printf("Enabling touch pad wakeup\n");
     esp_sleep_enable_touchpad_wakeup();
+    esp_sleep_pd_config(ESP_PD_DOMAIN_RTC_PERIPH, ESP_PD_OPTION_ON);
 #endif // CONFIG_ENABLE_TOUCH_WAKEUP
 
 #ifdef CONFIG_ENABLE_ULP_TEMPERATURE_WAKEUP
+#if CONFIG_IDF_TARGET_ESP32
     printf("Enabling ULP wakeup\n");
     esp_sleep_enable_ulp_wakeup();
 #endif
+#endif
 
+#if CONFIG_IDF_TARGET_ESP32
     // Isolate GPIO12 pin from external circuits. This is needed for modules
     // which have an external pull-up resistor on GPIO12 (such as ESP32-WROVER)
     // to minimize current consumption.
     rtc_gpio_isolate(GPIO_NUM_12);
+#endif
 
     printf("Entering deep sleep\n");
     gettimeofday(&sleep_enter_time, NULL);
 
 #ifdef CONFIG_ENABLE_ULP_TEMPERATURE_WAKEUP
+#if CONFIG_IDF_TARGET_ESP32
     start_ulp_temperature_monitoring();
+#endif
 #endif
 
     esp_deep_sleep_start();
-}
+} 
 
 #ifdef CONFIG_ENABLE_TOUCH_WAKEUP
 #if CONFIG_IDF_TARGET_ESP32
@@ -254,6 +274,7 @@ static void calibrate_touch_pad(touch_pad_t pad)
 #endif // CONFIG_ENABLE_TOUCH_WAKEUP
 
 #ifdef CONFIG_ENABLE_ULP_TEMPERATURE_WAKEUP
+#if CONFIG_IDF_TARGET_ESP32
 static void start_ulp_temperature_monitoring(void)
 {
     /*
@@ -353,5 +374,6 @@ static void start_ulp_temperature_monitoring(void)
     // Start ULP
     ESP_ERROR_CHECK( ulp_run(0) );
 }
+#endif // CONFIG_IDF_TARGET_ESP32
 #endif // CONFIG_ENABLE_ULP_TEMPERATURE_WAKEUP