ESP-IDF ESP32 Deep Sleep Modes and Wake up Sources

In this tutorial, we will learn about ESP32 deep sleep modes and wake up sources using ESP-IDF. We will show you how to put the ESP32 development board into deep sleep mode. Furthermore, we will also discuss different wake up sources through which ESP32 can go from sleep to normal execution mode such as timer, external events, touch pins and ULP coprocessor wakeup.

Before we move ahead, make sure you have the latest version of VS Code installed on your system with the ESP-IDF extension configured.

If you are using Arduino instead of esp-idf, you can refer to this guide:

ESP32 Deep Sleep Mode

Deep sleep mode in ESP32 helps to save battery life and reduce power consumption. The module consumes a lot of power, generally ranging up to 75mA in normal consumption mode, which increases to 240 mA incase of Wi-Fi usage. To reduce the this extra power consumption we can easily put our board in deep sleep mode when we want to perform some task after some specific duration. When we have successfully activated deep sleep in ESP32, the current consumption would be in the range of micro Amperes (μA) and batteries will also last longer.

The table below shows the peripherals and units that are active or inactive during different modes for ESP32. Note that in deep sleep mode, only the RTC memory and peripherals (RTC controller, RTC fast memory, RTC slow memory) and ULP coprocessor are ON, rest all units are OFF that include all the digital peripherals, most of the RAM, and the CPU.

ESP32 Peripherals in different modes

For better insight, follow the table below to note how the power consumption changes when the ESP32 board is in deep sleep mode as compared to the other modes.

ESP32 modes and power consumption

Configure Deep Sleep

After configuring the wakeup sources, the ESP32 board can enter deep sleep by the following call.

esp_deep_sleep_start()

This API is used to enter Deep-sleep. If a wakeup source is not configured already then the board remains in deep sleep mode until the external Reset button is pressed.

After the ESP32 board enters deep sleep, the RTC controller power downs/ turns off the digital peripherals and CPUs. Also, the hardware gets configured according to the wakeup sources that were configured.

ESP32 Wake Up Sources

To enable ESP32 to wakeup from deep sleep, various wakeup sources can be used. These include timer wakeup, touch pin wakeup, external wakeup and ULP coprocessor wakeup. These wakeup sources can act on their own to wake the board or even be combined together such that when any of the sources is triggered, the ESP32 board wakes up. These sources are configured in the code before the ESP32 board enters deep sleep mode. To enable a wakeup source, the following generic API is used:

esp_sleep_enable_X_wakeup() 

where ‘X’ is the wakeup source and can take either of the following values:

  • timer
  • touchpad
  • ext0
  • ext1
  • ulp

Likewise, to disable a wakeup source, the following generic API is used:

esp_sleep_disable_wakeup_source() 

Timer Wakeup

Timer wakeup is one of the simplest wakeup sources which uses the built-in timer of the real-time controller (RTC). The ESP32 board wakes up after the set amount of timer is over. The timer is defined in amount of microseconds although the exact resolution depends on the clock source that is selected for RTC SLOW_CLK. Although timer wakeup relies upon the built-in timer of RTC but there is no need to keep the RTC peripherals/RTC memories powered on during sleep in this wakeup mode.

The following function is used to enable deep sleep wakeup though timer:

esp_sleep_enable_timer_wakeup()

Touchpad

Touchpad wakeup or touch wakeup is another option to wake the ESP32 board from deep sleep. The wake up will occur when the user will touch one of the touch pins of the ESP32 board causing a touch sensor interrupt to occur.

The following function is used to enable deep sleep wakeup though touchpad:

esp_sleep_enable_touchpad_wakeup()

ESP32 Touch Sensor Pins

ESP-WROOM-32 consists of 10 on-board capacitive touch sensors. These are helpful as they act as touch sensors which can cause a touchpad interrupt wakeup when they are touched, detecting any electrical/magnetic waves around them. You can view the touch sensor pins featured on ESP32 board:

  • TOUCH0 – GPIO4
  • TOUCH1 – GPIO0
  • TOUCH2 – GPIO2
  • TOUCH3 – GPIO15
  • TOUCH4 – GPIO13
  • TOUCH5 – GPIO12
  • TOUCH6 – GPIO14
  • TOUCH7 – GPIO27
  • TOUCH8 – GPIO33
  • TOUCH9 – GPIO32

