fix(rmt): a disabled channel may pick up a pending transaction

because in the trans_done interrupt, the driver didn't check the channel FSM
This commit is contained in:
morris 2023-10-18 15:50:58 +08:00
parent 4ea0538a88
commit 15cefab479
8 changed files with 241 additions and 198 deletions

View File

@ -16,7 +16,6 @@
extern "C" {
#endif
/**
* @brief Group of RMT TX callbacks
* @note The callbacks are all running under ISR environment
@ -38,14 +37,14 @@ typedef struct {
In the DMA mode, this field controls the DMA buffer size, it can be set to a large value;
In the normal mode, this field controls the number of RMT memory block that will be used by the channel. */
size_t trans_queue_depth; /*!< Depth of internal transfer queue, increase this value can support more transfers pending in the background */
int intr_priority; /*!< RMT interrupt priority,
if set to 0, the driver will try to allocate an interrupt with a relative low priority (1,2,3) */
struct {
uint32_t invert_out: 1; /*!< Whether to invert the RMT channel signal before output to GPIO pad */
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 */
} flags; /*!< TX channel config flags */
int intr_priority; /*!< RMT interrupt priority,
if set to 0, the driver will try to allocate an interrupt with a relative low priority (1,2,3) */
} rmt_tx_channel_config_t;
/**
@ -54,8 +53,9 @@ typedef struct {
typedef struct {
int loop_count; /*!< Specify the times of transmission in a loop, -1 means transmitting in an infinite loop */
struct {
uint32_t eot_level : 1; /*!< Set the output level for the "End Of Transmission" */
} flags; /*!< Transmit config flags */
uint32_t eot_level : 1; /*!< Set the output level for the "End Of Transmission" */
uint32_t queue_nonblocking : 1; /*!< If set, when the transaction queue is full, driver will not block the thread but return directly */
} flags; /*!< Transmit specific config flags */
} rmt_transmit_config_t;
/**
@ -84,8 +84,11 @@ esp_err_t rmt_new_tx_channel(const rmt_tx_channel_config_t *config, rmt_channel_
/**
* @brief Transmit data by RMT TX channel
*
* @note This function will construct a transaction descriptor and push to a queue. The transaction will not start immediately until it's dispatched in the ISR.
* If there're too many transactions pending in the queue, this function will block until the queue has free space.
* @note This function constructs a transaction descriptor then pushes to a queue.
* The transaction will not start immediately if there's another one under processing.
* Based on the setting of `rmt_transmit_config_t::queue_nonblocking`,
* if there're too many transactions pending in the queue, this function can block until it has free slot,
* otherwise just return quickly.
* @note The data to be transmitted will be encoded into RMT symbols by the specific `encoder`.
*
* @param[in] tx_channel RMT TX channel that created by `rmt_new_tx_channel()`

View File

@ -205,7 +205,6 @@ esp_err_t rmt_apply_carrier(rmt_channel_handle_t channel, const rmt_carrier_conf
esp_err_t rmt_del_channel(rmt_channel_handle_t channel)
{
ESP_RETURN_ON_FALSE(channel, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
ESP_RETURN_ON_FALSE(channel->fsm == RMT_FSM_INIT, ESP_ERR_INVALID_STATE, TAG, "channel not in init state");
gpio_reset_pin(channel->gpio_num);
return channel->del(channel);
}
@ -213,14 +212,12 @@ esp_err_t rmt_del_channel(rmt_channel_handle_t channel)
esp_err_t rmt_enable(rmt_channel_handle_t channel)
{
ESP_RETURN_ON_FALSE(channel, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
ESP_RETURN_ON_FALSE(channel->fsm == RMT_FSM_INIT, ESP_ERR_INVALID_STATE, TAG, "channel not in init state");
return channel->enable(channel);
}
esp_err_t rmt_disable(rmt_channel_handle_t channel)
{
ESP_RETURN_ON_FALSE(channel, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
ESP_RETURN_ON_FALSE(channel->fsm == RMT_FSM_ENABLE, ESP_ERR_INVALID_STATE, TAG, "channel not in enable state");
return channel->disable(channel);
}

View File

@ -6,6 +6,7 @@
#pragma once
#include <stdatomic.h>
#include "sdkconfig.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
@ -80,8 +81,12 @@ typedef enum {
} rmt_channel_direction_t;
typedef enum {
RMT_FSM_INIT_WAIT,
RMT_FSM_INIT,
RMT_FSM_ENABLE_WAIT,
RMT_FSM_ENABLE,
RMT_FSM_RUN_WAIT,
RMT_FSM_RUN,
} rmt_fsm_t;
enum {
@ -119,7 +124,7 @@ struct rmt_channel_t {
portMUX_TYPE spinlock; // prevent channel resource accessing by user and interrupt concurrently
uint32_t resolution_hz; // channel clock resolution
intr_handle_t intr; // allocated interrupt handle for each channel
rmt_fsm_t fsm; // channel life cycle specific FSM
_Atomic rmt_fsm_t fsm; // channel life cycle specific FSM
rmt_channel_direction_t direction; // channel direction
rmt_symbol_word_t *hw_mem_base; // base address of RMT channel hardware memory
rmt_symbol_word_t *dma_mem_base; // base address of RMT channel DMA buffer

View File

@ -285,10 +285,10 @@ esp_err_t rmt_new_rx_channel(const rmt_rx_channel_config_t *config, rmt_channel_
gpio_hal_iomux_func_sel(GPIO_PIN_MUX_REG[config->gpio_num], PIN_FUNC_GPIO);
// initialize other members of rx channel
portMUX_INITIALIZE(&rx_channel->base.spinlock);
atomic_init(&rx_channel->base.fsm, RMT_FSM_INIT);
rx_channel->base.direction = RMT_CHANNEL_DIRECTION_RX;
rx_channel->base.fsm = RMT_FSM_INIT;
rx_channel->base.hw_mem_base = &RMTMEM.channels[channel_id + RMT_RX_CHANNEL_OFFSET_IN_GROUP].symbols[0];
rx_channel->base.spinlock = (portMUX_TYPE)portMUX_INITIALIZER_UNLOCKED;
// polymorphic methods
rx_channel->base.del = rmt_del_rx_channel;
rx_channel->base.set_carrier_action = rmt_rx_demodulate_carrier;
@ -310,6 +310,8 @@ err:
static esp_err_t rmt_del_rx_channel(rmt_channel_handle_t channel)
{
ESP_RETURN_ON_FALSE(atomic_load(&channel->fsm) == RMT_FSM_INIT,
ESP_ERR_INVALID_STATE, TAG, "channel not in init state");
rmt_rx_channel_t *rx_chan = __containerof(channel, rmt_rx_channel_t, base);
rmt_group_t *group = channel->group;
int group_id = group->group_id;
@ -344,7 +346,6 @@ esp_err_t rmt_receive(rmt_channel_handle_t channel, void *buffer, size_t buffer_
{
ESP_RETURN_ON_FALSE(channel && buffer && buffer_size && config, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
ESP_RETURN_ON_FALSE(channel->direction == RMT_CHANNEL_DIRECTION_RX, ESP_ERR_INVALID_ARG, TAG, "invalid channel direction");
ESP_RETURN_ON_FALSE(channel->fsm == RMT_FSM_ENABLE, ESP_ERR_INVALID_STATE, TAG, "channel not in enable state");
rmt_rx_channel_t *rx_chan = __containerof(channel, rmt_rx_channel_t, base);
if (channel->dma_chan) {
@ -369,6 +370,11 @@ esp_err_t rmt_receive(rmt_channel_handle_t channel, void *buffer, size_t buffer_
ESP_RETURN_ON_FALSE(filter_reg_value <= RMT_LL_MAX_FILTER_VALUE, ESP_ERR_INVALID_ARG, TAG, "signal_range_min_ns too big");
ESP_RETURN_ON_FALSE(idle_reg_value <= RMT_LL_MAX_IDLE_VALUE, ESP_ERR_INVALID_ARG, TAG, "signal_range_max_ns too big");
// check if we're in a proper state to start the receiver
rmt_fsm_t expected_fsm = RMT_FSM_ENABLE;
ESP_RETURN_ON_FALSE(atomic_compare_exchange_strong(&channel->fsm, &expected_fsm, RMT_FSM_RUN_WAIT),
ESP_ERR_INVALID_STATE, TAG, "channel not in enable state");
// fill in the transaction descriptor
rmt_rx_trans_desc_t *t = &rx_chan->trans_desc;
t->buffer = buffer;
@ -396,6 +402,11 @@ esp_err_t rmt_receive(rmt_channel_handle_t channel, void *buffer, size_t buffer_
// turn on RMT RX machine
rmt_ll_rx_enable(hal->regs, channel_id, true);
portEXIT_CRITICAL(&channel->spinlock);
// saying we're in running state, this state will last until the receiving is done
// i.e., we will switch back to the enable state in the receive done interrupt handler
atomic_store(&channel->fsm, RMT_FSM_RUN);
return ESP_OK;
}
@ -440,13 +451,18 @@ static esp_err_t rmt_rx_demodulate_carrier(rmt_channel_handle_t channel, const r
static esp_err_t rmt_rx_enable(rmt_channel_handle_t channel)
{
// can only enable the channel when it's in "init" state
rmt_fsm_t expected_fsm = RMT_FSM_INIT;
ESP_RETURN_ON_FALSE(atomic_compare_exchange_strong(&channel->fsm, &expected_fsm, RMT_FSM_ENABLE_WAIT),
ESP_ERR_INVALID_STATE, TAG, "channel not in init state");
rmt_group_t *group = channel->group;
rmt_hal_context_t *hal = &group->hal;
int channel_id = channel->channel_id;
// acquire power manager lock
if (channel->pm_lock) {
ESP_RETURN_ON_ERROR(esp_pm_lock_acquire(channel->pm_lock), TAG, "acquire pm_lock failed");
esp_pm_lock_acquire(channel->pm_lock);
}
if (channel->dma_chan) {
#if SOC_RMT_SUPPORT_DMA
@ -462,12 +478,26 @@ static esp_err_t rmt_rx_enable(rmt_channel_handle_t channel)
rmt_ll_enable_interrupt(hal->regs, RMT_LL_EVENT_RX_MASK(channel_id), true);
portEXIT_CRITICAL(&group->spinlock);
}
channel->fsm = RMT_FSM_ENABLE;
atomic_store(&channel->fsm, RMT_FSM_ENABLE);
return ESP_OK;
}
static esp_err_t rmt_rx_disable(rmt_channel_handle_t channel)
{
// can disable the channel when it's in `enable` or `run` state
bool valid_state = false;
rmt_fsm_t expected_fsm = RMT_FSM_ENABLE;
if (atomic_compare_exchange_strong(&channel->fsm, &expected_fsm, RMT_FSM_INIT_WAIT)) {
valid_state = true;
}
expected_fsm = RMT_FSM_RUN;
if (atomic_compare_exchange_strong(&channel->fsm, &expected_fsm, RMT_FSM_INIT_WAIT)) {
valid_state = true;
}
ESP_RETURN_ON_FALSE(valid_state, ESP_ERR_INVALID_STATE, TAG, "channel not in enable or run state");
rmt_group_t *group = channel->group;
rmt_hal_context_t *hal = &group->hal;
int channel_id = channel->channel_id;
@ -493,9 +523,11 @@ static esp_err_t rmt_rx_disable(rmt_channel_handle_t channel)
// release power manager lock
if (channel->pm_lock) {
ESP_RETURN_ON_ERROR(esp_pm_lock_release(channel->pm_lock), TAG, "release pm_lock failed");
esp_pm_lock_release(channel->pm_lock);
}
channel->fsm = RMT_FSM_INIT;
// now we can switch the state to init
atomic_store(&channel->fsm, RMT_FSM_INIT);
return ESP_OK;
}
@ -563,6 +595,8 @@ static bool IRAM_ATTR rmt_isr_handle_rx_done(rmt_rx_channel_t *rx_chan)
need_yield = true;
}
}
// switch back to the enable state, then user can call `rmt_receive` to start a new receive
atomic_store(&channel->fsm, RMT_FSM_ENABLE);
return need_yield;
}
@ -674,6 +708,8 @@ static bool IRAM_ATTR rmt_dma_rx_eof_cb(gdma_channel_handle_t dma_chan, gdma_eve
need_yield = true;
}
}
// switch back to the enable state, then user can call `rmt_receive` to start a new receive
atomic_store(&channel->fsm, RMT_FSM_ENABLE);
return need_yield;
}
#endif // SOC_RMT_SUPPORT_DMA

View File

@ -40,6 +40,7 @@ static esp_err_t rmt_tx_modulate_carrier(rmt_channel_handle_t channel, const rmt
static esp_err_t rmt_tx_enable(rmt_channel_handle_t channel);
static esp_err_t rmt_tx_disable(rmt_channel_handle_t channel);
static void rmt_tx_default_isr(void *args);
static void rmt_tx_do_transaction(rmt_tx_channel_t *tx_chan, rmt_tx_trans_desc_t *t);
#if SOC_RMT_SUPPORT_DMA
static bool rmt_dma_tx_eof_cb(gdma_channel_handle_t dma_chan, gdma_event_data_t *event_data, void *user_data);
@ -310,10 +311,10 @@ esp_err_t rmt_new_tx_channel(const rmt_tx_channel_config_t *config, rmt_channel_
config->flags.invert_out, false);
gpio_hal_iomux_func_sel(GPIO_PIN_MUX_REG[config->gpio_num], PIN_FUNC_GPIO);
portMUX_INITIALIZE(&tx_channel->base.spinlock);
atomic_init(&tx_channel->base.fsm, RMT_FSM_INIT);
tx_channel->base.direction = RMT_CHANNEL_DIRECTION_TX;
tx_channel->base.fsm = RMT_FSM_INIT;
tx_channel->base.hw_mem_base = &RMTMEM.channels[channel_id + RMT_TX_CHANNEL_OFFSET_IN_GROUP].symbols[0];
tx_channel->base.spinlock = (portMUX_TYPE)portMUX_INITIALIZER_UNLOCKED;
// polymorphic methods
tx_channel->base.del = rmt_del_tx_channel;
tx_channel->base.set_carrier_action = rmt_tx_modulate_carrier;
@ -335,6 +336,8 @@ err:
static esp_err_t rmt_del_tx_channel(rmt_channel_handle_t channel)
{
ESP_RETURN_ON_FALSE(atomic_load(&channel->fsm) == RMT_FSM_INIT,
ESP_ERR_INVALID_STATE, TAG, "channel not in init state");
rmt_tx_channel_t *tx_chan = __containerof(channel, rmt_tx_channel_t, base);
rmt_group_t *group = channel->group;
int group_id = group->group_id;
@ -373,7 +376,7 @@ esp_err_t rmt_new_sync_manager(const rmt_sync_manager_config_t *config, rmt_sync
channel = config->tx_channel_array[i];
ESP_GOTO_ON_FALSE(channel->direction == RMT_CHANNEL_DIRECTION_TX, ESP_ERR_INVALID_ARG, err, TAG, "sync manager supports TX channel only");
ESP_GOTO_ON_FALSE(channel->group == group, ESP_ERR_INVALID_ARG, err, TAG, "channels to be managed should locate in the same group");
ESP_GOTO_ON_FALSE(channel->fsm == RMT_FSM_ENABLE, ESP_ERR_INVALID_STATE, err, TAG, "channel should be started before creating sync manager");
ESP_GOTO_ON_FALSE(atomic_load(&channel->fsm) == RMT_FSM_ENABLE, ESP_ERR_INVALID_STATE, err, TAG, "channel not in enable state");
channel_mask |= 1 << channel->channel_id;
}
synchro->channel_mask = channel_mask;
@ -480,7 +483,6 @@ esp_err_t rmt_transmit(rmt_channel_handle_t channel, rmt_encoder_t *encoder, con
{
ESP_RETURN_ON_FALSE(channel && encoder && payload && payload_bytes && config, ESP_ERR_INVALID_ARG, TAG, "invalid argument");
ESP_RETURN_ON_FALSE(channel->direction == RMT_CHANNEL_DIRECTION_TX, ESP_ERR_INVALID_ARG, TAG, "invalid channel direction");
ESP_RETURN_ON_FALSE(channel->fsm == RMT_FSM_ENABLE, ESP_ERR_INVALID_STATE, TAG, "channel not in enable state");
#if !SOC_RMT_SUPPORT_TX_LOOP_COUNT
ESP_RETURN_ON_FALSE(config->loop_count <= 0, ESP_ERR_NOT_SUPPORTED, TAG, "loop count is not supported");
#endif // !SOC_RMT_SUPPORT_TX_LOOP_COUNT
@ -488,22 +490,20 @@ esp_err_t rmt_transmit(rmt_channel_handle_t channel, rmt_encoder_t *encoder, con
// payload is retrieved by the encoder, we should make sure it's still accessible even when the cache is disabled
ESP_RETURN_ON_FALSE(esp_ptr_internal(payload), ESP_ERR_INVALID_ARG, TAG, "payload not in internal RAM");
#endif
rmt_group_t *group = channel->group;
rmt_hal_context_t *hal = &group->hal;
int channel_id = channel->channel_id;
TickType_t queue_wait_ticks = portMAX_DELAY;
if (config->flags.queue_nonblocking) {
queue_wait_ticks = 0;
}
rmt_tx_channel_t *tx_chan = __containerof(channel, rmt_tx_channel_t, base);
rmt_tx_trans_desc_t *t = NULL;
// acquire one transaction description from ready_queue or done_queue
if (tx_chan->num_trans_inflight < tx_chan->queue_size) {
ESP_RETURN_ON_FALSE(xQueueReceive(tx_chan->trans_queues[RMT_TX_QUEUE_READY], &t, portMAX_DELAY) == pdTRUE,
ESP_FAIL, TAG, "no transaction in the ready queue");
} else {
ESP_RETURN_ON_FALSE(xQueueReceive(tx_chan->trans_queues[RMT_TX_QUEUE_COMPLETE], &t, portMAX_DELAY) == pdTRUE,
ESP_FAIL, TAG, "recycle transaction from done queue failed");
tx_chan->num_trans_inflight--;
// acquire one transaction description from ready queue or complete queue
if (xQueueReceive(tx_chan->trans_queues[RMT_TX_QUEUE_READY], &t, 0) != pdTRUE) {
if (xQueueReceive(tx_chan->trans_queues[RMT_TX_QUEUE_COMPLETE], &t, queue_wait_ticks) == pdTRUE) {
tx_chan->num_trans_inflight--;
}
}
// sanity check
assert(t);
ESP_RETURN_ON_FALSE(t, ESP_ERR_INVALID_STATE, TAG, "no free transaction descriptor, please consider increasing trans_queue_depth");
// fill in the transaction descriptor
memset(t, 0, sizeof(rmt_tx_trans_desc_t));
t->encoder = encoder;
@ -514,7 +514,7 @@ esp_err_t rmt_transmit(rmt_channel_handle_t channel, rmt_encoder_t *encoder, con
t->flags.eot_level = config->flags.eot_level;
// send the transaction descriptor to queue
if (xQueueSend(tx_chan->trans_queues[RMT_TX_QUEUE_PROGRESS], &t, portMAX_DELAY) == pdTRUE) {
if (xQueueSend(tx_chan->trans_queues[RMT_TX_QUEUE_PROGRESS], &t, 0) == pdTRUE) {
tx_chan->num_trans_inflight++;
} else {
// put the trans descriptor back to ready_queue
@ -522,13 +522,18 @@ esp_err_t rmt_transmit(rmt_channel_handle_t channel, rmt_encoder_t *encoder, con
ESP_ERR_INVALID_STATE, TAG, "ready queue full");
}
// we don't know which "transmission complete" event will be triggered, but must be one of them: trans_done, loop_done
// when we run at here, the interrupt status bit for tx_done or loop_end should already up (ensured by `rmt_tx_enable()`)
// that's why we can go into ISR as soon as we enable the interrupt bit
// in the ISR, we will fetch the transactions from trans_queue and start it
portENTER_CRITICAL(&group->spinlock);
rmt_ll_enable_interrupt(hal->regs, RMT_LL_EVENT_TX_DONE(channel_id) | RMT_LL_EVENT_TX_LOOP_END(channel_id), true);
portEXIT_CRITICAL(&group->spinlock);
// check if we need to start one pending transaction
rmt_fsm_t expected_fsm = RMT_FSM_ENABLE;
if (atomic_compare_exchange_strong(&channel->fsm, &expected_fsm, RMT_FSM_RUN_WAIT)) {
// check if we need to start one transaction
if (xQueueReceive(tx_chan->trans_queues[RMT_TX_QUEUE_PROGRESS], &t, 0) == pdTRUE) {
atomic_store(&channel->fsm, RMT_FSM_RUN);
rmt_tx_do_transaction(tx_chan, t);
} else {
atomic_store(&channel->fsm, RMT_FSM_ENABLE);
}
}
return ESP_OK;
}
@ -625,6 +630,9 @@ static void IRAM_ATTR rmt_tx_do_transaction(rmt_tx_channel_t *tx_chan, rmt_tx_tr
rmt_hal_context_t *hal = &group->hal;
int channel_id = channel->channel_id;
// update current transaction
tx_chan->cur_trans = t;
#if SOC_RMT_SUPPORT_DMA
if (channel->dma_chan) {
gdma_reset(channel->dma_chan);
@ -638,7 +646,7 @@ static void IRAM_ATTR rmt_tx_do_transaction(rmt_tx_channel_t *tx_chan, rmt_tx_tr
#endif // SOC_RMT_SUPPORT_DMA
// set transaction specific parameters
portENTER_CRITICAL_ISR(&channel->spinlock);
portENTER_CRITICAL_SAFE(&channel->spinlock);
rmt_ll_tx_reset_pointer(hal->regs, channel_id); // reset pointer for new transaction
rmt_ll_tx_enable_loop(hal->regs, channel_id, t->loop_count != 0);
#if SOC_RMT_SUPPORT_TX_LOOP_AUTO_STOP
@ -654,10 +662,10 @@ static void IRAM_ATTR rmt_tx_do_transaction(rmt_tx_channel_t *tx_chan, rmt_tx_tr
t->remain_loop_count -= this_loop_count;
}
#endif // SOC_RMT_SUPPORT_TX_LOOP_COUNT
portEXIT_CRITICAL_ISR(&channel->spinlock);
portEXIT_CRITICAL_SAFE(&channel->spinlock);
// enable/disable specific interrupts
portENTER_CRITICAL_ISR(&group->spinlock);
portENTER_CRITICAL_SAFE(&group->spinlock);
#if SOC_RMT_SUPPORT_TX_LOOP_COUNT
rmt_ll_enable_interrupt(hal->regs, RMT_LL_EVENT_TX_LOOP_END(channel_id), t->loop_count > 0);
#endif // SOC_RMT_SUPPORT_TX_LOOP_COUNT
@ -671,7 +679,7 @@ static void IRAM_ATTR rmt_tx_do_transaction(rmt_tx_channel_t *tx_chan, rmt_tx_tr
}
// don't generate trans done event for loop transmission
rmt_ll_enable_interrupt(hal->regs, RMT_LL_EVENT_TX_DONE(channel_id), t->loop_count == 0);
portEXIT_CRITICAL_ISR(&group->spinlock);
portEXIT_CRITICAL_SAFE(&group->spinlock);
// at the beginning of a new transaction, encoding memory offset should start from zero.
// It will increase in the encode function e.g. `rmt_encode_copy()`
@ -691,39 +699,29 @@ static void IRAM_ATTR rmt_tx_do_transaction(rmt_tx_channel_t *tx_chan, rmt_tx_tr
}
#endif
// turn on the TX machine
portENTER_CRITICAL_ISR(&channel->spinlock);
portENTER_CRITICAL_SAFE(&channel->spinlock);
rmt_ll_tx_fix_idle_level(hal->regs, channel_id, t->flags.eot_level, true);
rmt_ll_tx_start(hal->regs, channel_id);
portEXIT_CRITICAL_ISR(&channel->spinlock);
portEXIT_CRITICAL_SAFE(&channel->spinlock);
}
static esp_err_t rmt_tx_enable(rmt_channel_handle_t channel)
{
// can enable the channel when it's in "init" state
rmt_fsm_t expected_fsm = RMT_FSM_INIT;
ESP_RETURN_ON_FALSE(atomic_compare_exchange_strong(&channel->fsm, &expected_fsm, RMT_FSM_ENABLE_WAIT),
ESP_ERR_INVALID_STATE, TAG, "channel not in init state");
rmt_tx_channel_t *tx_chan = __containerof(channel, rmt_tx_channel_t, base);
// acquire power manager lock
if (channel->pm_lock) {
esp_pm_lock_acquire(channel->pm_lock);
}
#if SOC_RMT_SUPPORT_DMA
rmt_group_t *group = channel->group;
rmt_hal_context_t *hal = &group->hal;
int channel_id = channel->channel_id;
// acquire power manager lock
if (channel->pm_lock) {
ESP_RETURN_ON_ERROR(esp_pm_lock_acquire(channel->pm_lock), TAG, "acquire pm_lock failed");
}
portENTER_CRITICAL(&channel->spinlock);
rmt_ll_tx_reset_pointer(hal->regs, channel_id);
rmt_ll_tx_enable_loop(hal->regs, channel_id, false);
#if SOC_RMT_SUPPORT_TX_LOOP_COUNT
rmt_ll_tx_reset_loop_count(hal->regs, channel_id);
rmt_ll_tx_enable_loop_count(hal->regs, channel_id, false);
#endif // SOC_RMT_SUPPORT_TX_LOOP_COUNT
// trigger a quick trans done event by sending a EOF symbol, no signal should appear on the GPIO
tx_chan->cur_trans = NULL;
channel->hw_mem_base[0].val = 0;
rmt_ll_tx_start(hal->regs, channel_id);
portEXIT_CRITICAL(&channel->spinlock);
// wait the RMT interrupt line goes active, we won't go into the ISR handler until we enable the `RMT_LL_EVENT_TX_DONE` interrupt
while (!(rmt_ll_tx_get_interrupt_status_raw(hal->regs, channel_id) & RMT_LL_EVENT_TX_DONE(channel_id))) {}
#if SOC_RMT_SUPPORT_DMA
if (channel->dma_chan) {
// enable the DMA access mode
portENTER_CRITICAL(&channel->spinlock);
@ -734,12 +732,22 @@ static esp_err_t rmt_tx_enable(rmt_channel_handle_t channel)
}
#endif // SOC_RMT_SUPPORT_DMA
channel->fsm = RMT_FSM_ENABLE;
atomic_store(&channel->fsm, RMT_FSM_ENABLE);
// check if we need to start one pending transaction
rmt_tx_trans_desc_t *t = NULL;
expected_fsm = RMT_FSM_ENABLE;
if (atomic_compare_exchange_strong(&channel->fsm, &expected_fsm, RMT_FSM_RUN_WAIT)) {
if (xQueueReceive(tx_chan->trans_queues[RMT_TX_QUEUE_PROGRESS], &t, 0) == pdTRUE) {
// sanity check
assert(t);
atomic_store(&channel->fsm, RMT_FSM_RUN);
rmt_tx_do_transaction(tx_chan, t);
} else {
atomic_store(&channel->fsm, RMT_FSM_ENABLE);
}
}
// enable channel interrupt, dispatch transactions in ISR (in case there're transaction descriptors in the queue, then we should start them)
portENTER_CRITICAL(&group->spinlock);
rmt_ll_enable_interrupt(hal->regs, RMT_LL_EVENT_TX_DONE(channel_id), true);
portEXIT_CRITICAL(&group->spinlock);
return ESP_OK;
}
@ -750,24 +758,37 @@ static esp_err_t rmt_tx_disable(rmt_channel_handle_t channel)
rmt_hal_context_t *hal = &group->hal;
int channel_id = channel->channel_id;
portENTER_CRITICAL(&channel->spinlock);
rmt_ll_tx_enable_loop(hal->regs, channel->channel_id, false);
// can disable the channel when it's in `enable` or `run` state
bool valid_state = false;
rmt_fsm_t expected_fsm = RMT_FSM_ENABLE;
if (atomic_compare_exchange_strong(&channel->fsm, &expected_fsm, RMT_FSM_INIT_WAIT)) {
valid_state = true;
}
expected_fsm = RMT_FSM_RUN;
if (atomic_compare_exchange_strong(&channel->fsm, &expected_fsm, RMT_FSM_INIT_WAIT)) {
valid_state = true;
// disable the hardware
portENTER_CRITICAL(&channel->spinlock);
rmt_ll_tx_enable_loop(hal->regs, channel->channel_id, false);
#if SOC_RMT_SUPPORT_TX_ASYNC_STOP
rmt_ll_tx_stop(hal->regs, channel->channel_id);
rmt_ll_tx_stop(hal->regs, channel->channel_id);
#endif
portEXIT_CRITICAL(&channel->spinlock);
portEXIT_CRITICAL(&channel->spinlock);
portENTER_CRITICAL(&group->spinlock);
rmt_ll_enable_interrupt(hal->regs, RMT_LL_EVENT_TX_MASK(channel_id), false);
portENTER_CRITICAL(&group->spinlock);
rmt_ll_enable_interrupt(hal->regs, RMT_LL_EVENT_TX_MASK(channel_id), false);
#if !SOC_RMT_SUPPORT_TX_ASYNC_STOP
// we do a trick to stop the undergoing transmission
// stop interrupt, insert EOF marker to the RMT memory, polling the trans_done event
channel->hw_mem_base[0].val = 0;
while (!(rmt_ll_tx_get_interrupt_status_raw(hal->regs, channel_id) & RMT_LL_EVENT_TX_DONE(channel_id))) {}
// we do a trick to stop the undergoing transmission
// stop interrupt, insert EOF marker to the RMT memory, polling the trans_done event
channel->hw_mem_base[0].val = 0;
while (!(rmt_ll_tx_get_interrupt_status_raw(hal->regs, channel_id) & RMT_LL_EVENT_TX_DONE(channel_id))) {}
#endif
rmt_ll_clear_interrupt_status(hal->regs, RMT_LL_EVENT_TX_MASK(channel_id));
portEXIT_CRITICAL(&group->spinlock);
rmt_ll_clear_interrupt_status(hal->regs, RMT_LL_EVENT_TX_MASK(channel_id));
portEXIT_CRITICAL(&group->spinlock);
}
ESP_RETURN_ON_FALSE(valid_state, ESP_ERR_INVALID_STATE, TAG, "channel can't be disabled in state %d", expected_fsm);
// disable the DMA
#if SOC_RMT_SUPPORT_DMA
if (channel->dma_chan) {
gdma_stop(channel->dma_chan);
@ -779,9 +800,10 @@ static esp_err_t rmt_tx_disable(rmt_channel_handle_t channel)
portEXIT_CRITICAL(&channel->spinlock);
}
#endif
// recycle the interrupted transaction
if (tx_chan->cur_trans) {
xQueueSend(tx_chan->trans_queues[RMT_TX_QUEUE_COMPLETE], &tx_chan->cur_trans, portMAX_DELAY);
xQueueSend(tx_chan->trans_queues[RMT_TX_QUEUE_COMPLETE], &tx_chan->cur_trans, 0);
// reset corresponding encoder
rmt_encoder_reset(tx_chan->cur_trans->encoder);
}
@ -792,7 +814,9 @@ static esp_err_t rmt_tx_disable(rmt_channel_handle_t channel)
ESP_RETURN_ON_ERROR(esp_pm_lock_release(channel->pm_lock), TAG, "release pm_lock failed");
}
channel->fsm = RMT_FSM_INIT;
// finally we switch to the INIT state
atomic_store(&channel->fsm, RMT_FSM_INIT);
return ESP_OK;
}
@ -836,12 +860,7 @@ static esp_err_t rmt_tx_modulate_carrier(rmt_channel_handle_t channel, const rmt
static bool IRAM_ATTR rmt_isr_handle_tx_threshold(rmt_tx_channel_t *tx_chan)
{
rmt_channel_t *channel = &tx_chan->base;
rmt_group_t *group = channel->group;
rmt_hal_context_t *hal = &group->hal;
uint32_t channel_id = channel->channel_id;
// continue pingpong transmission
// continue ping-pong transmission
rmt_tx_trans_desc_t *t = tx_chan->cur_trans;
size_t encoded_symbols = t->transmitted_symbol_num;
// encoding finished, only need to send the EOF symbol
@ -854,73 +873,54 @@ static bool IRAM_ATTR rmt_isr_handle_tx_threshold(rmt_tx_channel_t *tx_chan)
t->transmitted_symbol_num = encoded_symbols;
tx_chan->mem_end = tx_chan->ping_pong_symbols * 3 - tx_chan->mem_end; // mem_end equals to either ping_pong_symbols or ping_pong_symbols*2
rmt_ll_clear_interrupt_status(hal->regs, RMT_LL_EVENT_TX_THRES(channel_id));
return false;
}
static bool IRAM_ATTR rmt_isr_handle_tx_done(rmt_tx_channel_t *tx_chan)
{
rmt_channel_t *channel = &tx_chan->base;
rmt_group_t *group = channel->group;
rmt_hal_context_t *hal = &group->hal;
uint32_t channel_id = channel->channel_id;
BaseType_t awoken = pdFALSE;
rmt_tx_trans_desc_t *trans_desc = NULL;
bool need_yield = false;
portENTER_CRITICAL_ISR(&group->spinlock);
// disable interrupt temporarily, re-enable it when there is transaction unhandled in the queue
rmt_ll_enable_interrupt(hal->regs, RMT_LL_EVENT_TX_DONE(channel_id), false);
portEXIT_CRITICAL_ISR(&group->spinlock);
trans_desc = tx_chan->cur_trans;
// process finished transaction
if (trans_desc) {
// don't care of the tx done event for any undergoing loop transaction
// mostly it's triggered when a loop transmission is undergoing and user calls `rmt_transmit()` where tx done interrupt is generated by accident
if (trans_desc->loop_count != 0) {
rmt_ll_clear_interrupt_status(hal->regs, RMT_LL_EVENT_TX_DONE(channel_id));
return need_yield;
}
if (tx_chan->on_trans_done) {
rmt_tx_done_event_data_t edata = {
.num_symbols = trans_desc->transmitted_symbol_num,
};
if (tx_chan->on_trans_done(channel, &edata, tx_chan->user_data)) {
need_yield = true;
}
}
// move transaction to done_queue
rmt_fsm_t expected_fsm = RMT_FSM_RUN;
if (atomic_compare_exchange_strong(&channel->fsm, &expected_fsm, RMT_FSM_ENABLE_WAIT)) {
trans_desc = tx_chan->cur_trans;
// move current finished transaction to the complete queue
xQueueSendFromISR(tx_chan->trans_queues[RMT_TX_QUEUE_COMPLETE], &trans_desc, &awoken);
if (awoken == pdTRUE) {
need_yield = true;
}
}
// fetch new transaction description from trans_queue
if (xQueueReceiveFromISR(tx_chan->trans_queues[RMT_TX_QUEUE_PROGRESS], &trans_desc, &awoken) == pdTRUE) {
// sanity check
assert(trans_desc);
// update current transaction
tx_chan->cur_trans = trans_desc;
portENTER_CRITICAL_ISR(&group->spinlock);
// only clear the trans done status when we're sure there still remains transaction to handle
rmt_ll_clear_interrupt_status(hal->regs, RMT_LL_EVENT_TX_DONE(channel_id));
// enable interrupt again, because the new transaction can trigger another trans done event
rmt_ll_enable_interrupt(hal->regs, RMT_LL_EVENT_TX_DONE(channel_id), trans_desc->loop_count == 0);
rmt_ll_enable_interrupt(hal->regs, RMT_LL_EVENT_TX_LOOP_END(channel_id), trans_desc->loop_count > 0);
portEXIT_CRITICAL_ISR(&group->spinlock);
// begin a new transaction
rmt_tx_do_transaction(tx_chan, trans_desc);
} else { // No transactions left in the queue
// don't clear interrupt status, so when next time user push new transaction to the queue and call esp_intr_enable,
// we can go to this ISR handler again
tx_chan->cur_trans = NULL;
atomic_store(&channel->fsm, RMT_FSM_ENABLE);
}
if (awoken == pdTRUE) {
need_yield = true;
// invoke callback
rmt_tx_done_callback_t done_cb = tx_chan->on_trans_done;
if (done_cb) {
rmt_tx_done_event_data_t edata = {
.num_symbols = trans_desc->transmitted_symbol_num,
};
if (done_cb(channel, &edata, tx_chan->user_data)) {
need_yield = true;
}
}
// let's try start the next pending transaction
expected_fsm = RMT_FSM_ENABLE;
if (atomic_compare_exchange_strong(&channel->fsm, &expected_fsm, RMT_FSM_RUN_WAIT)) {
if (xQueueReceiveFromISR(tx_chan->trans_queues[RMT_TX_QUEUE_PROGRESS], &trans_desc, &awoken) == pdTRUE) {
// sanity check
assert(trans_desc);
atomic_store(&channel->fsm, RMT_FSM_RUN);
// begin a new transaction
rmt_tx_do_transaction(tx_chan, trans_desc);
if (awoken == pdTRUE) {
need_yield = true;
}
} else {
atomic_store(&channel->fsm, RMT_FSM_ENABLE);
}
}
return need_yield;
@ -941,16 +941,16 @@ static bool IRAM_ATTR rmt_isr_handle_tx_loop_end(rmt_tx_channel_t *tx_chan)
if (trans_desc) {
#if !SOC_RMT_SUPPORT_TX_LOOP_AUTO_STOP
portENTER_CRITICAL_ISR(&channel->spinlock);
// This is a workaround for chips that don't support auto stop
// This is a workaround for chips that don't support loop auto stop
// Although we stop the transaction immediately in ISR handler, it's still possible that some rmt symbols have sneaked out
rmt_ll_tx_stop(hal->regs, channel_id);
portEXIT_CRITICAL_ISR(&channel->spinlock);
#endif // SOC_RMT_SUPPORT_TX_LOOP_AUTO_STOP
// continue unfinished loop transaction
if (trans_desc->remain_loop_count) {
uint32_t this_loop_count = MIN(trans_desc->remain_loop_count, RMT_LL_MAX_LOOP_COUNT_PER_BATCH);
trans_desc->remain_loop_count -= this_loop_count;
rmt_ll_clear_interrupt_status(hal->regs, RMT_LL_EVENT_TX_LOOP_END(channel_id));
portENTER_CRITICAL_ISR(&channel->spinlock);
rmt_ll_tx_set_loop_count(hal->regs, channel_id, this_loop_count);
rmt_ll_tx_reset_pointer(hal->regs, channel_id);
@ -958,51 +958,49 @@ static bool IRAM_ATTR rmt_isr_handle_tx_loop_end(rmt_tx_channel_t *tx_chan)
rmt_ll_tx_start(hal->regs, channel_id);
portEXIT_CRITICAL_ISR(&channel->spinlock);
return need_yield;
} else {
if (tx_chan->on_trans_done) {
rmt_tx_done_event_data_t edata = {
.num_symbols = trans_desc->transmitted_symbol_num,
};
if (tx_chan->on_trans_done(channel, &edata, tx_chan->user_data)) {
need_yield = true;
}
}
// move transaction to done_queue
}
// loop transaction finished
rmt_fsm_t expected_fsm = RMT_FSM_RUN;
if (atomic_compare_exchange_strong(&channel->fsm, &expected_fsm, RMT_FSM_ENABLE_WAIT)) {
// move current finished transaction to the complete queue
xQueueSendFromISR(tx_chan->trans_queues[RMT_TX_QUEUE_COMPLETE], &trans_desc, &awoken);
if (awoken == pdTRUE) {
need_yield = true;
}
tx_chan->cur_trans = NULL;
atomic_store(&channel->fsm, RMT_FSM_ENABLE);
}
// invoke callback
rmt_tx_done_callback_t done_cb = tx_chan->on_trans_done;
if (done_cb) {
rmt_tx_done_event_data_t edata = {
.num_symbols = trans_desc->transmitted_symbol_num,
};
if (done_cb(channel, &edata, tx_chan->user_data)) {
need_yield = true;
}
}
// let's try start the next pending transaction
expected_fsm = RMT_FSM_ENABLE;
if (atomic_compare_exchange_strong(&channel->fsm, &expected_fsm, RMT_FSM_RUN_WAIT)) {
if (xQueueReceiveFromISR(tx_chan->trans_queues[RMT_TX_QUEUE_PROGRESS], &trans_desc, &awoken) == pdTRUE) {
// sanity check
assert(trans_desc);
atomic_store(&channel->fsm, RMT_FSM_RUN);
// begin a new transaction
rmt_tx_do_transaction(tx_chan, trans_desc);
if (awoken == pdTRUE) {
need_yield = true;
}
} else {
atomic_store(&channel->fsm, RMT_FSM_ENABLE);
}
}
}
// trans_done and loop_done should be considered as one "transmission complete"
// but sometimes the trans done event might also be triggered together with loop done event, by accident, so clear it first
rmt_ll_clear_interrupt_status(hal->regs, RMT_LL_EVENT_TX_DONE(channel_id));
portENTER_CRITICAL_ISR(&group->spinlock);
// disable interrupt temporarily, re-enable it when there is transaction unhandled in the queue
rmt_ll_enable_interrupt(hal->regs, RMT_LL_EVENT_TX_LOOP_END(channel_id), false);
portEXIT_CRITICAL_ISR(&group->spinlock);
// fetch new transaction description from trans_queue
if (xQueueReceiveFromISR(tx_chan->trans_queues[RMT_TX_QUEUE_PROGRESS], &trans_desc, &awoken) == pdTRUE) {
// sanity check
assert(trans_desc);
tx_chan->cur_trans = trans_desc;
// clear the loop end status when we're sure there still remains transaction to handle
rmt_ll_clear_interrupt_status(hal->regs, RMT_LL_EVENT_TX_LOOP_END(channel_id));
portENTER_CRITICAL_ISR(&group->spinlock);
// enable interrupt again, because the new transaction can trigger new trans done event
rmt_ll_enable_interrupt(hal->regs, RMT_LL_EVENT_TX_DONE(channel_id), trans_desc->loop_count == 0);
rmt_ll_enable_interrupt(hal->regs, RMT_LL_EVENT_TX_LOOP_END(channel_id), trans_desc->loop_count > 0);
portEXIT_CRITICAL_ISR(&group->spinlock);
// begin a new transaction
rmt_tx_do_transaction(tx_chan, trans_desc);
} else { // No transactions left in the queue
// don't clear interrupt status, so when next time user push new transaction to the queue and call esp_intr_enable,
// we can go into ISR handler again
tx_chan->cur_trans = NULL;
}
if (awoken == pdTRUE) {
need_yield = true;
}
@ -1020,6 +1018,7 @@ static void IRAM_ATTR rmt_tx_default_isr(void *args)
bool need_yield = false;
uint32_t status = rmt_ll_tx_get_interrupt_status(hal->regs, channel_id);
rmt_ll_clear_interrupt_status(hal->regs, status);
// Tx threshold interrupt
if (status & RMT_LL_EVENT_TX_THRES(channel_id)) {

View File

@ -367,7 +367,7 @@ TEST_CASE("rmt infinite loop transaction", "[rmt]")
.resolution_hz = 1000000, // 1MHz, 1 tick = 1us
.mem_block_symbols = SOC_RMT_MEM_WORDS_PER_CHANNEL,
.gpio_num = TEST_RMT_GPIO_NUM_B,
.trans_queue_depth = 3,
.trans_queue_depth = 5,
.intr_priority = 1
};
printf("install tx channel\r\n");
@ -384,6 +384,7 @@ TEST_CASE("rmt infinite loop transaction", "[rmt]")
rmt_transmit_config_t transmit_config = {
.loop_count = -1, // infinite loop transmission
.flags.queue_nonblocking = true, // return immediately if the queue is full
};
printf("infinite loop transmission: keep spinning stepper motor\r\n");

View File

@ -56,7 +56,7 @@ The description of the RMT functionality is divided into the following sections:
- :ref:`rmt-resource-allocation` - covers how to allocate and properly configure RMT channels. It also covers how to recycle channels and other resources when they are no longer used.
- :ref:`rmt-carrier-modulation-and demodulation` - describes how to modulate and demodulate the carrier signals for TX and RX channels respectively.
- :ref:`rmt-register-event-callbacks` - covers how to register user-provided event callbacks in order to receive RMT channel events.
- :ref:`rmt-register-event-callbacks` - covers how to register user-provided event callbacks to receive RMT channel events.
- :ref:`rmt-enable-and-disable-channel` - shows how to enable and disable the RMT channel.
- :ref:`rmt-initiate-tx-transaction` - describes the steps to initiate a transaction for a TX channel.
- :ref:`rmt-initiate-rx-transaction` - describes the steps to initiate a transaction for an RX channel.
@ -84,7 +84,7 @@ To install an RMT TX channel, there is a configuration structure that needs to b
- :cpp:member:`rmt_tx_channel_config_t::resolution_hz` sets the resolution of the internal tick counter. The timing parameter of the RMT signal is calculated based on this **tick**.
- :cpp:member:`rmt_tx_channel_config_t::mem_block_symbols` has a slightly different meaning based on if the DMA backend is enabled or not.
- If the DMA is enabled via :cpp:member:`rmt_tx_channel_config_t::with_dma`, then this field controls the size of the internal DMA buffer. To achieve a better throughput and smaller CPU overhead, we recommend you set a large value, e.g., ``1024``.
- If the DMA is enabled via :cpp:member:`rmt_tx_channel_config_t::with_dma`, then this field controls the size of the internal DMA buffer. To achieve a better throughput and smaller CPU overhead, you can set a larger value, e.g., ``1024``.
- If DMA is not used, this field controls the size of the dedicated memory block owned by the channel, which should be at least {IDF_TARGET_SOC_RMT_MEM_WORDS_PER_CHANNEL}.
- :cpp:member:`rmt_tx_channel_config_t::trans_queue_depth` sets the depth of the internal transaction queue, the deeper the queue, the more transactions can be prepared in the backlog.
@ -205,7 +205,7 @@ The RX channel-supported event callbacks are listed in the :cpp:type:`rmt_rx_eve
Users can save their own context in :cpp:func:`rmt_tx_register_event_callbacks` and :cpp:func:`rmt_rx_register_event_callbacks` as well, via the parameter ``user_data``. The user data is directly passed to each callback function.
In the callback function, users can fetch the event-specific data that is filled by the driver in the ``edata``. Note that the ``edata`` pointer is only valid for the duration of the callback.
In the callback function, users can fetch the event-specific data that is filled by the driver in the ``edata``. Note that the ``edata`` pointer is only valid during the callback.
The TX-done event data is defined in :cpp:type:`rmt_tx_done_event_data_t`:
@ -237,7 +237,7 @@ Initiate TX Transaction
RMT is a special communication peripheral, as it is unable to transmit raw byte streams like SPI and I2C. RMT can only send data in its own format :cpp:type:`rmt_symbol_word_t`. However, the hardware does not help to convert the user data into RMT symbols, this can only be done in software by the so-called **RMT Encoder**. The encoder is responsible for encoding user data into RMT symbols and then writing to the RMT memory block or the DMA buffer. For how to create an RMT encoder, please refer to :ref:`rmt-rmt-encoder`.
Once we got an encoder, we can initiate a TX transaction by calling :cpp:func:`rmt_transmit`. This function takes several positional parameters like channel handle, encoder handle, and payload buffer. Besides, we also need to provide a transmission-specific configuration in :cpp:type:`rmt_transmit_config_t`:
Once you created an encoder, you can initiate a TX transaction by calling :cpp:func:`rmt_transmit`. This function takes several positional parameters like channel handle, encoder handle, and payload buffer. Besides, you also need to provide a transmission-specific configuration in :cpp:type:`rmt_transmit_config_t`:
- :cpp:member:`rmt_transmit_config_t::loop_count` sets the number of transmission loops. After the transmitter has finished one round of transmission, it can restart the same transmission again if this value is not set to zero. As the loop is controlled by hardware, the RMT channel can be used to generate many periodic sequences with minimal CPU intervention.
@ -249,6 +249,7 @@ Once we got an encoder, we can initiate a TX transaction by calling :cpp:func:`r
The **loop transmit** feature is not supported on all ESP chips, please refer to [`TRM <{IDF_TARGET_TRM_EN_URL}#rmt>`__] before you configure this option, or you might encounter :c:macro:`ESP_ERR_NOT_SUPPORTED` error.
- :cpp:member:`rmt_transmit_config_t::eot_level` sets the output level when the transmitter finishes working or stops working by calling :cpp:func:`rmt_disable`.
- :cpp:member:`rmt_transmit_config_t::queue_nonblocking` sets whether to wait for a free slot in the transaction queue when it is full. If this value is set to ``true``, then the function will return with an error code :c:macro:`ESP_ERR_INVALID_STATE` when the queue is full. Otherwise, the function will block until a free slot is available in the queue.
.. note::
@ -264,7 +265,7 @@ Internally, :cpp:func:`rmt_transmit` constructs a transaction descriptor and sen
Multiple Channels Simultaneous Transmission
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
In some real-time control applications (e.g., to make two robotic arms move simultaneously), we do not want any time drift in between when startup multiple TX channels. The RMT driver can help to manage this by creating a so-called **Sync Manager**. The sync manager is represented by :cpp:type:`rmt_sync_manager_handle_t` in the driver. The procedure of RMT sync transmission is shown as follows:
In some real-time control applications (e.g., to make two robotic arms move simultaneously), you do not want any time drift between different channels. The RMT driver can help to manage this by creating a so-called **Sync Manager**. The sync manager is represented by :cpp:type:`rmt_sync_manager_handle_t` in the driver. The procedure of RMT sync transmission is shown as follows:
.. figure:: /../_static/rmt_tx_sync.png
:align: center
@ -380,20 +381,20 @@ RMT Encoder
An RMT encoder is part of the RMT TX transaction, whose responsibility is to generate and write the correct RMT symbols into hardware memory or DMA buffer at a specific time. There are some special restrictions for an encoding function:
- During a single transaction, the encoding function may be called multiple times. This is necessary because the target RMT memory block cannot hold all the artifacts at once. To overcome this limitation, we utilize a **ping-pong** approach, where the encoding session is divided into multiple parts. This means that the encoder needs to **keep track of its state** in order to continue encoding from where it left off in the previous part.
- During a single transaction, the encoding function may be called multiple times. This is necessary because the target RMT memory block cannot hold all the artifacts at once. To overcome this limitation, the driver utilizes a **ping-pong** approach, where the encoding session is divided into multiple parts. This means that the encoder needs to **keep track of its state** to continue encoding from where it left off in the previous part.
- The encoding function is running in the ISR context. To speed up the encoding session, it is highly recommended to put the encoding function into IRAM. This can also avoid the cache miss during encoding.
To help get started with the RMT driver faster, some commonly-used encoders are provided out-of-the-box. They can either work alone or be chained together into a new encoder. See also `Composite Pattern <https://en.wikipedia.org/wiki/Composite_pattern>`__ for the principle behind it. The driver has defined the encoder interface in :cpp:type:`rmt_encoder_t`, it contains the following functions:
To help get started with the RMT driver faster, some commonly used encoders are provided out-of-the-box. They can either work alone or be chained together into a new encoder. See also `Composite Pattern <https://en.wikipedia.org/wiki/Composite_pattern>`__ for the principle behind it. The driver has defined the encoder interface in :cpp:type:`rmt_encoder_t`, it contains the following functions:
- :cpp:member:`rmt_encoder_t::encode` is the fundamental function of an encoder. This is where the encoding session happens.
- The function might be called multiple times within a single transaction. The encode function should return the state of the current encoding session.
- The supported states are listed in the :cpp:type:`rmt_encode_state_t`. If the result contains :cpp:enumerator:`RMT_ENCODING_COMPLETE`, it means the current encoder has finished work.
- If the result contains :cpp:enumerator:`RMT_ENCODING_MEM_FULL`, we need to yield from the current session, as there is no space to save more encoding artifacts.
- If the result contains :cpp:enumerator:`RMT_ENCODING_MEM_FULL`, the program needs to yield from the current session, as there is no space to save more encoding artifacts.
- :cpp:member:`rmt_encoder_t::reset` should reset the encoder state back to the initial state (the RMT encoder is stateful).
- If the RMT transmitter is manually stopped without resetting its corresponding encoder, subsequent encoding session can be erroneous.
- If the RMT transmitter is manually stopped without resetting its corresponding encoder, subsequent encoding session can be erroneous.
- This function is also called implicitly in :cpp:func:`rmt_disable`.
- :cpp:member:`rmt_encoder_t::del` should free the resources allocated by the encoder.
@ -424,7 +425,7 @@ Besides the primitive encoders provided by the driver, the user can implement hi
Customize RMT Encoder for NEC Protocol
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
In this section, we demonstrates how to write an NEC encoder. The NEC IR protocol uses pulse distance encoding of the message bits. Each pulse burst is ``562.5 µs`` in length, logical bits are transmitted as follows. It is worth mentioning that the least significant bit of each byte is sent first.
This section demonstrates how to write an NEC encoder. The NEC IR protocol uses pulse distance encoding of the message bits. Each pulse burst is ``562.5 µs`` in length, logical bits are transmitted as follows. It is worth mentioning that the least significant bit of each byte is sent first.
- Logical ``0``: a ``562.5 µs`` pulse burst followed by a ``562.5 µs`` space, with a total transmit time of ``1.125 ms``
- Logical ``1``: a ``562.5 µs`` pulse burst followed by a ``1.6875 ms`` space, with a total transmit time of ``2.25 ms``
@ -445,7 +446,7 @@ When a key is pressed on the remote controller, the transmitted message includes
- 8-bit logical inverse of the command
- a final ``562.5 µs`` pulse burst to signify the end of message transmission
Then we can construct the NEC :cpp:member:`rmt_encoder_t::encode` function in the same order, for example:
Then you can construct the NEC :cpp:member:`rmt_encoder_t::encode` function in the same order, for example:
.. code:: c

View File

@ -249,6 +249,7 @@ RMT 是一种特殊的通信外设,无法像 SPI 和 I2C 那样发送原始字
注意,不是所有 ESP 芯片都支持 **循环发送** 功能,在配置此选项前,请参阅 [`TRM <{IDF_TARGET_TRM_EN_URL}#rmt>`__]。若所选芯片不支持配置此选项,可能会报告 :c:macro:`ESP_ERR_NOT_SUPPORTED` 错误。
- :cpp:member:`rmt_transmit_config_t::eot_level` 设置发射器完成工作时的输出电平,该设置同时适用于调用 :cpp:func:`rmt_disable` 停止发射器工作时的输出电平。
- :cpp:member:`rmt_transmit_config_t::queue_nonblocking` 设置当传输队列满的时候该函数是否需要等待。如果该值设置为 ``true`` 那么当遇到队列满的时候,该函数会立即返回错误代码 :c:macro:`ESP_ERR_INVALID_STATE`。否则,函数会阻塞当前线程,直到传输队列有空档。
.. note::