feat(rmt): support sleep retention

by back up the registers
master
morris 2024-04-15 18:58:53 +08:00
rodzic 6a919dcc16
commit e8e975112a
34 zmienionych plików z 390 dodań i 37 usunięć

Wyświetl plik

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2022-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2022-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -42,6 +42,9 @@ typedef struct {
uint32_t invert_in: 1; /*!< Whether to invert the incoming RMT channel signal */
uint32_t with_dma: 1; /*!< If set, the driver will allocate an RMT channel with DMA capability */
uint32_t io_loop_back: 1; /*!< For debug/test, the signal output from the GPIO will be fed to the input path as well */
uint32_t backup_before_sleep: 1; /*!< If set, the driver will backup/restore the RMT registers before/after entering/exist sleep mode.
By this approach, the system can power off RMT's power domain.
This can save power, but at the expense of more RAM being consumed */
} flags; /*!< RX channel config flags */
} rmt_rx_channel_config_t;

Wyświetl plik

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2022-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2022-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -44,6 +44,9 @@ typedef struct {
uint32_t with_dma: 1; /*!< If set, the driver will allocate an RMT channel with DMA capability */
uint32_t io_loop_back: 1; /*!< The signal output from the GPIO will be fed to the input path as well */
uint32_t io_od_mode: 1; /*!< Configure the GPIO as open-drain mode */
uint32_t backup_before_sleep: 1; /*!< If set, the driver will backup/restore the RMT registers before/after entering/exist sleep mode.
By this approach, the system can power off RMT's power domain.
This can save power, but at the expense of more RAM being consumed */
} flags; /*!< TX channel config flags */
} rmt_tx_channel_config_t;

Wyświetl plik

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2022-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2022-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -43,6 +43,10 @@ typedef struct rmt_platform_t {
static rmt_platform_t s_platform; // singleton platform
#if RMT_USE_RETENTION_LINK
static esp_err_t rmt_create_sleep_retention_link_cb(void *arg);
#endif
rmt_group_t *rmt_acquire_group_handle(int group_id)
{
bool new_group = false;
@ -81,6 +85,24 @@ rmt_group_t *rmt_acquire_group_handle(int group_id)
_lock_release(&s_platform.mutex);
if (new_group) {
#if RMT_USE_RETENTION_LINK
sleep_retention_module_t module = RMT_LL_SLEEP_RETENTION_MODULE_ID(group_id);
sleep_retention_module_init_param_t init_param = {
.cbs = {
.create = {
.handle = rmt_create_sleep_retention_link_cb,
.arg = group,
},
},
.depends = BIT(SLEEP_RETENTION_MODULE_CLOCK_SYSTEM)
};
if (sleep_retention_module_init(module, &init_param) == ESP_OK) {
group->sleep_retention_module = module;
} else {
// even though the sleep retention module init failed, RMT driver should still work, so just warning here
ESP_LOGW(TAG, "init sleep retention failed %d, power domain may be turned off during sleep", group_id);
}
#endif // RMT_USE_RETENTION_LINK
ESP_LOGD(TAG, "new group(%d) at %p, occupy=%"PRIx32, group_id, group, group->occupy_mask);
}
return group;
@ -108,7 +130,6 @@ void rmt_release_group_handle(rmt_group_t *group)
RMT_RCC_ATOMIC() {
rmt_ll_enable_bus_clock(group_id, false);
}
free(group);
}
_lock_release(&s_platform.mutex);
@ -123,6 +144,15 @@ void rmt_release_group_handle(rmt_group_t *group)
}
if (do_deinitialize) {
#if RMT_USE_RETENTION_LINK
if (group->sleep_retention_module) {
if (group->retention_link_created) {
sleep_retention_module_free(group->sleep_retention_module);
}
sleep_retention_module_deinit(group->sleep_retention_module);
}
#endif
free(group);
ESP_LOGD(TAG, "del group(%d)", group_id);
}
}
@ -264,3 +294,33 @@ int rmt_get_isr_flags(rmt_group_t *group)
}
return isr_flags;
}
#if RMT_USE_RETENTION_LINK
static esp_err_t rmt_create_sleep_retention_link_cb(void *arg)
{
rmt_group_t *group = (rmt_group_t *)arg;
int group_id = group->group_id;
sleep_retention_module_t module = group->sleep_retention_module;
esp_err_t err = sleep_retention_entries_create(rmt_reg_retention_info[group_id].regdma_entry_array,
rmt_reg_retention_info[group_id].array_size,
REGDMA_LINK_PRI_RMT, module);
ESP_RETURN_ON_ERROR(err, TAG, "create retention link failed");
return ESP_OK;
}
void rmt_create_retention_module(rmt_group_t *group)
{
sleep_retention_module_t module = group->sleep_retention_module;
_lock_acquire(&s_platform.mutex);
if (group->retention_link_created == false) {
if (sleep_retention_module_allocate(module) != ESP_OK) {
// even though the sleep retention module create failed, RMT driver should still work, so just warning here
ESP_LOGW(TAG, "create retention module failed, power domain can't turn off");
} else {
group->retention_link_created = true;
}
}
_lock_release(&s_platform.mutex);
}
#endif // RMT_USE_RETENTION_LINK

Wyświetl plik

@ -417,7 +417,7 @@ static esp_err_t rmt_simple_encoder_reset(rmt_encoder_t *encoder)
static esp_err_t rmt_del_simple_encoder(rmt_encoder_t *encoder)
{
rmt_simple_encoder_t *simple_encoder = __containerof(encoder, rmt_simple_encoder_t, base);
if (simple_encoder) {
if (simple_encoder->ovf_buf) {
free(simple_encoder->ovf_buf);
}
free(simple_encoder);

Wyświetl plik

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2022-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2022-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -27,6 +27,7 @@
#include "esp_private/gdma.h"
#include "esp_private/esp_gpio_reserve.h"
#include "esp_private/gpio.h"
#include "esp_private/sleep_retention.h"
#include "driver/rmt_common.h"
#ifdef __cplusplus
@ -72,6 +73,9 @@ typedef dma_descriptor_align4_t rmt_dma_descriptor_t;
#define ALIGN_UP(num, align) (((num) + ((align) - 1)) & ~((align) - 1))
#define ALIGN_DOWN(num, align) ((num) & ~((align) - 1))
// Use retention link only when the target supports sleep retention and PM is enabled
#define RMT_USE_RETENTION_LINK (SOC_RMT_SUPPORT_SLEEP_BACKUP && CONFIG_PM_ENABLE && CONFIG_PM_POWER_DOWN_PERIPHERAL_IN_LIGHT_SLEEP)
typedef struct {
struct {
rmt_symbol_word_t symbols[SOC_RMT_MEM_WORDS_PER_CHANNEL];
@ -119,6 +123,10 @@ struct rmt_group_t {
rmt_rx_channel_t *rx_channels[SOC_RMT_RX_CANDIDATES_PER_GROUP]; // array of RMT RX channels
rmt_sync_manager_t *sync_manager; // sync manager, this can be extended into an array if there're more sync controllers in one RMT group
int intr_priority; // RMT interrupt priority
#if RMT_USE_RETENTION_LINK
sleep_retention_module_t sleep_retention_module; // sleep retention module
bool retention_link_created; // mark if the retention link is created
#endif
};
struct rmt_channel_t {
@ -247,6 +255,13 @@ bool rmt_set_intr_priority_to_group(rmt_group_t *group, int intr_priority);
*/
int rmt_get_isr_flags(rmt_group_t *group);
/**
* @brief Create sleep retention link
*
* @param group RMT group handle, returned from `rmt_acquire_group_handle`
*/
void rmt_create_retention_module(rmt_group_t *group);
#ifdef __cplusplus
}
#endif

Wyświetl plik

@ -188,6 +188,10 @@ esp_err_t rmt_new_rx_channel(const rmt_rx_channel_config_t *config, rmt_channel_
ESP_RETURN_ON_FALSE(config->flags.with_dma == 0, ESP_ERR_NOT_SUPPORTED, TAG, "DMA not supported");
#endif // SOC_RMT_SUPPORT_DMA
#if !SOC_RMT_SUPPORT_SLEEP_BACKUP
ESP_RETURN_ON_FALSE(config->flags.backup_before_sleep == 0, ESP_ERR_NOT_SUPPORTED, TAG, "register back up is not supported");
#endif // SOC_RMT_SUPPORT_SLEEP_BACKUP
// malloc channel memory
uint32_t mem_caps = RMT_MEM_ALLOC_CAPS;
rx_channel = heap_caps_calloc(1, sizeof(rmt_rx_channel_t), mem_caps);
@ -227,6 +231,12 @@ esp_err_t rmt_new_rx_channel(const rmt_rx_channel_config_t *config, rmt_channel_
int channel_id = rx_channel->base.channel_id;
int group_id = group->group_id;
#if RMT_USE_RETENTION_LINK
if (config->flags.backup_before_sleep != 0) {
rmt_create_retention_module(group);
}
#endif // RMT_USE_RETENTION_LINK
// reset channel, make sure the RX engine is not working, and events are cleared
portENTER_CRITICAL(&group->spinlock);
rmt_hal_rx_channel_reset(&group->hal, channel_id);

Wyświetl plik

@ -256,6 +256,10 @@ esp_err_t rmt_new_tx_channel(const rmt_tx_channel_config_t *config, rmt_channel_
ESP_RETURN_ON_FALSE(config->flags.with_dma == 0, ESP_ERR_NOT_SUPPORTED, TAG, "DMA not supported");
#endif
#if !SOC_RMT_SUPPORT_SLEEP_BACKUP
ESP_RETURN_ON_FALSE(config->flags.backup_before_sleep == 0, ESP_ERR_NOT_SUPPORTED, TAG, "register back up is not supported");
#endif // SOC_RMT_SUPPORT_SLEEP_BACKUP
// malloc channel memory
uint32_t mem_caps = RMT_MEM_ALLOC_CAPS;
tx_channel = heap_caps_calloc(1, sizeof(rmt_tx_channel_t) + sizeof(rmt_tx_trans_desc_t) * config->trans_queue_depth, mem_caps);
@ -291,6 +295,12 @@ esp_err_t rmt_new_tx_channel(const rmt_tx_channel_config_t *config, rmt_channel_
int channel_id = tx_channel->base.channel_id;
int group_id = group->group_id;
#if RMT_USE_RETENTION_LINK
if (config->flags.backup_before_sleep != 0) {
rmt_create_retention_module(group);
}
#endif // RMT_USE_RETENTION_LINK
// reset channel, make sure the TX engine is not working, and events are cleared
portENTER_CRITICAL(&group->spinlock);
rmt_hal_tx_channel_reset(&group->hal, channel_id);

Wyświetl plik

@ -8,6 +8,10 @@ if(CONFIG_RMT_ISR_IRAM_SAFE)
list(APPEND srcs "test_rmt_iram.c")
endif()
if(CONFIG_SOC_LIGHT_SLEEP_SUPPORTED AND CONFIG_PM_ENABLE)
list(APPEND srcs "test_rmt_sleep.c")
endif()
idf_component_register(SRCS "${srcs}"
PRIV_REQUIRES unity esp_driver_rmt esp_driver_gpio esp_timer esp_psram
WHOLE_ARCHIVE)

Wyświetl plik

@ -0,0 +1,138 @@
/*
* SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <stdio.h>
#include <string.h>
#include "sdkconfig.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "unity.h"
#include "unity_test_utils.h"
#include "driver/rmt_tx.h"
#include "driver/rmt_rx.h"
#include "esp_timer.h"
#include "esp_sleep.h"
#include "esp_private/sleep_cpu.h"
#include "test_util_rmt_encoders.h"
#include "test_board.h"
typedef struct {
TaskHandle_t task_to_notify;
size_t received_symbol_num;
} test_rx_user_data_t;
static bool test_rmt_rx_done_callback(rmt_channel_handle_t channel, const rmt_rx_done_event_data_t *edata, void *user_data)
{
BaseType_t high_task_wakeup = pdFALSE;
test_rx_user_data_t *test_user_data = (test_rx_user_data_t *)user_data;
rmt_symbol_word_t *remote_codes = edata->received_symbols;
esp_rom_printf("%u symbols decoded:\r\n", edata->num_symbols);
for (size_t i = 0; i < edata->num_symbols; i++) {
esp_rom_printf("{%d:%d},{%d:%d}\r\n", remote_codes[i].level0, remote_codes[i].duration0, remote_codes[i].level1, remote_codes[i].duration1);
}
test_user_data->received_symbol_num = edata->num_symbols;
vTaskNotifyGiveFromISR(test_user_data->task_to_notify, &high_task_wakeup);
return high_task_wakeup == pdTRUE;
}
/**
* @brief Test the RMT driver can still work after light sleep
*
* @param back_up_before_sleep Whether to back up RMT registers before sleep
*/
static void test_rmt_tx_rx_sleep_retention(bool back_up_before_sleep)
{
uint32_t const test_rx_buffer_symbols = 128;
rmt_symbol_word_t *remote_codes = heap_caps_aligned_calloc(64, test_rx_buffer_symbols, sizeof(rmt_symbol_word_t),
MALLOC_CAP_8BIT | MALLOC_CAP_INTERNAL | MALLOC_CAP_DMA);
TEST_ASSERT_NOT_NULL(remote_codes);
rmt_rx_channel_config_t rx_channel_cfg = {
.clk_src = RMT_CLK_SRC_DEFAULT,
.resolution_hz = 1000000,
.mem_block_symbols = SOC_RMT_MEM_WORDS_PER_CHANNEL,
.gpio_num = TEST_RMT_GPIO_NUM_A,
.flags.io_loop_back = true,
.flags.backup_before_sleep = back_up_before_sleep,
};
printf("install rx channel\r\n");
rmt_channel_handle_t rx_channel = NULL;
TEST_ESP_OK(rmt_new_rx_channel(&rx_channel_cfg, &rx_channel));
printf("register rx event callbacks\r\n");
rmt_rx_event_callbacks_t cbs = {
.on_recv_done = test_rmt_rx_done_callback,
};
test_rx_user_data_t test_user_data = {
.task_to_notify = xTaskGetCurrentTaskHandle(),
};
TEST_ESP_OK(rmt_rx_register_event_callbacks(rx_channel, &cbs, &test_user_data));
rmt_tx_channel_config_t tx_channel_cfg = {
.clk_src = RMT_CLK_SRC_DEFAULT,
.resolution_hz = 1000000,
.mem_block_symbols = SOC_RMT_MEM_WORDS_PER_CHANNEL,
.trans_queue_depth = 4,
.gpio_num = TEST_RMT_GPIO_NUM_A,
.flags.io_loop_back = true,
.flags.backup_before_sleep = back_up_before_sleep,
};
printf("install tx channel\r\n");
rmt_channel_handle_t tx_channel = NULL;
TEST_ESP_OK(rmt_new_tx_channel(&tx_channel_cfg, &tx_channel));
printf("install nec protocol encoder\r\n");
rmt_encoder_handle_t nec_encoder = NULL;
TEST_ESP_OK(test_rmt_new_nec_protocol_encoder(&nec_encoder));
rmt_transmit_config_t transmit_config = {
.loop_count = 0, // no loop
};
// Note: don't enable the RMT channel before going to sleep, ensure no power management lock is acquired by RMT
printf("go to light sleep for 2 seconds\r\n");
#if CONFIG_PM_POWER_DOWN_CPU_IN_LIGHT_SLEEP
TEST_ESP_OK(sleep_cpu_configure(true));
#endif
TEST_ESP_OK(esp_sleep_enable_timer_wakeup(2 * 1000 * 1000));
TEST_ESP_OK(esp_light_sleep_start());
printf("Waked up! Let's see if RMT driver can still work...\r\n");
#if CONFIG_PM_POWER_DOWN_CPU_IN_LIGHT_SLEEP
TEST_ESP_OK(sleep_cpu_configure(false));
#endif
TEST_ESP_OK(rmt_enable(tx_channel));
TEST_ESP_OK(rmt_enable(rx_channel));
rmt_receive_config_t receive_config = {
.signal_range_min_ns = 1250,
.signal_range_max_ns = 12000000,
};
// ready to receive
TEST_ESP_OK(rmt_receive(rx_channel, remote_codes, test_rx_buffer_symbols * sizeof(rmt_symbol_word_t), &receive_config));
printf("send NEC frame\r\n");
TEST_ESP_OK(rmt_transmit(tx_channel, nec_encoder, (uint16_t[]) {
0x0440, 0x3003 // address, command
}, 4, &transmit_config));
TEST_ASSERT_NOT_EQUAL(0, ulTaskNotifyTake(pdFALSE, pdMS_TO_TICKS(1000)));
TEST_ASSERT_EQUAL(34, test_user_data.received_symbol_num);
printf("uninstall the RMT driver\r\n");
TEST_ESP_OK(rmt_disable(tx_channel));
TEST_ESP_OK(rmt_disable(rx_channel));
TEST_ESP_OK(rmt_del_channel(rx_channel));
TEST_ESP_OK(rmt_del_channel(tx_channel));
TEST_ESP_OK(rmt_del_encoder(nec_encoder));
free(remote_codes);
}
TEST_CASE("rmt tx+rx after light sleep", "[rmt]")
{
test_rmt_tx_rx_sleep_retention(false);
#if SOC_RMT_SUPPORT_SLEEP_BACKUP
test_rmt_tx_rx_sleep_retention(true);
#endif
}

Wyświetl plik

@ -1,5 +1,6 @@
CONFIG_PM_ENABLE=y
CONFIG_FREERTOS_USE_TICKLESS_IDLE=y
CONFIG_PM_POWER_DOWN_PERIPHERAL_IN_LIGHT_SLEEP=y
CONFIG_PM_DFS_INIT_AUTO=y
CONFIG_COMPILER_OPTIMIZATION_SIZE=y
CONFIG_BOOTLOADER_COMPILER_OPTIMIZATION_SIZE=y

Wyświetl plik

@ -147,7 +147,11 @@ bool peripheral_domain_pd_allowed(void)
#if CONFIG_PM_POWER_DOWN_PERIPHERAL_IN_LIGHT_SLEEP
const uint32_t inited_modules = sleep_retention_get_inited_modules();
const uint32_t created_modules = sleep_retention_get_created_modules();
const uint32_t mask = (const uint32_t) (BIT(SLEEP_RETENTION_MODULE_SYS_PERIPH));
uint32_t mask = (const uint32_t) (BIT(SLEEP_RETENTION_MODULE_SYS_PERIPH));
#if SOC_RMT_SUPPORT_SLEEP_BACKUP
mask |= BIT(SLEEP_RETENTION_MODULE_RMT0);
#endif
return ((inited_modules & mask) == (created_modules & mask));
#else

Wyświetl plik

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2022-2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2022-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -18,6 +18,7 @@
#include "hal/rmt_types.h"
#include "soc/rmt_struct.h"
#include "soc/pcr_struct.h"
#include "soc/retention_periph_defs.h"
#ifdef __cplusplus
extern "C" {
@ -37,6 +38,8 @@ extern "C" {
#define RMT_LL_MAX_FILTER_VALUE 255
#define RMT_LL_MAX_IDLE_VALUE 32767
#define RMT_LL_SLEEP_RETENTION_MODULE_ID(group_id) (SLEEP_RETENTION_MODULE_RMT0)
typedef enum {
RMT_LL_MEM_OWNER_SW = 0,
RMT_LL_MEM_OWNER_HW = 1,
@ -112,7 +115,7 @@ static inline void rmt_ll_enable_mem_access_nonfifo(rmt_dev_t *dev, bool enable)
* @param divider_numerator Numerator part of the divider
*/
static inline void rmt_ll_set_group_clock_src(rmt_dev_t *dev, uint32_t channel, rmt_clock_source_t src,
uint32_t divider_integral, uint32_t divider_denominator, uint32_t divider_numerator)
uint32_t divider_integral, uint32_t divider_denominator, uint32_t divider_numerator)
{
// Formula: rmt_sclk = module_clock_src / (1 + div_num + div_a / div_b)
(void)channel; // the source clock is set for all channels
@ -433,7 +436,7 @@ static inline void rmt_ll_tx_set_carrier_level(rmt_dev_t *dev, uint32_t channel,
*
* @param dev Peripheral instance address
* @param channel RMT TX channel number
* @param enable True to output carrier signal in all RMT state, False to only ouput carrier signal for effective data
* @param enable True to output carrier signal in all RMT state, False to only output carrier signal for effective data
*/
static inline void rmt_ll_tx_enable_carrier_always_on(rmt_dev_t *dev, uint32_t channel, bool enable)
{
@ -664,7 +667,7 @@ static inline void rmt_ll_enable_interrupt(rmt_dev_t *dev, uint32_t mask, bool e
* @brief Clear RMT interrupt status by mask
*
* @param dev Peripheral instance address
* @param mask Interupt status mask
* @param mask Interrupt status mask
*/
__attribute__((always_inline))
static inline void rmt_ll_clear_interrupt_status(rmt_dev_t *dev, uint32_t mask)

Wyświetl plik

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2023 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2023-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -18,6 +18,7 @@
#include "hal/rmt_types.h"
#include "soc/rmt_struct.h"
#include "soc/pcr_struct.h"
#include "soc/retention_periph_defs.h"
#ifdef __cplusplus
extern "C" {
@ -37,6 +38,8 @@ extern "C" {
#define RMT_LL_MAX_FILTER_VALUE 255
#define RMT_LL_MAX_IDLE_VALUE 32767
#define RMT_LL_SLEEP_RETENTION_MODULE_ID(group_id) (SLEEP_RETENTION_MODULE_RMT0)
typedef enum {
RMT_LL_MEM_OWNER_SW = 0,
RMT_LL_MEM_OWNER_HW = 1,
@ -112,7 +115,7 @@ static inline void rmt_ll_enable_mem_access_nonfifo(rmt_dev_t *dev, bool enable)
* @param divider_numerator Numerator part of the divider
*/
static inline void rmt_ll_set_group_clock_src(rmt_dev_t *dev, uint32_t channel, rmt_clock_source_t src,
uint32_t divider_integral, uint32_t divider_denominator, uint32_t divider_numerator)
uint32_t divider_integral, uint32_t divider_denominator, uint32_t divider_numerator)
{
// Formula: rmt_sclk = module_clock_src / (1 + div_num + div_a / div_b)
(void)channel; // the source clock is set for all channels
@ -430,7 +433,7 @@ static inline void rmt_ll_tx_set_carrier_level(rmt_dev_t *dev, uint32_t channel,
*
* @param dev Peripheral instance address
* @param channel RMT TX channel number
* @param enable True to output carrier signal in all RMT state, False to only ouput carrier signal for effective data
* @param enable True to output carrier signal in all RMT state, False to only output carrier signal for effective data
*/
static inline void rmt_ll_tx_enable_carrier_always_on(rmt_dev_t *dev, uint32_t channel, bool enable)
{
@ -661,7 +664,7 @@ static inline void rmt_ll_enable_interrupt(rmt_dev_t *dev, uint32_t mask, bool e
* @brief Clear RMT interrupt status by mask
*
* @param dev Peripheral instance address
* @param mask Interupt status mask
* @param mask Interrupt status mask
*/
__attribute__((always_inline))
static inline void rmt_ll_clear_interrupt_status(rmt_dev_t *dev, uint32_t mask)

Wyświetl plik

@ -11,7 +11,6 @@
const rmt_signal_conn_t rmt_periph_signals = {
.groups = {
[0] = {
.module = PERIPH_RMT_MODULE,
.irq = ETS_RMT_INTR_SOURCE,
.channels = {
[0] = {

Wyświetl plik

@ -10,7 +10,6 @@
const rmt_signal_conn_t rmt_periph_signals = {
.groups = {
[0] = {
.module = PERIPH_RMT_MODULE,
.irq = ETS_RMT_INTR_SOURCE,
.channels = {
[0] = {

Wyświetl plik

@ -10,7 +10,6 @@
const rmt_signal_conn_t rmt_periph_signals = {
.groups = {
[0] = {
.module = PERIPH_RMT_MODULE,
.irq = ETS_RMT_INTR_SOURCE,
.channels = {
[0] = {

Wyświetl plik

@ -10,7 +10,6 @@
const rmt_signal_conn_t rmt_periph_signals = {
.groups = {
[0] = {
.module = PERIPH_RMT_MODULE,
.irq = ETS_RMT_INTR_SOURCE,
.channels = {
[0] = {

Wyświetl plik

@ -795,6 +795,10 @@ config SOC_RMT_SUPPORT_RC_FAST
bool
default y
config SOC_RMT_SUPPORT_SLEEP_BACKUP
bool
default y
config SOC_MCPWM_GROUPS
int
default 1

Wyświetl plik

@ -36,6 +36,7 @@ typedef enum periph_retention_module {
SLEEP_RETENTION_MODULE_GDMA_CH1 = 25,
SLEEP_RETENTION_MODULE_GDMA_CH2 = 26,
SLEEP_RETENTION_MODULE_I2C0 = 27,
SLEEP_RETENTION_MODULE_RMT0 = 28,
SLEEP_RETENTION_MODULE_MAX = 31
} periph_retention_module_t;
@ -62,6 +63,7 @@ typedef enum periph_retention_module_bitmap {
SLEEP_RETENTION_MODULE_BM_GDMA_CH1 = BIT(SLEEP_RETENTION_MODULE_GDMA_CH1),
SLEEP_RETENTION_MODULE_BM_GDMA_CH2 = BIT(SLEEP_RETENTION_MODULE_GDMA_CH2),
SLEEP_RETENTION_MODULE_BM_I2C0 = BIT(SLEEP_RETENTION_MODULE_I2C0),
SLEEP_RETENTION_MODULE_BM_RMT0 = BIT(SLEEP_RETENTION_MODULE_RMT0),
SLEEP_RETENTION_MODULE_BM_ALL = (uint32_t)-1
} periph_retention_module_bitmap_t;

Wyświetl plik

@ -313,6 +313,7 @@
#define SOC_RMT_SUPPORT_TX_CARRIER_DATA_ONLY 1 /*!< TX carrier can be modulated to data phase only */
#define SOC_RMT_SUPPORT_XTAL 1 /*!< Support set XTAL clock as the RMT clock source */
#define SOC_RMT_SUPPORT_RC_FAST 1 /*!< Support set RC_FAST as the RMT clock source */
#define SOC_RMT_SUPPORT_SLEEP_BACKUP 1 /*!< Support back up registers before sleep */
/*-------------------------- MCPWM CAPS --------------------------------------*/
#define SOC_MCPWM_GROUPS (1U) ///< 1 MCPWM groups on the chip (i.e., the number of independent MCPWM peripherals)

Wyświetl plik

@ -1,16 +1,16 @@
/*
* SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2022-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include "soc/rmt_periph.h"
#include "soc/rmt_reg.h"
#include "soc/gpio_sig_map.h"
const rmt_signal_conn_t rmt_periph_signals = {
.groups = {
[0] = {
.module = PERIPH_RMT_MODULE,
.irq = ETS_RMT_INTR_SOURCE,
.channels = {
[0] = {
@ -33,3 +33,32 @@ const rmt_signal_conn_t rmt_periph_signals = {
}
}
};
/**
* RMT Registers to be saved during sleep retention
* - Channel configuration registers, e.g.: RMT_CH0CONF0_REG, RMT_CH3CONF0_REG, RMT_CH3CONF1_REG, RMT_CH0_TX_LIM_REG, RMT_CH3_RX_LIM_REG
* - TX synchronization registers, e.g.: RMT_TX_SIM_REG
* - Interrupt enable registers, e.g.: RMT_INT_ENA_REG
* - Carrier duty registers, e.g.: RMT_CH0CARRIER_DUTY_REG, RMT_CH3_RX_CARRIER_RM_REG
* - Global configuration registers, e.g.: RMT_SYS_CONF_REG
*/
#define RMT_RETENTION_REGS_CNT 17
#define RMT_RETENTION_REGS_BASE (DR_REG_RMT_BASE + 0x10)
static const uint32_t rmt_regs_map[4] = {0xffd03f, 0x0, 0x0, 0x0};
static const regdma_entries_config_t rmt_regdma_entries[] = {
[0] = {
.config = REGDMA_LINK_ADDR_MAP_INIT(REGDMA_RMT_LINK(0x00),
RMT_RETENTION_REGS_BASE, RMT_RETENTION_REGS_BASE,
RMT_RETENTION_REGS_CNT, 0, 0,
rmt_regs_map[0], rmt_regs_map[1],
rmt_regs_map[2], rmt_regs_map[3]),
.owner = ENTRY(0) | ENTRY(2),
},
};
const rmt_reg_retention_info_t rmt_reg_retention_info[SOC_RMT_GROUPS] = {
[0] = {
.regdma_entry_array = rmt_regdma_entries,
.array_size = ARRAY_SIZE(rmt_regdma_entries)
},
};

Wyświetl plik

@ -779,6 +779,10 @@ config SOC_RMT_SUPPORT_RC_FAST
bool
default y
config SOC_RMT_SUPPORT_SLEEP_BACKUP
bool
default y
config SOC_MCPWM_GROUPS
int
default 1

Wyświetl plik

@ -35,6 +35,7 @@ typedef enum periph_retention_module {
SLEEP_RETENTION_MODULE_GDMA_CH2 = 26,
SLEEP_RETENTION_MODULE_I2C0 = 27,
SLEEP_RETENTION_MODULE_I2C1 = 28,
SLEEP_RETENTION_MODULE_RMT0 = 29,
SLEEP_RETENTION_MODULE_MAX = 31
} periph_retention_module_t;
@ -60,8 +61,9 @@ typedef enum periph_retention_module_bitmap {
SLEEP_RETENTION_MODULE_BM_GDMA_CH2 = BIT(SLEEP_RETENTION_MODULE_GDMA_CH2),
SLEEP_RETENTION_MODULE_BM_I2C0 = BIT(SLEEP_RETENTION_MODULE_I2C0),
SLEEP_RETENTION_MODULE_BM_I2C1 = BIT(SLEEP_RETENTION_MODULE_I2C1),
SLEEP_RETENTION_MODULE_BM_RMT0 = BIT(SLEEP_RETENTION_MODULE_RMT0),
SLEEP_RETENTION_MODULE_BM_ALL = (uint32_t)-1
SLEEP_RETENTION_MODULE_BM_ALL = (uint32_t) -1
} periph_retention_module_bitmap_t;
#ifdef __cplusplus

Wyświetl plik

@ -305,6 +305,7 @@
#define SOC_RMT_SUPPORT_TX_CARRIER_DATA_ONLY 1 /*!< TX carrier can be modulated to data phase only */
#define SOC_RMT_SUPPORT_XTAL 1 /*!< Support set XTAL clock as the RMT clock source */
#define SOC_RMT_SUPPORT_RC_FAST 1 /*!< Support set RC_FAST as the RMT clock source */
#define SOC_RMT_SUPPORT_SLEEP_BACKUP 1 /*!< Support back up registers before sleep */
/*-------------------------- MCPWM CAPS --------------------------------------*/
#define SOC_MCPWM_GROUPS (1U) ///< 1 MCPWM groups on the chip (i.e., the number of independent MCPWM peripherals)

Wyświetl plik

@ -1,16 +1,16 @@
/*
* SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2022-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
#include "soc/rmt_periph.h"
#include "soc/rmt_reg.h"
#include "soc/gpio_sig_map.h"
const rmt_signal_conn_t rmt_periph_signals = {
.groups = {
[0] = {
.module = PERIPH_RMT_MODULE,
.irq = ETS_RMT_INTR_SOURCE,
.channels = {
[0] = {
@ -33,3 +33,32 @@ const rmt_signal_conn_t rmt_periph_signals = {
}
}
};
/**
* RMT Registers to be saved during sleep retention
* - Channel configuration registers, e.g.: RMT_CH0CONF0_REG, RMT_CH3CONF0_REG, RMT_CH3CONF1_REG, RMT_CH0_TX_LIM_REG, RMT_CH3_RX_LIM_REG
* - TX synchronization registers, e.g.: RMT_TX_SIM_REG
* - Interrupt enable registers, e.g.: RMT_INT_ENA_REG
* - Carrier duty registers, e.g.: RMT_CH0CARRIER_DUTY_REG, RMT_CH3_RX_CARRIER_RM_REG
* - Global configuration registers, e.g.: RMT_SYS_CONF_REG
*/
#define RMT_RETENTION_REGS_CNT 17
#define RMT_RETENTION_REGS_BASE (DR_REG_RMT_BASE + 0x10)
static const uint32_t rmt_regs_map[4] = {0xffd03f, 0x0, 0x0, 0x0};
static const regdma_entries_config_t rmt_regdma_entries[] = {
[0] = {
.config = REGDMA_LINK_ADDR_MAP_INIT(REGDMA_RMT_LINK(0x00),
RMT_RETENTION_REGS_BASE, RMT_RETENTION_REGS_BASE,
RMT_RETENTION_REGS_CNT, 0, 0,
rmt_regs_map[0], rmt_regs_map[1],
rmt_regs_map[2], rmt_regs_map[3]),
.owner = ENTRY(0) | ENTRY(2),
},
};
const rmt_reg_retention_info_t rmt_reg_retention_info[SOC_RMT_GROUPS] = {
[0] = {
.regdma_entry_array = rmt_regdma_entries,
.array_size = ARRAY_SIZE(rmt_regdma_entries)
},
};

Wyświetl plik

@ -10,7 +10,6 @@
const rmt_signal_conn_t rmt_periph_signals = {
.groups = {
[0] = {
.module = PERIPH_RMT_MODULE,
.irq = ETS_RMT_INTR_SOURCE,
.channels = {
[0] = {

Wyświetl plik

@ -10,7 +10,6 @@
const rmt_signal_conn_t rmt_periph_signals = {
.groups = {
[0] = {
.module = PERIPH_RMT_MODULE,
.irq = ETS_RMT_INTR_SOURCE,
.channels = {
[0] = {

Wyświetl plik

@ -10,7 +10,6 @@
const rmt_signal_conn_t rmt_periph_signals = {
.groups = {
[0] = {
.module = PERIPH_RMT_MODULE,
.irq = ETS_RMT_INTR_SOURCE,
.channels = {
[0] = {

Wyświetl plik

@ -46,6 +46,7 @@ extern "C" {
#define REGDMA_MODEM_IEEE802154_LINK(_pri) ((0x17 << 8) | _pri)
#define REGDMA_GDMA_LINK(_pri) ((0x18 << 8) | _pri)
#define REGDMA_I2C_LINK(_pri) ((0x19 << 8) | _pri)
#define REGDMA_RMT_LINK(_pri) ((0x20 << 8) | _pri)
#define REGDMA_MODEM_FE_LINK(_pri) ((0xFF << 8) | _pri)
#define REGDMA_LINK_PRI_SYS_CLK REGDMA_LINK_PRI_0
@ -58,6 +59,7 @@ extern "C" {
#define REGDMA_LINK_PRI_SYS_PERIPH_LOW REGDMA_LINK_PRI_6 // TG0 & IO MUX & SPI MEM & Systimer
#define REGDMA_LINK_PRI_IEEE802154 REGDMA_LINK_PRI_7
#define REGDMA_LINK_PRI_GDMA REGDMA_LINK_PRI_7
#define REGDMA_LINK_PRI_RMT REGDMA_LINK_PRI_7
typedef enum {
REGDMA_LINK_PRI_0 = 0,

Wyświetl plik

@ -1,5 +1,5 @@
/*
* SPDX-FileCopyrightText: 2015-2022 Espressif Systems (Shanghai) CO LTD
* SPDX-FileCopyrightText: 2015-2024 Espressif Systems (Shanghai) CO LTD
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -8,6 +8,7 @@
#include "soc/soc_caps.h"
#include "soc/periph_defs.h"
#include "soc/regdma.h"
#ifdef __cplusplus
extern "C" {
@ -18,7 +19,6 @@ extern "C" {
typedef struct {
struct {
const int irq;
const periph_module_t module;
struct {
struct {
const int tx_sig;
@ -30,6 +30,18 @@ typedef struct {
extern const rmt_signal_conn_t rmt_periph_signals;
#if SOC_RMT_SUPPORT_SLEEP_BACKUP
typedef struct {
const regdma_entries_config_t *regdma_entry_array;
uint32_t array_size;
} rmt_reg_retention_info_t;
// TODO: implement the retention link on the channel level, this can:
// - save memory when not all RMT channels are used
// - specify different retention dependency, e.g. only RMT channel x is capable to use DMA, we only want to add the DMA dependency for that channel
extern const rmt_reg_retention_info_t rmt_reg_retention_info[SOC_RMT_GROUPS];
#endif // SOC_RMT_SUPPORT_SLEEP_BACKUP
#endif // SOC_RMT_SUPPORTED
#ifdef __cplusplus

Wyświetl plik

@ -93,6 +93,7 @@ To install an RMT TX channel, there is a configuration structure that needs to b
- :cpp:member:`rmt_tx_channel_config_t::io_loop_back` enables both input and output capabilities on the channel's assigned GPIO. Thus, by binding a TX and RX channel to the same GPIO, loopback can be achieved.
- :cpp:member:`rmt_tx_channel_config_t::io_od_mode` configures the channel's assigned GPIO as open-drain. When combined with :cpp:member:`rmt_tx_channel_config_t::io_loop_back`, a bi-directional bus (e.g., 1-wire) can be achieved.
- :cpp:member:`rmt_tx_channel_config_t::intr_priority` Set the priority of the interrupt. If set to ``0`` , then the driver will use a interrupt with low or medium priority (priority level may be one of 1,2 or 3), otherwise use the priority indicated by :cpp:member:`rmt_tx_channel_config_t::intr_priority`. Please use the number form (1,2,3) , not the bitmask form ((1<<1),(1<<2),(1<<3)). Please pay attention that once the interrupt priority is set, it cannot be changed until :cpp:func:`rmt_del_channel` is called.
- :cpp:member:`rmt_tx_channel_config_t::backup_before_sleep` enables the backup of the RMT registers before entering sleep mode. This option implies an balance between power consumption and memory usage. If the power consumption is not a concern, you can disable this option to save memory. But if you want to save power, you should enable this option to save the RMT registers before entering sleep mode, and restore them after waking up. This feature depends on specific hardware module, if you enable this flag on an unsupported chip, you will get an error message like ``register back up is not supported``.
Once the :cpp:type:`rmt_tx_channel_config_t` structure is populated with mandatory parameters, users can call :cpp:func:`rmt_new_tx_channel` to allocate and initialize a TX channel. This function returns an RMT channel handle if it runs correctly. Specifically, when there are no more free channels in the RMT resource pool, this function returns :c:macro:`ESP_ERR_NOT_FOUND` error. If some feature (e.g., DMA backend) is not supported by the hardware, it returns :c:macro:`ESP_ERR_NOT_SUPPORTED` error.
@ -127,6 +128,7 @@ To install an RMT RX channel, there is a configuration structure that needs to b
- :cpp:member:`rmt_rx_channel_config_t::with_dma` enables the DMA backend for the channel. Using the DMA allows a significant amount of the channel's workload to be offloaded from the CPU. However, the DMA backend is not available on all ESP chips, please refer to [`TRM <{IDF_TARGET_TRM_EN_URL}#rmt>`__] before you enable this option. Or you might encounter a :c:macro:`ESP_ERR_NOT_SUPPORTED` error.
- :cpp:member:`rmt_rx_channel_config_t::io_loop_back` enables both input and output capabilities on the channel's assigned GPIO. Thus, by binding a TX and RX channel to the same GPIO, loopback can be achieved.
- :cpp:member:`rmt_rx_channel_config_t::intr_priority` Set the priority of the interrupt. If set to ``0`` , then the driver will use a interrupt with low or medium priority (priority level may be one of 1,2 or 3), otherwise use the priority indicated by :cpp:member:`rmt_rx_channel_config_t::intr_priority`. Please use the number form (1,2,3) , not the bitmask form ((1<<1),(1<<2),(1<<3)). Please pay attention that once the interrupt priority is set, it cannot be changed until :cpp:func:`rmt_del_channel` is called.
- :cpp:member:`rmt_rx_channel_config_t::backup_before_sleep` enables the backup of the RMT registers before entering sleep mode. This option implies an balance between power consumption and memory usage. If the power consumption is not a concern, you can disable this option to save memory. But if you want to save power, you should enable this option to save the RMT registers before entering sleep mode, and restore them after waking up. This feature depends on specific hardware module, if you enable this flag on an unsupported chip, you will get an error message like ``register back up is not supported``.
Once the :cpp:type:`rmt_rx_channel_config_t` structure is populated with mandatory parameters, users can call :cpp:func:`rmt_new_rx_channel` to allocate and initialize an RX channel. This function returns an RMT channel handle if it runs correctly. Specifically, when there are no more free channels in the RMT resource pool, this function returns :c:macro:`ESP_ERR_NOT_FOUND` error. If some feature (e.g., DMA backend) is not supported by the hardware, it returns :c:macro:`ESP_ERR_NOT_SUPPORTED` error.
@ -549,11 +551,13 @@ A full sample code can be found in :example:`peripherals/rmt/ir_nec_transceiver`
Power Management
^^^^^^^^^^^^^^^^
When power management is enabled, i.e., :ref:`CONFIG_PM_ENABLE` is on, the system adjusts the APB frequency before going into Light-sleep, thus potentially changing the resolution of the RMT internal counter.
When power management is enabled, i.e., :ref:`CONFIG_PM_ENABLE` is on, the system may adjust or disable the clock source before going to sleep. As a result, the time base inside the RMT can't work as expected.
However, the driver can prevent the system from changing APB frequency by acquiring a power management lock of type :cpp:enumerator:`ESP_PM_APB_FREQ_MAX`. Whenever the user creates an RMT channel that has selected :cpp:enumerator:`RMT_CLK_SRC_APB` as the clock source, the driver guarantees that the power management lock is acquired after the channel enabled by :cpp:func:`rmt_enable`. Likewise, the driver releases the lock after :cpp:func:`rmt_disable` is called for the same channel. This also reveals that the :cpp:func:`rmt_enable` and :cpp:func:`rmt_disable` should appear in pairs.
The driver can prevent the above issue by creating a power management lock. The lock type is set based on different clock sources. The driver will acquire the lock in :cpp:func:`rmt_enable`, and release it in :cpp:func:`rmt_disable`. That means, any RMT transactions in between these two functions are guaranteed to work correctly, regardless of the power management strategy. The clock source won't be disabled or adjusted its frequency during this time.
If the channel clock source is selected to others like :cpp:enumerator:`RMT_CLK_SRC_XTAL`, then the driver does not install a power management lock for it, which is more suitable for a low-power application as long as the source clock can still provide sufficient resolution.
.. only:: SOC_RMT_SUPPORT_SLEEP_BACKUP
Besides the potential changes to the clock source, when the power management is enabled, the system can also power down a domain where RMT register located. To ensure the RMT driver can continue work after sleep, we can either backup the RMT registers to the RAM, or just refuse to power down. You can choose what to do in :cpp:member:`rmt_tx_channel_config_t::backup_before_sleep` and :cpp:member:`rmt_rx_channel_config_t::backup_before_sleep`. It's a balance between power saving and memory consumption. Set it based on your application requirements.
.. _rmt-iram-safe:

Wyświetl plik

@ -146,6 +146,7 @@ Light-sleep Peripheral Power Down
- TIMG0
- SPI0/1
- SYSTIMER
- RMT
The following peripherals are not yet supported:
- ETM
@ -160,7 +161,6 @@ Light-sleep Peripheral Power Down
- TWAI
- LEDC
- MCPWM
- RMT
- SARADC
- SDIO
- PARL_IO

Wyświetl plik

@ -93,6 +93,7 @@ RMT 接收器可以对输入信号采样,将其转换为 RMT 数据格式,
- :cpp:member:`rmt_tx_channel_config_t::io_loop_back` 启用通道所分配的 GPIO 上的输入和输出功能,将发送通道和接收通道绑定到同一个 GPIO 上,从而实现回环功能。
- :cpp:member:`rmt_tx_channel_config_t::io_od_mode` 配置通道分配的 GPIO 为开漏模式 (open-drain)。当与 :cpp:member:`rmt_tx_channel_config_t::io_loop_back` 结合使用时,可以实现双向总线,如 1-wire。
- :cpp:member:`rmt_tx_channel_config_t::intr_priority` 设置中断的优先级。如果设置为 ``0`` ,驱动将会使用一个中低优先级的中断(优先级可能为 12 或 3否则会使用 :cpp:member:`rmt_tx_channel_config_t::intr_priority` 指定的优先级。请使用优先级序号 (1, 2, 3),而不是 bitmask 的形式((1<<1)(1<<2)(1<<3))。请注意,中断优先级一旦设置,在 :cpp:func:`rmt_del_channel` 被调用之前不可再次修改。
- :cpp:member:`rmt_tx_channel_config_t::backup_before_sleep` 用于使能在进入睡眠模式前备份 RMT 寄存器。这个选项需要用户在功耗和内存使用之间取得平衡。如果功耗不是一个问题,可以禁用这个选项来节省内存。但如果想要节省功耗,应该使能这个选项,在进入睡眠模式前保存 RMT 寄存器,并在唤醒后恢复它们。这个功能依赖于特定的硬件模块,如果你在不支持的芯片上启用这个标志,你会得到一个错误信息,如 ``register back up is not supported``
将必要参数填充到结构体 :cpp:type:`rmt_tx_channel_config_t` 后,可以调用 :cpp:func:`rmt_new_tx_channel` 来分配和初始化 TX 通道。如果函数运行正确,会返回 RMT 通道句柄;如果 RMT 资源池内缺少空闲通道,会返回 :c:macro:`ESP_ERR_NOT_FOUND` 错误;如果硬件不支持 DMA 后端等部分功能,则返回 :c:macro:`ESP_ERR_NOT_SUPPORTED` 错误。
@ -127,6 +128,7 @@ RMT 接收器可以对输入信号采样,将其转换为 RMT 数据格式,
- :cpp:member:`rmt_rx_channel_config_t::with_dma` 为通道启用 DMA 后端。启用 DMA 后端可以释放 CPU 上的大部分通道工作负载,显著减轻 CPU 负担。但并非所有 ESP 芯片都支持 DMA 后端,在启用此选项前,请参阅 [`TRM <{IDF_TARGET_TRM_EN_URL}#rmt>`__]。若所选芯片不支持 DMA 后端,可能会报告 :c:macro:`ESP_ERR_NOT_SUPPORTED` 错误。
- :cpp:member:`rmt_rx_channel_config_t::io_loop_back` 启用通道所分配的 GPIO 上的输入和输出功能,将发送通道和接收通道绑定到同一个 GPIO 上,从而实现回环功能。
- :cpp:member:`rmt_rx_channel_config_t::intr_priority` 设置中断的优先级。如果设置为 ``0`` ,驱动将会使用一个中低优先级的中断(优先级可能为 12 或 3否则会使用 :cpp:member:`rmt_rx_channel_config_t::intr_priority` 指定的优先级。请使用优先级序号 (123),而不是 bitmask 的形式((1<<1)(1<<2)(1<<3))。请注意,中断优先级一旦设置,在 :cpp:func:`rmt_del_channel` 被调用之前不可再次修改。
- :cpp:member:`rmt_rx_channel_config_t::backup_before_sleep` 用于使能在进入睡眠模式前备份 RMT 寄存器。这个选项需要用户在功耗和内存使用之间取得平衡。如果功耗不是一个问题,可以禁用这个选项来节省内存。但如果想要节省功耗,应该使能这个选项,在进入睡眠模式前保存 RMT 寄存器,并在唤醒后恢复它们。这个功能依赖于特定的硬件模块,如果你在不支持的芯片上启用这个标志,你会得到一个错误信息,如 ``register back up is not supported``
将必要参数填充到结构体 :cpp:type:`rmt_rx_channel_config_t` 后,可以调用 :cpp:func:`rmt_new_rx_channel` 来分配和初始化 RX 通道。如果函数运行正确,会返回 RMT 通道句柄;如果 RMT 资源池内缺少空闲通道,会返回 :c:macro:`ESP_ERR_NOT_FOUND` 错误;如果硬件不支持 DMA 后端等部分功能,则返回 :c:macro:`ESP_ERR_NOT_SUPPORTED` 错误。
@ -428,6 +430,18 @@ RMT 编码器是 RMT TX 事务的一部分,用于在特定时间生成正确
:caption: RMT 编码器链
:align: center
简易回调编码器
~~~~~~~~~~~~~~
简易回调编码器通过调用 :cpp:func:`rmt_new_simple_encoder` 创建。简易回调编码器允许用户提供一个回调函数,该函数从用户空间读取数据并将 RMT 符号写入输出流,无需链式组合其他编码器。回调函数会接收到传递给 :cpp:func:`rmt_transmit` 的数据指针、回调函数在此次传输中已写入的符号数量计数器、编码后的 RMT 符号指针以及空闲空间大小。如果空间不足以编码数据,回调函数可以返回 0此时 RMT 驱动将等待先前的符号传输完成,然后再次调用回调函数,此时应该会有更多的空间可用。如果回调函数成功编码 RMT 符号,应返回已编码的符号数量。
在调用 :cpp:func:`rmt_new_simple_encoder` 前,应预先提供配置结构体 :cpp:type:`rmt_simple_encoder_config_t`,具体配置如下:
- :cpp:member:`rmt_simple_encoder_config_t::callback`:cpp:member:`rmt_simple_encoder_config_t::arg` 为必选项,分别用于提供回调函数和传递给回调函数的不透明参数。
- :cpp:member:`rmt_simple_encoder_config_t::min_chunk_size` 指定了编码器始终能够写入一些数据的最小空闲空间,以符号为单位。换句话说,当传递给编码器的空闲空间达到这个数量时,它不应该返回 0除非编码器已经完成了符号的编码
简易回调编码器的功能通常可以通过链式组合其他编码器来实现,但相比编码器链,简易回调编码器更易于理解和维护。
自定义 NEC 协议的 RMT 编码器
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
@ -537,11 +551,13 @@ RMT 编码器是 RMT TX 事务的一部分,用于在特定时间生成正确
电源管理
^^^^^^^^^^^^^^^^
通过 :ref:`CONFIG_PM_ENABLE` 选项启用电源管理时,系统会在进入 Light-sleep 模式前调整 APB 频率。该操作可能改变 RMT 内部计数器的分辨率
当电源管理 :ref:`CONFIG_PM_ENABLE` 被启用的时候系统在进入睡眠前可能会调整或禁用时钟源。结果是RMT 内部的时间基准无法按预期工作
然而,驱动程序可以通过获取 :cpp:enumerator:`ESP_PM_APB_FREQ_MAX` 类型的电源管理锁,防止系统改变 APB 频率。每当驱动创建以 :cpp:enumerator:`RMT_CLK_SRC_APB` 作为时钟源的 RMT 通道时,都会在通过 :cpp:func:`rmt_enable` 启用通道后获取电源管理锁。反之,调用 :cpp:func:`rmt_disable` 时,驱动程序释放锁。这也意味着 :cpp:func:`rmt_enable`:cpp:func:`rmt_disable` 应成对出现
驱动程序可以通过创建一个电源管理锁来防止上述问题。锁的类型会根据不同的时钟源来设置。驱动程序将在 :cpp:func:`rmt_enable` 中拿锁,并在 :cpp:func:`rmt_disable` 中释放锁。这意味着,无论电源管理策略如何,在这两个函数之间的任何 RMT 事务都可以保证正常工作。在此期间,时钟源不会被禁用或调整频率
如果将通道时钟源设置为其他选项,如 :cpp:enumerator:`RMT_CLK_SRC_XTAL`,则驱动程序不会为其安装电源管理锁。对于低功耗应用程序来说,只要时钟源仍然可以提供足够的分辨率,不安装电源管理锁更为合适。
.. only:: SOC_RMT_SUPPORT_SLEEP_BACKUP
除了时钟源的潜在变化外,当启用电源管理时,系统还可以关闭 RMT 寄存器所在的电源域。为确保 RMT 驱动程序在睡眠后继续工作,用户要么选择将 RMT 相关的寄存器备份到 RAM 中,要么拒绝关闭电源域。你可以根据应用需求在 :cpp:member:`rmt_tx_channel_config_t::backup_before_sleep`:cpp:member:`rmt_rx_channel_config_t::backup_before_sleep` 中设置是否需要启用寄存器备份,在功耗和内存使用之间做权衡。
.. _rmt-iram-safe:

Wyświetl plik

@ -146,6 +146,7 @@ Light-sleep 外设下电
- TIMG0
- SPI0/1
- SYSTIMER
- RMT
以下外设尚未支持:
- ETM
@ -160,7 +161,6 @@ Light-sleep 外设下电
- TWAI
- LEDC
- MCPWM
- RMT
- SARADC
- SDIO
- PARL_IO