External Wakeup

External wakeup is also used as a wakeup source, where the changing of a GPIO pin’s state wakes up the ESP32 board from deep sleep. The wakeup source is configured before setting the ESP32 board into deep sleep mode. There are two kinds of external wakeups that we can set up: ext0 and ext1. In ext0, one GPIO pin is configured to act as an external wakeup. However, if you are using multiple GPIO pins, then ext1 is used instead.

One important point to note here is that we can only use RTC GPIO pins as a wake up source for external wakeup.

The ESP32 DevKit V1-DOIT has 14 RTC GPIO pins that can be used to invoke external interrupt wakeup.

  • RTC_GPIO0 : GPIO36
  • RTC_GPIO3: GPIO39
  • RTC_GPIO9: GPIO32
  • RTC_GPIO8: GPIO33
  • RTC_GPIO6: GPIO25
  • RTC_GPIO7: GPIO26
  • RTC_GPIO17: GPIO27
  • RTC_GPIO16: GPIO14
  • RTC_GPIO15: GPIO12
  • RTC_GPIO14: GPIO13
  • RTC_GPIO11: GPIO0
  • RTC_GPIO13: GPIO15
  • RTC_GPIO12: GPIO2
  • RTC_GPIO10: GPIO4

External Wake Up – ext0

As we mentioned before, ext0 is used when a single RTC GPIO is being used to act as an external wakeup. To enable ext0 wakeup source, we use the following API:

esp_sleep_enable_ext0_wakeup()

The RTC IO module is responsible for triggering the ext0 wakeup. As the RTC IO module is part of the RTC peripherals power domain, hence, the RTC peripherals have to be powered ON during deep sleep mode, if using ext0 as a wakeup source.

As we mentioned before, multiple wakeup sources can be combined together where any one can trigger a wakeup. However, when using ext0, we can not use touchpad or ULP wakeup sources alongside it. They are not compatible with this external wakeup.

External Wake Up -ext1

As we mentioned before, ext1 is used when multiple RTC GPIOs are being used to act as external wakeups. To enable ext1 wakeup source, we use the following API:

esp_sleep_enable_ext1_wakeup()

The RTC controller is responsible for triggering the ext1 wakeup. Therefore, the RTC peripherals can be powered off while using ext1 wakeup sources. To trigger a wakeup using ext1, we can use either of the two logic functions: ESP_EXT1_WAKEUP_ANY_HIGH or ESP_EXT1_WAKEUP_ALL_LOW. In the case of the first logic function, wakeup is triggered when any of the set RTC GPIO is in a HIGH state. In the case of the second logic, function, wakeup is triggered when all of the set RTC GPIOs are in a LOW state.

ULP Coprocessor Wakeup

Lastly, we will look at the ULP coprocessor wakeup. In this case, wakeup is triggered when any specific event occurs related to the the ULP coprocessor that is being monitored. The ULP coprocessor is powered on while the ESP32 board is in deep sleep mode, hence it can act as a wakeup source. If using ULP coprocessor as a wakeup source, the RTC slow memory will be powered on. This is because ULP is a part of the RTC peripherals power domain and also responsible for running the program which is kept in the RTC slow memory. Therefore, when the ULP runs the program, RTC peripherals will also be powered on and will shit down once the ULP finishes running the program.

To enable this wakeup source, we use the following API:

esp_sleep_enable_ulp_wakeup()

ESP-IDF Deep Sleep Example 

In this section, we will build and test a deep sleep example provided by ESP-IDF under the system tab. This example configures various wakeup sources and then sets the ESP32 board into deep using using esp_sleep.h API.

Create Example Project

Open your VS Code and head over to View > Command Palette. Type ESP-IDF: New Project in the search bar and press enter.

Specify the project name and directory. We have named our project ‘ESP_IDF_DEEP_SLEEP.’ For the ESP-IDF board, we have chosen the custom board option. For ESP-IDF target, we have chosen ESP32 module. Click ‘Choose Template’ button to proceed forward.

ESP32 Deep Sleep Project using ESP-IDF 1

In the Extension, select ESP-IDF option:

ESP-IDF in VS Code New Project 2

We will click the ‘deep_sleep’ under the system tab. Now click ‘Create project using template deep_sleep.’

