diff --git a/components/driver/rmt/rmt_common.c b/components/driver/rmt/rmt_common.c index 09911b729c..e3dc6ed448 100644 --- a/components/driver/rmt/rmt_common.c +++ b/components/driver/rmt/rmt_common.c @@ -74,6 +74,7 @@ rmt_group_t *rmt_acquire_group_handle(int group_id) void rmt_release_group_handle(rmt_group_t *group) { int group_id = group->group_id; + rmt_clock_source_t clk_src = group->clk_src; bool do_deinitialize = false; _lock_acquire(&s_platform.mutex); @@ -88,6 +89,16 @@ void rmt_release_group_handle(rmt_group_t *group) } _lock_release(&s_platform.mutex); + switch (clk_src) { +#if SOC_RMT_SUPPORT_RC_FAST + case RMT_CLK_SRC_RC_FAST: + periph_rtc_dig_clk8m_disable(); + break; +#endif // SOC_RMT_SUPPORT_RC_FAST + default: + break; + } + if (do_deinitialize) { ESP_LOGD(TAG, "del group(%d)", group_id); } diff --git a/components/hal/esp32/include/hal/rmt_ll.h b/components/hal/esp32/include/hal/rmt_ll.h index 9936a5cf78..e16763ccd5 100644 --- a/components/hal/esp32/include/hal/rmt_ll.h +++ b/components/hal/esp32/include/hal/rmt_ll.h @@ -99,6 +99,20 @@ static inline void rmt_ll_set_group_clock_src(rmt_dev_t *dev, uint32_t channel, } } +/** + * @brief Enable RMT peripheral source clock + * + * @note RMT doesn't support enable/disable clock source, this function is only for compatibility + * + * @param dev Peripheral instance address + * @param en True to enable, False to disable + */ +static inline void rmt_ll_enable_group_clock(rmt_dev_t *dev, bool en) +{ + (void)dev; + (void)en; +} + ////////////////////////////////////////TX Channel Specific///////////////////////////////////////////////////////////// /** diff --git a/components/hal/esp32c3/include/hal/rmt_ll.h b/components/hal/esp32c3/include/hal/rmt_ll.h index 2658a453bf..7b8106dfe0 100644 --- a/components/hal/esp32c3/include/hal/rmt_ll.h +++ b/components/hal/esp32c3/include/hal/rmt_ll.h @@ -90,7 +90,6 @@ static inline void rmt_ll_set_group_clock_src(rmt_dev_t *dev, uint32_t channel, // Formula: rmt_sclk = module_clock_src / (1 + div_num + div_a / div_b) (void)channel; // the source clock is set for all channels HAL_ASSERT(divider_integral >= 1); - dev->sys_conf.sclk_active = 0; HAL_FORCE_MODIFY_U32_REG_FIELD(dev->sys_conf, sclk_div_num, divider_integral - 1); dev->sys_conf.sclk_div_a = divider_numerator; dev->sys_conf.sclk_div_b = divider_denominator; @@ -108,7 +107,17 @@ static inline void rmt_ll_set_group_clock_src(rmt_dev_t *dev, uint32_t channel, HAL_ASSERT(false && "unsupported RMT clock source"); break; } - dev->sys_conf.sclk_active = 1; +} + +/** + * @brief Enable RMT peripheral source clock + * + * @param dev Peripheral instance address + * @param en True to enable, False to disable + */ +static inline void rmt_ll_enable_group_clock(rmt_dev_t *dev, bool en) +{ + dev->sys_conf.sclk_active = en; } ////////////////////////////////////////TX Channel Specific///////////////////////////////////////////////////////////// diff --git a/components/hal/esp32c6/include/hal/rmt_ll.h b/components/hal/esp32c6/include/hal/rmt_ll.h new file mode 100644 index 0000000000..35beca2c9c --- /dev/null +++ b/components/hal/esp32c6/include/hal/rmt_ll.h @@ -0,0 +1,849 @@ +/* + * SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD + * + * SPDX-License-Identifier: Apache-2.0 + */ + +/** + * @note TX and RX channels are index from 0 in the LL driver, i.e. tx_channel = [0,1], rx_channel = [0,1] + */ + +#pragma once + +#include +#include +#include +#include "hal/misc.h" +#include "hal/assert.h" +#include "hal/rmt_types.h" +#include "soc/rmt_struct.h" +#include "soc/pcr_struct.h" + +#ifdef __cplusplus +extern "C" { +#endif + +#define RMT_LL_EVENT_TX_DONE(channel) (1 << (channel)) +#define RMT_LL_EVENT_TX_THRES(channel) (1 << ((channel) + 8)) +#define RMT_LL_EVENT_TX_LOOP_END(channel) (1 << ((channel) + 12)) +#define RMT_LL_EVENT_TX_ERROR(channel) (1 << ((channel) + 4)) +#define RMT_LL_EVENT_RX_DONE(channel) (1 << ((channel) + 2)) +#define RMT_LL_EVENT_RX_THRES(channel) (1 << ((channel) + 10)) +#define RMT_LL_EVENT_RX_ERROR(channel) (1 << ((channel) + 6)) +#define RMT_LL_EVENT_TX_MASK(channel) (RMT_LL_EVENT_TX_DONE(channel) | RMT_LL_EVENT_TX_THRES(channel) | RMT_LL_EVENT_TX_LOOP_END(channel)) +#define RMT_LL_EVENT_RX_MASK(channel) (RMT_LL_EVENT_RX_DONE(channel) | RMT_LL_EVENT_RX_THRES(channel)) + +#define RMT_LL_MAX_LOOP_COUNT_PER_BATCH 1023 + +typedef enum { + RMT_LL_MEM_OWNER_SW = 0, + RMT_LL_MEM_OWNER_HW = 1, +} rmt_ll_mem_owner_t; + +/** + * @brief Enable clock gate for register and memory + * + * @param dev Peripheral instance address + * @param enable True to enable, False to disable + */ +static inline void rmt_ll_enable_periph_clock(rmt_dev_t *dev, bool enable) +{ + dev->sys_conf.clk_en = enable; // register clock gating + dev->sys_conf.mem_clk_force_on = enable; // memory clock gating +} + +/** + * @brief Power down memory + * + * @param dev Peripheral instance address + * @param enable True to power down, False to power up + */ +static inline void rmt_ll_power_down_mem(rmt_dev_t *dev, bool enable) +{ + dev->sys_conf.mem_force_pu = !enable; + dev->sys_conf.mem_force_pd = enable; +} + +/** + * @brief Enable APB accessing RMT memory in nonfifo mode + * + * @param dev Peripheral instance address + * @param enable True to enable, False to disable + */ +static inline void rmt_ll_enable_mem_access_nonfifo(rmt_dev_t *dev, bool enable) +{ + dev->sys_conf.apb_fifo_mask = enable; +} + +/** + * @brief Set clock source and divider for RMT channel group + * + * @param dev Peripheral instance address + * @param channel not used as clock source is set for all channels + * @param src Clock source + * @param divider_integral Integral part of the divider + * @param divider_denominator Denominator part of the divider + * @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) +{ + // Formula: rmt_sclk = module_clock_src / (1 + div_num + div_a / div_b) + (void)channel; // the source clock is set for all channels + HAL_ASSERT(divider_integral >= 1); + HAL_FORCE_MODIFY_U32_REG_FIELD(PCR.rmt_sclk_conf, rmt_sclk_div_num, divider_integral - 1); + PCR.rmt_sclk_conf.rmt_sclk_div_a = divider_numerator; + PCR.rmt_sclk_conf.rmt_sclk_div_b = divider_denominator; + switch (src) { + case RMT_CLK_SRC_APB: + PCR.rmt_sclk_conf.rmt_sclk_sel = 1; + break; + case RMT_CLK_SRC_XTAL: + PCR.rmt_sclk_conf.rmt_sclk_sel = 3; + break; + default: + HAL_ASSERT(false); + break; + } +} + +/** + * @brief Enable RMT peripheral source clock + * + * @param dev Peripheral instance address + * @param en True to enable, False to disable + */ +static inline void rmt_ll_enable_group_clock(rmt_dev_t *dev, bool en) +{ + (void)dev; + PCR.rmt_sclk_conf.rmt_sclk_en = en; +} + +////////////////////////////////////////TX Channel Specific///////////////////////////////////////////////////////////// + +/** + * @brief Reset clock divider for TX channels by mask + * + * @param dev Peripheral instance address + * @param channel_mask Mask of TX channels + */ +static inline void rmt_ll_tx_reset_channels_clock_div(rmt_dev_t *dev, uint32_t channel_mask) +{ + // write 1 to reset + dev->ref_cnt_rst.val |= channel_mask & 0x03; +} + +/** + * @brief Set TX channel clock divider + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @param div Division value + */ +static inline void rmt_ll_tx_set_channel_clock_div(rmt_dev_t *dev, uint32_t channel, uint32_t div) +{ + HAL_ASSERT(div >= 1 && div <= 256 && "divider out of range"); + // limit the maximum divider to 256 + if (div >= 256) { + div = 0; // 0 means 256 division + } + HAL_FORCE_MODIFY_U32_REG_FIELD(dev->chnconf0[channel], div_cnt_chn, div); +} + +/** + * @brief Reset RMT reading pointer for TX channel + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + */ +__attribute__((always_inline)) +static inline void rmt_ll_tx_reset_pointer(rmt_dev_t *dev, uint32_t channel) +{ + dev->chnconf0[channel].mem_rd_rst_chn = 1; + dev->chnconf0[channel].mem_rd_rst_chn = 0; + dev->chnconf0[channel].apb_mem_rst_chn = 1; + dev->chnconf0[channel].apb_mem_rst_chn = 0; +} + +/** + * @brief Start transmitting for TX channel + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + */ +__attribute__((always_inline)) +static inline void rmt_ll_tx_start(rmt_dev_t *dev, uint32_t channel) +{ + // update other configuration registers before start transmitting + dev->chnconf0[channel].conf_update_chn = 1; + dev->chnconf0[channel].tx_start_chn = 1; +} + +/** + * @brief Stop transmitting for TX channel + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + */ +__attribute__((always_inline)) +static inline void rmt_ll_tx_stop(rmt_dev_t *dev, uint32_t channel) +{ + dev->chnconf0[channel].tx_stop_chn = 1; + // stop won't take place until configurations updated + dev->chnconf0[channel].conf_update_chn = 1; +} + +/** + * @brief Set memory block number for TX channel + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @param block_num memory block number + */ +static inline void rmt_ll_tx_set_mem_blocks(rmt_dev_t *dev, uint32_t channel, uint8_t block_num) +{ + dev->chnconf0[channel].mem_size_chn = block_num; +} + +/** + * @brief Enable TX wrap + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @param enable True to enable, False to disable + */ +static inline void rmt_ll_tx_enable_wrap(rmt_dev_t *dev, uint32_t channel, bool enable) +{ + dev->chnconf0[channel].mem_tx_wrap_en_chn = enable; +} + +/** + * @brief Enable transmitting in a loop + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @param enable True to enable, False to disable + */ +__attribute__((always_inline)) +static inline void rmt_ll_tx_enable_loop(rmt_dev_t *dev, uint32_t channel, bool enable) +{ + dev->chnconf0[channel].tx_conti_mode_chn = enable; +} + +/** + * @brief Set loop count for TX channel + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @param count TX loop count + */ +__attribute__((always_inline)) +static inline void rmt_ll_tx_set_loop_count(rmt_dev_t *dev, uint32_t channel, uint32_t count) +{ + HAL_ASSERT(count <= RMT_LL_MAX_LOOP_COUNT_PER_BATCH && "loop count out of range"); + dev->chn_tx_lim[channel].tx_loop_num_chn = count; +} + +/** + * @brief Reset loop count for TX channel + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + */ +__attribute__((always_inline)) +static inline void rmt_ll_tx_reset_loop_count(rmt_dev_t *dev, uint32_t channel) +{ + dev->chn_tx_lim[channel].loop_count_reset_chn = 1; + dev->chn_tx_lim[channel].loop_count_reset_chn = 0; +} + +/** + * @brief Enable loop count for TX channel + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @param enable True to enable, False to disable + */ +__attribute__((always_inline)) +static inline void rmt_ll_tx_enable_loop_count(rmt_dev_t *dev, uint32_t channel, bool enable) +{ + dev->chn_tx_lim[channel].tx_loop_cnt_en_chn = enable; +} + +/** + * @brief Enable loop stop at count value automatically + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @param enable True to enable, False to disable + */ +__attribute__((always_inline)) +static inline void rmt_ll_tx_enable_loop_autostop(rmt_dev_t *dev, uint32_t channel, bool enable) +{ + dev->chn_tx_lim[channel].loop_stop_en_chn = enable; +} + +/** + * @brief Enable transmit multiple channels synchronously + * + * @param dev Peripheral instance address + * @param enable True to enable, False to disable + */ +static inline void rmt_ll_tx_enable_sync(rmt_dev_t *dev, bool enable) +{ + dev->tx_sim.tx_sim_en = enable; +} + +/** + * @brief Clear the TX channels synchronous group + * + * @param dev Peripheral instance address + */ +static inline void rmt_ll_tx_clear_sync_group(rmt_dev_t *dev) +{ + dev->tx_sim.val &= ~(0x03); +} + +/** + * @brief Add TX channels to the synchronous group + * + * @param dev Peripheral instance address + * @param channel_mask Mask of TX channels to be added to the synchronous group + */ +static inline void rmt_ll_tx_sync_group_add_channels(rmt_dev_t *dev, uint32_t channel_mask) +{ + dev->tx_sim.val |= (channel_mask & 0x03); +} + +/** + * @brief Remove TX channels from the synchronous group + * + * @param dev Peripheral instance address + * @param channel_mask Mask of TX channels to be removed from the synchronous group + */ +static inline void rmt_ll_tx_sync_group_remove_channels(rmt_dev_t *dev, uint32_t channel_mask) +{ + dev->tx_sim.val &= ~channel_mask; +} + +/** + * @brief Fix the output level when TX channel is in IDLE state + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @param level IDLE level (1 => high, 0 => low) + * @param enable True to fix the IDLE level, otherwise the IDLE level is determined by EOF encoder + */ +__attribute__((always_inline)) +static inline void rmt_ll_tx_fix_idle_level(rmt_dev_t *dev, uint32_t channel, uint8_t level, bool enable) +{ + dev->chnconf0[channel].idle_out_en_chn = enable; + dev->chnconf0[channel].idle_out_lv_chn = level; +} + +/** + * @brief Set the amount of RMT symbols that can trigger the limitation interrupt + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @param limit Specify the number of symbols + */ +static inline void rmt_ll_tx_set_limit(rmt_dev_t *dev, uint32_t channel, uint32_t limit) +{ + dev->chn_tx_lim[channel].tx_lim_chn = limit; +} + +/** + * @brief Set high and low duration of carrier signal + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @param high_ticks Duration of high level + * @param low_ticks Duration of low level + */ +static inline void rmt_ll_tx_set_carrier_high_low_ticks(rmt_dev_t *dev, uint32_t channel, uint32_t high_ticks, uint32_t low_ticks) +{ + HAL_ASSERT(high_ticks >= 1 && high_ticks <= 65536 && low_ticks >= 1 && low_ticks <= 65536 && "out of range high/low ticks"); + // ticks=0 means 65536 in hardware + if (high_ticks >= 65536) { + high_ticks = 0; + } + if (low_ticks >= 65536) { + low_ticks = 0; + } + HAL_FORCE_MODIFY_U32_REG_FIELD(dev->chncarrier_duty[channel], carrier_high_chn, high_ticks); + HAL_FORCE_MODIFY_U32_REG_FIELD(dev->chncarrier_duty[channel], carrier_low_chn, low_ticks); +} + +/** + * @brief Enable modulating carrier signal to TX channel + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @param enable True to enable, False to disable + */ +static inline void rmt_ll_tx_enable_carrier_modulation(rmt_dev_t *dev, uint32_t channel, bool enable) +{ + dev->chnconf0[channel].carrier_en_chn = enable; +} + +/** + * @brief Set on high or low to modulate the carrier signal + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @param level Which level to modulate on (0=>low level, 1=>high level) + */ +static inline void rmt_ll_tx_set_carrier_level(rmt_dev_t *dev, uint32_t channel, uint8_t level) +{ + dev->chnconf0[channel].carrier_out_lv_chn = level; +} + +/** + * @brief Enable to always output carrier signal, regardless of a valid data transmission + * + * @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 + */ +static inline void rmt_ll_tx_enable_carrier_always_on(rmt_dev_t *dev, uint32_t channel, bool enable) +{ + dev->chnconf0[channel].carrier_eff_en_chn = !enable; +} + +////////////////////////////////////////RX Channel Specific///////////////////////////////////////////////////////////// + +/** + * @brief Reset clock divider for RX channels by mask + * + * @param dev Peripheral instance address + * @param channel_mask Mask of RX channels + */ +static inline void rmt_ll_rx_reset_channels_clock_div(rmt_dev_t *dev, uint32_t channel_mask) +{ + // write 1 to reset + dev->ref_cnt_rst.val |= ((channel_mask & 0x03) << 2); +} + +/** + * @brief Set RX channel clock divider + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + * @param div Division value + */ +static inline void rmt_ll_rx_set_channel_clock_div(rmt_dev_t *dev, uint32_t channel, uint32_t div) +{ + HAL_ASSERT(div >= 1 && div <= 256 && "divider out of range"); + // limit the maximum divider to 256 + if (div >= 256) { + div = 0; // 0 means 256 division + } + HAL_FORCE_MODIFY_U32_REG_FIELD(dev->chmconf[channel].conf0, div_cnt_chm, div); +} + +/** + * @brief Reset RMT writing pointer for RX channel + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + */ +static inline void rmt_ll_rx_reset_pointer(rmt_dev_t *dev, uint32_t channel) +{ + dev->chmconf[channel].conf1.mem_wr_rst_chm = 1; + dev->chmconf[channel].conf1.mem_wr_rst_chm = 0; + dev->chmconf[channel].conf1.apb_mem_rst_chm = 1; + dev->chmconf[channel].conf1.apb_mem_rst_chm = 0; +} + +/** + * @brief Enable receiving for RX channel + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + * @param enable True to enable, False to disable + */ +__attribute__((always_inline)) +static inline void rmt_ll_rx_enable(rmt_dev_t *dev, uint32_t channel, bool enable) +{ + dev->chmconf[channel].conf1.rx_en_chm = enable; + // rx won't be enabled until configurations updated + dev->chmconf[channel].conf1.conf_update_chm = 1; +} + +/** + * @brief Set memory block number for RX channel + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + * @param block_num memory block number + */ +static inline void rmt_ll_rx_set_mem_blocks(rmt_dev_t *dev, uint32_t channel, uint8_t block_num) +{ + dev->chmconf[channel].conf0.mem_size_chm = block_num; +} + +/** + * @brief Set the time length for RX channel before going into IDLE state + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + * @param thres Time length threshold + */ +static inline void rmt_ll_rx_set_idle_thres(rmt_dev_t *dev, uint32_t channel, uint32_t thres) +{ + dev->chmconf[channel].conf0.idle_thres_chm = thres; +} + +/** + * @brief Set RMT memory owner for RX channel + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + * @param owner Memory owner + */ +__attribute__((always_inline)) +static inline void rmt_ll_rx_set_mem_owner(rmt_dev_t *dev, uint32_t channel, rmt_ll_mem_owner_t owner) +{ + dev->chmconf[channel].conf1.mem_owner_chm = owner; +} + +/** + * @brief Enable filter for RX channel + * + * @param dev Peripheral instance address + * @param channel RMT RX chanenl number + * @param enable True to enable, False to disable + */ +static inline void rmt_ll_rx_enable_filter(rmt_dev_t *dev, uint32_t channel, bool enable) +{ + dev->chmconf[channel].conf1.rx_filter_en_chm = enable; +} + +/** + * @brief Set RX channel filter threshold (i.e. the maximum width of one pulse signal that would be treated as a noise) + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + * @param thres Filter threshold + */ +static inline void rmt_ll_rx_set_filter_thres(rmt_dev_t *dev, uint32_t channel, uint32_t thres) +{ + HAL_FORCE_MODIFY_U32_REG_FIELD(dev->chmconf[channel].conf1, rx_filter_thres_chm, thres); +} + +/** + * @brief Get RMT memory write cursor offset + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + * @return writer offset + */ +__attribute__((always_inline)) +static inline uint32_t rmt_ll_rx_get_memory_writer_offset(rmt_dev_t *dev, uint32_t channel) +{ + return dev->chmstatus[channel].mem_waddr_ex_chm - (channel + 2) * 48; +} + +/** + * @brief Set the amount of RMT symbols that can trigger the limitation interrupt + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + * @param limit Specify the number of symbols + */ +static inline void rmt_ll_rx_set_limit(rmt_dev_t *dev, uint32_t channel, uint32_t limit) +{ + dev->chm_rx_lim[channel].rmt_rx_lim_chm = limit; +} + +/** + * @brief Set high and low duration of carrier signal + * + * @param dev dev Peripheral instance address + * @param channel RMT TX channel number + * @param high_ticks Duration of high level + * @param low_ticks Duration of low level + */ +static inline void rmt_ll_rx_set_carrier_high_low_ticks(rmt_dev_t *dev, uint32_t channel, uint32_t high_ticks, uint32_t low_ticks) +{ + HAL_ASSERT(high_ticks >= 1 && high_ticks <= 65536 && low_ticks >= 1 && low_ticks <= 65536 && "out of range high/low ticks"); + HAL_FORCE_MODIFY_U32_REG_FIELD(dev->chm_rx_carrier_rm[channel], carrier_high_thres_chm, high_ticks - 1); + HAL_FORCE_MODIFY_U32_REG_FIELD(dev->chm_rx_carrier_rm[channel], carrier_low_thres_chm, low_ticks - 1); +} + +/** + * @brief Enable demodulating the carrier on RX channel + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + * @param enable True to enable, False to disable + */ +static inline void rmt_ll_rx_enable_carrier_demodulation(rmt_dev_t *dev, uint32_t channel, bool enable) +{ + dev->chmconf[channel].conf0.carrier_en_chm = enable; +} + +/** + * @brief Set on high or low to demodulate the carrier signal + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + * @param level Which level to demodulate (0=>low level, 1=>high level) + */ +static inline void rmt_ll_rx_set_carrier_level(rmt_dev_t *dev, uint32_t channel, uint8_t level) +{ + dev->chmconf[channel].conf0.carrier_out_lv_chm = level; +} + +/** + * @brief Enable RX wrap + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + * @param enable True to enable, False to disable + */ +static inline void rmt_ll_rx_enable_wrap(rmt_dev_t *dev, uint32_t channel, bool enable) +{ + dev->chmconf[channel].conf1.mem_rx_wrap_en_chm = enable; +} + +//////////////////////////////////////////Interrupt Specific//////////////////////////////////////////////////////////// + +/** + * @brief Enable RMT interrupt for specific event mask + * + * @param dev Peripheral instance address + * @param mask Event mask + * @param enable True to enable, False to disable + */ +__attribute__((always_inline)) +static inline void rmt_ll_enable_interrupt(rmt_dev_t *dev, uint32_t mask, bool enable) +{ + if (enable) { + dev->int_ena.val |= mask; + } else { + dev->int_ena.val &= ~mask; + } +} + +/** + * @brief Clear RMT interrupt status by mask + * + * @param dev Peripheral instance address + * @param mask Interupt status mask + */ +__attribute__((always_inline)) +static inline void rmt_ll_clear_interrupt_status(rmt_dev_t *dev, uint32_t mask) +{ + dev->int_clr.val = mask; +} + +/** + * @brief Get interrupt status register address + * + * @param dev Peripheral instance address + * @return Register address + */ +static inline volatile void *rmt_ll_get_interrupt_status_reg(rmt_dev_t *dev) +{ + return &dev->int_st; +} + +/** + * @brief Get interrupt status for TX channel + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @return Interrupt status + */ +__attribute__((always_inline)) +static inline uint32_t rmt_ll_tx_get_interrupt_status(rmt_dev_t *dev, uint32_t channel) +{ + return dev->int_st.val & RMT_LL_EVENT_TX_MASK(channel); +} + +/** + * @brief Get interrupt raw status for TX channel + * + * @param dev Peripheral instance address + * @param channel RMT TX channel number + * @return Interrupt raw status + */ +static inline uint32_t rmt_ll_tx_get_interrupt_status_raw(rmt_dev_t *dev, uint32_t channel) +{ + return dev->int_raw.val & (RMT_LL_EVENT_TX_MASK(channel) | RMT_LL_EVENT_TX_ERROR(channel)); +} + +/** + * @brief Get interrupt raw status for RX channel + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + * @return Interrupt raw status + */ +static inline uint32_t rmt_ll_rx_get_interrupt_status_raw(rmt_dev_t *dev, uint32_t channel) +{ + return dev->int_raw.val & (RMT_LL_EVENT_RX_MASK(channel) | RMT_LL_EVENT_RX_ERROR(channel)); +} + +/** + * @brief Get interrupt status for RX channel + * + * @param dev Peripheral instance address + * @param channel RMT RX channel number + * @return Interrupt status + */ +__attribute__((always_inline)) +static inline uint32_t rmt_ll_rx_get_interrupt_status(rmt_dev_t *dev, uint32_t channel) +{ + return dev->int_st.val & RMT_LL_EVENT_RX_MASK(channel); +} + +//////////////////////////////////////////Deprecated Functions////////////////////////////////////////////////////////// +/////////////////////////////The following functions are only used by the legacy driver///////////////////////////////// +/////////////////////////////They might be removed in the next major release (ESP-IDF 6.0)////////////////////////////// +//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_tx_get_status_word(rmt_dev_t *dev, uint32_t channel) +{ + return dev->chnstatus[channel].val; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_rx_get_status_word(rmt_dev_t *dev, uint32_t channel) +{ + return dev->chmstatus[channel].val; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_tx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel) +{ + uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->chnconf0[channel], div_cnt_chn); + return div == 0 ? 256 : div; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_rx_get_channel_clock_div(rmt_dev_t *dev, uint32_t channel) +{ + uint32_t div = HAL_FORCE_READ_U32_REG_FIELD(dev->chmconf[channel].conf0, div_cnt_chm); + return div == 0 ? 256 : div; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_rx_get_idle_thres(rmt_dev_t *dev, uint32_t channel) +{ + return dev->chmconf[channel].conf0.idle_thres_chm; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_tx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel) +{ + return dev->chnconf0[channel].mem_size_chn; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_rx_get_mem_blocks(rmt_dev_t *dev, uint32_t channel) +{ + return dev->chmconf[channel].conf0.mem_size_chm; +} + +__attribute__((always_inline)) +static inline bool rmt_ll_tx_is_loop_enabled(rmt_dev_t *dev, uint32_t channel) +{ + return dev->chnconf0[channel].tx_conti_mode_chn; +} + +__attribute__((always_inline)) +static inline rmt_clock_source_t rmt_ll_get_group_clock_src(rmt_dev_t *dev, uint32_t channel) +{ + rmt_clock_source_t clk_src = RMT_CLK_SRC_APB; + switch (PCR.rmt_sclk_conf.rmt_sclk_sel) { + case 1: + clk_src = RMT_CLK_SRC_APB; + break; + case 3: + clk_src = RMT_CLK_SRC_XTAL; + break; + } + return clk_src; +} + +__attribute__((always_inline)) +static inline bool rmt_ll_tx_is_idle_enabled(rmt_dev_t *dev, uint32_t channel) +{ + return dev->chnconf0[channel].idle_out_en_chn; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_tx_get_idle_level(rmt_dev_t *dev, uint32_t channel) +{ + return dev->chnconf0[channel].idle_out_lv_chn; +} + +static inline bool rmt_ll_is_mem_powered_down(rmt_dev_t *dev) +{ + // the RTC domain can also power down RMT memory + // so it's probably not enough to detect whether it's powered down or not + // mem_force_pd has higher priority than mem_force_pu + return (dev->sys_conf.mem_force_pd) || !(dev->sys_conf.mem_force_pu); +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_rx_get_mem_owner(rmt_dev_t *dev, uint32_t channel) +{ + return dev->chmconf[channel].conf1.mem_owner_chm; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_rx_get_limit(rmt_dev_t *dev, uint32_t channel) +{ + return dev->chm_rx_lim[channel].rmt_rx_lim_chm; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_get_tx_end_interrupt_status(rmt_dev_t *dev) +{ + return dev->int_st.val & 0x03; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_get_rx_end_interrupt_status(rmt_dev_t *dev) +{ + return (dev->int_st.val >> 2) & 0x03; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_get_tx_err_interrupt_status(rmt_dev_t *dev) +{ + return (dev->int_st.val >> 4) & 0x03; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_get_rx_err_interrupt_status(rmt_dev_t *dev) +{ + return (dev->int_st.val >> 6) & 0x03; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_get_tx_thres_interrupt_status(rmt_dev_t *dev) +{ + return (dev->int_st.val >> 8) & 0x03; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_get_rx_thres_interrupt_status(rmt_dev_t *dev) +{ + return (dev->int_st.val >> 10) & 0x03; +} + +__attribute__((always_inline)) +static inline uint32_t rmt_ll_get_tx_loop_interrupt_status(rmt_dev_t *dev) +{ + return (dev->int_st.val >> 12) & 0x03; +} + +#ifdef __cplusplus +} +#endif diff --git a/components/hal/esp32h2/include/hal/rmt_ll.h b/components/hal/esp32h2/include/hal/rmt_ll.h index 5d18929689..826227ffa9 100644 --- a/components/hal/esp32h2/include/hal/rmt_ll.h +++ b/components/hal/esp32h2/include/hal/rmt_ll.h @@ -90,7 +90,6 @@ static inline void rmt_ll_set_group_clock_src(rmt_dev_t *dev, uint32_t channel, // Formula: rmt_sclk = module_clock_src / (1 + div_num + div_a / div_b) (void)channel; // the source clock is set for all channels HAL_ASSERT(divider_integral >= 1); - dev->sys_conf.sclk_active = 0; HAL_FORCE_MODIFY_U32_REG_FIELD(dev->sys_conf, sclk_div_num, divider_integral - 1); dev->sys_conf.sclk_div_a = divider_numerator; dev->sys_conf.sclk_div_b = divider_denominator; @@ -105,7 +104,17 @@ static inline void rmt_ll_set_group_clock_src(rmt_dev_t *dev, uint32_t channel, HAL_ASSERT(false && "unsupported RMT clock source"); break; } - dev->sys_conf.sclk_active = 1; +} + +/** + * @brief Enable RMT peripheral source clock + * + * @param dev Peripheral instance address + * @param en True to enable, False to disable + */ +static inline void rmt_ll_enable_group_clock(rmt_dev_t *dev, bool en) +{ + dev->sys_conf.sclk_active = en; } ////////////////////////////////////////TX Channel Specific///////////////////////////////////////////////////////////// diff --git a/components/hal/esp32s2/include/hal/rmt_ll.h b/components/hal/esp32s2/include/hal/rmt_ll.h index 49ad57b9f0..23510d674a 100644 --- a/components/hal/esp32s2/include/hal/rmt_ll.h +++ b/components/hal/esp32s2/include/hal/rmt_ll.h @@ -104,6 +104,20 @@ static inline void rmt_ll_set_group_clock_src(rmt_dev_t *dev, uint32_t channel, } } +/** + * @brief Enable RMT peripheral source clock + * + * @note RMT doesn't support enable/disable clock source, this function is only for compatibility + * + * @param dev Peripheral instance address + * @param en True to enable, False to disable + */ +static inline void rmt_ll_enable_group_clock(rmt_dev_t *dev, bool en) +{ + (void)dev; + (void)en; +} + ////////////////////////////////////////TX Channel Specific///////////////////////////////////////////////////////////// /** diff --git a/components/hal/esp32s3/include/hal/rmt_ll.h b/components/hal/esp32s3/include/hal/rmt_ll.h index 2096a92624..9489593940 100644 --- a/components/hal/esp32s3/include/hal/rmt_ll.h +++ b/components/hal/esp32s3/include/hal/rmt_ll.h @@ -90,7 +90,6 @@ static inline void rmt_ll_set_group_clock_src(rmt_dev_t *dev, uint32_t channel, // Formula: rmt_sclk = module_clock_src / (1 + div_num + div_a / div_b) (void)channel; // the source clock is set for all channels HAL_ASSERT(divider_integral >= 1); - dev->sys_conf.sclk_active = 0; HAL_FORCE_MODIFY_U32_REG_FIELD(dev->sys_conf, sclk_div_num, divider_integral - 1); dev->sys_conf.sclk_div_a = divider_numerator; dev->sys_conf.sclk_div_b = divider_denominator; @@ -108,7 +107,17 @@ static inline void rmt_ll_set_group_clock_src(rmt_dev_t *dev, uint32_t channel, HAL_ASSERT(false && "unsupported RMT clock source"); break; } - dev->sys_conf.sclk_active = 1; +} + +/** + * @brief Enable RMT peripheral source clock + * + * @param dev Peripheral instance address + * @param en True to enable, False to disable + */ +static inline void rmt_ll_enable_group_clock(rmt_dev_t *dev, bool en) +{ + dev->sys_conf.sclk_active = en; } ////////////////////////////////////////TX Channel Specific///////////////////////////////////////////////////////////// diff --git a/components/hal/rmt_hal.c b/components/hal/rmt_hal.c index d83e5952da..c14c8501cc 100644 --- a/components/hal/rmt_hal.c +++ b/components/hal/rmt_hal.c @@ -14,6 +14,7 @@ void rmt_hal_init(rmt_hal_context_t *hal) rmt_ll_enable_mem_access_nonfifo(hal->regs, true); // APB access the RMTMEM in nonfifo mode rmt_ll_enable_interrupt(hal->regs, UINT32_MAX, false); // disable all interupt events rmt_ll_clear_interrupt_status(hal->regs, UINT32_MAX); // clear all pending events + rmt_ll_enable_group_clock(hal->regs, true); // enable clock source #if SOC_RMT_SUPPORT_TX_SYNCHRO rmt_ll_tx_clear_sync_group(hal->regs); #endif // SOC_RMT_SUPPORT_TX_SYNCHRO @@ -24,6 +25,7 @@ void rmt_hal_deinit(rmt_hal_context_t *hal) rmt_ll_enable_interrupt(hal->regs, UINT32_MAX, false); // disable all interupt events rmt_ll_clear_interrupt_status(hal->regs, UINT32_MAX); // clear all pending events rmt_ll_power_down_mem(hal->regs, true); // turn off RMTMEM power domain + rmt_ll_enable_group_clock(hal->regs, false); // disable clock source hal->regs = NULL; } diff --git a/components/soc/esp32c6/include/soc/Kconfig.soc_caps.in b/components/soc/esp32c6/include/soc/Kconfig.soc_caps.in index e9053f90bf..d40af008cb 100644 --- a/components/soc/esp32c6/include/soc/Kconfig.soc_caps.in +++ b/components/soc/esp32c6/include/soc/Kconfig.soc_caps.in @@ -51,6 +51,10 @@ config SOC_I2S_SUPPORTED bool default y +config SOC_RMT_SUPPORTED + bool + default y + config SOC_SYSTIMER_SUPPORTED bool default y @@ -415,6 +419,10 @@ config SOC_RMT_SUPPORT_TX_LOOP_COUNT bool default y +config SOC_RMT_SUPPORT_TX_LOOP_AUTO_STOP + bool + default y + config SOC_RMT_SUPPORT_TX_SYNCHRO bool default y diff --git a/components/soc/esp32c6/include/soc/clk_tree_defs.h b/components/soc/esp32c6/include/soc/clk_tree_defs.h index 126288f8e3..220706dc38 100644 --- a/components/soc/esp32c6/include/soc/clk_tree_defs.h +++ b/components/soc/esp32c6/include/soc/clk_tree_defs.h @@ -161,16 +161,23 @@ typedef enum { /** * @brief Array initializer for all supported clock sources of RMT */ -#define SOC_RMT_CLKS {SOC_MOD_CLK_APB, SOC_MOD_CLK_RC_FAST, SOC_MOD_CLK_XTAL} +#if CONFIG_IDF_ENV_FPGA +#define SOC_RMT_CLKS {SOC_MOD_CLK_XTAL} +#else +#define SOC_RMT_CLKS {SOC_MOD_CLK_APB, SOC_MOD_CLK_XTAL} +#endif /** * @brief Type of RMT clock source */ typedef enum { RMT_CLK_SRC_APB = SOC_MOD_CLK_APB, /*!< Select APB as the source clock */ - RMT_CLK_SRC_RC_FAST = SOC_MOD_CLK_RC_FAST, /*!< Select RC_FAST as the source clock */ RMT_CLK_SRC_XTAL = SOC_MOD_CLK_XTAL, /*!< Select XTAL as the source clock */ +#if CONFIG_IDF_ENV_FPGA + RMT_CLK_SRC_DEFAULT = SOC_MOD_CLK_XTAL, /*!< Select XTAL as the default choice */ +#else RMT_CLK_SRC_DEFAULT = SOC_MOD_CLK_APB, /*!< Select APB as the default choice */ +#endif } soc_periph_rmt_clk_src_t; /** diff --git a/components/soc/esp32c6/include/soc/rmt_reg.h b/components/soc/esp32c6/include/soc/rmt_reg.h index 6d409a9c8e..0bc75f17fc 100644 --- a/components/soc/esp32c6/include/soc/rmt_reg.h +++ b/components/soc/esp32c6/include/soc/rmt_reg.h @@ -1,7 +1,7 @@ /** * SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD * - * SPDX-License-Identifier: Apache-2.0 + * SPDX-License-Identifier: Apache-2.0 */ #pragma once @@ -183,121 +183,121 @@ extern "C" { * Channel 1 configure register 0 */ #define RMT_CH1CONF0_REG (DR_REG_RMT_BASE + 0x14) -/** RMT_TX_START_CH0 : WT; bitpos: [0]; default: 0; +/** RMT_TX_START_CH1 : WT; bitpos: [0]; default: 0; * Set this bit to start sending data on CHANNEL1. */ -#define RMT_TX_START_CH0 (BIT(0)) -#define RMT_TX_START_CH0_M (RMT_TX_START_CH0_V << RMT_TX_START_CH0_S) -#define RMT_TX_START_CH0_V 0x00000001U -#define RMT_TX_START_CH0_S 0 -/** RMT_MEM_RD_RST_CH0 : WT; bitpos: [1]; default: 0; +#define RMT_TX_START_CH1 (BIT(0)) +#define RMT_TX_START_CH1_M (RMT_TX_START_CH1_V << RMT_TX_START_CH1_S) +#define RMT_TX_START_CH1_V 0x00000001U +#define RMT_TX_START_CH1_S 0 +/** RMT_MEM_RD_RST_CH1 : WT; bitpos: [1]; default: 0; * Set this bit to reset read ram address for CHANNEL1 by accessing transmitter. */ -#define RMT_MEM_RD_RST_CH0 (BIT(1)) -#define RMT_MEM_RD_RST_CH0_M (RMT_MEM_RD_RST_CH0_V << RMT_MEM_RD_RST_CH0_S) -#define RMT_MEM_RD_RST_CH0_V 0x00000001U -#define RMT_MEM_RD_RST_CH0_S 1 -/** RMT_APB_MEM_RST_CH0 : WT; bitpos: [2]; default: 0; +#define RMT_MEM_RD_RST_CH1 (BIT(1)) +#define RMT_MEM_RD_RST_CH1_M (RMT_MEM_RD_RST_CH1_V << RMT_MEM_RD_RST_CH1_S) +#define RMT_MEM_RD_RST_CH1_V 0x00000001U +#define RMT_MEM_RD_RST_CH1_S 1 +/** RMT_APB_MEM_RST_CH1 : WT; bitpos: [2]; default: 0; * Set this bit to reset W/R ram address for CHANNEL1 by accessing apb fifo. */ -#define RMT_APB_MEM_RST_CH0 (BIT(2)) -#define RMT_APB_MEM_RST_CH0_M (RMT_APB_MEM_RST_CH0_V << RMT_APB_MEM_RST_CH0_S) -#define RMT_APB_MEM_RST_CH0_V 0x00000001U -#define RMT_APB_MEM_RST_CH0_S 2 -/** RMT_TX_CONTI_MODE_CH0 : R/W; bitpos: [3]; default: 0; +#define RMT_APB_MEM_RST_CH1 (BIT(2)) +#define RMT_APB_MEM_RST_CH1_M (RMT_APB_MEM_RST_CH1_V << RMT_APB_MEM_RST_CH1_S) +#define RMT_APB_MEM_RST_CH1_V 0x00000001U +#define RMT_APB_MEM_RST_CH1_S 2 +/** RMT_TX_CONTI_MODE_CH1 : R/W; bitpos: [3]; default: 0; * Set this bit to restart transmission from the first data to the last data in * CHANNEL1. */ -#define RMT_TX_CONTI_MODE_CH0 (BIT(3)) -#define RMT_TX_CONTI_MODE_CH0_M (RMT_TX_CONTI_MODE_CH0_V << RMT_TX_CONTI_MODE_CH0_S) -#define RMT_TX_CONTI_MODE_CH0_V 0x00000001U -#define RMT_TX_CONTI_MODE_CH0_S 3 -/** RMT_MEM_TX_WRAP_EN_CH0 : R/W; bitpos: [4]; default: 0; +#define RMT_TX_CONTI_MODE_CH1 (BIT(3)) +#define RMT_TX_CONTI_MODE_CH1_M (RMT_TX_CONTI_MODE_CH1_V << RMT_TX_CONTI_MODE_CH1_S) +#define RMT_TX_CONTI_MODE_CH1_V 0x00000001U +#define RMT_TX_CONTI_MODE_CH1_S 3 +/** RMT_MEM_TX_WRAP_EN_CH1 : R/W; bitpos: [4]; default: 0; * This is the channel 1 enable bit for wraparound mode: it will resume sending at the * start when the data to be sent is more than its memory size. */ -#define RMT_MEM_TX_WRAP_EN_CH0 (BIT(4)) -#define RMT_MEM_TX_WRAP_EN_CH0_M (RMT_MEM_TX_WRAP_EN_CH0_V << RMT_MEM_TX_WRAP_EN_CH0_S) -#define RMT_MEM_TX_WRAP_EN_CH0_V 0x00000001U -#define RMT_MEM_TX_WRAP_EN_CH0_S 4 -/** RMT_IDLE_OUT_LV_CH0 : R/W; bitpos: [5]; default: 0; +#define RMT_MEM_TX_WRAP_EN_CH1 (BIT(4)) +#define RMT_MEM_TX_WRAP_EN_CH1_M (RMT_MEM_TX_WRAP_EN_CH1_V << RMT_MEM_TX_WRAP_EN_CH1_S) +#define RMT_MEM_TX_WRAP_EN_CH1_V 0x00000001U +#define RMT_MEM_TX_WRAP_EN_CH1_S 4 +/** RMT_IDLE_OUT_LV_CH1 : R/W; bitpos: [5]; default: 0; * This bit configures the level of output signal in CHANNEL1 when the latter is in * IDLE state. */ -#define RMT_IDLE_OUT_LV_CH0 (BIT(5)) -#define RMT_IDLE_OUT_LV_CH0_M (RMT_IDLE_OUT_LV_CH0_V << RMT_IDLE_OUT_LV_CH0_S) -#define RMT_IDLE_OUT_LV_CH0_V 0x00000001U -#define RMT_IDLE_OUT_LV_CH0_S 5 -/** RMT_IDLE_OUT_EN_CH0 : R/W; bitpos: [6]; default: 0; +#define RMT_IDLE_OUT_LV_CH1 (BIT(5)) +#define RMT_IDLE_OUT_LV_CH1_M (RMT_IDLE_OUT_LV_CH1_V << RMT_IDLE_OUT_LV_CH1_S) +#define RMT_IDLE_OUT_LV_CH1_V 0x00000001U +#define RMT_IDLE_OUT_LV_CH1_S 5 +/** RMT_IDLE_OUT_EN_CH1 : R/W; bitpos: [6]; default: 0; * This is the output enable-control bit for CHANNEL1 in IDLE state. */ -#define RMT_IDLE_OUT_EN_CH0 (BIT(6)) -#define RMT_IDLE_OUT_EN_CH0_M (RMT_IDLE_OUT_EN_CH0_V << RMT_IDLE_OUT_EN_CH0_S) -#define RMT_IDLE_OUT_EN_CH0_V 0x00000001U -#define RMT_IDLE_OUT_EN_CH0_S 6 -/** RMT_TX_STOP_CH0 : R/W/SC; bitpos: [7]; default: 0; +#define RMT_IDLE_OUT_EN_CH1 (BIT(6)) +#define RMT_IDLE_OUT_EN_CH1_M (RMT_IDLE_OUT_EN_CH1_V << RMT_IDLE_OUT_EN_CH1_S) +#define RMT_IDLE_OUT_EN_CH1_V 0x00000001U +#define RMT_IDLE_OUT_EN_CH1_S 6 +/** RMT_TX_STOP_CH1 : R/W/SC; bitpos: [7]; default: 0; * Set this bit to stop the transmitter of CHANNEL1 sending data out. */ -#define RMT_TX_STOP_CH0 (BIT(7)) -#define RMT_TX_STOP_CH0_M (RMT_TX_STOP_CH0_V << RMT_TX_STOP_CH0_S) -#define RMT_TX_STOP_CH0_V 0x00000001U -#define RMT_TX_STOP_CH0_S 7 -/** RMT_DIV_CNT_CH0 : R/W; bitpos: [15:8]; default: 2; +#define RMT_TX_STOP_CH1 (BIT(7)) +#define RMT_TX_STOP_CH1_M (RMT_TX_STOP_CH1_V << RMT_TX_STOP_CH1_S) +#define RMT_TX_STOP_CH1_V 0x00000001U +#define RMT_TX_STOP_CH1_S 7 +/** RMT_DIV_CNT_CH1 : R/W; bitpos: [15:8]; default: 2; * This register is used to configure the divider for clock of CHANNEL1. */ -#define RMT_DIV_CNT_CH0 0x000000FFU -#define RMT_DIV_CNT_CH0_M (RMT_DIV_CNT_CH0_V << RMT_DIV_CNT_CH0_S) -#define RMT_DIV_CNT_CH0_V 0x000000FFU -#define RMT_DIV_CNT_CH0_S 8 -/** RMT_MEM_SIZE_CH0 : R/W; bitpos: [18:16]; default: 1; +#define RMT_DIV_CNT_CH1 0x000000FFU +#define RMT_DIV_CNT_CH1_M (RMT_DIV_CNT_CH1_V << RMT_DIV_CNT_CH1_S) +#define RMT_DIV_CNT_CH1_V 0x000000FFU +#define RMT_DIV_CNT_CH1_S 8 +/** RMT_MEM_SIZE_CH1 : R/W; bitpos: [18:16]; default: 1; * This register is used to configure the maximum size of memory allocated to CHANNEL1. */ -#define RMT_MEM_SIZE_CH0 0x00000007U -#define RMT_MEM_SIZE_CH0_M (RMT_MEM_SIZE_CH0_V << RMT_MEM_SIZE_CH0_S) -#define RMT_MEM_SIZE_CH0_V 0x00000007U -#define RMT_MEM_SIZE_CH0_S 16 -/** RMT_CARRIER_EFF_EN_CH0 : R/W; bitpos: [20]; default: 1; +#define RMT_MEM_SIZE_CH1 0x00000007U +#define RMT_MEM_SIZE_CH1_M (RMT_MEM_SIZE_CH1_V << RMT_MEM_SIZE_CH1_S) +#define RMT_MEM_SIZE_CH1_V 0x00000007U +#define RMT_MEM_SIZE_CH1_S 16 +/** RMT_CARRIER_EFF_EN_CH1 : R/W; bitpos: [20]; default: 1; * 1: Add carrier modulation on the output signal only at the send data state for * CHANNEL1. 0: Add carrier modulation on the output signal at all state for CHANNEL1. * Only valid when RMT_CARRIER_EN_CH1 is 1. */ -#define RMT_CARRIER_EFF_EN_CH0 (BIT(20)) -#define RMT_CARRIER_EFF_EN_CH0_M (RMT_CARRIER_EFF_EN_CH0_V << RMT_CARRIER_EFF_EN_CH0_S) -#define RMT_CARRIER_EFF_EN_CH0_V 0x00000001U -#define RMT_CARRIER_EFF_EN_CH0_S 20 -/** RMT_CARRIER_EN_CH0 : R/W; bitpos: [21]; default: 1; +#define RMT_CARRIER_EFF_EN_CH1 (BIT(20)) +#define RMT_CARRIER_EFF_EN_CH1_M (RMT_CARRIER_EFF_EN_CH1_V << RMT_CARRIER_EFF_EN_CH1_S) +#define RMT_CARRIER_EFF_EN_CH1_V 0x00000001U +#define RMT_CARRIER_EFF_EN_CH1_S 20 +/** RMT_CARRIER_EN_CH1 : R/W; bitpos: [21]; default: 1; * This is the carrier modulation enable-control bit for CHANNEL1. 1: Add carrier * modulation in the output signal. 0: No carrier modulation in sig_out. */ -#define RMT_CARRIER_EN_CH0 (BIT(21)) -#define RMT_CARRIER_EN_CH0_M (RMT_CARRIER_EN_CH0_V << RMT_CARRIER_EN_CH0_S) -#define RMT_CARRIER_EN_CH0_V 0x00000001U -#define RMT_CARRIER_EN_CH0_S 21 -/** RMT_CARRIER_OUT_LV_CH0 : R/W; bitpos: [22]; default: 1; +#define RMT_CARRIER_EN_CH1 (BIT(21)) +#define RMT_CARRIER_EN_CH1_M (RMT_CARRIER_EN_CH1_V << RMT_CARRIER_EN_CH1_S) +#define RMT_CARRIER_EN_CH1_V 0x00000001U +#define RMT_CARRIER_EN_CH1_S 21 +/** RMT_CARRIER_OUT_LV_CH1 : R/W; bitpos: [22]; default: 1; * This bit is used to configure the position of carrier wave for CHANNEL1. * * 1'h0: add carrier wave on low level. * * 1'h1: add carrier wave on high level. */ -#define RMT_CARRIER_OUT_LV_CH0 (BIT(22)) -#define RMT_CARRIER_OUT_LV_CH0_M (RMT_CARRIER_OUT_LV_CH0_V << RMT_CARRIER_OUT_LV_CH0_S) -#define RMT_CARRIER_OUT_LV_CH0_V 0x00000001U -#define RMT_CARRIER_OUT_LV_CH0_S 22 -/** RMT_AFIFO_RST_CH0 : WT; bitpos: [23]; default: 0; +#define RMT_CARRIER_OUT_LV_CH1 (BIT(22)) +#define RMT_CARRIER_OUT_LV_CH1_M (RMT_CARRIER_OUT_LV_CH1_V << RMT_CARRIER_OUT_LV_CH1_S) +#define RMT_CARRIER_OUT_LV_CH1_V 0x00000001U +#define RMT_CARRIER_OUT_LV_CH1_S 22 +/** RMT_AFIFO_RST_CH1 : WT; bitpos: [23]; default: 0; * Reserved */ -#define RMT_AFIFO_RST_CH0 (BIT(23)) -#define RMT_AFIFO_RST_CH0_M (RMT_AFIFO_RST_CH0_V << RMT_AFIFO_RST_CH0_S) -#define RMT_AFIFO_RST_CH0_V 0x00000001U -#define RMT_AFIFO_RST_CH0_S 23 -/** RMT_CONF_UPDATE_CH0 : WT; bitpos: [24]; default: 0; +#define RMT_AFIFO_RST_CH1 (BIT(23)) +#define RMT_AFIFO_RST_CH1_M (RMT_AFIFO_RST_CH1_V << RMT_AFIFO_RST_CH1_S) +#define RMT_AFIFO_RST_CH1_V 0x00000001U +#define RMT_AFIFO_RST_CH1_S 23 +/** RMT_CONF_UPDATE_CH1 : WT; bitpos: [24]; default: 0; * synchronization bit for CHANNEL1 */ -#define RMT_CONF_UPDATE_CH0 (BIT(24)) -#define RMT_CONF_UPDATE_CH0_M (RMT_CONF_UPDATE_CH0_V << RMT_CONF_UPDATE_CH0_S) -#define RMT_CONF_UPDATE_CH0_V 0x00000001U -#define RMT_CONF_UPDATE_CH0_S 24 +#define RMT_CONF_UPDATE_CH1 (BIT(24)) +#define RMT_CONF_UPDATE_CH1_M (RMT_CONF_UPDATE_CH1_V << RMT_CONF_UPDATE_CH1_S) +#define RMT_CONF_UPDATE_CH1_V 0x00000001U +#define RMT_CONF_UPDATE_CH1_S 24 /** RMT_CH2CONF0_REG register * Channel 2 configure register 0 @@ -423,121 +423,121 @@ extern "C" { * Channel 3 configure register 0 */ #define RMT_CH3CONF0_REG (DR_REG_RMT_BASE + 0x20) -/** RMT_DIV_CNT_CH2 : R/W; bitpos: [7:0]; default: 2; +/** RMT_DIV_CNT_CH3 : R/W; bitpos: [7:0]; default: 2; * This register is used to configure the divider for clock of CHANNEL3. */ -#define RMT_DIV_CNT_CH2 0x000000FFU -#define RMT_DIV_CNT_CH2_M (RMT_DIV_CNT_CH2_V << RMT_DIV_CNT_CH2_S) -#define RMT_DIV_CNT_CH2_V 0x000000FFU -#define RMT_DIV_CNT_CH2_S 0 -/** RMT_IDLE_THRES_CH2 : R/W; bitpos: [22:8]; default: 32767; +#define RMT_DIV_CNT_CH3 0x000000FFU +#define RMT_DIV_CNT_CH3_M (RMT_DIV_CNT_CH3_V << RMT_DIV_CNT_CH3_S) +#define RMT_DIV_CNT_CH3_V 0x000000FFU +#define RMT_DIV_CNT_CH3_S 0 +/** RMT_IDLE_THRES_CH3 : R/W; bitpos: [22:8]; default: 32767; * When no edge is detected on the input signal and continuous clock cycles is longer * than this register value, received process is finished. */ -#define RMT_IDLE_THRES_CH2 0x00007FFFU -#define RMT_IDLE_THRES_CH2_M (RMT_IDLE_THRES_CH2_V << RMT_IDLE_THRES_CH2_S) -#define RMT_IDLE_THRES_CH2_V 0x00007FFFU -#define RMT_IDLE_THRES_CH2_S 8 -/** RMT_MEM_SIZE_CH2 : R/W; bitpos: [25:23]; default: 1; +#define RMT_IDLE_THRES_CH3 0x00007FFFU +#define RMT_IDLE_THRES_CH3_M (RMT_IDLE_THRES_CH3_V << RMT_IDLE_THRES_CH3_S) +#define RMT_IDLE_THRES_CH3_V 0x00007FFFU +#define RMT_IDLE_THRES_CH3_S 8 +/** RMT_MEM_SIZE_CH3 : R/W; bitpos: [25:23]; default: 1; * This register is used to configure the maximum size of memory allocated to CHANNEL3. */ -#define RMT_MEM_SIZE_CH2 0x00000007U -#define RMT_MEM_SIZE_CH2_M (RMT_MEM_SIZE_CH2_V << RMT_MEM_SIZE_CH2_S) -#define RMT_MEM_SIZE_CH2_V 0x00000007U -#define RMT_MEM_SIZE_CH2_S 23 -/** RMT_CARRIER_EN_CH2 : R/W; bitpos: [28]; default: 1; +#define RMT_MEM_SIZE_CH3 0x00000007U +#define RMT_MEM_SIZE_CH3_M (RMT_MEM_SIZE_CH3_V << RMT_MEM_SIZE_CH3_S) +#define RMT_MEM_SIZE_CH3_V 0x00000007U +#define RMT_MEM_SIZE_CH3_S 23 +/** RMT_CARRIER_EN_CH3 : R/W; bitpos: [28]; default: 1; * This is the carrier modulation enable-control bit for CHANNEL3. 1: Add carrier * modulation in the output signal. 0: No carrier modulation in sig_out. */ -#define RMT_CARRIER_EN_CH2 (BIT(28)) -#define RMT_CARRIER_EN_CH2_M (RMT_CARRIER_EN_CH2_V << RMT_CARRIER_EN_CH2_S) -#define RMT_CARRIER_EN_CH2_V 0x00000001U -#define RMT_CARRIER_EN_CH2_S 28 -/** RMT_CARRIER_OUT_LV_CH2 : R/W; bitpos: [29]; default: 1; +#define RMT_CARRIER_EN_CH3 (BIT(28)) +#define RMT_CARRIER_EN_CH3_M (RMT_CARRIER_EN_CH3_V << RMT_CARRIER_EN_CH3_S) +#define RMT_CARRIER_EN_CH3_V 0x00000001U +#define RMT_CARRIER_EN_CH3_S 28 +/** RMT_CARRIER_OUT_LV_CH3 : R/W; bitpos: [29]; default: 1; * This bit is used to configure the position of carrier wave for CHANNEL3. * * 1'h0: add carrier wave on low level. * * 1'h1: add carrier wave on high level. */ -#define RMT_CARRIER_OUT_LV_CH2 (BIT(29)) -#define RMT_CARRIER_OUT_LV_CH2_M (RMT_CARRIER_OUT_LV_CH2_V << RMT_CARRIER_OUT_LV_CH2_S) -#define RMT_CARRIER_OUT_LV_CH2_V 0x00000001U -#define RMT_CARRIER_OUT_LV_CH2_S 29 +#define RMT_CARRIER_OUT_LV_CH3 (BIT(29)) +#define RMT_CARRIER_OUT_LV_CH3_M (RMT_CARRIER_OUT_LV_CH3_V << RMT_CARRIER_OUT_LV_CH3_S) +#define RMT_CARRIER_OUT_LV_CH3_V 0x00000001U +#define RMT_CARRIER_OUT_LV_CH3_S 29 /** RMT_CH3CONF1_REG register * Channel 3 configure register 1 */ #define RMT_CH3CONF1_REG (DR_REG_RMT_BASE + 0x24) -/** RMT_RX_EN_CH2 : R/W; bitpos: [0]; default: 0; +/** RMT_RX_EN_CH3 : R/W; bitpos: [0]; default: 0; * Set this bit to enable receiver to receive data on CHANNEL3. */ -#define RMT_RX_EN_CH2 (BIT(0)) -#define RMT_RX_EN_CH2_M (RMT_RX_EN_CH2_V << RMT_RX_EN_CH2_S) -#define RMT_RX_EN_CH2_V 0x00000001U -#define RMT_RX_EN_CH2_S 0 -/** RMT_MEM_WR_RST_CH2 : WT; bitpos: [1]; default: 0; +#define RMT_RX_EN_CH3 (BIT(0)) +#define RMT_RX_EN_CH3_M (RMT_RX_EN_CH3_V << RMT_RX_EN_CH3_S) +#define RMT_RX_EN_CH3_V 0x00000001U +#define RMT_RX_EN_CH3_S 0 +/** RMT_MEM_WR_RST_CH3 : WT; bitpos: [1]; default: 0; * Set this bit to reset write ram address for CHANNEL3 by accessing receiver. */ -#define RMT_MEM_WR_RST_CH2 (BIT(1)) -#define RMT_MEM_WR_RST_CH2_M (RMT_MEM_WR_RST_CH2_V << RMT_MEM_WR_RST_CH2_S) -#define RMT_MEM_WR_RST_CH2_V 0x00000001U -#define RMT_MEM_WR_RST_CH2_S 1 -/** RMT_APB_MEM_RST_CH2 : WT; bitpos: [2]; default: 0; +#define RMT_MEM_WR_RST_CH3 (BIT(1)) +#define RMT_MEM_WR_RST_CH3_M (RMT_MEM_WR_RST_CH3_V << RMT_MEM_WR_RST_CH3_S) +#define RMT_MEM_WR_RST_CH3_V 0x00000001U +#define RMT_MEM_WR_RST_CH3_S 1 +/** RMT_APB_MEM_RST_CH3 : WT; bitpos: [2]; default: 0; * Set this bit to reset W/R ram address for CHANNEL3 by accessing apb fifo. */ -#define RMT_APB_MEM_RST_CH2 (BIT(2)) -#define RMT_APB_MEM_RST_CH2_M (RMT_APB_MEM_RST_CH2_V << RMT_APB_MEM_RST_CH2_S) -#define RMT_APB_MEM_RST_CH2_V 0x00000001U -#define RMT_APB_MEM_RST_CH2_S 2 -/** RMT_MEM_OWNER_CH2 : R/W/SC; bitpos: [3]; default: 1; +#define RMT_APB_MEM_RST_CH3 (BIT(2)) +#define RMT_APB_MEM_RST_CH3_M (RMT_APB_MEM_RST_CH3_V << RMT_APB_MEM_RST_CH3_S) +#define RMT_APB_MEM_RST_CH3_V 0x00000001U +#define RMT_APB_MEM_RST_CH3_S 2 +/** RMT_MEM_OWNER_CH3 : R/W/SC; bitpos: [3]; default: 1; * This register marks the ownership of CHANNEL3's ram block. * * 1'h1: Receiver is using the ram. * * 1'h0: APB bus is using the ram. */ -#define RMT_MEM_OWNER_CH2 (BIT(3)) -#define RMT_MEM_OWNER_CH2_M (RMT_MEM_OWNER_CH2_V << RMT_MEM_OWNER_CH2_S) -#define RMT_MEM_OWNER_CH2_V 0x00000001U -#define RMT_MEM_OWNER_CH2_S 3 -/** RMT_RX_FILTER_EN_CH2 : R/W; bitpos: [4]; default: 0; +#define RMT_MEM_OWNER_CH3 (BIT(3)) +#define RMT_MEM_OWNER_CH3_M (RMT_MEM_OWNER_CH3_V << RMT_MEM_OWNER_CH3_S) +#define RMT_MEM_OWNER_CH3_V 0x00000001U +#define RMT_MEM_OWNER_CH3_S 3 +/** RMT_RX_FILTER_EN_CH3 : R/W; bitpos: [4]; default: 0; * This is the receive filter's enable bit for CHANNEL3. */ -#define RMT_RX_FILTER_EN_CH2 (BIT(4)) -#define RMT_RX_FILTER_EN_CH2_M (RMT_RX_FILTER_EN_CH2_V << RMT_RX_FILTER_EN_CH2_S) -#define RMT_RX_FILTER_EN_CH2_V 0x00000001U -#define RMT_RX_FILTER_EN_CH2_S 4 -/** RMT_RX_FILTER_THRES_CH2 : R/W; bitpos: [12:5]; default: 15; +#define RMT_RX_FILTER_EN_CH3 (BIT(4)) +#define RMT_RX_FILTER_EN_CH3_M (RMT_RX_FILTER_EN_CH3_V << RMT_RX_FILTER_EN_CH3_S) +#define RMT_RX_FILTER_EN_CH3_V 0x00000001U +#define RMT_RX_FILTER_EN_CH3_S 4 +/** RMT_RX_FILTER_THRES_CH3 : R/W; bitpos: [12:5]; default: 15; * Ignores the input pulse when its width is smaller than this register value in APB * clock periods (in receive mode). */ -#define RMT_RX_FILTER_THRES_CH2 0x000000FFU -#define RMT_RX_FILTER_THRES_CH2_M (RMT_RX_FILTER_THRES_CH2_V << RMT_RX_FILTER_THRES_CH2_S) -#define RMT_RX_FILTER_THRES_CH2_V 0x000000FFU -#define RMT_RX_FILTER_THRES_CH2_S 5 -/** RMT_MEM_RX_WRAP_EN_CH2 : R/W; bitpos: [13]; default: 0; +#define RMT_RX_FILTER_THRES_CH3 0x000000FFU +#define RMT_RX_FILTER_THRES_CH3_M (RMT_RX_FILTER_THRES_CH3_V << RMT_RX_FILTER_THRES_CH3_S) +#define RMT_RX_FILTER_THRES_CH3_V 0x000000FFU +#define RMT_RX_FILTER_THRES_CH3_S 5 +/** RMT_MEM_RX_WRAP_EN_CH3 : R/W; bitpos: [13]; default: 0; * This is the channel 3 enable bit for wraparound mode: it will resume receiving at * the start when the data to be received is more than its memory size. */ -#define RMT_MEM_RX_WRAP_EN_CH2 (BIT(13)) -#define RMT_MEM_RX_WRAP_EN_CH2_M (RMT_MEM_RX_WRAP_EN_CH2_V << RMT_MEM_RX_WRAP_EN_CH2_S) -#define RMT_MEM_RX_WRAP_EN_CH2_V 0x00000001U -#define RMT_MEM_RX_WRAP_EN_CH2_S 13 -/** RMT_AFIFO_RST_CH2 : WT; bitpos: [14]; default: 0; +#define RMT_MEM_RX_WRAP_EN_CH3 (BIT(13)) +#define RMT_MEM_RX_WRAP_EN_CH3_M (RMT_MEM_RX_WRAP_EN_CH3_V << RMT_MEM_RX_WRAP_EN_CH3_S) +#define RMT_MEM_RX_WRAP_EN_CH3_V 0x00000001U +#define RMT_MEM_RX_WRAP_EN_CH3_S 13 +/** RMT_AFIFO_RST_CH3 : WT; bitpos: [14]; default: 0; * Reserved */ -#define RMT_AFIFO_RST_CH2 (BIT(14)) -#define RMT_AFIFO_RST_CH2_M (RMT_AFIFO_RST_CH2_V << RMT_AFIFO_RST_CH2_S) -#define RMT_AFIFO_RST_CH2_V 0x00000001U -#define RMT_AFIFO_RST_CH2_S 14 -/** RMT_CONF_UPDATE_CH2 : WT; bitpos: [15]; default: 0; +#define RMT_AFIFO_RST_CH3 (BIT(14)) +#define RMT_AFIFO_RST_CH3_M (RMT_AFIFO_RST_CH3_V << RMT_AFIFO_RST_CH3_S) +#define RMT_AFIFO_RST_CH3_V 0x00000001U +#define RMT_AFIFO_RST_CH3_S 14 +/** RMT_CONF_UPDATE_CH3 : WT; bitpos: [15]; default: 0; * synchronization bit for CHANNEL3 */ -#define RMT_CONF_UPDATE_CH2 (BIT(15)) -#define RMT_CONF_UPDATE_CH2_M (RMT_CONF_UPDATE_CH2_V << RMT_CONF_UPDATE_CH2_S) -#define RMT_CONF_UPDATE_CH2_V 0x00000001U -#define RMT_CONF_UPDATE_CH2_S 15 +#define RMT_CONF_UPDATE_CH3 (BIT(15)) +#define RMT_CONF_UPDATE_CH3_M (RMT_CONF_UPDATE_CH3_V << RMT_CONF_UPDATE_CH3_S) +#define RMT_CONF_UPDATE_CH3_V 0x00000001U +#define RMT_CONF_UPDATE_CH3_S 15 /** RMT_CH0STATUS_REG register * Channel 0 status register @@ -601,59 +601,59 @@ extern "C" { * Channel 1 status register */ #define RMT_CH1STATUS_REG (DR_REG_RMT_BASE + 0x2c) -/** RMT_MEM_RADDR_EX_CH0 : RO; bitpos: [8:0]; default: 0; +/** RMT_MEM_RADDR_EX_CH1 : RO; bitpos: [8:0]; default: 0; * This register records the memory address offset when transmitter of CHANNEL1 is * using the RAM. */ -#define RMT_MEM_RADDR_EX_CH0 0x000001FFU -#define RMT_MEM_RADDR_EX_CH0_M (RMT_MEM_RADDR_EX_CH0_V << RMT_MEM_RADDR_EX_CH0_S) -#define RMT_MEM_RADDR_EX_CH0_V 0x000001FFU -#define RMT_MEM_RADDR_EX_CH0_S 0 -/** RMT_STATE_CH0 : RO; bitpos: [11:9]; default: 0; +#define RMT_MEM_RADDR_EX_CH1 0x000001FFU +#define RMT_MEM_RADDR_EX_CH1_M (RMT_MEM_RADDR_EX_CH1_V << RMT_MEM_RADDR_EX_CH1_S) +#define RMT_MEM_RADDR_EX_CH1_V 0x000001FFU +#define RMT_MEM_RADDR_EX_CH1_S 0 +/** RMT_STATE_CH1 : RO; bitpos: [11:9]; default: 0; * This register records the FSM status of CHANNEL1. */ -#define RMT_STATE_CH0 0x00000007U -#define RMT_STATE_CH0_M (RMT_STATE_CH0_V << RMT_STATE_CH0_S) -#define RMT_STATE_CH0_V 0x00000007U -#define RMT_STATE_CH0_S 9 -/** RMT_APB_MEM_WADDR_CH0 : RO; bitpos: [20:12]; default: 0; +#define RMT_STATE_CH1 0x00000007U +#define RMT_STATE_CH1_M (RMT_STATE_CH1_V << RMT_STATE_CH1_S) +#define RMT_STATE_CH1_V 0x00000007U +#define RMT_STATE_CH1_S 9 +/** RMT_APB_MEM_WADDR_CH1 : RO; bitpos: [20:12]; default: 0; * This register records the memory address offset when writes RAM over APB bus. */ -#define RMT_APB_MEM_WADDR_CH0 0x000001FFU -#define RMT_APB_MEM_WADDR_CH0_M (RMT_APB_MEM_WADDR_CH0_V << RMT_APB_MEM_WADDR_CH0_S) -#define RMT_APB_MEM_WADDR_CH0_V 0x000001FFU -#define RMT_APB_MEM_WADDR_CH0_S 12 -/** RMT_APB_MEM_RD_ERR_CH0 : RO; bitpos: [21]; default: 0; +#define RMT_APB_MEM_WADDR_CH1 0x000001FFU +#define RMT_APB_MEM_WADDR_CH1_M (RMT_APB_MEM_WADDR_CH1_V << RMT_APB_MEM_WADDR_CH1_S) +#define RMT_APB_MEM_WADDR_CH1_V 0x000001FFU +#define RMT_APB_MEM_WADDR_CH1_S 12 +/** RMT_APB_MEM_RD_ERR_CH1 : RO; bitpos: [21]; default: 0; * This status bit will be set if the offset address out of memory size when reading * via APB bus. */ -#define RMT_APB_MEM_RD_ERR_CH0 (BIT(21)) -#define RMT_APB_MEM_RD_ERR_CH0_M (RMT_APB_MEM_RD_ERR_CH0_V << RMT_APB_MEM_RD_ERR_CH0_S) -#define RMT_APB_MEM_RD_ERR_CH0_V 0x00000001U -#define RMT_APB_MEM_RD_ERR_CH0_S 21 -/** RMT_MEM_EMPTY_CH0 : RO; bitpos: [22]; default: 0; +#define RMT_APB_MEM_RD_ERR_CH1 (BIT(21)) +#define RMT_APB_MEM_RD_ERR_CH1_M (RMT_APB_MEM_RD_ERR_CH1_V << RMT_APB_MEM_RD_ERR_CH1_S) +#define RMT_APB_MEM_RD_ERR_CH1_V 0x00000001U +#define RMT_APB_MEM_RD_ERR_CH1_S 21 +/** RMT_MEM_EMPTY_CH1 : RO; bitpos: [22]; default: 0; * This status bit will be set when the data to be set is more than memory size and * the wraparound mode is disabled. */ -#define RMT_MEM_EMPTY_CH0 (BIT(22)) -#define RMT_MEM_EMPTY_CH0_M (RMT_MEM_EMPTY_CH0_V << RMT_MEM_EMPTY_CH0_S) -#define RMT_MEM_EMPTY_CH0_V 0x00000001U -#define RMT_MEM_EMPTY_CH0_S 22 -/** RMT_APB_MEM_WR_ERR_CH0 : RO; bitpos: [23]; default: 0; +#define RMT_MEM_EMPTY_CH1 (BIT(22)) +#define RMT_MEM_EMPTY_CH1_M (RMT_MEM_EMPTY_CH1_V << RMT_MEM_EMPTY_CH1_S) +#define RMT_MEM_EMPTY_CH1_V 0x00000001U +#define RMT_MEM_EMPTY_CH1_S 22 +/** RMT_APB_MEM_WR_ERR_CH1 : RO; bitpos: [23]; default: 0; * This status bit will be set if the offset address out of memory size when writes * via APB bus. */ -#define RMT_APB_MEM_WR_ERR_CH0 (BIT(23)) -#define RMT_APB_MEM_WR_ERR_CH0_M (RMT_APB_MEM_WR_ERR_CH0_V << RMT_APB_MEM_WR_ERR_CH0_S) -#define RMT_APB_MEM_WR_ERR_CH0_V 0x00000001U -#define RMT_APB_MEM_WR_ERR_CH0_S 23 -/** RMT_APB_MEM_RADDR_CH0 : RO; bitpos: [31:24]; default: 0; +#define RMT_APB_MEM_WR_ERR_CH1 (BIT(23)) +#define RMT_APB_MEM_WR_ERR_CH1_M (RMT_APB_MEM_WR_ERR_CH1_V << RMT_APB_MEM_WR_ERR_CH1_S) +#define RMT_APB_MEM_WR_ERR_CH1_V 0x00000001U +#define RMT_APB_MEM_WR_ERR_CH1_S 23 +/** RMT_APB_MEM_RADDR_CH1 : RO; bitpos: [31:24]; default: 0; * This register records the memory address offset when reading RAM over APB bus. */ -#define RMT_APB_MEM_RADDR_CH0 0x000000FFU -#define RMT_APB_MEM_RADDR_CH0_M (RMT_APB_MEM_RADDR_CH0_V << RMT_APB_MEM_RADDR_CH0_S) -#define RMT_APB_MEM_RADDR_CH0_V 0x000000FFU -#define RMT_APB_MEM_RADDR_CH0_S 24 +#define RMT_APB_MEM_RADDR_CH1 0x000000FFU +#define RMT_APB_MEM_RADDR_CH1_M (RMT_APB_MEM_RADDR_CH1_V << RMT_APB_MEM_RADDR_CH1_S) +#define RMT_APB_MEM_RADDR_CH1_V 0x000000FFU +#define RMT_APB_MEM_RADDR_CH1_S 24 /** RMT_CH2STATUS_REG register * Channel 2 status register @@ -708,50 +708,50 @@ extern "C" { * Channel 3 status register */ #define RMT_CH3STATUS_REG (DR_REG_RMT_BASE + 0x34) -/** RMT_MEM_WADDR_EX_CH2 : RO; bitpos: [8:0]; default: 0; +/** RMT_MEM_WADDR_EX_CH3 : RO; bitpos: [8:0]; default: 0; * This register records the memory address offset when receiver of CHANNEL3 is using * the RAM. */ -#define RMT_MEM_WADDR_EX_CH2 0x000001FFU -#define RMT_MEM_WADDR_EX_CH2_M (RMT_MEM_WADDR_EX_CH2_V << RMT_MEM_WADDR_EX_CH2_S) -#define RMT_MEM_WADDR_EX_CH2_V 0x000001FFU -#define RMT_MEM_WADDR_EX_CH2_S 0 -/** RMT_APB_MEM_RADDR_CH2 : RO; bitpos: [20:12]; default: 0; +#define RMT_MEM_WADDR_EX_CH3 0x000001FFU +#define RMT_MEM_WADDR_EX_CH3_M (RMT_MEM_WADDR_EX_CH3_V << RMT_MEM_WADDR_EX_CH3_S) +#define RMT_MEM_WADDR_EX_CH3_V 0x000001FFU +#define RMT_MEM_WADDR_EX_CH3_S 0 +/** RMT_APB_MEM_RADDR_CH3 : RO; bitpos: [20:12]; default: 0; * This register records the memory address offset when reads RAM over APB bus. */ -#define RMT_APB_MEM_RADDR_CH2 0x000001FFU -#define RMT_APB_MEM_RADDR_CH2_M (RMT_APB_MEM_RADDR_CH2_V << RMT_APB_MEM_RADDR_CH2_S) -#define RMT_APB_MEM_RADDR_CH2_V 0x000001FFU -#define RMT_APB_MEM_RADDR_CH2_S 12 -/** RMT_STATE_CH2 : RO; bitpos: [24:22]; default: 0; +#define RMT_APB_MEM_RADDR_CH3 0x000001FFU +#define RMT_APB_MEM_RADDR_CH3_M (RMT_APB_MEM_RADDR_CH3_V << RMT_APB_MEM_RADDR_CH3_S) +#define RMT_APB_MEM_RADDR_CH3_V 0x000001FFU +#define RMT_APB_MEM_RADDR_CH3_S 12 +/** RMT_STATE_CH3 : RO; bitpos: [24:22]; default: 0; * This register records the FSM status of CHANNEL3. */ -#define RMT_STATE_CH2 0x00000007U -#define RMT_STATE_CH2_M (RMT_STATE_CH2_V << RMT_STATE_CH2_S) -#define RMT_STATE_CH2_V 0x00000007U -#define RMT_STATE_CH2_S 22 -/** RMT_MEM_OWNER_ERR_CH2 : RO; bitpos: [25]; default: 0; +#define RMT_STATE_CH3 0x00000007U +#define RMT_STATE_CH3_M (RMT_STATE_CH3_V << RMT_STATE_CH3_S) +#define RMT_STATE_CH3_V 0x00000007U +#define RMT_STATE_CH3_S 22 +/** RMT_MEM_OWNER_ERR_CH3 : RO; bitpos: [25]; default: 0; * This status bit will be set when the ownership of memory block is wrong. */ -#define RMT_MEM_OWNER_ERR_CH2 (BIT(25)) -#define RMT_MEM_OWNER_ERR_CH2_M (RMT_MEM_OWNER_ERR_CH2_V << RMT_MEM_OWNER_ERR_CH2_S) -#define RMT_MEM_OWNER_ERR_CH2_V 0x00000001U -#define RMT_MEM_OWNER_ERR_CH2_S 25 -/** RMT_MEM_FULL_CH2 : RO; bitpos: [26]; default: 0; +#define RMT_MEM_OWNER_ERR_CH3 (BIT(25)) +#define RMT_MEM_OWNER_ERR_CH3_M (RMT_MEM_OWNER_ERR_CH3_V << RMT_MEM_OWNER_ERR_CH3_S) +#define RMT_MEM_OWNER_ERR_CH3_V 0x00000001U +#define RMT_MEM_OWNER_ERR_CH3_S 25 +/** RMT_MEM_FULL_CH3 : RO; bitpos: [26]; default: 0; * This status bit will be set if the receiver receives more data than the memory size. */ -#define RMT_MEM_FULL_CH2 (BIT(26)) -#define RMT_MEM_FULL_CH2_M (RMT_MEM_FULL_CH2_V << RMT_MEM_FULL_CH2_S) -#define RMT_MEM_FULL_CH2_V 0x00000001U -#define RMT_MEM_FULL_CH2_S 26 -/** RMT_APB_MEM_RD_ERR_CH2 : RO; bitpos: [27]; default: 0; +#define RMT_MEM_FULL_CH3 (BIT(26)) +#define RMT_MEM_FULL_CH3_M (RMT_MEM_FULL_CH3_V << RMT_MEM_FULL_CH3_S) +#define RMT_MEM_FULL_CH3_V 0x00000001U +#define RMT_MEM_FULL_CH3_S 26 +/** RMT_APB_MEM_RD_ERR_CH3 : RO; bitpos: [27]; default: 0; * This status bit will be set if the offset address out of memory size when reads via * APB bus. */ -#define RMT_APB_MEM_RD_ERR_CH2 (BIT(27)) -#define RMT_APB_MEM_RD_ERR_CH2_M (RMT_APB_MEM_RD_ERR_CH2_V << RMT_APB_MEM_RD_ERR_CH2_S) -#define RMT_APB_MEM_RD_ERR_CH2_V 0x00000001U -#define RMT_APB_MEM_RD_ERR_CH2_S 27 +#define RMT_APB_MEM_RD_ERR_CH3 (BIT(27)) +#define RMT_APB_MEM_RD_ERR_CH3_M (RMT_APB_MEM_RD_ERR_CH3_V << RMT_APB_MEM_RD_ERR_CH3_S) +#define RMT_APB_MEM_RD_ERR_CH3_V 0x00000001U +#define RMT_APB_MEM_RD_ERR_CH3_S 27 /** RMT_INT_RAW_REG register * Raw interrupt status @@ -786,28 +786,28 @@ extern "C" { #define RMT_CH3_RX_END_INT_RAW_V 0x00000001U #define RMT_CH3_RX_END_INT_RAW_S 3 /** RMT_CH0_ERR_INT_RAW : R/WTC/SS; bitpos: [4]; default: 0; - * The interrupt raw bit for CHANNEL$m. Triggered when error occurs. + * The interrupt raw bit for CHANNEL0. Triggered when error occurs. */ #define RMT_CH0_ERR_INT_RAW (BIT(4)) #define RMT_CH0_ERR_INT_RAW_M (RMT_CH0_ERR_INT_RAW_V << RMT_CH0_ERR_INT_RAW_S) #define RMT_CH0_ERR_INT_RAW_V 0x00000001U #define RMT_CH0_ERR_INT_RAW_S 4 /** RMT_CH1_ERR_INT_RAW : R/WTC/SS; bitpos: [5]; default: 0; - * The interrupt raw bit for CHANNEL$m. Triggered when error occurs. + * The interrupt raw bit for CHANNEL1. Triggered when error occurs. */ #define RMT_CH1_ERR_INT_RAW (BIT(5)) #define RMT_CH1_ERR_INT_RAW_M (RMT_CH1_ERR_INT_RAW_V << RMT_CH1_ERR_INT_RAW_S) #define RMT_CH1_ERR_INT_RAW_V 0x00000001U #define RMT_CH1_ERR_INT_RAW_S 5 /** RMT_CH2_ERR_INT_RAW : R/WTC/SS; bitpos: [6]; default: 0; - * The interrupt raw bit for CHANNEL$m. Triggered when error occurs. + * The interrupt raw bit for CHANNEL2. Triggered when error occurs. */ #define RMT_CH2_ERR_INT_RAW (BIT(6)) #define RMT_CH2_ERR_INT_RAW_M (RMT_CH2_ERR_INT_RAW_V << RMT_CH2_ERR_INT_RAW_S) #define RMT_CH2_ERR_INT_RAW_V 0x00000001U #define RMT_CH2_ERR_INT_RAW_S 6 /** RMT_CH3_ERR_INT_RAW : R/WTC/SS; bitpos: [7]; default: 0; - * The interrupt raw bit for CHANNEL$m. Triggered when error occurs. + * The interrupt raw bit for CHANNEL3. Triggered when error occurs. */ #define RMT_CH3_ERR_INT_RAW (BIT(7)) #define RMT_CH3_ERR_INT_RAW_M (RMT_CH3_ERR_INT_RAW_V << RMT_CH3_ERR_INT_RAW_S) @@ -1196,22 +1196,22 @@ extern "C" { * Channel 1 duty cycle configuration register */ #define RMT_CH1CARRIER_DUTY_REG (DR_REG_RMT_BASE + 0x4c) -/** RMT_CARRIER_LOW_CH0 : R/W; bitpos: [15:0]; default: 64; +/** RMT_CARRIER_LOW_CH1 : R/W; bitpos: [15:0]; default: 64; * This register is used to configure carrier wave 's low level clock period for * CHANNEL1. */ -#define RMT_CARRIER_LOW_CH0 0x0000FFFFU -#define RMT_CARRIER_LOW_CH0_M (RMT_CARRIER_LOW_CH0_V << RMT_CARRIER_LOW_CH0_S) -#define RMT_CARRIER_LOW_CH0_V 0x0000FFFFU -#define RMT_CARRIER_LOW_CH0_S 0 -/** RMT_CARRIER_HIGH_CH0 : R/W; bitpos: [31:16]; default: 64; +#define RMT_CARRIER_LOW_CH1 0x0000FFFFU +#define RMT_CARRIER_LOW_CH1_M (RMT_CARRIER_LOW_CH1_V << RMT_CARRIER_LOW_CH1_S) +#define RMT_CARRIER_LOW_CH1_V 0x0000FFFFU +#define RMT_CARRIER_LOW_CH1_S 0 +/** RMT_CARRIER_HIGH_CH1 : R/W; bitpos: [31:16]; default: 64; * This register is used to configure carrier wave 's high level clock period for * CHANNEL1. */ -#define RMT_CARRIER_HIGH_CH0 0x0000FFFFU -#define RMT_CARRIER_HIGH_CH0_M (RMT_CARRIER_HIGH_CH0_V << RMT_CARRIER_HIGH_CH0_S) -#define RMT_CARRIER_HIGH_CH0_V 0x0000FFFFU -#define RMT_CARRIER_HIGH_CH0_S 16 +#define RMT_CARRIER_HIGH_CH1 0x0000FFFFU +#define RMT_CARRIER_HIGH_CH1_M (RMT_CARRIER_HIGH_CH1_V << RMT_CARRIER_HIGH_CH1_S) +#define RMT_CARRIER_HIGH_CH1_V 0x0000FFFFU +#define RMT_CARRIER_HIGH_CH1_S 16 /** RMT_CH2_RX_CARRIER_RM_REG register * Channel 2 carrier remove register @@ -1238,22 +1238,22 @@ extern "C" { * Channel 3 carrier remove register */ #define RMT_CH3_RX_CARRIER_RM_REG (DR_REG_RMT_BASE + 0x54) -/** RMT_CARRIER_LOW_THRES_CH2 : R/W; bitpos: [15:0]; default: 0; +/** RMT_CARRIER_LOW_THRES_CH3 : R/W; bitpos: [15:0]; default: 0; * The low level period in a carrier modulation mode is * (REG_RMT_REG_CARRIER_LOW_THRES_CH3 + 1) for channel 3. */ -#define RMT_CARRIER_LOW_THRES_CH2 0x0000FFFFU -#define RMT_CARRIER_LOW_THRES_CH2_M (RMT_CARRIER_LOW_THRES_CH2_V << RMT_CARRIER_LOW_THRES_CH2_S) -#define RMT_CARRIER_LOW_THRES_CH2_V 0x0000FFFFU -#define RMT_CARRIER_LOW_THRES_CH2_S 0 -/** RMT_CARRIER_HIGH_THRES_CH2 : R/W; bitpos: [31:16]; default: 0; +#define RMT_CARRIER_LOW_THRES_CH3 0x0000FFFFU +#define RMT_CARRIER_LOW_THRES_CH3_M (RMT_CARRIER_LOW_THRES_CH3_V << RMT_CARRIER_LOW_THRES_CH3_S) +#define RMT_CARRIER_LOW_THRES_CH3_V 0x0000FFFFU +#define RMT_CARRIER_LOW_THRES_CH3_S 0 +/** RMT_CARRIER_HIGH_THRES_CH3 : R/W; bitpos: [31:16]; default: 0; * The high level period in a carrier modulation mode is * (REG_RMT_REG_CARRIER_HIGH_THRES_CH3 + 1) for channel 3. */ -#define RMT_CARRIER_HIGH_THRES_CH2 0x0000FFFFU -#define RMT_CARRIER_HIGH_THRES_CH2_M (RMT_CARRIER_HIGH_THRES_CH2_V << RMT_CARRIER_HIGH_THRES_CH2_S) -#define RMT_CARRIER_HIGH_THRES_CH2_V 0x0000FFFFU -#define RMT_CARRIER_HIGH_THRES_CH2_S 16 +#define RMT_CARRIER_HIGH_THRES_CH3 0x0000FFFFU +#define RMT_CARRIER_HIGH_THRES_CH3_M (RMT_CARRIER_HIGH_THRES_CH3_V << RMT_CARRIER_HIGH_THRES_CH3_S) +#define RMT_CARRIER_HIGH_THRES_CH3_V 0x0000FFFFU +#define RMT_CARRIER_HIGH_THRES_CH3_S 16 /** RMT_CH0_TX_LIM_REG register * Channel 0 Tx event configuration register @@ -1301,43 +1301,43 @@ extern "C" { * Channel 1 Tx event configuration register */ #define RMT_CH1_TX_LIM_REG (DR_REG_RMT_BASE + 0x5c) -/** RMT_TX_LIM_CH0 : R/W; bitpos: [8:0]; default: 128; +/** RMT_TX_LIM_CH1 : R/W; bitpos: [8:0]; default: 128; * This register is used to configure the maximum entries that CHANNEL1 can send out. */ -#define RMT_TX_LIM_CH0 0x000001FFU -#define RMT_TX_LIM_CH0_M (RMT_TX_LIM_CH0_V << RMT_TX_LIM_CH0_S) -#define RMT_TX_LIM_CH0_V 0x000001FFU -#define RMT_TX_LIM_CH0_S 0 -/** RMT_TX_LOOP_NUM_CH0 : R/W; bitpos: [18:9]; default: 0; +#define RMT_TX_LIM_CH1 0x000001FFU +#define RMT_TX_LIM_CH1_M (RMT_TX_LIM_CH1_V << RMT_TX_LIM_CH1_S) +#define RMT_TX_LIM_CH1_V 0x000001FFU +#define RMT_TX_LIM_CH1_S 0 +/** RMT_TX_LOOP_NUM_CH1 : R/W; bitpos: [18:9]; default: 0; * This register is used to configure the maximum loop count when tx_conti_mode is * valid. */ -#define RMT_TX_LOOP_NUM_CH0 0x000003FFU -#define RMT_TX_LOOP_NUM_CH0_M (RMT_TX_LOOP_NUM_CH0_V << RMT_TX_LOOP_NUM_CH0_S) -#define RMT_TX_LOOP_NUM_CH0_V 0x000003FFU -#define RMT_TX_LOOP_NUM_CH0_S 9 -/** RMT_TX_LOOP_CNT_EN_CH0 : R/W; bitpos: [19]; default: 0; +#define RMT_TX_LOOP_NUM_CH1 0x000003FFU +#define RMT_TX_LOOP_NUM_CH1_M (RMT_TX_LOOP_NUM_CH1_V << RMT_TX_LOOP_NUM_CH1_S) +#define RMT_TX_LOOP_NUM_CH1_V 0x000003FFU +#define RMT_TX_LOOP_NUM_CH1_S 9 +/** RMT_TX_LOOP_CNT_EN_CH1 : R/W; bitpos: [19]; default: 0; * This register is the enabled bit for loop count. */ -#define RMT_TX_LOOP_CNT_EN_CH0 (BIT(19)) -#define RMT_TX_LOOP_CNT_EN_CH0_M (RMT_TX_LOOP_CNT_EN_CH0_V << RMT_TX_LOOP_CNT_EN_CH0_S) -#define RMT_TX_LOOP_CNT_EN_CH0_V 0x00000001U -#define RMT_TX_LOOP_CNT_EN_CH0_S 19 -/** RMT_LOOP_COUNT_RESET_CH0 : WT; bitpos: [20]; default: 0; +#define RMT_TX_LOOP_CNT_EN_CH1 (BIT(19)) +#define RMT_TX_LOOP_CNT_EN_CH1_M (RMT_TX_LOOP_CNT_EN_CH1_V << RMT_TX_LOOP_CNT_EN_CH1_S) +#define RMT_TX_LOOP_CNT_EN_CH1_V 0x00000001U +#define RMT_TX_LOOP_CNT_EN_CH1_S 19 +/** RMT_LOOP_COUNT_RESET_CH1 : WT; bitpos: [20]; default: 0; * This register is used to reset the loop count when tx_conti_mode is valid. */ -#define RMT_LOOP_COUNT_RESET_CH0 (BIT(20)) -#define RMT_LOOP_COUNT_RESET_CH0_M (RMT_LOOP_COUNT_RESET_CH0_V << RMT_LOOP_COUNT_RESET_CH0_S) -#define RMT_LOOP_COUNT_RESET_CH0_V 0x00000001U -#define RMT_LOOP_COUNT_RESET_CH0_S 20 -/** RMT_LOOP_STOP_EN_CH0 : R/W; bitpos: [21]; default: 0; +#define RMT_LOOP_COUNT_RESET_CH1 (BIT(20)) +#define RMT_LOOP_COUNT_RESET_CH1_M (RMT_LOOP_COUNT_RESET_CH1_V << RMT_LOOP_COUNT_RESET_CH1_S) +#define RMT_LOOP_COUNT_RESET_CH1_V 0x00000001U +#define RMT_LOOP_COUNT_RESET_CH1_S 20 +/** RMT_LOOP_STOP_EN_CH1 : R/W; bitpos: [21]; default: 0; * This bit is used to enable the loop send stop function after the loop counter * counts to loop number for CHANNEL1. */ -#define RMT_LOOP_STOP_EN_CH0 (BIT(21)) -#define RMT_LOOP_STOP_EN_CH0_M (RMT_LOOP_STOP_EN_CH0_V << RMT_LOOP_STOP_EN_CH0_S) -#define RMT_LOOP_STOP_EN_CH0_V 0x00000001U -#define RMT_LOOP_STOP_EN_CH0_S 21 +#define RMT_LOOP_STOP_EN_CH1 (BIT(21)) +#define RMT_LOOP_STOP_EN_CH1_M (RMT_LOOP_STOP_EN_CH1_V << RMT_LOOP_STOP_EN_CH1_S) +#define RMT_LOOP_STOP_EN_CH1_V 0x00000001U +#define RMT_LOOP_STOP_EN_CH1_S 21 /** RMT_CH2_RX_LIM_REG register * Channel 2 Rx event configuration register diff --git a/components/soc/esp32c6/include/soc/soc_caps.h b/components/soc/esp32c6/include/soc/soc_caps.h index 92e70c7fba..e7da19ada6 100644 --- a/components/soc/esp32c6/include/soc/soc_caps.h +++ b/components/soc/esp32c6/include/soc/soc_caps.h @@ -41,7 +41,7 @@ #define SOC_RTC_FAST_MEM_SUPPORTED 1 #define SOC_RTC_MEM_SUPPORTED 1 #define SOC_I2S_SUPPORTED 1 -// #define SOC_RMT_SUPPORTED 1 // TODO: IDF-5320 +#define SOC_RMT_SUPPORTED 1 // #define SOC_SDM_SUPPORTED 1 // TODO: IDF-5318 // #define SOC_LEDC_SUPPORTED 1 // TODO: IDF-5328 // #define SOC_I2C_SUPPORTED 1 // TODO: IDF-5326 @@ -213,7 +213,6 @@ #define SOC_PCNT_THRES_POINT_PER_UNIT 2 #define SOC_PCNT_SUPPORT_RUNTIME_THRES_UPDATE 1 -// TODO: IDF-5320 (Copy from esp32c3, need check) /*--------------------------- RMT CAPS ---------------------------------------*/ #define SOC_RMT_GROUPS 1U /*!< One RMT group */ #define SOC_RMT_TX_CANDIDATES_PER_GROUP 2 /*!< Number of channels that capable of Transmit */ @@ -224,6 +223,7 @@ #define SOC_RMT_SUPPORT_RX_DEMODULATION 1 /*!< Support signal demodulation on RX path (i.e. remove carrier) */ #define SOC_RMT_SUPPORT_TX_ASYNC_STOP 1 /*!< Support stop transmission asynchronously */ #define SOC_RMT_SUPPORT_TX_LOOP_COUNT 1 /*!< Support transmit specified number of cycles in loop mode */ +#define SOC_RMT_SUPPORT_TX_LOOP_AUTO_STOP 1 /*!< Hardware support of auto-stop in loop mode */ #define SOC_RMT_SUPPORT_TX_SYNCHRO 1 /*!< Support coordinate a group of TX channels to start simultaneously */ #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 */ diff --git a/examples/peripherals/.build-test-rules.yml b/examples/peripherals/.build-test-rules.yml index 9fa2752d25..bed4e447d7 100644 --- a/examples/peripherals/.build-test-rules.yml +++ b/examples/peripherals/.build-test-rules.yml @@ -115,8 +115,8 @@ examples/peripherals/rmt/onewire_ds18b20: - if: SOC_RMT_SUPPORTED != 1 examples/peripherals/rmt/stepper_motor: - enable: - - if: SOC_RMT_SUPPORT_TX_LOOP_AUTO_STOP == 1 + disable: + - if: SOC_RMT_SUPPORT_TX_LOOP_AUTO_STOP != 1 examples/peripherals/sdio: disable: