From f33428f2e5b75b9846a8c135db4664e7640e1bf4 Mon Sep 17 00:00:00 2001 From: morris Date: Wed, 22 Jun 2022 16:34:13 +0800 Subject: [PATCH] sdm: added channel allocator for sigma delta module --- components/driver/.build-test-rules.yml | 4 + components/driver/Kconfig | 26 ++ components/driver/include/driver/gptimer.h | 2 +- components/driver/include/driver/sdm.h | 111 +++++++ components/driver/linker.lf | 2 + components/driver/sdm.c | 311 ++++++++++++++++++ .../driver/test_apps/sdm/CMakeLists.txt | 18 + components/driver/test_apps/sdm/README.md | 2 + .../driver/test_apps/sdm/main/CMakeLists.txt | 7 + .../driver/test_apps/sdm/main/test_app_main.c | 51 +++ .../driver/test_apps/sdm/main/test_sdm.c | 68 ++++ components/driver/test_apps/sdm/pytest_sdm.py | 24 ++ .../test_apps/sdm/sdkconfig.ci.iram_safe | 5 + .../driver/test_apps/sdm/sdkconfig.ci.release | 5 + .../driver/test_apps/sdm/sdkconfig.defaults | 2 + 15 files changed, 637 insertions(+), 1 deletion(-) create mode 100644 components/driver/include/driver/sdm.h create mode 100644 components/driver/sdm.c create mode 100644 components/driver/test_apps/sdm/CMakeLists.txt create mode 100644 components/driver/test_apps/sdm/README.md create mode 100644 components/driver/test_apps/sdm/main/CMakeLists.txt create mode 100644 components/driver/test_apps/sdm/main/test_app_main.c create mode 100644 components/driver/test_apps/sdm/main/test_sdm.c create mode 100644 components/driver/test_apps/sdm/pytest_sdm.py create mode 100644 components/driver/test_apps/sdm/sdkconfig.ci.iram_safe create mode 100644 components/driver/test_apps/sdm/sdkconfig.ci.release create mode 100644 components/driver/test_apps/sdm/sdkconfig.defaults diff --git a/components/driver/.build-test-rules.yml b/components/driver/.build-test-rules.yml index ce158906c7..d25382f32d 100644 --- a/components/driver/.build-test-rules.yml +++ b/components/driver/.build-test-rules.yml @@ -28,6 +28,10 @@ components/driver/test_apps/rmt: disable: - if: SOC_RMT_SUPPORTED != 1 +components/driver/test_apps/sdm: + disable: + - if: SOC_SDM_SUPPORTED != 1 + components/driver/test_apps/temperature_sensor: disable: - if: SOC_TEMP_SENSOR_SUPPORTED != 1 diff --git a/components/driver/Kconfig b/components/driver/Kconfig index e3afb0d64a..bb46a084f6 100644 --- a/components/driver/Kconfig +++ b/components/driver/Kconfig @@ -224,6 +224,32 @@ menu "Driver Configurations" so that these functions can be IRAM-safe and able to be called in the other IRAM interrupt context. endmenu # GPIO Configuration + menu "Sigma Delta Modulator Configuration" + depends on SOC_SDM_SUPPORTED + config SDM_CTRL_FUNC_IN_IRAM + bool "Place SDM control functions into IRAM" + default n + help + Place SDM control functions (like set_duty) into IRAM, + so that these functions can be IRAM-safe and able to be called in the other IRAM interrupt context. + Enabling this option can improve driver performance as well. + + config SDM_SUPPRESS_DEPRECATE_WARN + bool "Suppress legacy driver deprecated warning" + default n + help + Wether to suppress the deprecation warnings when using legacy sigma delta driver. + If you want to continue using the legacy driver, and don't want to see related deprecation warnings, + you can enable this option. + + config SDM_ENABLE_DEBUG_LOG + bool "Enable debug log" + default n + help + Wether to enable the debug log message for SDM driver. + Note that, this option only controls the SDM driver log, won't affect other drivers. + endmenu # Sigma Delta Modulator Configuration + menu "GPTimer Configuration" config GPTIMER_CTRL_FUNC_IN_IRAM bool "Place GPTimer control functions into IRAM" diff --git a/components/driver/include/driver/gptimer.h b/components/driver/include/driver/gptimer.h index a2d60a2c46..e6fe50420d 100644 --- a/components/driver/include/driver/gptimer.h +++ b/components/driver/include/driver/gptimer.h @@ -41,7 +41,7 @@ typedef bool (*gptimer_alarm_cb_t) (gptimer_handle_t timer, const gptimer_alarm_ /** * @brief Group of supported GPTimer callbacks * @note The callbacks are all running under ISR environment - * @note When CONFIG_GPTIMER_ISR_IRAM_SAFE is enabled, the callback itself and functions callbed by it should be placed in IRAM. + * @note When CONFIG_GPTIMER_ISR_IRAM_SAFE is enabled, the callback itself and functions called by it should be placed in IRAM. */ typedef struct { gptimer_alarm_cb_t on_alarm; /*!< Timer alarm callback */ diff --git a/components/driver/include/driver/sdm.h b/components/driver/include/driver/sdm.h new file mode 100644 index 0000000000..46b14fd576 --- /dev/null +++ b/components/driver/include/driver/sdm.h @@ -0,0 +1,111 @@ +/* + * SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#pragma once + +#include +#include "hal/sdm_types.h" +#include "esp_err.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief Type of Sigma Delta channel handle + */ +typedef struct sdm_channel_t *sdm_channel_handle_t; + +/** + * @brief Sigma Delta channel configuration + */ +typedef struct { + int gpio_num; /*!< GPIO number */ + sdm_clock_source_t clk_src; /*!< Clock source */ + uint32_t sample_rate_hz; /*!< Sample rate in Hz, it determines how frequent the modulator outputs a pulse */ + struct { + uint32_t invert_out: 1; /*!< Whether to invert the output signal */ + uint32_t io_loop_back: 1; /*!< For debug/test, the signal output from the GPIO will be fed to the input path as well */ + } flags; /*!< Extra flags */ +} sdm_config_t; + +/** + * @brief Create a new Sigma Delta channel + * + * @param[in] config SDM configuration + * @param[out] ret_chan Returned SDM channel handle + * @return + * - ESP_OK: Create SDM channel successfully + * - ESP_ERR_INVALID_ARG: Create SDM channel failed because of invalid argument + * - ESP_ERR_NO_MEM: Create SDM channel failed because out of memory + * - ESP_ERR_NOT_FOUND: Create SDM channel failed because all channels are used up and no more free one + * - ESP_FAIL: Create SDM channel failed because of other error + */ +esp_err_t sdm_new_channel(const sdm_config_t *config, sdm_channel_handle_t *ret_chan); + +/** + * @brief Delete the Sigma Delta channel + * + * @param[in] chan SDM channel created by `sdm_new_channel` + * @return + * - ESP_OK: Delete the SDM channel successfully + * - ESP_ERR_INVALID_ARG: Delete the SDM channel failed because of invalid argument + * - ESP_ERR_INVALID_STATE: Delete the SDM channel failed because the channel is not in init state + * - ESP_FAIL: Delete the SDM channel failed because of other error + */ +esp_err_t sdm_del_channel(sdm_channel_handle_t chan); + +/** + * @brief Enable the Sigma Delta channel + * + * @note This function will transit the channel state from init to enable. + * @note This function will acquire a PM lock, if a specific source clock (e.g. APB) is selected in the `sdm_config_t`, while `CONFIG_PM_ENABLE` is enabled. + * + * @param[in] chan SDM channel created by `sdm_new_channel` + * @return + * - ESP_OK: Enable SDM channel successfully + * - ESP_ERR_INVALID_ARG: Enable SDM channel failed because of invalid argument + * - ESP_ERR_INVALID_STATE: Enable SDM channel failed because the channel is already enabled + * - ESP_FAIL: Enable SDM channel failed because of other error + */ +esp_err_t sdm_channel_enable(sdm_channel_handle_t chan); + +/** + * @brief Disable the Sigma Delta channel + * + * @note This function will do the opposite work to the `sdm_channel_enable()` + * + * @param[in] chan SDM channel created by `sdm_new_channel` + * @return + * - ESP_OK: Disable SDM channel successfully + * - ESP_ERR_INVALID_ARG: Disable SDM channel failed because of invalid argument + * - ESP_ERR_INVALID_STATE: Disable SDM channel failed because the channel is not enabled yet + * - ESP_FAIL: Disable SDM channel failed because of other error + */ +esp_err_t sdm_channel_disable(sdm_channel_handle_t chan); + +/** + * @brief Set the duty cycle of the PDM output signal. + * + * @note For PDM signals, duty cycle refers to the percentage of high level cycles to the whole statistical period. + * The average output voltage could be Vout = VDD_IO / 256 * duty + VDD_IO / 2 + * @note If the duty is set to zero, the output signal is like a 50% duty cycle square wave, with a frequency around (sample_rate_hz / 4). + * @note The duty is proportional to the equivalent output voltage after a low-pass-filter. + * @note This function is allowed to run within ISR context + * @note This function will be placed into IRAM if `CONFIG_SDM_CTRL_FUNC_IN_IRAM` is on, so that it's allowed to be executed when Cache is disabled + * + * @param[in] chan SDM channel created by `sdm_new_channel` + * @param[in] duty Equivalent duty cycle of the PDM output signal, ranges from -128 to 127. But the range of [-90, 90] can provide a better randomness. + * @return + * - ESP_OK: Set duty cycle successfully + * - ESP_ERR_INVALID_ARG: Set duty cycle failed because of invalid argument + * - ESP_FAIL: Set duty cycle failed because of other error + */ +esp_err_t sdm_channel_set_duty(sdm_channel_handle_t chan, int8_t duty); + +#ifdef __cplusplus +} +#endif diff --git a/components/driver/linker.lf b/components/driver/linker.lf index 3e45d3dcc2..36e884f64d 100644 --- a/components/driver/linker.lf +++ b/components/driver/linker.lf @@ -15,3 +15,5 @@ entries: if GPIO_CTRL_FUNC_IN_IRAM = y: gpio: gpio_set_level (noflash) gpio: gpio_intr_disable (noflash) + if SDM_CTRL_FUNC_IN_IRAM = y: + sdm: sdm_channel_set_duty (noflash) diff --git a/components/driver/sdm.c b/components/driver/sdm.c new file mode 100644 index 0000000000..6e20defff5 --- /dev/null +++ b/components/driver/sdm.c @@ -0,0 +1,311 @@ +/* + * SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include "sdkconfig.h" +#if CONFIG_SDM_ENABLE_DEBUG_LOG +// The local log level must be defined before including esp_log.h +// Set the maximum log level for this source file +#define LOG_LOCAL_LEVEL ESP_LOG_DEBUG +#endif +#include "freertos/FreeRTOS.h" +#include "esp_attr.h" +#include "esp_err.h" +#include "esp_heap_caps.h" +#include "esp_log.h" +#include "esp_check.h" +#include "esp_pm.h" +#include "driver/gpio.h" +#include "driver/sdm.h" +#include "hal/gpio_hal.h" +#include "hal/sdm_hal.h" +#include "hal/sdm_ll.h" +#include "soc/sdm_periph.h" +#include "esp_private/esp_clk.h" + +#if CONFIG_SDM_CTRL_FUNC_IN_IRAM +#define SDM_MEM_ALLOC_CAPS (MALLOC_CAP_INTERNAL | MALLOC_CAP_8BIT) +#else +#define SDM_MEM_ALLOC_CAPS MALLOC_CAP_DEFAULT +#endif + +#define SDM_PM_LOCK_NAME_LEN_MAX 16 + +static const char *TAG = "sdm"; + +typedef struct sdm_platform_t sdm_platform_t; +typedef struct sdm_group_t sdm_group_t; +typedef struct sdm_channel_t sdm_channel_t; + +struct sdm_platform_t { + _lock_t mutex; // platform level mutex lock + sdm_group_t *groups[SOC_SDM_GROUPS]; // sdm group pool + int group_ref_counts[SOC_SDM_GROUPS]; // reference count used to protect group install/uninstall +}; + +struct sdm_group_t { + int group_id; // Group ID, index from 0 + portMUX_TYPE spinlock; // to protect per-group register level concurrent access + sdm_hal_context_t hal; // hal context + sdm_channel_t *channels[SOC_SDM_CHANNELS_PER_GROUP]; // array of sdm channels + sdm_clock_source_t clk_src; // Clock source +}; + +typedef enum { + SDM_FSM_INIT, + SDM_FSM_ENABLE, +} sdm_fsm_t; + +struct sdm_channel_t { + sdm_group_t *group; // which group the sdm channel belongs to + uint32_t chan_id; // allocated channel numerical ID + int gpio_num; // GPIO number + uint32_t sample_rate_hz; // Sample rate, in Hz + portMUX_TYPE spinlock; // to protect per-channels resources concurrently accessed by task and ISR handler + esp_pm_lock_handle_t pm_lock; // PM lock, for glitch filter, as that module can only be functional under APB + sdm_fsm_t fsm; // FSM state +#if CONFIG_PM_ENABLE + char pm_lock_name[SDM_PM_LOCK_NAME_LEN_MAX]; // pm lock name +#endif +}; + +// sdm driver platform, it's always a singleton +static sdm_platform_t s_platform; + +static sdm_group_t *sdm_acquire_group_handle(int group_id) +{ + bool new_group = false; + sdm_group_t *group = NULL; + + // prevent install sdm group concurrently + _lock_acquire(&s_platform.mutex); + if (!s_platform.groups[group_id]) { + group = heap_caps_calloc(1, sizeof(sdm_group_t), SDM_MEM_ALLOC_CAPS); + if (group) { + new_group = true; + s_platform.groups[group_id] = group; // register to platform + // initialize sdm group members + group->group_id = group_id; + group->spinlock = (portMUX_TYPE)portMUX_INITIALIZER_UNLOCKED; + group->clk_src = SDM_CLK_SRC_NONE; + // initialize HAL context + sdm_hal_init(&group->hal, group_id); + // enable clock + // note that, this will enables all the channels' output, and channel can't be disable/enable separately + sdm_ll_enable_clock(group->hal.dev, true); + } + } else { + group = s_platform.groups[group_id]; + } + if (group) { + // someone acquired the group handle means we have a new object that refer to this group + s_platform.group_ref_counts[group_id]++; + } + _lock_release(&s_platform.mutex); + + if (new_group) { + ESP_LOGD(TAG, "new group (%d) at %p", group_id, group); + } + + return group; +} + +static void sdm_release_group_handle(sdm_group_t *group) +{ + int group_id = group->group_id; + bool do_deinitialize = false; + + _lock_acquire(&s_platform.mutex); + s_platform.group_ref_counts[group_id]--; + if (s_platform.group_ref_counts[group_id] == 0) { + assert(s_platform.groups[group_id]); + do_deinitialize = true; + s_platform.groups[group_id] = NULL; // deregister from platform + sdm_ll_enable_clock(group->hal.dev, false); + } + _lock_release(&s_platform.mutex); + + if (do_deinitialize) { + free(group); + ESP_LOGD(TAG, "del group (%d)", group_id); + } +} + +static esp_err_t sdm_register_to_group(sdm_channel_t *chan) +{ + sdm_group_t *group = NULL; + int chan_id = -1; + for (int i = 0; i < SOC_SDM_GROUPS; i++) { + group = sdm_acquire_group_handle(i); + ESP_RETURN_ON_FALSE(group, ESP_ERR_NO_MEM, TAG, "no mem for group (%d)", i); + // loop to search free unit in the group + portENTER_CRITICAL(&group->spinlock); + for (int j = 0; j < SOC_SDM_CHANNELS_PER_GROUP; j++) { + if (!group->channels[j]) { + chan_id = j; + group->channels[j] = chan; + break; + } + } + portEXIT_CRITICAL(&group->spinlock); + if (chan_id < 0) { + sdm_release_group_handle(group); + group = NULL; + } else { + chan->group = group; + chan->chan_id = chan_id; + break; + } + } + ESP_RETURN_ON_FALSE(chan_id != -1, ESP_ERR_NOT_FOUND, TAG, "no free channels"); + return ESP_OK; +} + +static void sdm_unregister_from_group(sdm_channel_t *chan) +{ + sdm_group_t *group = chan->group; + int chan_id = chan->chan_id; + portENTER_CRITICAL(&group->spinlock); + group->channels[chan_id] = NULL; + portEXIT_CRITICAL(&group->spinlock); + // channel has a reference on group, release it now + sdm_release_group_handle(group); +} + +static esp_err_t sdm_destory(sdm_channel_t *chan) +{ + if (chan->pm_lock) { + ESP_RETURN_ON_ERROR(esp_pm_lock_delete(chan->pm_lock), TAG, "delete pm lock failed"); + } + if (chan->group) { + sdm_unregister_from_group(chan); + } + free(chan); + return ESP_OK; +} + +esp_err_t sdm_new_channel(const sdm_config_t *config, sdm_channel_handle_t *ret_chan) +{ +#if CONFIG_SDM_ENABLE_DEBUG_LOG + esp_log_level_set(TAG, ESP_LOG_DEBUG); +#endif + esp_err_t ret = ESP_OK; + sdm_channel_t *chan = NULL; + ESP_GOTO_ON_FALSE(config && ret_chan, ESP_ERR_INVALID_ARG, err, TAG, "invalid argument"); + ESP_GOTO_ON_FALSE(GPIO_IS_VALID_OUTPUT_GPIO(config->gpio_num), ESP_ERR_INVALID_ARG, err, TAG, "invalid GPIO number"); + + chan = heap_caps_calloc(1, sizeof(sdm_channel_t), SDM_MEM_ALLOC_CAPS); + ESP_GOTO_ON_FALSE(chan, ESP_ERR_NO_MEM, err, TAG, "no mem for channel"); + // register channel to the group + ESP_GOTO_ON_ERROR(sdm_register_to_group(chan), err, TAG, "register to group failed"); + sdm_group_t *group = chan->group; + int group_id = group->group_id; + int chan_id = chan->chan_id; + + ESP_GOTO_ON_FALSE(group->clk_src == SDM_CLK_SRC_NONE || group->clk_src == config->clk_src, ESP_ERR_INVALID_ARG, err, TAG, "clock source conflict"); + uint32_t src_clk_hz = 0; + switch (config->clk_src) { + case SDM_CLK_SRC_APB: + src_clk_hz = esp_clk_apb_freq(); +#if CONFIG_PM_ENABLE + sprintf(chan->pm_lock_name, "sdm_%d_%d", group->group_id, chan_id); // e.g. sdm_0_0 + ret = esp_pm_lock_create(ESP_PM_APB_FREQ_MAX, 0, chan->pm_lock_name, &chan->pm_lock); + ESP_RETURN_ON_ERROR(ret, TAG, "create APB_FREQ_MAX lock failed"); +#endif + break; + default: + ESP_GOTO_ON_FALSE(false, ESP_ERR_NOT_SUPPORTED, err, TAG, "clock source %d is not support", config->clk_src); + break; + } + group->clk_src = config->clk_src; + + // GPIO configuration + gpio_config_t gpio_conf = { + .intr_type = GPIO_INTR_DISABLE, + // also enable the input path is `io_loop_back` is on, this is useful for debug + .mode = GPIO_MODE_OUTPUT | (config->flags.io_loop_back ? GPIO_MODE_INPUT : 0), + .pull_down_en = false, + .pull_up_en = true, + .pin_bit_mask = 1ULL << config->gpio_num, + }; + ESP_GOTO_ON_ERROR(gpio_config(&gpio_conf), err, TAG, "config GPIO failed"); + esp_rom_gpio_connect_out_signal(config->gpio_num, sigma_delta_periph_signals.channels[chan_id].sd_sig, config->flags.invert_out, false); + chan->gpio_num = config->gpio_num; + + // set prescale based on sample rate + uint32_t prescale = src_clk_hz / config->sample_rate_hz; + sdm_ll_set_prescale(group->hal.dev, chan_id, prescale); + chan->sample_rate_hz = src_clk_hz / prescale; + // preset the duty cycle to zero + sdm_ll_set_duty(group->hal.dev, chan_id, 0); + + // initialize other members of timer + chan->spinlock = (portMUX_TYPE)portMUX_INITIALIZER_UNLOCKED; + chan->fsm = SDM_FSM_INIT; // put the channel into init state + + ESP_LOGD(TAG, "new sdm channel (%d,%d) at %p, gpio=%d, sample rate=%uHz", group_id, chan_id, chan, chan->gpio_num, chan->sample_rate_hz); + *ret_chan = chan; + return ESP_OK; +err: + if (chan) { + sdm_destory(chan); + } + return ret; +} + +esp_err_t sdm_del_channel(sdm_channel_handle_t chan) +{ + ESP_RETURN_ON_FALSE(chan, ESP_ERR_INVALID_ARG, TAG, "invalid argument"); + ESP_RETURN_ON_FALSE(chan->fsm == SDM_FSM_INIT, ESP_ERR_INVALID_STATE, TAG, "channel not in init state"); + sdm_group_t *group = chan->group; + int group_id = group->group_id; + int chan_id = chan->chan_id; + ESP_LOGD(TAG, "del channel (%d,%d)", group_id, chan_id); + // recycle memory resource + ESP_RETURN_ON_ERROR(sdm_destory(chan), TAG, "destory channel failed"); + return ESP_OK; +} + +esp_err_t sdm_channel_enable(sdm_channel_handle_t chan) +{ + ESP_RETURN_ON_FALSE(chan, ESP_ERR_INVALID_ARG, TAG, "invalid argument"); + ESP_RETURN_ON_FALSE(chan->fsm == SDM_FSM_INIT, ESP_ERR_INVALID_STATE, TAG, "channel not in init state"); + + // acquire power manager lock + if (chan->pm_lock) { + ESP_RETURN_ON_ERROR(esp_pm_lock_acquire(chan->pm_lock), TAG, "acquire pm_lock failed"); + } + chan->fsm = SDM_FSM_ENABLE; + return ESP_OK; +} + +esp_err_t sdm_channel_disable(sdm_channel_handle_t chan) +{ + ESP_RETURN_ON_FALSE(chan, ESP_ERR_INVALID_ARG, TAG, "invalid argument"); + ESP_RETURN_ON_FALSE(chan->fsm == SDM_FSM_ENABLE, ESP_ERR_INVALID_STATE, TAG, "channel not in enable state"); + + // release power manager lock + if (chan->pm_lock) { + ESP_RETURN_ON_ERROR(esp_pm_lock_release(chan->pm_lock), TAG, "release pm_lock failed"); + } + chan->fsm = SDM_FSM_INIT; + return ESP_OK; +} + +esp_err_t sdm_channel_set_duty(sdm_channel_handle_t chan, int8_t duty) +{ + ESP_RETURN_ON_FALSE_ISR(chan, ESP_ERR_INVALID_ARG, TAG, "invalid argument"); + + sdm_group_t *group = chan->group; + int chan_id = chan->chan_id; + + portENTER_CRITICAL_SAFE(&chan->spinlock); + sdm_ll_set_duty(group->hal.dev, chan_id, duty); + portEXIT_CRITICAL_SAFE(&chan->spinlock); + + return ESP_OK; +} diff --git a/components/driver/test_apps/sdm/CMakeLists.txt b/components/driver/test_apps/sdm/CMakeLists.txt new file mode 100644 index 0000000000..9830fb8ada --- /dev/null +++ b/components/driver/test_apps/sdm/CMakeLists.txt @@ -0,0 +1,18 @@ +# This is the project CMakeLists.txt file for the test subproject +cmake_minimum_required(VERSION 3.16) + +include($ENV{IDF_PATH}/tools/cmake/project.cmake) +project(sdm_test) + +if(CONFIG_COMPILER_DUMP_RTL_FILES) + add_custom_target(check_test_app_sections ALL + COMMAND ${PYTHON} $ENV{IDF_PATH}/tools/ci/check_callgraph.py + --rtl-dir ${CMAKE_BINARY_DIR}/esp-idf/driver/ + --elf-file ${CMAKE_BINARY_DIR}/sdm_test.elf + find-refs + --from-sections=.iram0.text + --to-sections=.flash.text,.flash.rodata + --exit-code + DEPENDS ${elf} + ) +endif() diff --git a/components/driver/test_apps/sdm/README.md b/components/driver/test_apps/sdm/README.md new file mode 100644 index 0000000000..497a93ba72 --- /dev/null +++ b/components/driver/test_apps/sdm/README.md @@ -0,0 +1,2 @@ +| Supported Targets | ESP32 | ESP32-C3 | ESP32-S2 | ESP32-S3 | +| ----------------- | ----- | -------- | -------- | -------- | diff --git a/components/driver/test_apps/sdm/main/CMakeLists.txt b/components/driver/test_apps/sdm/main/CMakeLists.txt new file mode 100644 index 0000000000..c304c90d3a --- /dev/null +++ b/components/driver/test_apps/sdm/main/CMakeLists.txt @@ -0,0 +1,7 @@ +set(srcs "test_app_main.c" + "test_sdm.c") + +# In order for the cases defined by `TEST_CASE` to be linked into the final elf, +# the component can be registered as WHOLE_ARCHIVE +idf_component_register(SRCS ${srcs} + WHOLE_ARCHIVE) diff --git a/components/driver/test_apps/sdm/main/test_app_main.c b/components/driver/test_apps/sdm/main/test_app_main.c new file mode 100644 index 0000000000..6394c16e0c --- /dev/null +++ b/components/driver/test_apps/sdm/main/test_app_main.c @@ -0,0 +1,51 @@ +/* + * SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include "unity.h" +#include "unity_test_runner.h" +#include "esp_heap_caps.h" + +// Some resources are lazy allocated in pulse_cnt driver, the threshold is left for that case +#define TEST_MEMORY_LEAK_THRESHOLD (-200) + +static size_t before_free_8bit; +static size_t before_free_32bit; + +static void check_leak(size_t before_free, size_t after_free, const char *type) +{ + ssize_t delta = after_free - before_free; + printf("MALLOC_CAP_%s: Before %u bytes free, After %u bytes free (delta %d)\n", type, before_free, after_free, delta); + TEST_ASSERT_MESSAGE(delta >= TEST_MEMORY_LEAK_THRESHOLD, "memory leak"); +} + +void setUp(void) +{ + before_free_8bit = heap_caps_get_free_size(MALLOC_CAP_8BIT); + before_free_32bit = heap_caps_get_free_size(MALLOC_CAP_32BIT); +} + +void tearDown(void) +{ + size_t after_free_8bit = heap_caps_get_free_size(MALLOC_CAP_8BIT); + size_t after_free_32bit = heap_caps_get_free_size(MALLOC_CAP_32BIT); + check_leak(before_free_8bit, after_free_8bit, "8BIT"); + check_leak(before_free_32bit, after_free_32bit, "32BIT"); +} + +void app_main(void) +{ + // ____ ____ ___ ___ ____ ____ __ __ + // / ___| _ \_ _/ _ \ / ___|| _ \| \/ | + // | | _| |_) | | | | | \___ \| | | | |\/| | + // | |_| | __/| | |_| | ___) | |_| | | | | + // \____|_| |___\___/ |____/|____/|_| |_| + printf(" ____ ____ ___ ___ ____ ____ __ __\r\n"); + printf(" / ___| _ \\_ _/ _ \\ / ___|| _ \\| \\/ |\r\n"); + printf("| | _| |_) | | | | | \\___ \\| | | | |\\/| |\r\n"); + printf("| |_| | __/| | |_| | ___) | |_| | | | |\r\n"); + printf(" \\____|_| |___\\___/ |____/|____/|_| |_|\r\n"); + unity_run_menu(); +} diff --git a/components/driver/test_apps/sdm/main/test_sdm.c b/components/driver/test_apps/sdm/main/test_sdm.c new file mode 100644 index 0000000000..776f2416fe --- /dev/null +++ b/components/driver/test_apps/sdm/main/test_sdm.c @@ -0,0 +1,68 @@ +/* + * SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include "sdkconfig.h" +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "unity.h" +#include "driver/sdm.h" +#include "soc/soc_caps.h" +#include "esp_attr.h" + +TEST_CASE("sdm_channel_install_uninstall", "[sdm]") +{ + printf("install sdm channels exhaustively\r\n"); + sdm_config_t config = { + .clk_src = SDM_CLK_SRC_DEFAULT, + .sample_rate_hz = 1000000, + .gpio_num = 0, + }; + sdm_channel_handle_t chans[SOC_SDM_GROUPS][SOC_SDM_CHANNELS_PER_GROUP] = {}; + for (int i = 0; i < SOC_SDM_GROUPS; i++) { + for (int j = 0; j < SOC_SDM_CHANNELS_PER_GROUP; j++) { + TEST_ESP_OK(sdm_new_channel(&config, &chans[i][j])); + } + TEST_ESP_ERR(ESP_ERR_NOT_FOUND, sdm_new_channel(&config, &chans[0][0])); + } + + printf("delete sdm channels\r\n"); + for (int i = 0; i < SOC_SDM_GROUPS; i++) { + for (int j = 0; j < SOC_SDM_CHANNELS_PER_GROUP; j++) { + TEST_ESP_OK(sdm_del_channel(chans[i][j])); + } + } +} + +TEST_CASE("sdm_channel_set_duty", "[sdm]") +{ + const int sdm_chan_gpios[2] = {0, 2}; + sdm_config_t config = { + .clk_src = SDM_CLK_SRC_DEFAULT, + .sample_rate_hz = 1000000, + }; + sdm_channel_handle_t chans[2] = {}; + for (size_t i = 0; i < 2; i++) { + config.gpio_num = sdm_chan_gpios[i]; + TEST_ESP_OK(sdm_new_channel(&config, &chans[i])); + // should see a ~250KHz (sample_rate/4) square wave + TEST_ESP_OK(sdm_channel_set_duty(chans[i], 0)); + TEST_ESP_OK(sdm_channel_enable(chans[i])); + } + vTaskDelay(pdMS_TO_TICKS(500)); + + // can't delete the channel if the channel is in the enable state + TEST_ESP_ERR(ESP_ERR_INVALID_STATE, sdm_del_channel(chans[0])); + + TEST_ESP_OK(sdm_channel_set_duty(chans[0], 127)); + TEST_ESP_OK(sdm_channel_set_duty(chans[1], -128)); + vTaskDelay(pdMS_TO_TICKS(500)); + + for (size_t i = 0; i < 2; i++) { + TEST_ESP_OK(sdm_channel_disable(chans[i])); + TEST_ESP_OK(sdm_del_channel(chans[i])); + } +} diff --git a/components/driver/test_apps/sdm/pytest_sdm.py b/components/driver/test_apps/sdm/pytest_sdm.py new file mode 100644 index 0000000000..4f36a104e0 --- /dev/null +++ b/components/driver/test_apps/sdm/pytest_sdm.py @@ -0,0 +1,24 @@ +# SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD +# SPDX-License-Identifier: CC0-1.0 + +import pytest +from pytest_embedded import Dut + + +@pytest.mark.esp32 +@pytest.mark.esp32s2 +@pytest.mark.esp32s3 +@pytest.mark.esp32c3 +@pytest.mark.generic +@pytest.mark.parametrize( + 'config', + [ + 'iram_safe', + 'release', + ], + indirect=True, +) +def test_sdm(dut: Dut) -> None: + dut.expect_exact('Press ENTER to see the list of tests') + dut.write('*') + dut.expect_unity_test_output() diff --git a/components/driver/test_apps/sdm/sdkconfig.ci.iram_safe b/components/driver/test_apps/sdm/sdkconfig.ci.iram_safe new file mode 100644 index 0000000000..0986dcf2e6 --- /dev/null +++ b/components/driver/test_apps/sdm/sdkconfig.ci.iram_safe @@ -0,0 +1,5 @@ +CONFIG_COMPILER_DUMP_RTL_FILES=y +CONFIG_SDM_CTRL_FUNC_IN_IRAM=y + +# silent the error check, as the error string are stored in rodata, causing RTL check failure +CONFIG_COMPILER_OPTIMIZATION_CHECKS_SILENT=y diff --git a/components/driver/test_apps/sdm/sdkconfig.ci.release b/components/driver/test_apps/sdm/sdkconfig.ci.release new file mode 100644 index 0000000000..91d93f163e --- /dev/null +++ b/components/driver/test_apps/sdm/sdkconfig.ci.release @@ -0,0 +1,5 @@ +CONFIG_PM_ENABLE=y +CONFIG_FREERTOS_USE_TICKLESS_IDLE=y +CONFIG_COMPILER_OPTIMIZATION_SIZE=y +CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_SIZE=y +CONFIG_COMPILER_OPTIMIZATION_ASSERTIONS_SILENT=y diff --git a/components/driver/test_apps/sdm/sdkconfig.defaults b/components/driver/test_apps/sdm/sdkconfig.defaults new file mode 100644 index 0000000000..b308cb2ddd --- /dev/null +++ b/components/driver/test_apps/sdm/sdkconfig.defaults @@ -0,0 +1,2 @@ +CONFIG_FREERTOS_HZ=1000 +CONFIG_ESP_TASK_WDT=n