ESP32 Deep Sleep Project using ESP-I

You will get a notification that the project has been created. To open the project in a new window, click ‘Yes.’

This opens our ESP_IDF_DEEP_SLEEP project that we created, inside the EXPLORER tab. There are several folders inside our project folder. This is the same for every project which you will create through ESP-IDF Explorer.

Project Configuration

Lets first head over to the menuconfig. Click the icon shown below. It opens the ESP-IDF SDK Configuration Editor.

ESP32 Deep Sleep Project using ESP-IDF 3

Scroll down and open the Example Configuration for our project. Here you can enable the wakeup sources which you want to include for the example. By default, touch wake up, temperature monitoring by ULP and wakeup from GPIO have been enabled. You can disable any option according to your preference as well.

ESP32 Deep Sleep Project using

Lets head over to the main.c file. The main folder contains the source code meaning the main.c file will be found here.

Now go to main > deep_sleep_example_main.c and open it.

The following code opens up which is shown below. This example code will demonstrate how to setup ESP32 into deep sleep mode and configure four wakeup sources which are mentioned below.

  • Timer wakeup: The built-in RTC timer triggers the ESP32 to wake up after every 20 seconds.
  • External wakeup ext1: The ext1 triggers a wakeup using ESP_EXT1_WAKEUP_ANY_HIGH. This means that when either of the RTC GPIO is in a HIGH state the ESP32 board wakes up. In this example, GPIO2 and GPIO4 are used as RTC GPIOs.
  • Touchpad wakeup: The wake up will occur when the user will touch any of the touch pins: GPIO32 or GPIO33 for ESP32 and GPIO9 for ESP32-S2. This will cause a touch sensor interrupt to occur.
  • ULP Coprocessor wakeup: In this case the ULP coprocessor continuously monitors the temperature of the microcontroller chip. When the temperature exceeds 5 degree Celsius, the wakeup is triggered.

This example sketch uses the APIs that we discussed previously to configure the timer, ext1, touch and ULP wakeup sources and then sets the ESP32 board in deep sleep mode.

ESP-IDF Code: ESP32 Deep Sleep

/* Deep sleep wake up example

   This example code is in the Public Domain (or CC0 licensed, at your option.)

   Unless required by applicable law or agreed to in writing, this
   software is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR
   CONDITIONS OF ANY KIND, either express or implied.
*/

#include <stdio.h>
#include <string.h>
#include <stdlib.h>
#include <time.h>
#include <sys/time.h>
#include "sdkconfig.h"
#include "soc/soc_caps.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "esp_sleep.h"
#include "esp_log.h"
#include "driver/adc.h"
#include "driver/rtc_io.h"
#include "soc/rtc.h"

#if CONFIG_IDF_TARGET_ESP32
#include "esp32/ulp.h"
#endif

#if SOC_TOUCH_SENSOR_NUM > 0
#include "soc/sens_periph.h"
#include "driver/touch_pad.h"
#endif

#ifdef CONFIG_IDF_TARGET_ESP32C3
#define DEFAULT_WAKEUP_PIN      CONFIG_EXAMPLE_GPIO_WAKEUP_PIN
#ifdef CONFIG_EXAMPLE_GPIO_WAKEUP_HIGH_LEVEL
#define DEFAULT_WAKEUP_LEVEL    ESP_GPIO_WAKEUP_GPIO_HIGH
#else
#define DEFAULT_WAKEUP_LEVEL    ESP_GPIO_WAKEUP_GPIO_LOW
#endif
#endif

static RTC_DATA_ATTR struct timeval sleep_enter_time;

#ifdef CONFIG_EXAMPLE_ULP_TEMPERATURE_WAKEUP
#if CONFIG_IDF_TARGET_ESP32

/*
 * Offset (in 32-bit words) in RTC Slow memory where the data is placed
 * by the ULP coprocessor. It can be chosen to be any value greater or equal
 * to ULP program size, and less than the CONFIG_ESP32_ULP_COPROC_RESERVE_MEM/4 - 6,
 * where 6 is the number of words used by the ULP coprocessor.
 */
#define ULP_DATA_OFFSET     36

_Static_assert(ULP_DATA_OFFSET < CONFIG_ESP32_ULP_COPROC_RESERVE_MEM/4 - 6,
        "ULP_DATA_OFFSET is set too high, or CONFIG_ESP32_ULP_COPROC_RESERVE_MEM is not sufficient");

/**
 * @brief Start ULP temperature monitoring program
 *
 * This function loads a program into the RTC Slow memory and starts up the ULP.
 * The program monitors on-chip temperature sensor and wakes up the SoC when
 * the temperature goes lower or higher than certain thresholds.
 */
static void start_ulp_temperature_monitoring(void);

/**
 * @brief Utility function which reads data written by ULP program
 *
 * @param offset offset from ULP_DATA_OFFSET in RTC Slow memory, in words
 * @return lower 16-bit part of the word writable by the ULP
 */
static inline uint16_t ulp_data_read(size_t offset)
{
    return RTC_SLOW_MEM[ULP_DATA_OFFSET + offset] & 0xffff;
}

/**
 * @brief Utility function which writes data to be ready by ULP program
 *
 * @param offset offset from ULP_DATA_OFFSET in RTC Slow memory, in words
 * @param value lower 16-bit part of the word to be stored
 */
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_EXAMPLE_ULP_TEMPERATURE_WAKEUP

#ifdef CONFIG_EXAMPLE_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)
{
    struct timeval now;
    gettimeofday(&now, NULL);
    int sleep_time_ms = (now.tv_sec - sleep_enter_time.tv_sec) * 1000 + (now.tv_usec - sleep_enter_time.tv_usec) / 1000;

    switch (esp_sleep_get_wakeup_cause()) {
#ifdef CONFIG_EXAMPLE_EXT1_WAKEUP
        case ESP_SLEEP_WAKEUP_EXT1: {
            uint64_t wakeup_pin_mask = esp_sleep_get_ext1_wakeup_status();
            if (wakeup_pin_mask != 0) {
                int pin = __builtin_ffsll(wakeup_pin_mask) - 1;
                    printf("Wake up from GPIO %d\n", pin);
            } else {
                printf("Wake up from GPIO\n");
            }
            break;
        }
#endif // CONFIG_EXAMPLE_EXT1_WAKEUP
#if SOC_GPIO_SUPPORT_DEEPSLEEP_WAKEUP
        case ESP_SLEEP_WAKEUP_GPIO: {
            uint64_t wakeup_pin_mask = esp_sleep_get_gpio_wakeup_status();
            if (wakeup_pin_mask != 0) {
                int pin = __builtin_ffsll(wakeup_pin_mask) - 1;
                printf("Wake up from GPIO %d\n", pin);
            } else {
                printf("Wake up from GPIO\n");
            }
            break;
        }
#endif //SOC_GPIO_SUPPORT_DEEPSLEEP_WAKEUP
        case ESP_SLEEP_WAKEUP_TIMER: {
            printf("Wake up from timer. Time spent in deep sleep: %dms\n", sleep_time_ms);
            break;
        }
#ifdef CONFIG_EXAMPLE_TOUCH_WAKEUP
        case ESP_SLEEP_WAKEUP_TOUCHPAD: {
            printf("Wake up from touch on pad %d\n", esp_sleep_get_touchpad_wakeup_status());
            break;
        }
#endif // CONFIG_EXAMPLE_TOUCH_WAKEUP
#ifdef CONFIG_EXAMPLE_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);
            int16_t diff_low = (int16_t) ulp_data_read(4);
            if (diff_high < 0) {
                printf("High temperature alarm was triggered\n");
            } else if (diff_low < 0) {
                printf("Low temperature alarm was triggered\n");
            } else {
                assert(false && "temperature has stayed within limits, but got ULP wakeup\n");
            }
            break;
        }
#endif // CONFIG_IDF_TARGET_ESP32
#endif // CONFIG_EXAMPLE_ULP_TEMPERATURE_WAKEUP
        case ESP_SLEEP_WAKEUP_UNDEFINED:
        default:
            printf("Not a deep sleep reset\n");
    }

#ifdef CONFIG_EXAMPLE_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_EXAMPLE_ULP_TEMPERATURE_WAKEUP

    vTaskDelay(1000 / portTICK_PERIOD_MS);

    const int wakeup_time_sec = 20;
    printf("Enabling timer wakeup, %ds\n", wakeup_time_sec);
    esp_sleep_enable_timer_wakeup(wakeup_time_sec * 1000000);

#ifdef CONFIG_EXAMPLE_EXT1_WAKEUP
    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 = 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);
    esp_sleep_enable_ext1_wakeup(ext_wakeup_pin_1_mask | ext_wakeup_pin_2_mask, ESP_EXT1_WAKEUP_ANY_HIGH);
#endif // CONFIG_EXAMPLE_EXT1_WAKEUP

#ifdef CONFIG_EXAMPLE_GPIO_WAKEUP
    const gpio_config_t config = {
        .pin_bit_mask = BIT(DEFAULT_WAKEUP_PIN),
        .mode = GPIO_MODE_INPUT,
    };
    ESP_ERROR_CHECK(gpio_config(&config));
    ESP_ERROR_CHECK(esp_deep_sleep_enable_gpio_wakeup(BIT(DEFAULT_WAKEUP_PIN), DEFAULT_WAKEUP_LEVEL));
    printf("Enabling GPIO wakeup on pins GPIO%d\n", DEFAULT_WAKEUP_PIN);
#endif

#ifdef CONFIG_EXAMPLE_TOUCH_WAKEUP
#if CONFIG_IDF_TARGET_ESP32
    // Initialize touch pad peripheral.
    // The default fsm mode is software trigger mode.
    ESP_ERROR_CHECK(touch_pad_init());
    // If use touch pad wake up, should set touch sensor FSM mode at 'TOUCH_FSM_MODE_TIMER'.
    touch_pad_set_fsm_mode(TOUCH_FSM_MODE_TIMER);
    // Set reference voltage for charging/discharging
    // In this case, the high reference valtage will be 2.4V - 1V = 1.4V
    // The low reference voltage will be 0.5
    // The larger the range, the larger the pulse count value.
    touch_pad_set_voltage(TOUCH_HVOLT_2V4, TOUCH_LVOLT_0V5, TOUCH_HVOLT_ATTEN_1V);
    //init RTC IO and mode for touch pad.
    touch_pad_config(TOUCH_PAD_NUM8, TOUCH_THRESH_NO_USE);
    touch_pad_config(TOUCH_PAD_NUM9, TOUCH_THRESH_NO_USE);
    calibrate_touch_pad(TOUCH_PAD_NUM8);
    calibrate_touch_pad(TOUCH_PAD_NUM9);
#elif CONFIG_IDF_TARGET_ESP32S2
    /* Initialize touch pad peripheral. */
    touch_pad_init();
    /* Only support one touch channel in sleep mode. */
    touch_pad_config(TOUCH_PAD_NUM9);
    /* Denoise setting at TouchSensor 0. */
    touch_pad_denoise_t denoise = {
        /* The bits to be cancelled are determined according to the noise level. */
        .grade = TOUCH_PAD_DENOISE_BIT4,
        .cap_level = TOUCH_PAD_DENOISE_CAP_L4,
    };
    touch_pad_denoise_set_config(&denoise);
    touch_pad_denoise_enable();
    printf("Denoise function init\n");
    /* Filter setting */
    touch_filter_config_t filter_info = {
        .mode = TOUCH_PAD_FILTER_IIR_16,
        .debounce_cnt = 1,      // 1 time count.
        .noise_thr = 0,         // 50%
        .jitter_step = 4,       // use for jitter mode.
        .smh_lvl = TOUCH_PAD_SMOOTH_IIR_2,
    };
    touch_pad_filter_set_config(&filter_info);
    touch_pad_filter_enable();
    printf("touch pad filter init %d\n", TOUCH_PAD_FILTER_IIR_8);
    /* Set sleep touch pad. */
    touch_pad_sleep_channel_enable(TOUCH_PAD_NUM9, true);
    touch_pad_sleep_channel_enable_proximity(TOUCH_PAD_NUM9, false);
    /* Reducing the operating frequency can effectively reduce power consumption. */
    touch_pad_sleep_channel_set_work_time(1000, TOUCH_PAD_MEASURE_CYCLE_DEFAULT);
    /* 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_read_smooth(TOUCH_PAD_NUM9, &touch_value);
    touch_pad_sleep_set_threshold(TOUCH_PAD_NUM9, touch_value * 0.1); //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_EXAMPLE_TOUCH_WAKEUP

#ifdef CONFIG_EXAMPLE_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_EXAMPLE_ULP_TEMPERATURE_WAKEUP
#if CONFIG_IDF_TARGET_ESP32
    start_ulp_temperature_monitoring();
#endif
#endif

    esp_deep_sleep_start();
}

#ifdef CONFIG_EXAMPLE_TOUCH_WAKEUP
#if CONFIG_IDF_TARGET_ESP32
static void calibrate_touch_pad(touch_pad_t pad)
{
    int avg = 0;
    const size_t calibration_count = 128;
    for (int i = 0; i < calibration_count; ++i) {
        uint16_t val;
        touch_pad_read(pad, &val);
        avg += val;
    }
    avg /= calibration_count;
    const int min_reading = 300;
    if (avg < min_reading) {
        printf("Touch pad #%d average reading is too low: %d (expecting at least %d). "
               "Not using for deep sleep wakeup.\n", pad, avg, min_reading);
        touch_pad_config(pad, 0);
    } else {
        int threshold = avg - 100;
        printf("Touch pad #%d average: %d, wakeup threshold set to %d.\n", pad, avg, threshold);
        touch_pad_config(pad, threshold);
    }
}
#endif
#endif // CONFIG_EXAMPLE_TOUCH_WAKEUP

#ifdef CONFIG_EXAMPLE_ULP_TEMPERATURE_WAKEUP
#if CONFIG_IDF_TARGET_ESP32
static void start_ulp_temperature_monitoring(void)
{
    /*
     * This ULP program monitors the on-chip temperature sensor and wakes the chip up when
     * the temperature goes outside of certain window.
     * When the program runs for the first time, it saves the temperature measurement,
     * it is considered initial temperature (T0).
     *
     * On each subsequent run, temperature measured and compared to T0.
     * If the measured value is higher than T0 + max_temp_diff or lower than T0 - max_temp_diff,
     * the chip is woken up from deep sleep.
     */

    /* Temperature difference threshold which causes wakeup
     * With settings here (TSENS_CLK_DIV=2, 8000 cycles),
     * TSENS measurement is done in units of 0.73 degrees Celsius.
     * Therefore, max_temp_diff below is equivalent to ~2.2 degrees Celsius.
     */
    const int16_t max_temp_diff = 3;

    // Number of measurements ULP should do per second
    const uint32_t measurements_per_sec = 5;

    // Allow TSENS to be controlled by the ULP
    SET_PERI_REG_BITS(SENS_SAR_TSENS_CTRL_REG, SENS_TSENS_CLK_DIV, 2, SENS_TSENS_CLK_DIV_S);
    SET_PERI_REG_BITS(SENS_SAR_MEAS_WAIT2_REG, SENS_FORCE_XPD_SAR, 3, SENS_FORCE_XPD_SAR_S);
    CLEAR_PERI_REG_MASK(SENS_SAR_TSENS_CTRL_REG, SENS_TSENS_POWER_UP);
    CLEAR_PERI_REG_MASK(SENS_SAR_TSENS_CTRL_REG, SENS_TSENS_DUMP_OUT);
    CLEAR_PERI_REG_MASK(SENS_SAR_TSENS_CTRL_REG, SENS_TSENS_POWER_UP_FORCE);

    // Clear the part of RTC_SLOW_MEM reserved for the ULP. Makes debugging easier.
    memset(RTC_SLOW_MEM, 0, CONFIG_ESP32_ULP_COPROC_RESERVE_MEM);

    // The first word of memory (at data offset) is used to store the initial temperature (T0)
    // Zero it out here, then ULP will update it on the first run.
    ulp_data_write(0, 0);
    // The second word is used to store measurement count, zero it out as well.
    ulp_data_write(1, 0);

    const ulp_insn_t program[] = {
        // load data offset into R2
        I_MOVI(R2, ULP_DATA_OFFSET),
        // load/increment/store measurement counter using R1
        I_LD(R1, R2, 1),
        I_ADDI(R1, R1, 1),
        I_ST(R1, R2, 1),
        // enable temperature sensor
        I_WR_REG(SENS_SAR_MEAS_WAIT2_REG, SENS_FORCE_XPD_SAR_S, SENS_FORCE_XPD_SAR_S + 1, 3),
        // do temperature measurement and store result in R3
        I_TSENS(R3, 8000),
        // disable temperature sensor
        I_WR_REG(SENS_SAR_MEAS_WAIT2_REG, SENS_FORCE_XPD_SAR_S, SENS_FORCE_XPD_SAR_S + 1, 0),
        // Save current measurement at offset+2
        I_ST(R3, R2, 2),
        // load initial value into R0
        I_LD(R0, R2, 0),
        // if threshold value >=1 (i.e. initialized), goto 1
        M_BGE(1, 1),
            // otherwise, save the current value as initial (T0)
            I_MOVR(R0, R3),
            I_ST(R0, R2, 0),
        M_LABEL(1),
        // check if the temperature is greater or equal (T0 + max_temp_diff)
        // uses R1 as scratch register, difference is saved at offset + 3
        I_ADDI(R1, R0, max_temp_diff - 1),
        I_SUBR(R1, R1, R3),
        I_ST(R1, R2, 3),
        M_BXF(2),
        // check if the temperature is less or equal (T0 - max_temp_diff)
        // uses R1 as scratch register, difference is saved at offset + 4
        I_SUBI(R1, R0, max_temp_diff - 1),
        I_SUBR(R1, R3, R1),
        I_ST(R1, R2, 4),
        M_BXF(2),
            // temperature is within (T0 - max_temp_diff; T0 + max_temp_diff)
            // stop ULP until the program timer starts it again
            I_HALT(),
        M_LABEL(2),
            // temperature is out of bounds
            // disable ULP program timer
            I_WR_REG_BIT(RTC_CNTL_STATE0_REG, RTC_CNTL_ULP_CP_SLP_TIMER_EN_S, 0),
            // initiate wakeup of the SoC
            I_WAKE(),
            // stop the ULP program
            I_HALT()
    };

    // Load ULP program into RTC_SLOW_MEM, at offset 0
    size_t size = sizeof(program)/sizeof(ulp_insn_t);
    ESP_ERROR_CHECK( ulp_process_macros_and_load(0, program, &size) );
    assert(size < ULP_DATA_OFFSET && "ULP_DATA_OFFSET needs to be greater or equal to the program size");

    // Set ULP wakeup period
    const uint32_t sleep_cycles = rtc_clk_slow_freq_get_hz() / measurements_per_sec;
    REG_WRITE(SENS_ULP_CP_SLEEP_CYC0_REG, sleep_cycles);

    // Start ULP
    ESP_ERROR_CHECK( ulp_run(0) );
}
#endif // CONFIG_IDF_TARGET_ESP32
#endif // CONFIG_EXAMPLE_ULP_TEMPERATURE_WAKEUP

Compiling the Sketch

To flash your chip, type the following command in the serial terminal. Remember to replace the COM port with the one through which your board is connected.

idf.py -p COMX flash monitor
ESP32 Deep Sleep Project using ESP

After the code flashes successfully, the ESP-ID terminal displays the following messages. This is the initial startup hence it shows that by printing ‘Not a deep sleep reset.’ The timer wakeup is enabled for a predefined time of 20s. The ext1 wakeup is set on GPIO2 and GPIO4. For the touchpad wakeup, GPIO33 and GPIO32 were configured which correspond to touch pad 8 and touch pad 9 respectively. The average reading along with the set threshold is printed for both the touch pads. Then, the touch pad and ULP wakeup are enabled. Finally, the ESP32 board goes into deep sleep mode.

ESP32 Deep Sleep Project using ESP-I

These are the output messages that we received in our terminal when the ESP32 woke up from deep sleep. The ESP32 boots again but this time the terminal prints that it woke up and the source which caused it. In our case, the wakeup occurred from ULP. The ESP32 again goes to deep sleep after printing all the output messages showing the ULP temperature measurements and enabling the wakeup sources.

ESP32 Deep Sleep Project using ESP-IDF Terminal 2

To trigger wakeup through ext1, first make sure GPIO2 and GPIO4 of ESP32 are in a LOW state to avoid floating pins and then either of these two pins should be connected to HIGH. Likewise, to trigger a wakeup using the touchpad, connect a wire with GPIO32, GPIO33 and touch it. You can also connect these pins with touch sensors. Without using any additional hardware, only the timer and ULP wakeup sources will work.

You may also like to read:

Leave a Comment