This is an automated email from the ASF dual-hosted git repository.

xiaoxiang pushed a commit to branch master
in repository https://gitbox.apache.org/repos/asf/nuttx.git

commit e49684d7815095c5b14d05d6b36eeb79654cdb46
Author: Tiago Medicci Serrano <tiago.medi...@espressif.com>
AuthorDate: Wed Jan 31 16:07:58 2024 -0300

    risc-v/esp_<rmt|ws2812>: Implement the RMT peripheral for ESP32 RVs
    
    This commit implements the RMT peripheral for all the supported
    Espressif's RISC-V devices. It also implements the support for the
    WS2812 addressable RGB LED using the RMT peripheral.
---
 arch/risc-v/src/Makefile                           |    1 +
 arch/risc-v/src/common/espressif/Kconfig           |   10 +
 arch/risc-v/src/common/espressif/Make.defs         |    7 +
 arch/risc-v/src/common/espressif/esp_gpio.h        |   18 +
 arch/risc-v/src/common/espressif/esp_rmt.c         | 1944 ++++++++++++++++++++
 .../risc-v/src/common/espressif/esp_rmt.h          |   66 +-
 arch/risc-v/src/common/espressif/esp_ws2812.c      |  667 +++++++
 arch/risc-v/src/common/espressif/esp_ws2812.h      |  100 +
 arch/risc-v/src/esp32c3/hal_esp32c3.mk             |    2 +
 arch/risc-v/src/esp32c6/hal_esp32c6.mk             |    2 +
 arch/risc-v/src/esp32h2/hal_esp32h2.mk             |    2 +
 .../include/esp_board_rmt.h}                       |   60 +-
 boards/risc-v/esp32c3/common/src/Make.defs         |    4 +
 boards/risc-v/esp32c3/common/src/esp_board_rmt.c   |  150 ++
 .../esp32c3/esp32c3-generic/configs/rmt/defconfig  |   59 +
 .../esp32c3/esp32c3-generic/src/esp32c3-generic.h  |   13 +
 .../esp32c3/esp32c3-generic/src/esp32c3_bringup.c  |   18 +
 .../common/include/esp_board_rmt.h}                |   60 +-
 boards/risc-v/esp32c6/common/src/Make.defs         |    4 +
 boards/risc-v/esp32c6/common/src/esp_board_rmt.c   |  150 ++
 .../esp32c6/esp32c6-devkit/configs/rmt/defconfig   |   59 +
 .../esp32c6/esp32c6-devkit/src/esp32c6-devkit.h    |   13 +
 .../esp32c6/esp32c6-devkit/src/esp32c6_bringup.c   |   18 +
 .../common/include/esp_board_rmt.h}                |   60 +-
 boards/risc-v/esp32h2/common/src/Make.defs         |    4 +
 boards/risc-v/esp32h2/common/src/esp_board_rmt.c   |  150 ++
 .../esp32h2/esp32h2-devkit/configs/rmt/defconfig   |   59 +
 .../esp32h2/esp32h2-devkit/src/esp32h2-devkit.h    |   13 +
 .../esp32h2/esp32h2-devkit/src/esp32h2_bringup.c   |   18 +
 29 files changed, 3634 insertions(+), 97 deletions(-)

diff --git a/arch/risc-v/src/Makefile b/arch/risc-v/src/Makefile
index 11914e50c8..76ffe125aa 100644
--- a/arch/risc-v/src/Makefile
+++ b/arch/risc-v/src/Makefile
@@ -130,6 +130,7 @@ endif
 
 VPATH += chip
 VPATH += common
+VPATH += common/espressif
 VPATH += $(SBI_DIR)
 VPATH += $(ARCH_SUBDIR)
 VPATH += $(CHIP_DIR)
diff --git a/arch/risc-v/src/common/espressif/Kconfig 
b/arch/risc-v/src/common/espressif/Kconfig
index 4edb6fae25..c5aa9cc0d0 100644
--- a/arch/risc-v/src/common/espressif/Kconfig
+++ b/arch/risc-v/src/common/espressif/Kconfig
@@ -298,6 +298,16 @@ config ESPRESSIF_BROWNOUT_DET
                than a specific value. If this happens, it will reset the chip 
in
                order to prevent unintended behaviour.
 
+config ESP_RMT
+       bool "Remote Control Module (RMT)"
+       default n
+       depends on RMT
+       ---help---
+               The RMT (Remote Control Transceiver) peripheral was designed to 
act as
+               an infrared transceiver. However, due to the flexibility of its 
data
+               format, RMT can be extended to a versatile and general-purpose
+               transceiver, transmitting or receiving many other types of 
signals.
+
 endmenu # Peripheral Support
 
 menu "UART Configuration"
diff --git a/arch/risc-v/src/common/espressif/Make.defs 
b/arch/risc-v/src/common/espressif/Make.defs
index 6e5d445c1b..48710e581b 100644
--- a/arch/risc-v/src/common/espressif/Make.defs
+++ b/arch/risc-v/src/common/espressif/Make.defs
@@ -73,6 +73,13 @@ ifeq ($(CONFIG_ESPRESSIF_USBSERIAL),y)
   CHIP_CSRCS += esp_usbserial.c
 endif
 
+ifeq ($(CONFIG_ESP_RMT),y)
+  CHIP_CSRCS += esp_rmt.c
+  ifeq ($(CONFIG_WS2812_NON_SPI_DRIVER),y)
+    CHIP_CSRCS += esp_ws2812.c
+  endif
+endif
+
 #############################################################################
 # Espressif HAL for 3rd Party Platforms
 #############################################################################
diff --git a/arch/risc-v/src/common/espressif/esp_gpio.h 
b/arch/risc-v/src/common/espressif/esp_gpio.h
index 05152584e7..6c9651e591 100644
--- a/arch/risc-v/src/common/espressif/esp_gpio.h
+++ b/arch/risc-v/src/common/espressif/esp_gpio.h
@@ -98,6 +98,24 @@
 #define ONLOW             0x04
 #define ONHIGH            0x05
 
+/* Check whether it is a valid GPIO number */
+
+#define GPIO_IS_VALID_GPIO(gpio_num)   ((gpio_num >= 0) && \
+                                        (((1ULL << (gpio_num)) & \
+                                         SOC_GPIO_VALID_GPIO_MASK) != 0))
+
+/* Check whether it can be a valid GPIO number of output mode */
+
+#define GPIO_IS_VALID_OUTPUT_GPIO(gpio_num) \
+  ((gpio_num >= 0) && \
+      (((1ULL << (gpio_num)) & SOC_GPIO_VALID_OUTPUT_GPIO_MASK) != 0))
+
+/* Check whether it can be a valid digital I/O pad */
+
+#define GPIO_IS_VALID_DIGITAL_IO_PAD(gpio_num) \
+  ((gpio_num >= 0) && \
+    (((1ULL << (gpio_num)) & SOC_GPIO_VALID_DIGITAL_IO_PAD_MASK) != 0))
+
 /****************************************************************************
  * Public Types
  ****************************************************************************/
diff --git a/arch/risc-v/src/common/espressif/esp_rmt.c 
b/arch/risc-v/src/common/espressif/esp_rmt.c
new file mode 100644
index 0000000000..45e603d8ef
--- /dev/null
+++ b/arch/risc-v/src/common/espressif/esp_rmt.c
@@ -0,0 +1,1944 @@
+/****************************************************************************
+ * arch/risc-v/src/common/espressif/esp_rmt.c
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdio.h>
+#include <sys/types.h>
+#include <inttypes.h>
+#include <stdint.h>
+#include <stdbool.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/kmalloc.h>
+#include <arch/board/board.h>
+#include <nuttx/irq.h>
+#include <nuttx/arch.h>
+#include <nuttx/rmt/rmt.h>
+#include <nuttx/spinlock.h>
+#include <nuttx/mm/circbuf.h>
+
+#include "esp_gpio.h"
+#include "esp_irq.h"
+
+#include "esp_attr.h"
+#include "hal/gpio_types.h"
+#include "hal/rmt_hal.h"
+#include "hal/rmt_ll.h"
+#include "periph_ctrl.h"
+#include "soc/gpio_sig_map.h"
+#include "soc/rmt_periph.h"
+#include "soc/soc_caps.h"
+#include "esp_clk_tree.h"
+
+#include "esp_rmt.h"
+
+#ifdef CONFIG_ESP_RMT
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define RMT_RX_CHANNEL_ENCODING_START \
+  (SOC_RMT_CHANNELS_PER_GROUP-SOC_RMT_TX_CANDIDATES_PER_GROUP)
+#define RMT_TX_CHANNEL_ENCODING_END   (SOC_RMT_TX_CANDIDATES_PER_GROUP-1)
+
+#define RMT_IS_RX_CHANNEL(channel)  \
+  ((channel) >= RMT_RX_CHANNEL_ENCODING_START)
+#define RMT_IS_TX_CHANNEL(channel)  \
+  ((channel) <= RMT_TX_CHANNEL_ENCODING_END)
+#define RMT_DECODE_RX_CHANNEL(encode_chan)  \
+  ((encode_chan - RMT_RX_CHANNEL_ENCODING_START))
+#define RMT_ENCODE_RX_CHANNEL(decode_chan)  \
+  ((decode_chan + RMT_RX_CHANNEL_ENCODING_START))
+
+/* Default configuration for TX channel */
+
+#define RMT_DEFAULT_CONFIG_TX(gpio, channel_id)     \
+  {                                                 \
+    .rmt_mode = RMT_MODE_TX,                        \
+    .channel = channel_id,                          \
+    .gpio_num = gpio,                               \
+    .clk_div = RMT_DEFAULT_CLK_DIV,                 \
+    .mem_block_num = 1,                             \
+    .flags = 0,                                     \
+    .tx_config = {                                  \
+        .carrier_freq_hz = 38000,                   \
+        .carrier_level = RMT_CARRIER_LEVEL_HIGH,    \
+        .idle_level = RMT_IDLE_LEVEL_LOW,           \
+        .carrier_duty_percent = 33,                 \
+        .loop_count = 0,                            \
+        .carrier_en = false,                        \
+        .loop_en = false,                           \
+        .idle_output_en = true,                     \
+    }                                               \
+  }
+
+/* Default configuration for RX channel */
+
+#define RMT_DEFAULT_CONFIG_RX(gpio, channel_id)   \
+  {                                               \
+      .rmt_mode = RMT_MODE_RX,                    \
+      .channel = channel_id,                      \
+      .gpio_num = gpio,                           \
+      .clk_div = RMT_DEFAULT_CLK_DIV,             \
+      .mem_block_num = 1,                         \
+      .flags = 0,                                 \
+      .rx_config = {                              \
+          .idle_threshold = 12000,                \
+          .filter_ticks_thresh = 100,             \
+          .filter_en = true,                      \
+      }                                           \
+  }
+
+#define rmt_item32_t rmt_symbol_word_t
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/* RMT channel ID */
+
+enum rmt_channel_e
+{
+  RMT_CHANNEL_0,  /* RMT channel number 0 */
+  RMT_CHANNEL_1,  /* RMT channel number 1 */
+  RMT_CHANNEL_2,  /* RMT channel number 2 */
+  RMT_CHANNEL_3,  /* RMT channel number 3 */
+#if SOC_RMT_CHANNELS_PER_GROUP > 4
+  RMT_CHANNEL_4,  /* RMT channel number 4 */
+  RMT_CHANNEL_5,  /* RMT channel number 5 */
+  RMT_CHANNEL_6,  /* RMT channel number 6 */
+  RMT_CHANNEL_7,  /* RMT channel number 7 */
+#endif
+  RMT_CHANNEL_MAX /* Number of RMT channels */
+};
+
+typedef enum rmt_channel_e rmt_channel_t;
+
+/* RMT Channel Working Mode (TX or RX) */
+
+enum rmt_mode_e
+{
+  RMT_MODE_TX, /* RMT TX mode */
+  RMT_MODE_RX, /* RMT RX mode */
+  RMT_MODE_MAX
+};
+
+typedef enum rmt_mode_e rmt_mode_t;
+
+/* RMT Idle Level */
+
+enum rmt_idle_level_e
+{
+  RMT_IDLE_LEVEL_LOW,  /* RMT TX idle level: low Level */
+  RMT_IDLE_LEVEL_HIGH, /* RMT TX idle level: high Level */
+  RMT_IDLE_LEVEL_MAX,
+};
+
+typedef enum rmt_idle_level_e rmt_idle_level_t;
+
+/* RMT Carrier Level */
+
+enum rmt_carrier_level_e
+{
+  RMT_CARRIER_LEVEL_LOW,  /* RMT carrier wave is modulated for low Level 
output */
+  RMT_CARRIER_LEVEL_HIGH, /* RMT carrier wave is modulated for high Level 
output */
+  RMT_CARRIER_LEVEL_MAX
+};
+
+typedef enum rmt_carrier_level_e rmt_carrier_level_t;
+
+/* RMT Channel Status */
+
+enum rmt_channel_status_e
+{
+  RMT_CHANNEL_UNINIT, /* RMT channel uninitialized */
+  RMT_CHANNEL_IDLE,   /* RMT channel status idle */
+  RMT_CHANNEL_BUSY,   /* RMT channel status busy */
+};
+
+typedef enum rmt_channel_status_e rmt_channel_status_t;
+
+/* RMT hardware memory layout */
+
+struct rmt_channel_data_s
+{
+  volatile rmt_item32_t data32[SOC_RMT_MEM_WORDS_PER_CHANNEL];
+};
+
+struct rmt_mem_s
+{
+  struct rmt_channel_data_s chan[SOC_RMT_CHANNELS_PER_GROUP];
+};
+
+typedef struct rmt_mem_s rmt_mem_t;
+
+struct rmt_dev_common_s
+{
+  rmt_hal_context_t hal;          /* HAL context */
+  rmutex_t rmt_driver_isr_lock;
+
+  /* Mutex lock for protecting concurrent register/unregister of the RMT
+   * channels' ISR.
+   */
+
+  spinlock_t rmt_spinlock;
+
+  /* Bitmask of installed drivers' channels, used to protect concurrent
+   * register/unregister of the RMT channels' ISR.
+   */
+
+  uint8_t rmt_driver_channels;
+  bool rmt_module_enabled;
+
+  /* Bitmap of channels already added in the synchronous group */
+
+  uint32_t synchro_channel_mask;
+};
+
+struct rmt_dev_lowerhalf_s
+{
+  /* The following block is part of the upper-hald device struct */
+
+  FAR const struct rmt_ops_s *ops;
+  FAR struct circbuf_s       *circbuf;
+  sem_t                      *recvsem;
+  int                         minor;
+
+  /* The following is private to the ESP32 RMT driver */
+
+  rmt_mode_t               mode;
+  struct rmt_dev_common_s *common; /* RMT peripheral common parameters */
+};
+
+struct rmt_obj_s
+{
+  size_t tx_offset;
+  size_t tx_len_rem;
+  size_t tx_sub_len;
+  bool wait_done;     /* Mark whether wait tx done */
+  bool loop_autostop; /* mark whether loop auto-stop is enabled */
+  rmt_channel_t channel;
+  const rmt_item32_t *tx_data;
+  sem_t tx_sem;
+#if CONFIG_SPIRAM_USE_MALLOC
+  int intr_alloc_flags;
+  sem_t tx_sem_buffer;
+#endif
+  rmt_item32_t *tx_buf;
+  struct circbuf_s rx_buf;
+  sem_t rx_sem;
+#if SOC_RMT_SUPPORT_RX_PINGPONG
+  rmt_item32_t *rx_item_buf;
+  uint32_t rx_item_buf_size;
+  uint32_t rx_item_len;
+  int rx_item_start_idx;
+#endif
+  void *tx_context;
+  size_t sample_size_remain;
+  const uint8_t *sample_cur;
+};
+
+typedef struct rmt_obj_s rmt_obj_t;
+
+/* Data struct of RMT TX configure parameters */
+
+struct rmt_tx_config_s
+{
+  uint32_t carrier_freq_hz;           /* RMT carrier frequency */
+  rmt_carrier_level_t carrier_level;  /* Level of the RMT output, when the 
carrier is applied */
+  rmt_idle_level_t idle_level;        /* RMT idle level */
+  uint8_t carrier_duty_percent;       /* RMT carrier duty (%) */
+  uint32_t loop_count;                /* Maximum loop count, only take effect 
for chips that is capable of `SOC_RMT_SUPPORT_TX_LOOP_COUNT` */
+  bool carrier_en;                    /* RMT carrier enable */
+  bool loop_en;                       /* Enable sending RMT items in a loop */
+  bool idle_output_en;                /* RMT idle level output enable */
+};
+
+/* Data struct of RMT RX configure parameters */
+
+struct rmt_rx_config_s
+{
+  uint16_t idle_threshold;            /* RMT RX idle threshold */
+  uint8_t filter_ticks_thresh;        /* RMT filter tick number */
+  bool filter_en;                     /* RMT receiver filter enable */
+#if SOC_RMT_SUPPORT_RX_DEMODULATION
+  bool rm_carrier;                    /* RMT receiver remove carrier enable */
+  uint32_t carrier_freq_hz;           /* RMT carrier frequency */
+  uint8_t carrier_duty_percent;       /* RMT carrier duty (%) */
+  rmt_carrier_level_t carrier_level;  /* The level to remove the carrier */
+#endif
+};
+
+struct rmt_channel_config_s
+{
+  rmt_mode_t rmt_mode;   /* RMT mode: transmitter or receiver */
+  rmt_channel_t channel; /* RMT channel */
+  int gpio_num;          /* RMT GPIO number */
+  uint8_t clk_div;       /* RMT channel counter divider */
+  uint8_t mem_block_num; /* RMT memory block number */
+  uint32_t flags;        /* RMT channel extra configurations, OR'd with 
RMT_CHANNEL_FLAGS_[*] */
+  union
+    {
+      struct rmt_tx_config_s tx_config; /* RMT TX parameter */
+      struct rmt_rx_config_s rx_config; /* RMT RX parameter */
+    };
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static void rmt_module_enable(void);
+static int rmt_rx_start(rmt_channel_t channel, bool rx_idx_rst);
+static int rmt_tx_start(rmt_channel_t channel, bool tx_idx_rst);
+static int rmt_set_tx_loop_mode(rmt_channel_t channel, bool loop_en);
+static int rmt_set_tx_thr_intr_en(rmt_channel_t channel, bool en,
+                                  uint16_t evt_thresh);
+static int rmt_set_gpio(rmt_channel_t channel, rmt_mode_t mode,
+                        gpio_num_t gpio_num, bool invert_signal);
+static bool rmt_is_channel_number_valid(rmt_channel_t channel, uint8_t mode);
+static int rmt_internal_config(rmt_dev_t *dev,
+                               const struct rmt_channel_config_s *rmt_param);
+static int rmt_config(const struct rmt_channel_config_s *rmt_param);
+static void rmt_fill_memory(rmt_channel_t channel, const rmt_item32_t *item,
+                            uint16_t item_num, uint16_t mem_offset);
+static int rmt_isr_register(int (*fn)(int, void *, void *), void *arg,
+                            int intr_alloc_flags);
+static int rmt_driver_isr_default(int irq, void *context, void *arg);
+static int rmt_driver_install(rmt_channel_t channel, size_t rx_buf_size,
+                              int intr_alloc_flags);
+static int rmt_write_items(rmt_channel_t channel,
+                           const rmt_item32_t *rmt_item,
+                           int item_num,
+                           bool wait_tx_done);
+static ssize_t esp_rmt_read(struct rmt_dev_s *dev, char *buffer,
+                            size_t buflen);
+static ssize_t esp_rmt_write(FAR struct rmt_dev_s *dev,
+                             FAR const char *buffer,
+                             size_t buflen);
+static struct rmt_dev_s
+    *esp_rmtinitialize(struct rmt_channel_config_s config);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const struct rmt_ops_s g_rmtops =
+{
+  .read = esp_rmt_read,
+  .write = esp_rmt_write,
+};
+
+static struct rmt_dev_common_s g_rmtdev_common =
+{
+  .hal.regs = &RMT,
+  .rmt_driver_isr_lock = NXRMUTEX_INITIALIZER,
+  .rmt_driver_channels = 0,
+  .rmt_module_enabled = false,
+  .synchro_channel_mask = 0
+};
+
+static struct rmt_obj_s *p_rmt_obj[RMT_CHANNEL_MAX];
+
+#ifdef CONFIG_RMT_LOOP_TEST_MODE
+static rmt_channel_t g_tx_channel = RMT_CHANNEL_MAX;
+static rmt_channel_t g_rx_channel = RMT_CHANNEL_MAX;
+#endif
+
+#if SOC_RMT_CHANNEL_CLK_INDEPENDENT
+uint32_t g_rmt_source_clock_hz[RMT_CHANNEL_MAX];
+#else
+uint32_t g_rmt_source_clock_hz;
+#endif
+
+/* RMTMEM address is declared in <target>.peripherals.ld */
+
+extern rmt_mem_t RMTMEM;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: rmt_module_enable
+ *
+ * Description:
+ *   This function enables the RMT (Remote Control) module if it's not
+ *   already enabled.
+ *
+ * Input Parameters:
+ *   None.
+ *
+ * Returned Value:
+ *   None.
+ *
+ ****************************************************************************/
+
+static void rmt_module_enable(void)
+{
+  irqstate_t flags;
+
+  flags = spin_lock_irqsave(g_rmtdev_common.rmt_spinlock);
+
+  if (g_rmtdev_common.rmt_module_enabled == false)
+    {
+      periph_module_reset(rmt_periph_signals.groups[0].module);
+      periph_module_enable(rmt_periph_signals.groups[0].module);
+      g_rmtdev_common.rmt_module_enabled = true;
+    }
+
+  spin_unlock_irqrestore(&g_rmtdev_common.rmt_spinlock, flags);
+}
+
+/****************************************************************************
+ * Name: rmt_set_rx_thr_intr_en
+ *
+ * Description:
+ *   This function enables or disables the RMT RX threshold interrupt. When
+ *   the number of received items reaches the threshold, an interrupt is
+ *   triggered if this feature is enabled.
+ *
+ * Input Parameters:
+ *   channel    - The RMT channel.
+ *   en         - Enable (true) or disable (false) the RX threshold int.
+ *   evt_thresh - The number of received items that triggers the interrupt.
+ *
+ * Returned Value:
+ *   Returns 0 on success; a negated errno value is returned on any failure.
+ *
+ ****************************************************************************/
+
+#if SOC_RMT_SUPPORT_RX_PINGPONG
+static int rmt_set_rx_thr_intr_en(rmt_channel_t channel, bool en,
+                                  uint16_t evt_thresh)
+{
+  irqstate_t flags;
+  uint32_t mask;
+
+  DEBUGASSERT(RMT_IS_RX_CHANNEL(channel) && channel < RMT_CHANNEL_MAX);
+
+  if (en)
+    {
+      uint32_t item_block_len =
+          rmt_ll_rx_get_mem_blocks(g_rmtdev_common.hal.regs,
+              RMT_DECODE_RX_CHANNEL(channel)) * RMT_MEM_ITEM_NUM;
+
+      if (evt_thresh >= item_block_len)
+        {
+          rmterr("Invalid threshold value %d\n", evt_thresh);
+          return -EINVAL;
+        }
+
+      flags = spin_lock_irqsave(g_rmtdev_common.rmt_spinlock);
+      rmt_ll_rx_set_limit(g_rmtdev_common.hal.regs,
+                          RMT_DECODE_RX_CHANNEL(channel), evt_thresh);
+      mask = RMT_LL_EVENT_RX_THRES(RMT_DECODE_RX_CHANNEL(channel));
+      rmt_ll_enable_interrupt(g_rmtdev_common.hal.regs, mask, true);
+      spin_unlock_irqrestore(&g_rmtdev_common.rmt_spinlock, flags);
+    }
+  else
+    {
+      flags = spin_lock_irqsave(g_rmtdev_common.rmt_spinlock);
+      mask = RMT_LL_EVENT_RX_THRES(RMT_DECODE_RX_CHANNEL(channel));
+      rmt_ll_enable_interrupt(g_rmtdev_common.hal.regs, mask, false);
+      spin_unlock_irqrestore(&g_rmtdev_common.rmt_spinlock, flags);
+    }
+
+  return OK;
+}
+#endif
+
+/****************************************************************************
+ * Name: rmt_rx_start
+ *
+ * Description:
+ *   This function starts the RMT module in receiving mode for a specific
+ *   channel.
+ *
+ * Input Parameters:
+ *   channel    - The RMT peripheral channel number.
+ *   rx_idx_rst - If true, the RX index for the channel is reset, which means
+ *                the receiving process will start from the beginning of the
+ *                RMT memory block.
+ *
+ * Returned Value:
+ *   Returns OK on successful start of the RMT module in receiving mode; a
+ *   negated errno value is returned on any failure.
+ *
+ ****************************************************************************/
+
+static int rmt_rx_start(rmt_channel_t channel, bool rx_idx_rst)
+{
+  irqstate_t flags;
+  rmt_channel_t ch = RMT_DECODE_RX_CHANNEL(channel);
+#if SOC_RMT_SUPPORT_RX_PINGPONG
+  const uint32_t item_block_len =
+    rmt_ll_rx_get_mem_blocks(g_rmtdev_common.hal.regs, ch) *
+    RMT_MEM_ITEM_NUM;
+#endif
+
+  DEBUGASSERT(RMT_IS_RX_CHANNEL(channel));
+
+  flags = spin_lock_irqsave(g_rmtdev_common.rmt_spinlock);
+
+  rmt_ll_rx_enable(g_rmtdev_common.hal.regs, ch, false);
+  if (rx_idx_rst)
+    {
+      rmt_ll_rx_reset_pointer(g_rmtdev_common.hal.regs, ch);
+    }
+
+  rmt_ll_clear_interrupt_status(g_rmtdev_common.hal.regs,
+                                RMT_LL_EVENT_RX_DONE(ch));
+  rmt_ll_enable_interrupt(g_rmtdev_common.hal.regs,
+                          RMT_LL_EVENT_RX_DONE(ch), true);
+
+#if SOC_RMT_SUPPORT_RX_PINGPONG
+  p_rmt_obj[channel]->rx_item_start_idx = 0;
+  p_rmt_obj[channel]->rx_item_len = 0;
+  rmt_set_rx_thr_intr_en(channel, true, item_block_len / 2);
+#endif
+
+  rmt_ll_rx_enable(g_rmtdev_common.hal.regs, ch, true);
+
+  spin_unlock_irqrestore(&g_rmtdev_common.rmt_spinlock, flags);
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: rmt_tx_start
+ *
+ * Description:
+ *   This function starts sending RMT items from the specific channel.
+ *
+ * Input Parameters:
+ *   channel    - The RMT peripheral channel number.
+ *   tx_idx_rst - Set it true to reset memory index for TX.
+ *
+ * Returned Value:
+ *   Returns OK on successful start of transmission.
+ *
+ ****************************************************************************/
+
+static int rmt_tx_start(rmt_channel_t channel, bool tx_idx_rst)
+{
+  irqstate_t flags;
+
+  DEBUGASSERT(RMT_IS_TX_CHANNEL(channel));
+
+  flags = spin_lock_irqsave(g_rmtdev_common.rmt_spinlock);
+  if (tx_idx_rst)
+    {
+      rmt_ll_tx_reset_pointer(g_rmtdev_common.hal.regs, channel);
+    }
+
+  rmt_ll_clear_interrupt_status(g_rmtdev_common.hal.regs,
+                                RMT_LL_EVENT_TX_DONE(channel));
+
+  /* enable tx end interrupt in non-loop mode */
+
+  if (!rmt_ll_tx_is_loop_enabled(g_rmtdev_common.hal.regs, channel))
+    {
+      rmt_ll_enable_interrupt(g_rmtdev_common.hal.regs,
+                              RMT_LL_EVENT_TX_DONE(channel), true);
+    }
+  else
+    {
+#if SOC_RMT_SUPPORT_TX_LOOP_COUNT
+      rmt_ll_tx_reset_loop_count(g_rmtdev_common.hal.regs, channel);
+      rmt_ll_tx_enable_loop_count(g_rmtdev_common.hal.regs, channel, true);
+      rmt_ll_clear_interrupt_status(g_rmtdev_common.hal.regs,
+                                    RMT_LL_EVENT_TX_LOOP_END(channel));
+      rmt_ll_enable_interrupt(g_rmtdev_common.hal.regs,
+                              RMT_LL_EVENT_TX_LOOP_END(channel), true);
+#endif
+    }
+
+  rmt_ll_tx_start(g_rmtdev_common.hal.regs, channel);
+  spin_unlock_irqrestore(&g_rmtdev_common.rmt_spinlock, flags);
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: rmt_set_tx_loop_mode
+ *
+ * Description:
+ *   This function enables or disables the loop mode for RMT transmission on
+ *   the specified channel. The loop mode, when enabled, allows the RMT
+ *   transmitter to continuously send items.
+ *
+ * Input Parameters:
+ *   channel - The RMT peripheral channel number.
+ *   loop_en - A boolean indicating whether to enable (true) or disable
+ *             (false) the loop mode.
+ *
+ * Returned Value:
+ *   Returns OK on successful setting of the loop mode.
+ *
+ ****************************************************************************/
+
+static int rmt_set_tx_loop_mode(rmt_channel_t channel, bool loop_en)
+{
+  irqstate_t flags;
+
+  DEBUGASSERT(RMT_IS_TX_CHANNEL(channel));
+
+  flags = spin_lock_irqsave(g_rmtdev_common.rmt_spinlock);
+  rmt_ll_tx_enable_loop(g_rmtdev_common.hal.regs, channel, loop_en);
+  spin_unlock_irqrestore(&g_rmtdev_common.rmt_spinlock, flags);
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: rmt_set_tx_thr_intr_en
+ *
+ * Description:
+ *   This function enables or disables the RMT TX threshold interrupt for the
+ *   specified channel. The threshold is set to trigger an interrupt when the
+ *   number of transmitted items reaches the specified value.
+ *
+ * Input Parameters:
+ *   channel    - The RMT peripheral channel number.
+ *   en         - A boolean indicating whether to enable (true) or disable
+ *                (false) the TX threshold interrupt.
+ *   evt_thresh - The number of transmitted items at which to trigger the
+ *                interrupt.
+ *
+ * Returned Value:
+ *   Returns OK on successful setting of the interrupt.
+ *
+ ****************************************************************************/
+
+static int rmt_set_tx_thr_intr_en(rmt_channel_t channel, bool en,
+                                  uint16_t evt_thresh)
+{
+  irqstate_t flags;
+
+  DEBUGASSERT(RMT_IS_TX_CHANNEL(channel));
+
+  if (en)
+    {
+      uint32_t item_block_len =
+          rmt_ll_tx_get_mem_blocks(g_rmtdev_common.hal.regs, channel) * \
+          RMT_MEM_ITEM_NUM;
+
+      DEBUGASSERT(evt_thresh <= item_block_len);
+
+      flags = spin_lock_irqsave(g_rmtdev_common.rmt_spinlock);
+      rmt_ll_tx_set_limit(g_rmtdev_common.hal.regs, channel, evt_thresh);
+      rmt_ll_enable_interrupt(g_rmtdev_common.hal.regs,
+                              RMT_LL_EVENT_TX_THRES(channel), true);
+      spin_unlock_irqrestore(&g_rmtdev_common.rmt_spinlock, flags);
+    }
+  else
+    {
+      flags = spin_lock_irqsave(g_rmtdev_common.rmt_spinlock);
+      rmt_ll_enable_interrupt(g_rmtdev_common.hal.regs,
+                              RMT_LL_EVENT_TX_THRES(channel), false);
+      spin_unlock_irqrestore(&g_rmtdev_common.rmt_spinlock, flags);
+    }
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: rmt_set_gpio
+ *
+ * Description:
+ *   This function configures the GPIO for the specified RMT (Remote Control)
+ *   channel and mode. It sets the GPIO to the appropriate input or output
+ *   function based on the mode, and configures the signal inversion if
+ *   necessary.
+ *
+ * Input Parameters:
+ *   channel       - The RMT peripheral channel number.
+ *   mode          - The mode of operation for the RMT channel (RMT_MODE_TX
+ *                   for transmission, RMT_MODE_RX for reception).
+ *   gpio_num      - The GPIO number to configure for the RMT channel.
+ *   invert_signal - A boolean indicating whether to invert the signal.
+ *
+ * Returned Value:
+ *   Returns OK on successful configuration of the GPIO.
+ *
+ ****************************************************************************/
+
+static int rmt_set_gpio(rmt_channel_t channel, rmt_mode_t mode,
+                        gpio_num_t gpio_num, bool invert_signal)
+{
+  int ret;
+
+  DEBUGASSERT(channel < RMT_CHANNEL_MAX);
+  DEBUGASSERT(mode < RMT_MODE_MAX);
+  DEBUGASSERT((GPIO_IS_VALID_GPIO(gpio_num) && (mode == RMT_MODE_RX)) ||
+              (GPIO_IS_VALID_OUTPUT_GPIO(gpio_num) &&
+               (mode == RMT_MODE_TX)));
+
+  if (mode == RMT_MODE_TX)
+    {
+      DEBUGASSERT(RMT_IS_TX_CHANNEL(channel));
+      esp_configgpio(gpio_num, OUTPUT);
+      esp_gpio_matrix_out(
+        gpio_num,
+        rmt_periph_signals.groups[0].channels[channel].tx_sig,
+        invert_signal, 0);
+    }
+  else
+    {
+      DEBUGASSERT(RMT_IS_RX_CHANNEL(channel));
+      esp_configgpio(gpio_num, INPUT);
+      esp_gpio_matrix_in(
+        gpio_num,
+        rmt_periph_signals.groups[0].channels[channel].rx_sig,
+        invert_signal);
+    }
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: rmt_is_channel_number_valid
+ *
+ * Description:
+ *   This function checks if the provided RMT channel number is valid for the
+ *   specified mode (TX or RX). For RX mode, it checks if the channel number
+ *   is within the range of valid RX channels and less than the maximum
+ *   channel number. For TX mode, it checks if the channel number is a valid
+ *   TX channel.
+ *
+ * Input Parameters:
+ *   channel - The RMT peripheral channel number.
+ *   mode    - The mode of operation for the RMT channel (RMT_MODE_TX for
+ *             transmission, RMT_MODE_RX for reception).
+ *
+ * Returned Value:
+ *   Returns true if the channel number is valid, false otherwise.
+ *
+ ****************************************************************************/
+
+static bool rmt_is_channel_number_valid(rmt_channel_t channel, uint8_t mode)
+{
+  if (mode == RMT_MODE_RX)
+    {
+      return RMT_IS_RX_CHANNEL(channel) && (channel < RMT_CHANNEL_MAX);
+    }
+
+  return (channel >= 0) && RMT_IS_TX_CHANNEL(channel);
+}
+
+/****************************************************************************
+ * Name: rmt_internal_config
+ *
+ * Description:
+ *   This function configures the RMT peripheral with provided parameters.
+ *   It sets the mode (TX or RX), channel, GPIO number, memory block number,
+ *   clock divider, carrier frequency, and carrier enable flag. It also
+ *   configures the clock source, memory access, idle level, carrier
+ *   modulation, and other settings based on the mode and parameters.
+ *
+ * Input Parameters:
+ *   dev       - Pointer to the RMT peripheral device structure.
+ *   rmt_param - Pointer to the structure containing the RMT channel
+ *               configuration parameters.
+ *
+ * Returned Value:
+ *   Returns OK on successful configuration of the RMT peripheral.
+ *
+ ****************************************************************************/
+
+static int rmt_internal_config(rmt_dev_t *dev,
+                               const struct rmt_channel_config_s *rmt_param)
+{
+  uint8_t mode = rmt_param->rmt_mode;
+  uint8_t channel = rmt_param->channel;
+  uint8_t gpio_num = rmt_param->gpio_num;
+  uint8_t mem_cnt = rmt_param->mem_block_num;
+  uint8_t clk_div = rmt_param->clk_div;
+  uint32_t carrier_freq_hz = rmt_param->tx_config.carrier_freq_hz;
+  bool carrier_en = rmt_param->tx_config.carrier_en;
+  uint32_t rmt_source_clk_hz;
+  irqstate_t flags;
+
+  if (!rmt_is_channel_number_valid(channel, mode))
+    {
+      rmterr("Invalid channel number %u for %s mode!",
+             channel, mode == RMT_MODE_TX ? "transmitter" : "receiver");
+      return -EINVAL;
+    }
+
+  DEBUGASSERT(mem_cnt + channel <= SOC_RMT_CHANNELS_PER_GROUP &&
+              mem_cnt > 0);
+  DEBUGASSERT(clk_div > 0);
+
+  if (mode == RMT_MODE_TX && carrier_en && carrier_freq_hz <= 0)
+    {
+      return -EINVAL;
+    }
+
+  flags = spin_lock_irqsave(g_rmtdev_common.rmt_spinlock);
+
+  rmt_ll_enable_mem_access_nonfifo(dev, true);
+
+  if (rmt_param->flags & RMT_CHANNEL_FLAGS_AWARE_DFS)
+    {
+#if SOC_RMT_SUPPORT_XTAL
+
+      /* clock src: XTAL_CLK */
+
+      esp_clk_tree_src_get_freq_hz((soc_module_clk_t)RMT_BASECLK_XTAL,
+                                   ESP_CLK_TREE_SRC_FREQ_PRECISION_CACHED,
+                                   &rmt_source_clk_hz);
+      rmt_ll_set_group_clock_src(dev, channel,
+                                 (rmt_clock_source_t)RMT_BASECLK_XTAL,
+                                 1, 0, 0);
+#elif SOC_RMT_SUPPORT_REF_TICK
+
+      /* clock src: REF_CLK */
+
+      esp_clk_tree_src_get_freq_hz((soc_module_clk_t)RMT_BASECLK_REF,
+                                   ESP_CLK_TREE_SRC_FREQ_PRECISION_CACHED,
+                                   &rmt_source_clk_hz);
+      rmt_ll_set_group_clock_src(dev, channel,
+                                 (rmt_clock_source_t)RMT_BASECLK_REF,
+                                 1, 0, 0);
+#else
+#error "No clock source is aware of DFS"
+#endif
+    }
+  else
+    {
+      /* fallback to use default clock source */
+
+      esp_clk_tree_src_get_freq_hz((soc_module_clk_t)RMT_BASECLK_DEFAULT,
+                                   ESP_CLK_TREE_SRC_FREQ_PRECISION_CACHED,
+                                   &rmt_source_clk_hz);
+      rmt_ll_set_group_clock_src(dev, channel,
+                                 (rmt_clock_source_t)RMT_BASECLK_DEFAULT,
+                                 1, 0, 0);
+    }
+
+  spin_unlock_irqrestore(&g_rmtdev_common.rmt_spinlock, flags);
+
+#if SOC_RMT_CHANNEL_CLK_INDEPENDENT
+  g_rmt_source_clock_hz[channel] = rmt_source_clk_hz;
+#else
+  if (g_rmt_source_clock_hz && rmt_source_clk_hz != g_rmt_source_clock_hz)
+    {
+      rmterr("RMT clock source has been configured to %"PRIu32" by other "
+             "channel, now reconfigure it to %"PRIu32"",
+             g_rmt_source_clock_hz, rmt_source_clk_hz);
+    }
+
+  g_rmt_source_clock_hz = rmt_source_clk_hz;
+#endif
+  rmtinfo("rmt_source_clk_hz: %"PRIu32, rmt_source_clk_hz);
+
+  if (mode == RMT_MODE_TX)
+    {
+      uint16_t carrier_duty_percent =
+                  rmt_param->tx_config.carrier_duty_percent;
+      uint8_t carrier_level = rmt_param->tx_config.carrier_level;
+      uint8_t idle_level = rmt_param->tx_config.idle_level;
+
+      flags = spin_lock_irqsave(g_rmtdev_common.rmt_spinlock);
+      rmt_ll_tx_set_channel_clock_div(dev, channel, clk_div);
+      rmt_ll_tx_set_mem_blocks(dev, channel, mem_cnt);
+      rmt_ll_tx_reset_pointer(dev, channel);
+      rmt_ll_tx_enable_loop(dev, channel, rmt_param->tx_config.loop_en);
+#if SOC_RMT_SUPPORT_TX_LOOP_COUNT
+      if (rmt_param->tx_config.loop_en)
+        {
+          rmt_ll_tx_set_loop_count(dev, channel,
+                                   rmt_param->tx_config.loop_count);
+        }
+#endif
+
+      /* always enable tx ping-pong */
+
+      rmt_ll_tx_enable_wrap(dev, channel, true);
+
+      /* Set idle level */
+
+      rmt_ll_tx_fix_idle_level(dev, channel, idle_level,
+                               rmt_param->tx_config.idle_output_en);
+
+      /* Set carrier */
+
+      rmt_ll_tx_enable_carrier_modulation(dev, channel, carrier_en);
+      if (carrier_en)
+        {
+          uint32_t duty_div;
+          uint32_t duty_h;
+          uint32_t duty_l;
+          duty_div = rmt_source_clk_hz / carrier_freq_hz;
+          duty_h = duty_div * carrier_duty_percent / 100;
+          duty_l = duty_div - duty_h;
+          rmt_ll_tx_set_carrier_level(dev, channel, carrier_level);
+          rmt_ll_tx_set_carrier_high_low_ticks(dev, channel, duty_h, duty_l);
+        }
+      else
+        {
+          rmt_ll_tx_set_carrier_level(dev, channel, 0);
+        }
+
+      spin_unlock_irqrestore(&g_rmtdev_common.rmt_spinlock, flags);
+
+      rmtinfo("Rmt Tx Channel %u|Gpio %u|Sclk_Hz %"PRIu32"|Div %u|Carrier_Hz"
+              " %"PRIu32"|Duty %u", channel, gpio_num, rmt_source_clk_hz,
+              clk_div, carrier_freq_hz, carrier_duty_percent);
+    }
+  else if (RMT_MODE_RX == mode)
+    {
+      uint8_t filter_cnt = rmt_param->rx_config.filter_ticks_thresh;
+      uint16_t threshold = rmt_param->rx_config.idle_threshold;
+
+      flags = spin_lock_irqsave(g_rmtdev_common.rmt_spinlock);
+      rmt_ll_rx_set_channel_clock_div(dev, RMT_DECODE_RX_CHANNEL(channel),
+                                      clk_div);
+      rmt_ll_rx_set_mem_blocks(dev, RMT_DECODE_RX_CHANNEL(channel), mem_cnt);
+      rmt_ll_rx_reset_pointer(dev, RMT_DECODE_RX_CHANNEL(channel));
+      rmt_ll_rx_set_mem_owner(dev, RMT_DECODE_RX_CHANNEL(channel),
+                              RMT_LL_MEM_OWNER_HW);
+
+      /* Set idle threshold */
+
+      rmt_ll_rx_set_idle_thres(dev, RMT_DECODE_RX_CHANNEL(channel),
+                               threshold);
+
+      /* Set RX filter */
+
+      rmt_ll_rx_set_filter_thres(dev, RMT_DECODE_RX_CHANNEL(channel),
+                                 filter_cnt);
+      rmt_ll_rx_enable_filter(dev, RMT_DECODE_RX_CHANNEL(channel),
+                              rmt_param->rx_config.filter_en);
+
+#if SOC_RMT_SUPPORT_RX_PINGPONG
+
+      /* always enable rx ping-pong */
+
+      rmt_ll_rx_enable_wrap(dev, RMT_DECODE_RX_CHANNEL(channel), true);
+#endif
+
+#if SOC_RMT_SUPPORT_RX_DEMODULATION
+      rmt_ll_rx_enable_carrier_demodulation(dev,
+                                            RMT_DECODE_RX_CHANNEL(channel),
+                                            rmt_param->rx_config.rm_carrier);
+      if (rmt_param->rx_config.rm_carrier)
+        {
+          uint32_t duty_total;
+          uint32_t duty_high;
+          uint32_t ch_clk_div =
+            rmt_ll_rx_get_channel_clock_div(dev,
+                                            RMT_DECODE_RX_CHANNEL(channel));
+          duty_total = rmt_source_clk_hz / \
+                       ch_clk_div / \
+                       rmt_param->rx_config.carrier_freq_hz;
+          duty_high = duty_total *
+                      rmt_param->rx_config.carrier_duty_percent / 100;
+
+          /* there could be residual in timing the carrier pulse, so double
+           * enlarge the theoretical value.
+           */
+
+          rmt_ll_rx_set_carrier_high_low_ticks(
+              dev, RMT_DECODE_RX_CHANNEL(channel), duty_high * 2,
+              (duty_total - duty_high) * 2);
+          rmt_ll_rx_set_carrier_level(dev, RMT_DECODE_RX_CHANNEL(channel),
+                                      rmt_param->rx_config.carrier_level);
+        }
+#endif
+
+      spin_unlock_irqrestore(&g_rmtdev_common.rmt_spinlock, flags);
+
+      rmtinfo("Rmt Rx Channel %u|Gpio %u|Sclk_Hz %"PRIu32"|Div %u|Thresold "
+              "%u|Filter %u", channel, gpio_num, rmt_source_clk_hz, clk_div,
+              threshold, filter_cnt);
+    }
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: rmt_config
+ *
+ * Description:
+ *   This function configures the RMT channel with the provided parameters.
+ *   It enables the RMT module, sets the GPIO for the RMT channel, and
+ *   configures the RMT peripheral using the internal configuration function.
+ *
+ * Input Parameters:
+ *   rmt_param - Pointer to the structure containing the RMT channel
+ *               configuration parameters.
+ *
+ * Returned Value:
+ *   Returns OK on successful configuration of the RMT channel; a negated
+ *   errno value is returned on any failure.
+ *
+ ****************************************************************************/
+
+static int rmt_config(const struct rmt_channel_config_s *rmt_param)
+{
+  int ret = ERROR;
+
+  rmt_module_enable();
+
+  rmt_set_gpio(rmt_param->channel, rmt_param->rmt_mode, rmt_param->gpio_num,
+               rmt_param->flags & RMT_CHANNEL_FLAGS_INVERT_SIG);
+
+  ret = rmt_internal_config(&RMT, rmt_param);
+
+  return ret;
+}
+
+/****************************************************************************
+ * Name: rmt_fill_memory
+ *
+ * Description:
+ *   This function fills the RMT memory with the provided items. It copies
+ *   the items from the source to the RMT memory for the specified channel,
+ *   starting at the specified memory offset.
+ *
+ * Input Parameters:
+ *   channel    - The RMT peripheral channel number.
+ *   item       - Pointer to the items to be copied to the RMT memory.
+ *   item_num   - The number of items to be copied.
+ *   mem_offset - The memory offset at which to start copying.
+ *
+ * Returned Value:
+ *   None.
+ *
+ ****************************************************************************/
+
+static void IRAM_ATTR rmt_fill_memory(rmt_channel_t channel,
+                                      const rmt_item32_t *item,
+                                      uint16_t item_num,
+                                      uint16_t mem_offset)
+{
+  uint32_t *from = (uint32_t *)item;
+  volatile uint32_t *to =
+      (volatile uint32_t *)&RMTMEM.chan[channel].data32[0].val;
+
+  to += mem_offset;
+
+  while (item_num--)
+    {
+      *to++ = *from++;
+    }
+}
+
+/****************************************************************************
+ * Name: rmt_isr_register
+ *
+ * Description:
+ *   This function registers an interrupt service routine (ISR) for the RMT
+ *   peripheral. It allocates a CPU interrupt, attaches the ISR to the
+ *   interrupt, and returns the status of the operation.
+ *
+ * Input Parameters:
+ *   fn               - Pointer to the ISR function.
+ *   arg              - Pointer to the argument to be passed to the ISR.
+ *   intr_alloc_flags - Flags for the interrupt allocation.
+ *
+ * Returned Value:
+ *   Returns OK on successful registration of the ISR; a negated errno value
+ *   is returned on any failure.
+ *
+ ****************************************************************************/
+
+static int rmt_isr_register(int (*fn)(int, void *, void *), void *arg,
+                            int intr_alloc_flags)
+{
+  int cpuint;
+  int ret;
+  int cpu = up_cpu_index();
+
+  DEBUGASSERT(fn);
+  DEBUGASSERT(g_rmtdev_common.rmt_driver_channels == 0);
+
+  cpuint = esp_setup_irq(rmt_periph_signals.groups[0].irq,
+                         ESP_IRQ_PRIORITY_DEFAULT,
+                         ESP_IRQ_TRIGGER_LEVEL);
+  if (cpuint < 0)
+    {
+      rmterr("Failed to allocate a CPU interrupt.\n");
+      return -ENOMEM;
+    }
+
+  ret = irq_attach(ESP_SOURCE2IRQ(rmt_periph_signals.groups[0].irq),
+                   fn, &g_rmtdev_common.hal);
+  if (ret < 0)
+    {
+      rmterr("Couldn't attach IRQ to handler.\n");
+      esp_teardown_irq(rmt_periph_signals.groups[0].irq, cpuint);
+      return ret;
+    }
+
+  up_enable_irq(ESP_SOURCE2IRQ(rmt_periph_signals.groups[0].irq));
+
+  return ret;
+}
+
+/****************************************************************************
+ * Name: rmt_driver_isr_default
+ *
+ * Description:
+ *   This function is the default interrupt service routine (ISR) for the RMT
+ *   peripheral. It handles TX end, TX threshold, RX end, RX threshold, loop
+ *   count, RX error, and TX error interrupts. For each interrupt type, it
+ *   checks the status, clears the interrupt, and performs the appropriate
+ *   actions based on the RMT object associated with the channel.
+ *
+ * Input Parameters:
+ *   irq     - The interrupt request number.
+ *   context - Pointer to the interrupt context.
+ *   arg     - Pointer to the argument to be passed to the ISR.
+ *
+ * Returned Value:
+ *   Returns OK after handling all active interrupts.
+ *
+ ****************************************************************************/
+
+static int IRAM_ATTR rmt_driver_isr_default(int irq, void *context,
+                                            void *arg)
+{
+  uint32_t status = 0;
+  rmt_item32_t *addr = NULL;
+  uint8_t channel = 0;
+  rmt_hal_context_t *hal = (rmt_hal_context_t *)arg;
+
+  /* Tx end interrupt */
+
+  status = rmt_ll_get_tx_end_interrupt_status(hal->regs);
+  while (status)
+    {
+      channel = __builtin_ffs(status) - 1;
+      status &= ~(1 << channel);
+      rmt_obj_t *p_rmt = p_rmt_obj[channel];
+      if (p_rmt)
+        {
+          nxsem_post(&p_rmt->tx_sem);
+          rmt_ll_tx_reset_pointer(g_rmtdev_common.hal.regs, channel);
+          p_rmt->tx_data = NULL;
+          p_rmt->tx_len_rem = 0;
+          p_rmt->tx_offset = 0;
+          p_rmt->tx_sub_len = 0;
+          p_rmt->sample_cur = NULL;
+        }
+
+      rmt_ll_clear_interrupt_status(hal->regs,
+                                    RMT_LL_EVENT_TX_DONE(channel));
+    }
+
+  /* Tx thres interrupt */
+
+  status = rmt_ll_get_tx_thres_interrupt_status(hal->regs);
+  while (status)
+    {
+      channel = __builtin_ffs(status) - 1;
+      status &= ~(1 << channel);
+      rmt_obj_t *p_rmt = p_rmt_obj[channel];
+      if (p_rmt)
+        {
+          const rmt_item32_t *pdata = p_rmt->tx_data;
+          size_t len_rem = p_rmt->tx_len_rem;
+          rmt_idle_level_t idle_level =
+              rmt_ll_tx_get_idle_level(hal->regs, channel);
+          rmt_item32_t stop_data = (rmt_item32_t)
+            {
+              .level0 = idle_level,
+              .duration0 = 0,
+            };
+
+          if (len_rem >= p_rmt->tx_sub_len)
+            {
+              rmt_fill_memory(channel, pdata, p_rmt->tx_sub_len,
+                              p_rmt->tx_offset);
+              p_rmt->tx_data += p_rmt->tx_sub_len;
+              p_rmt->tx_len_rem -= p_rmt->tx_sub_len;
+            }
+          else if (len_rem == 0)
+            {
+              rmt_fill_memory(channel, &stop_data, 1, p_rmt->tx_offset);
+            }
+          else
+            {
+              rmt_fill_memory(channel, pdata, len_rem, p_rmt->tx_offset);
+              rmt_fill_memory(channel, &stop_data, 1,
+                              p_rmt->tx_offset + len_rem);
+              p_rmt->tx_data += len_rem;
+              p_rmt->tx_len_rem -= len_rem;
+            }
+
+          if (p_rmt->tx_offset == 0)
+            {
+              p_rmt->tx_offset = p_rmt->tx_sub_len;
+            }
+          else
+            {
+              p_rmt->tx_offset = 0;
+            }
+        }
+
+      rmt_ll_clear_interrupt_status(hal->regs,
+                                    RMT_LL_EVENT_TX_THRES(channel));
+    }
+
+  /* Rx end interrupt */
+
+  status = rmt_ll_get_rx_end_interrupt_status(hal->regs);
+  while (status)
+    {
+      channel = __builtin_ffs(status) - 1;
+      status &= ~(1 << channel);
+      rmt_obj_t *p_rmt = p_rmt_obj[RMT_ENCODE_RX_CHANNEL(channel)];
+      if (p_rmt)
+        {
+          int item_len;
+          rmt_ll_rx_enable(g_rmtdev_common.hal.regs, channel, false);
+          item_len =
+            rmt_ll_rx_get_memory_writer_offset(g_rmtdev_common.hal.regs,
+                                               channel);
+          rmt_ll_rx_set_mem_owner(g_rmtdev_common.hal.regs, channel,
+                                  RMT_LL_MEM_OWNER_SW);
+          if (circbuf_is_init(&p_rmt->rx_buf))
+            {
+              int bytes;
+
+              addr = (rmt_item32_t *)
+                RMTMEM.chan[RMT_ENCODE_RX_CHANNEL(channel)].data32;
+#if SOC_RMT_SUPPORT_RX_PINGPONG
+              if (item_len > p_rmt->rx_item_start_idx)
+                {
+                  item_len = item_len - p_rmt->rx_item_start_idx;
+                }
+
+              /* Check for RX buffer max length */
+
+              if ((p_rmt->rx_item_len + item_len) > \
+                  (p_rmt->rx_item_buf_size / 4))
+                {
+                  int remaining_len = (p_rmt->rx_item_buf_size / 4) - \
+                                      p_rmt->rx_item_len;
+                  rmterr("ERROR: RX buffer too small: %d items dropped\n",
+                         item_len - remaining_len);
+                  item_len = remaining_len;
+                }
+
+              memcpy((void *)(p_rmt->rx_item_buf + p_rmt->rx_item_len),
+                     (void *)(addr + p_rmt->rx_item_start_idx),
+                     item_len * 4);
+              p_rmt->rx_item_len += item_len;
+              bytes = circbuf_write(&p_rmt->rx_buf,
+                                    (void *)(p_rmt->rx_item_buf),
+                                    p_rmt->rx_item_len * 4);
+#else
+              bytes = circbuf_write(&p_rmt->rx_buf, (void *)addr,
+                                    item_len * 4);
+#endif
+              nxsem_post(&p_rmt->rx_sem);
+              if (bytes < (item_len * 4))
+                {
+                  rmterr("RMT RX BUFFER FULL");
+                }
+            }
+          else
+            {
+              rmterr("RMT RX BUFFER ERROR");
+            }
+
+#if SOC_RMT_SUPPORT_RX_PINGPONG
+          p_rmt->rx_item_start_idx = 0;
+          p_rmt->rx_item_len = 0;
+          memset((void *)p_rmt->rx_item_buf, 0, p_rmt->rx_item_buf_size);
+#endif
+          rmt_ll_rx_reset_pointer(g_rmtdev_common.hal.regs, channel);
+          rmt_ll_rx_set_mem_owner(g_rmtdev_common.hal.regs, channel,
+                                  RMT_LL_MEM_OWNER_HW);
+          rmt_ll_rx_enable(g_rmtdev_common.hal.regs, channel, true);
+        }
+
+      rmt_ll_clear_interrupt_status(hal->regs,
+                                    RMT_LL_EVENT_RX_DONE(channel));
+    }
+
+#if SOC_RMT_SUPPORT_RX_PINGPONG
+
+  /* Rx thres interrupt */
+
+  status = rmt_ll_get_rx_thres_interrupt_status(hal->regs);
+  while (status)
+    {
+      int mem_item_size;
+      int rx_thres_lim;
+      int item_len;
+
+      channel = __builtin_ffs(status) - 1;
+      status &= ~(1 << channel);
+      rmt_obj_t *p_rmt = p_rmt_obj[RMT_ENCODE_RX_CHANNEL(channel)];
+      mem_item_size = rmt_ll_rx_get_mem_blocks(g_rmtdev_common.hal.regs,
+                                               channel) * RMT_MEM_ITEM_NUM;
+      rx_thres_lim = rmt_ll_rx_get_limit(g_rmtdev_common.hal.regs, channel);
+      item_len = (p_rmt->rx_item_start_idx == 0) ? rx_thres_lim : \
+                 (mem_item_size - rx_thres_lim);
+      if ((p_rmt->rx_item_len + item_len) > (p_rmt->rx_item_buf_size / 4))
+        {
+          int remaining_len = (p_rmt->rx_item_buf_size / 4) - \
+                              p_rmt->rx_item_len;
+          rmterr("ERROR: RX buffer too small!\n");
+          item_len = remaining_len;
+        }
+
+      rmt_ll_rx_set_mem_owner(g_rmtdev_common.hal.regs, channel,
+                              RMT_LL_MEM_OWNER_SW);
+      memcpy(
+        (void *)(p_rmt->rx_item_buf + p_rmt->rx_item_len),
+        (void *)(RMTMEM.chan[RMT_ENCODE_RX_CHANNEL(channel)].data32 \
+        + p_rmt->rx_item_start_idx), item_len * 4);
+      rmt_ll_rx_set_mem_owner(g_rmtdev_common.hal.regs, channel,
+                              RMT_LL_MEM_OWNER_HW);
+      p_rmt->rx_item_len += item_len;
+      p_rmt->rx_item_start_idx += item_len;
+      if (p_rmt->rx_item_start_idx >= mem_item_size)
+        {
+          p_rmt->rx_item_start_idx = 0;
+        }
+
+      rmt_ll_clear_interrupt_status(hal->regs,
+                                    RMT_LL_EVENT_RX_THRES(channel));
+    }
+#endif
+
+#if SOC_RMT_SUPPORT_TX_LOOP_COUNT
+
+  /* loop count interrupt */
+
+  status = rmt_ll_get_tx_loop_interrupt_status(hal->regs);
+  while (status)
+    {
+      channel = __builtin_ffs(status) - 1;
+      status &= ~(1 << channel);
+      rmt_obj_t *p_rmt = p_rmt_obj[channel];
+      if (p_rmt)
+        {
+          if (p_rmt->loop_autostop)
+            {
+#ifndef SOC_RMT_SUPPORT_TX_LOOP_AUTO_STOP
+
+              /* hardware doesn't support automatically stop output so driver
+               * should stop output here (possibility already overshotted
+               * several us).
+               */
+
+              rmt_ll_tx_stop(g_rmtdev_common.hal.regs, channel);
+              rmt_ll_tx_reset_pointer(g_rmtdev_common.hal.regs, channel);
+#endif
+            }
+
+          nxsem_post(&p_rmt->tx_sem);
+        }
+
+      rmt_ll_clear_interrupt_status(hal->regs,
+                                    RMT_LL_EVENT_TX_LOOP_END(channel));
+    }
+#endif
+
+  /* RX Err interrupt */
+
+  status = rmt_ll_get_rx_err_interrupt_status(hal->regs);
+  while (status)
+    {
+      channel = __builtin_ffs(status) - 1;
+      status &= ~(1 << channel);
+      rmt_obj_t *p_rmt = p_rmt_obj[RMT_ENCODE_RX_CHANNEL(channel)];
+      if (p_rmt)
+        {
+          /* Reset the receiver's write/read addresses to prevent endless
+           * err interrupts.
+           */
+
+          rmt_ll_rx_reset_pointer(g_rmtdev_common.hal.regs, channel);
+          rmtinfo("RMT RX channel %d error", channel);
+          rmtinfo("status: 0x%08lx",
+                  rmt_ll_rx_get_status_word(g_rmtdev_common.hal.regs,
+                                            channel));
+        }
+
+      rmt_ll_clear_interrupt_status(hal->regs,
+                                    RMT_LL_EVENT_RX_ERROR(channel));
+    }
+
+  /* TX Err interrupt */
+
+  status = rmt_ll_get_tx_err_interrupt_status(hal->regs);
+  while (status)
+    {
+      channel = __builtin_ffs(status) - 1;
+      status &= ~(1 << channel);
+      rmt_obj_t *p_rmt = p_rmt_obj[channel];
+      if (p_rmt)
+        {
+          /* Reset the transmitter's write/read addresses to prevent
+           * endless err interrupts.
+           */
+
+          rmt_ll_tx_reset_pointer(g_rmtdev_common.hal.regs, channel);
+          rmtinfo("RMT TX channel %d error", channel);
+          rmtinfo("status: 0x%08lx",
+                  rmt_ll_tx_get_status_word(g_rmtdev_common.hal.regs,
+                                            channel));
+        }
+
+      rmt_ll_clear_interrupt_status(hal->regs,
+                                    RMT_LL_EVENT_TX_ERROR(channel));
+    }
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: rmt_driver_install
+ *
+ * Description:
+ *   This function installs the RMT driver for a specific channel. It
+ *   allocates memory for the RMT object, initializes the object properties,
+ *   and sets up the RX buffer if specified. It also registers the default
+ *   ISR if this is the first RMT channel using the driver, and resets the
+ *   RMT channel.
+ *
+ * Input Parameters:
+ *   channel          - The RMT peripheral channel number.
+ *   rx_buf_size      - The size of the RX buffer.
+ *   intr_alloc_flags - Flags for the interrupt allocation.
+ *
+ * Returned Value:
+ *   Returns OK on successful installation of the RMT driver; a negated errno
+ *   value is returned on any failure.
+ *
+ ****************************************************************************/
+
+static int rmt_driver_install(rmt_channel_t channel, size_t rx_buf_size,
+                              int intr_alloc_flags)
+{
+  DEBUGASSERT(channel < RMT_CHANNEL_MAX);
+
+  int ret = OK;
+
+  if (p_rmt_obj[channel])
+    {
+      rmtwarn("RMT driver already installed");
+      return ERROR;
+    }
+
+#if CONFIG_RINGBUF_PLACE_ISR_FUNCTIONS_INTO_FLASH
+  if (intr_alloc_flags & ESP_INTR_FLAG_IRAM)
+    {
+      rmterr("ringbuf ISR functions in flash, but used in IRAM interrupt");
+      return -EINVAL;
+    }
+#endif
+
+#if !CONFIG_SPIRAM_USE_MALLOC
+  p_rmt_obj[channel] = calloc(1, sizeof(rmt_obj_t));
+#else
+  if (!(intr_alloc_flags & ESP_INTR_FLAG_IRAM))
+    {
+      p_rmt_obj[channel] = calloc(1, sizeof(rmt_obj_t));
+    }
+  else
+    {
+      p_rmt_obj[channel] = heap_caps_calloc(1, sizeof(rmt_obj_t),
+                                            MALLOC_CAP_INTERNAL | \
+                                            MALLOC_CAP_8BIT);
+    }
+#endif
+
+  if (p_rmt_obj[channel] == NULL)
+    {
+      rmterr("RMT driver malloc error");
+      return -ENOMEM;
+    }
+
+  p_rmt_obj[channel]->tx_len_rem = 0;
+  p_rmt_obj[channel]->tx_data = NULL;
+  p_rmt_obj[channel]->channel = channel;
+  p_rmt_obj[channel]->tx_offset = 0;
+  p_rmt_obj[channel]->tx_sub_len = 0;
+  p_rmt_obj[channel]->wait_done = false;
+  p_rmt_obj[channel]->loop_autostop = false;
+
+#if !CONFIG_SPIRAM_USE_MALLOC
+  nxsem_init(&p_rmt_obj[channel]->tx_sem, 0, 0);
+  nxsem_init(&p_rmt_obj[channel]->rx_sem, 0, 0);
+#endif
+
+  nxsem_post(&p_rmt_obj[channel]->tx_sem);
+
+  if (!circbuf_is_init(&p_rmt_obj[channel]->rx_buf) && rx_buf_size > 0)
+    {
+      circbuf_init(&p_rmt_obj[channel]->rx_buf, NULL, rx_buf_size);
+    }
+
+#if SOC_RMT_SUPPORT_RX_PINGPONG
+  if (p_rmt_obj[channel]->rx_item_buf == NULL && rx_buf_size > 0)
+    {
+#if !CONFIG_SPIRAM_USE_MALLOC
+      p_rmt_obj[channel]->rx_item_buf = calloc(1, rx_buf_size);
+#else
+      if (!(p_rmt_obj[channel]->intr_alloc_flags & ESP_INTR_FLAG_IRAM))
+        {
+          p_rmt_obj[channel]->rx_item_buf = calloc(1, rx_buf_size);
+        }
+      else
+        {
+          p_rmt_obj[channel]->rx_item_buf =
+              heap_caps_calloc(1, rx_buf_size,
+                               MALLOC_CAP_INTERNAL | MALLOC_CAP_8BIT);
+        }
+
+#endif
+      if (p_rmt_obj[channel]->rx_item_buf == NULL)
+        {
+          rmterr("RMT malloc fail");
+          nxsem_destroy(&p_rmt_obj[channel]->rx_sem);
+          return -ENOMEM;
+        }
+
+      p_rmt_obj[channel]->rx_item_buf_size = rx_buf_size;
+    }
+#endif
+
+  nxrmutex_lock(&(g_rmtdev_common.rmt_driver_isr_lock));
+
+  if (g_rmtdev_common.rmt_driver_channels == 0)
+    {
+      /* first RMT channel using driver */
+
+      ret = rmt_isr_register(rmt_driver_isr_default, &g_rmtdev_common.hal,
+                             intr_alloc_flags);
+    }
+
+  if (ret == OK)
+    {
+      g_rmtdev_common.rmt_driver_channels |= BIT(channel);
+    }
+
+  nxrmutex_unlock(&(g_rmtdev_common.rmt_driver_isr_lock));
+
+  rmt_module_enable();
+
+  if (RMT_IS_RX_CHANNEL(channel))
+    {
+      rmt_hal_rx_channel_reset(&g_rmtdev_common.hal,
+                               RMT_DECODE_RX_CHANNEL(channel));
+    }
+  else
+    {
+      rmt_hal_tx_channel_reset(&g_rmtdev_common.hal, channel);
+    }
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: rmt_write_items
+ *
+ * Description:
+ *   This function writes items to the RMT memory for a specific channel. It
+ *   checks the validity of the parameters, calculates the memory blocks and
+ *   item lengths, and fills the memory with the items. If the number of
+ *   items is greater than the memory block length, it enables the TX
+ *   threshold interrupt and sets up the remaining items to be sent. If the
+ *   number of items is less than the memory block length, it fills the
+ *   remaining memory with idle level items. It then starts the TX process
+ *   and waits for it to finish if specified.
+ *
+ * Input Parameters:
+ *   channel       - The RMT peripheral channel number.
+ *   rmt_item      - Pointer to the items to be written to the RMT memory.
+ *   item_num      - The number of items to be written.
+ *   wait_tx_done  - Flag to indicate whether to wait for the TX process to
+ *                   finish.
+ *
+ * Returned Value:
+ *   Returns OK on successful writing of the items to the RMT memory; a
+ *   negated errno value is returned on any failure.
+ *
+ ****************************************************************************/
+
+static int rmt_write_items(rmt_channel_t channel,
+                           const rmt_item32_t *rmt_item,
+                           int item_num,
+                           bool wait_tx_done)
+{
+  DEBUGASSERT(RMT_IS_TX_CHANNEL(channel));
+  DEBUGASSERT(p_rmt_obj[channel]);
+  DEBUGASSERT(rmt_item);
+  DEBUGASSERT(item_num > 0);
+
+  uint32_t mem_blocks = rmt_ll_tx_get_mem_blocks(g_rmtdev_common.hal.regs,
+                                                 channel);
+
+  DEBUGASSERT(mem_blocks + channel <= SOC_RMT_CHANNELS_PER_GROUP);
+#if CONFIG_SPIRAM_USE_MALLOC
+  if (p_rmt_obj[channel]->intr_alloc_flags & ESP_INTR_FLAG_IRAM)
+    {
+      if (!esp_ptr_internal(rmt_item))
+        {
+          remterr(RMT_PSRAM_BUFFER_WARN_STR);
+          return ESP_ERR_INVALID_ARG;
+        }
+    }
+#endif
+
+  rmt_obj_t *p_rmt = p_rmt_obj[channel];
+  int item_block_len = mem_blocks * RMT_MEM_ITEM_NUM;
+  int item_sub_len = mem_blocks * RMT_MEM_ITEM_NUM / 2;
+  int len_rem = item_num;
+  nxsem_wait(&p_rmt->tx_sem);
+
+  /* fill the memory block first */
+
+  if (item_num >= item_block_len)
+    {
+      rmt_fill_memory(channel, rmt_item, item_block_len, 0);
+      len_rem -= item_block_len;
+      rmt_set_tx_loop_mode(channel, false);
+      rmt_set_tx_thr_intr_en(channel, 1, item_sub_len);
+      p_rmt->tx_data = rmt_item + item_block_len;
+      p_rmt->tx_len_rem = len_rem;
+      p_rmt->tx_offset = 0;
+      p_rmt->tx_sub_len = item_sub_len;
+    }
+  else
+    {
+      rmt_idle_level_t idle_level;
+      rmt_fill_memory(channel, rmt_item, len_rem, 0);
+      idle_level = rmt_ll_tx_get_idle_level(g_rmtdev_common.hal.regs,
+                                            channel);
+      rmt_item32_t stop_data = (rmt_item32_t)
+        {
+          .level0 = idle_level,
+          .duration0 = 0,
+        };
+
+      rmt_fill_memory(channel, &stop_data, 1, len_rem);
+      p_rmt->tx_len_rem = 0;
+    }
+
+  rmt_tx_start(channel, true);
+  p_rmt->wait_done = wait_tx_done;
+  if (wait_tx_done)
+    {
+      /* wait loop done */
+
+      if (rmt_ll_tx_is_loop_enabled(g_rmtdev_common.hal.regs, channel))
+        {
+#if SOC_RMT_SUPPORT_TX_LOOP_COUNT
+          nxsem_wait(&p_rmt->tx_sem);
+          nxsem_post(&p_rmt->tx_sem);
+#endif
+        }
+      else
+        {
+          /* wait tx end */
+
+          nxsem_wait(&p_rmt->tx_sem);
+          nxsem_post(&p_rmt->tx_sem);
+        }
+    }
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: esp_rmt_read
+ *
+ * Description:
+ *   This function reads data from the RMT device.
+ *   It starts the RMT module in receiving mode for a specific channel and
+ *   checks for any errors. If an error occurs during the start of the RMT
+ *   module, it returns the error code. Please note that this function
+ *   starts the receiver, but the actual data is read from the ring buffer
+ *   by the upper half driver.
+ *
+ * Input Parameters:
+ *   dev     - Pointer to the RMT device structure.
+ *   buffer  - Pointer to the buffer where the read data should be stored.
+ *   buflen  - The maximum amount of data to be read.
+ *
+ * Returned Value:
+ *   Returns the number of bytes read from the RMT device; a negated errno
+ *   value is returned on any failure.
+ *
+ ****************************************************************************/
+
+static ssize_t esp_rmt_read(struct rmt_dev_s *dev, char *buffer,
+                            size_t buflen)
+{
+  struct rmt_dev_lowerhalf_s *priv = (struct rmt_dev_lowerhalf_s *)dev;
+  rmt_mode_t mode = priv->mode;
+  int channel = priv->minor;
+  int ret;
+  ssize_t nread;
+
+  if (mode != RMT_MODE_RX)
+    {
+      rmterr("ERROR: RMT channel %d is not in RX mode\n", channel);
+      return -EINVAL;
+    }
+
+  DEBUGASSERT((buflen % 4) == 0);
+
+  if ((buflen / 4) > (CONFIG_RMT_DEFAULT_RX_BUFFER_SIZE / 4))
+    {
+      rmtwarn("WARN: RMT RX buffer (%d bytes) is smaller than requested "
+              "read bytes (%d bytes). A partial read will take place!\n",
+              CONFIG_RMT_DEFAULT_RX_BUFFER_SIZE,
+              buflen);
+    }
+
+#ifndef SOC_RMT_SUPPORT_RX_PINGPONG
+  if ((buflen / 4) > RMT_MEM_ITEM_NUM)
+    {
+      rmtwarn("WARN: RMT RX channel is able to receive up to "
+              "%d RMT items (%d bytes)!",
+              RMT_MEM_ITEM_NUM, RMT_MEM_ITEM_NUM * 4);
+    }
+#endif
+
+  ret = rmt_rx_start(channel, true);
+  if (ret < 0)
+    {
+      rmterr("ERROR: rmt_rx_start failed: %d\n", ret);
+      return (ssize_t)ret;
+    }
+
+  return (ssize_t)ret;
+}
+
+/****************************************************************************
+ * Name: esp_rmt_write
+ *
+ * Description:
+ *   This function writes data to the RMT memory for a specific channel. It
+ *   asserts that the length of the data is a multiple of 4, then calls the
+ *   rmt_write_items function to write the items to the RMT memory.
+ *
+ * Input Parameters:
+ *   dev     - Pointer to the RMT device structure.
+ *   buffer  - Pointer to the data to be written to the RMT memory.
+ *   buflen  - The length of the data to be written.
+ *
+ * Returned Value:
+ *   Returns the number of items written to the RMT memory.
+ *
+ ****************************************************************************/
+
+static ssize_t esp_rmt_write(struct rmt_dev_s *dev, const char *buffer,
+                             size_t buflen)
+{
+  struct rmt_dev_lowerhalf_s *priv = (struct rmt_dev_lowerhalf_s *)dev;
+  rmt_mode_t mode = priv->mode;
+  int channel = priv->minor;
+  int ret;
+  struct timespec timeout;
+
+  if (mode != RMT_MODE_TX)
+    {
+      rmterr("ERROR: RMT channel %d is not in TX mode\n", channel);
+      return -EINVAL;
+    }
+
+  DEBUGASSERT((buflen % 4) == 0);
+
+  ret = rmt_write_items(channel, (const rmt_item32_t *)buffer,
+                        (buflen / 4), true);
+
+  if (ret < 0)
+    {
+      rmterr("ERROR: rmt_write_items failed: %d\n", ret);
+      return (ssize_t)0;
+    }
+
+  return (ssize_t)buflen;
+}
+
+/****************************************************************************
+ * Name: esp_rmtinitialize
+ *
+ * Description:
+ *   This function initializes the specified RMT (Remote Control) device
+ *   with the provided configuration.
+ *
+ * Input Parameters:
+ *   config - A structure containing the configuration settings for the
+ *            RMT channel to be initialized.
+ *
+ * Returned Value:
+ *   On success, this function returns a valid pointer to the RMT device
+ *   structure. If the initialization fails, it returns NULL.
+ *
+ ****************************************************************************/
+
+static struct rmt_dev_s
+    *esp_rmtinitialize(struct rmt_channel_config_s config)
+{
+  struct rmt_dev_lowerhalf_s *priv;
+  int ret;
+#ifdef CONFIG_RMT_LOOP_TEST_MODE
+  uint8_t channel;
+#endif
+
+#if (CONFIG_RMT_DEFAULT_RX_BUFFER_SIZE % 4) != 0
+#  error "CONFIG_RMT_DEFAULT_RX_BUFFER_SIZE must be a multiple of 4"
+#endif
+
+  priv = kmm_zalloc(sizeof(struct rmt_dev_lowerhalf_s));
+  if (priv)
+    {
+      ret = rmt_config(&config);
+      if (ret < 0)
+        {
+          rmterr("ERROR: rmt_config failed: %d\n", ret);
+          return NULL;
+        }
+
+#ifdef CONFIG_RMT_LOOP_TEST_MODE
+      if (config.rmt_mode == RMT_MODE_TX)
+        {
+          if (g_tx_channel != RMT_CHANNEL_MAX)
+            {
+              rmterr("ERROR: only one TX channel can be used in loop test "
+                     "mode\n");
+              PANIC();
+            }
+
+          g_tx_channel = config.channel;
+        }
+      else
+        {
+          if (g_rx_channel != RMT_CHANNEL_MAX)
+            {
+              rmterr("ERROR: only one RX channel can be used in loop test "
+                     "mode\n");
+              PANIC();
+            }
+
+          g_rx_channel = config.channel;
+        }
+
+      if (g_rx_channel != RMT_CHANNEL_MAX && g_tx_channel != RMT_CHANNEL_MAX)
+        {
+          esp_configgpio(config.gpio_num, OUTPUT | INPUT);
+          esp_gpio_matrix_out(config.gpio_num,
+                              RMT_SIG_OUT0_IDX + g_tx_channel,
+                              0, 0);
+          esp_gpio_matrix_in(config.gpio_num,
+                             RMT_SIG_IN0_IDX + g_rx_channel,
+                             0);
+          rmtwarn("RX channel %d and TX channel %d are used in loop test "
+                  "mode\n", g_rx_channel, g_tx_channel);
+        }
+#endif
+
+      ret = rmt_driver_install(config.channel,
+                               config.rmt_mode == RMT_MODE_RX ? \
+                               CONFIG_RMT_DEFAULT_RX_BUFFER_SIZE : 0, 0);
+      if (ret < 0)
+        {
+          rmterr("ERROR: rmt_driver_install failed: %d\n", ret);
+          return NULL;
+        }
+
+      priv->ops = &g_rmtops;
+      priv->recvsem = &p_rmt_obj[config.channel]->rx_sem;
+      priv->circbuf = &p_rmt_obj[config.channel]->rx_buf;
+      priv->minor = config.channel;
+
+      priv->common = &g_rmtdev_common;
+      priv->mode = config.rmt_mode;
+    }
+  else
+    {
+      rmterr("ERROR: memory allocation failed\n");
+      return NULL;
+    }
+
+  return (struct rmt_dev_s *)priv;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: esp_rmt_tx_init
+ *
+ * Description:
+ *   Initialize the selected RMT device in TX mode
+ *
+ * Input Parameters:
+ *   ch   - the RMT's channel that will be used
+ *   pin  - The pin used for the TX channel
+ *
+ * Returned Value:
+ *   Valid RMT device structure reference on success; NULL, otherwise.
+ *
+ ****************************************************************************/
+
+struct rmt_dev_s *esp_rmt_tx_init(int ch, int pin)
+{
+  struct rmt_channel_config_s config = RMT_DEFAULT_CONFIG_TX(pin, ch);
+
+  return esp_rmtinitialize(config);
+}
+
+/****************************************************************************
+ * Name: esp_rmt_rx_init
+ *
+ * Description:
+ *   Initialize the selected RMT device in RC mode
+ *
+ * Input Parameters:
+ *   ch   - the RMT's channel that will be used
+ *   pin  - The pin used for the RX channel
+ *
+ * Returned Value:
+ *   Valid RMT device structure reference on success; NULL, otherwise.
+ *
+ ****************************************************************************/
+
+struct rmt_dev_s *esp_rmt_rx_init(int ch, int pin)
+{
+  struct rmt_channel_config_s config = RMT_DEFAULT_CONFIG_RX(pin, ch);
+
+  return esp_rmtinitialize(config);
+}
+
+#endif
diff --git a/boards/risc-v/esp32c6/esp32c6-devkit/src/esp32c6-devkit.h 
b/arch/risc-v/src/common/espressif/esp_rmt.h
similarity index 65%
copy from boards/risc-v/esp32c6/esp32c6-devkit/src/esp32c6-devkit.h
copy to arch/risc-v/src/common/espressif/esp_rmt.h
index ad6766b0e4..606f34e2ab 100644
--- a/boards/risc-v/esp32c6/esp32c6-devkit/src/esp32c6-devkit.h
+++ b/arch/risc-v/src/common/espressif/esp_rmt.h
@@ -1,5 +1,5 @@
 /****************************************************************************
- * boards/risc-v/esp32c6/esp32c6-devkit/src/esp32c6-devkit.h
+ * arch/risc-v/src/common/espressif/esp_rmt.h
  *
  * Licensed to the Apache Software Foundation (ASF) under one or more
  * contributor license agreements.  See the NOTICE file distributed with
@@ -18,19 +18,33 @@
  *
  ****************************************************************************/
 
-#ifndef __BOARDS_RISCV_ESP32C6_ESP32C6_DEVKIT_SRC_ESP32C6_DEVKIT_H
-#define __BOARDS_RISCV_ESP32C6_ESP32C6_DEVKIT_SRC_ESP32C6_DEVKIT_H
+#ifndef __ARCH_RISC_V_SRC_COMMON_ESPRESSIF_ESP_RMT_H
+#define __ARCH_RISC_V_SRC_COMMON_ESPRESSIF_ESP_RMT_H
 
 /****************************************************************************
  * Included Files
  ****************************************************************************/
 
 #include <nuttx/config.h>
+#include <semaphore.h>
+#include <nuttx/spinlock.h>
 
 /****************************************************************************
  * Pre-processor Definitions
  ****************************************************************************/
 
+#define RMT_MEM_ITEM_NUM SOC_RMT_MEM_WORDS_PER_CHANNEL
+
+#define RMT_DEFAULT_CLK_DIV 1
+
+/* Channel can work during APB clock scaling */
+
+#define RMT_CHANNEL_FLAGS_AWARE_DFS (1 << 0)
+
+/* Invert RMT signal */
+
+#define RMT_CHANNEL_FLAGS_INVERT_SIG (1 << 1)
+
 /****************************************************************************
  * Public Types
  ****************************************************************************/
@@ -40,48 +54,56 @@
  ****************************************************************************/
 
 #ifndef __ASSEMBLY__
+#ifdef __cplusplus
+extern "C"
+{
+#endif
 
 /****************************************************************************
- * Public Function Prototypes
+ * Public Functions Prototypes
  ****************************************************************************/
 
+#if defined(CONFIG_ESP_RMT)
+
 /****************************************************************************
- * Name: esp_bringup
+ * Name: esp_rmt_tx_init
  *
  * Description:
- *   Perform architecture-specific initialization.
- *
- *   CONFIG_BOARD_LATE_INITIALIZE=y :
- *     Called from board_late_initialize().
- *
- *   CONFIG_BOARD_LATE_INITIALIZE=y && CONFIG_BOARDCTL=y :
- *     Called from the NSH library via board_app_initialize().
+ *   Initialize the selected RMT device in TX mode
  *
  * Input Parameters:
- *   None.
+ *   ch   - the RMT's channel that will be used
+ *   pin  - The pin used for the TX channel
  *
  * Returned Value:
- *   Zero (OK) is returned on success; A negated errno value is returned on
- *   any failure.
+ *   Valid RMT device structure reference on success; NULL, otherwise.
  *
  ****************************************************************************/
 
-int esp_bringup(void);
+struct rmt_dev_s *esp_rmt_tx_init(int ch, int pin);
 
 /****************************************************************************
- * Name: esp_gpio_init
+ * Name: esp_rmt_rx_init
  *
  * Description:
- *   Configure the GPIO driver.
+ *   Initialize the selected RMT device in RC mode
+ *
+ * Input Parameters:
+ *   ch   - the RMT's channel that will be used
+ *   pin  - The pin used for the RX channel
  *
  * Returned Value:
- *   Zero (OK).
+ *   Valid RMT device structure reference on success; NULL, otherwise.
  *
  ****************************************************************************/
 
-#ifdef CONFIG_DEV_GPIO
-int esp_gpio_init(void);
+struct rmt_dev_s *esp_rmt_rx_init(int ch, int pin);
+
 #endif
 
+#ifdef __cplusplus
+}
+#endif
 #endif /* __ASSEMBLY__ */
-#endif /* __BOARDS_RISCV_ESP32C6_ESP32C6_DEVKIT_SRC_ESP32C6_DEVKIT_H */
+
+#endif /* __ARCH_RISC_V_SRC_COMMON_ESPRESSIF_ESP_RMT_H */
diff --git a/arch/risc-v/src/common/espressif/esp_ws2812.c 
b/arch/risc-v/src/common/espressif/esp_ws2812.c
new file mode 100644
index 0000000000..a3726d5f95
--- /dev/null
+++ b/arch/risc-v/src/common/espressif/esp_ws2812.c
@@ -0,0 +1,667 @@
+/****************************************************************************
+ * arch/risc-v/src/common/espressif/esp_ws2812.c
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <stdlib.h>
+#include <fcntl.h>
+#include <stdlib.h>
+#include <string.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/signal.h>
+#include <nuttx/leds/ws2812.h>
+#include <nuttx/rmt/rmt.h>
+
+#include "hal/rmt_types.h"
+#include "soc/soc.h"
+
+#include "esp_rmt.h"
+
+#include "esp_ws2812.h"
+
+#ifdef CONFIG_WS2812
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define rmt_item32_t rmt_symbol_word_t
+
+/****************************************************************************
+ * Private Type
+ ****************************************************************************/
+
+struct rgbw_led_s
+{
+  union
+    {
+      struct
+        {
+          uint8_t b;
+          uint8_t g;
+          uint8_t r;
+          uint8_t w;
+        };
+      uint32_t val;
+    };
+};
+
+struct esp_ws2812_dev_s
+{
+  struct rmt_dev_s    *rmt;
+  uint8_t             *buf;
+  size_t               buflen;
+  size_t               open_count;   /* Number of opens on this instance. */
+};
+
+/* RMT channel ID */
+
+enum rmt_channel_e
+{
+  RMT_CHANNEL_0,  /* RMT channel number 0 */
+  RMT_CHANNEL_1,  /* RMT channel number 1 */
+  RMT_CHANNEL_2,  /* RMT channel number 2 */
+  RMT_CHANNEL_3,  /* RMT channel number 3 */
+#if SOC_RMT_CHANNELS_PER_GROUP > 4
+  RMT_CHANNEL_4,  /* RMT channel number 4 */
+  RMT_CHANNEL_5,  /* RMT channel number 5 */
+  RMT_CHANNEL_6,  /* RMT channel number 6 */
+  RMT_CHANNEL_7,  /* RMT channel number 7 */
+#endif
+  RMT_CHANNEL_MAX /* Number of RMT channels */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static uint32_t map_byte_to_words(struct esp_ws2812_dev_s *dev,
+                                  uint8_t byte,
+                                  uint32_t *dst);
+static int map_leds_to_words(struct esp_ws2812_dev_s *dev,
+                             struct rgbw_led_s *leds,
+                             uint32_t n_leds,
+                             uint32_t *dst,
+                             bool has_white);
+static int esp_open(struct file *filep);
+static int esp_close(struct file *filep);
+static int esp_write(struct file *filep, const char *data, size_t len);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+#if SOC_RMT_CHANNEL_CLK_INDEPENDENT
+extern uint32_t g_rmt_source_clock_hz[RMT_CHANNEL_MAX];
+#else
+extern uint32_t g_rmt_source_clock_hz;
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: map_byte_to_words
+ *
+ * Description:
+ *   Maps a byte to a sequence of RMT items. Each bit in the byte is
+ *   represented by an RMT item (32-bit value). Iterates over each bit in
+ *   the byte, creating an RMT item for each bit, set or not. The created
+ *   RMT items are stored in the destination array.
+ *
+ * Input Parameters:
+ *   dev  - Pointer to the RMT-based WS2812 device structure.
+ *   byte - The byte to be mapped.
+ *   dst  - Destination array for the RMT items.
+ *
+ * Returned Value:
+ *   Number of RMT items mapped.
+ *
+ ****************************************************************************/
+
+static uint32_t map_byte_to_words(struct esp_ws2812_dev_s *dev,
+                                  uint8_t byte,
+                                  uint32_t *dst)
+{
+  uint32_t mapped;
+  uint8_t mask;
+  uint16_t t0h;
+  uint16_t t0l;
+  uint16_t t1h;
+  uint16_t t1l;
+  uint32_t clock_period_ps;
+  uint32_t rmt_period_ps;
+
+#if SOC_RMT_CHANNEL_CLK_INDEPENDENT
+  clock_period_ps = 1000000000000 / g_rmt_source_clock_hz[dev->rmt->minor];
+#else
+  clock_period_ps = 1000000000000 / g_rmt_source_clock_hz;
+#endif
+  rmt_period_ps = clock_period_ps / RMT_DEFAULT_CLK_DIV;
+
+  /* Calculate the RMT period to encode WS2812 frames */
+
+  t0h = ((uint16_t)(350000 / rmt_period_ps));
+  t0l = ((uint16_t)(900000 / rmt_period_ps));
+  t1h = ((uint16_t)(900000 / rmt_period_ps));
+  t1l = ((uint16_t)(350000 / rmt_period_ps));
+
+  mapped = 0;
+  mask = 0x80;
+  for (int i = 0; i < 8; i++)
+    {
+      uint32_t word;
+      uint8_t bit = (byte & mask);
+
+      mask >>= 1;
+
+      if (bit)
+        {
+          word = (t1l << 16) | (0x8000 | t1h);
+        }
+        else
+        {
+          word = (t0l << 16) | (0x8000 | t0h);
+        }
+
+      *dst = word;
+      dst++;
+      mapped++;
+    }
+
+  return mapped;
+}
+
+/****************************************************************************
+ * Name: map_leds_to_words
+ *
+ * Description:
+ *   Maps an array of LEDs to a sequence of RMT items. Each LED in the array
+ *   is represented by a sequence of RMT items, one for each bit in the RGB
+ *   (and optionally white) values. Iterates over each LED in the array,
+ *   mapping the RGB (and optionally white) values to RMT items using the
+ *   map_byte_to_words function. The RMT items are stored in the destination
+ *   array.
+ *
+ * Input Parameters:
+ *   dev       - Pointer to the RMT-based WS2812 device structure.
+ *   leds      - Pointer to the array of LEDs.
+ *   n_leds    - Number of LEDs in the array.
+ *   dst       - Destination array for the RMT items.
+ *   has_white - Flag indicating if the LEDs include a white component.
+ *
+ * Returned Value:
+ *   Number of RMT items mapped; a negated errno value is returned on
+ *   failure.
+ *
+ ****************************************************************************/
+
+static int map_leds_to_words(struct esp_ws2812_dev_s *dev,
+                             struct rgbw_led_s *leds,
+                             uint32_t n_leds,
+                             uint32_t *dst,
+                             bool has_white)
+{
+  uint32_t dst_offset;
+
+  if (!dst || !leds)
+    {
+      return -EINVAL;
+    }
+
+  dst_offset = 0;
+  for (uint32_t led_idx = 0; led_idx < n_leds; led_idx++)
+    {
+      dst_offset += map_byte_to_words(dev,
+                                      leds[led_idx].g,
+                                      dst + dst_offset);
+      dst_offset += map_byte_to_words(dev,
+                                      leds[led_idx].r,
+                                      dst + dst_offset);
+      dst_offset += map_byte_to_words(dev,
+                                      leds[led_idx].b,
+                                      dst + dst_offset);
+      if (has_white)
+        {
+          dst_offset += map_byte_to_words(dev,
+                                          leds[led_idx].w,
+                                          dst + dst_offset);
+        }
+    }
+
+  return dst_offset;
+}
+
+/****************************************************************************
+ * Name: esp_open
+ *
+ * Description:
+ *   This function opens a WS2812 device instance. It locks the device,
+ *   checks if the device has already been initialized, and if not, it
+ *   allocates and initializes the pixel buffer. It then increases the open
+ *   count and unlocks the device.
+ *
+ * Input Parameters:
+ *   filep - Pointer to the file structure.
+ *
+ * Returned Value:
+ *   Returns OK on successful open of the device; a negated errno value
+ *   is returned on any failure.
+ *
+ ****************************************************************************/
+
+static int esp_open(struct file *filep)
+{
+  struct inode              *inode     = filep->f_inode;
+  struct ws2812_dev_s       *dev_data  = inode->i_private;
+  struct esp_ws2812_dev_s   *priv;
+  uint8_t                    colors;
+  irqstate_t                 flags;
+  size_t                     buflen;
+  int                        i;
+  int                        ret;
+
+  priv = (struct esp_ws2812_dev_s *)dev_data->private;
+
+  flags = enter_critical_section();
+
+  if (priv->buf != NULL)
+    {
+      /* We've already been initialized.  Keep on truckin' */
+
+      ledinfo("esp_ws2812 re-open dev: 0x%p\n", dev_data);
+
+      ret = OK;
+      goto post_and_return;
+    }
+
+  ledinfo("esp_ws2812 open dev: 0x%p\n", dev_data);
+
+  /* Allocate the pixel buffer */
+
+  if (priv->open_count == 0)
+    {
+      struct rgbw_led_s *led;
+
+      /* Number of colors of each LED */
+
+      colors = (dev_data->has_white ? 4 : 3);
+
+      /* Each LED color is represented by 8 RMT items + 1 last item. Each RMT
+       * item is 32-bit long.
+       */
+
+      buflen = (dev_data->nleds * colors * 8 + 1) * sizeof(rmt_item32_t);
+
+      priv->buf = kmm_zalloc(buflen);
+
+      if (priv->buf == NULL)
+        {
+          lederr("esp_ws2812 open: out of memory\n");
+
+          ret = -ENOMEM;
+          goto post_and_return;
+        }
+
+      priv->buflen = buflen;
+
+      /* Clear all LEDs in the LED strip */
+
+      led = kmm_zalloc(sizeof(struct rgbw_led_s));
+
+      if (led == NULL)
+        {
+          lederr("esp_ws2812 open: out of memory\n");
+
+          ret = -ENOMEM;
+          goto post_and_return;
+        }
+
+      for (i = 0; i < dev_data->nleds; i++)
+        {
+          map_leds_to_words(priv,
+                            led,
+                            1,
+                            ((uint32_t *)priv->buf + i * colors * 8),
+                            dev_data->has_white);
+        }
+
+      kmm_free(led);
+    }
+  else
+    {
+      ledwarn("esp_ws2812 open: already open\n");
+    }
+
+  priv->open_count += 1;
+
+  ret = OK;
+
+post_and_return:
+  leave_critical_section(flags);
+  return ret;
+}
+
+/****************************************************************************
+ * Name: esp_close
+ *
+ * Description:
+ *   This function closes a previously opened WS2812 device instance. It
+ *   locks the device, decreases the open count, and if no other instances
+ *   are open, it frees the buffer associated with the device. It then
+ *   unlocks the device and returns OK.
+ *
+ * Input Parameters:
+ *   filep - Pointer to the file structure.
+ *
+ * Returned Value:
+ *   Returns OK on successful close of the device; a negated errno value
+ *   is returned on any failure.
+ *
+ ****************************************************************************/
+
+static int esp_close(struct file *filep)
+{
+  struct inode        *inode    = filep->f_inode;
+  struct ws2812_dev_s *dev_data = inode->i_private;
+  struct esp_ws2812_dev_s *priv;
+
+  priv = (struct esp_ws2812_dev_s *)dev_data->private;
+
+  nxmutex_lock(&dev_data->lock);
+
+  ledinfo("esp_ws2812 close dev: 0x%p\n", dev_data);
+
+  priv->open_count -= 1;
+
+  if (priv->open_count == 0)
+    {
+      kmm_free(priv->buf);
+      priv->buf = NULL;
+    }
+
+  nxmutex_unlock(&dev_data->lock);
+  return OK;
+}
+
+/****************************************************************************
+ * Name: esp_write
+ *
+ * Description:
+ *   This function writes the LED data to the WS2812 device. It checks if the
+ *   data and length are valid, locks the device, maps the LED data to the
+ *   buffer, updates the file position, writes the buffer to the RMT device,
+ *   and unlocks the device. It returns the number of LED pixels that had
+ *   their values changed.
+ *
+ * Input Parameters:
+ *   filep - Pointer to the file structure.
+ *   data  - Pointer to the LED data to be written.
+ *   len   - The length of the data to be written.
+ *
+ * Returned Value:
+ *   Returns the number of LED pixels that had their values changed on
+ *   successful write; a negated errno value is returned on any failure.
+ *
+ ****************************************************************************/
+
+static ssize_t esp_write(struct file *filep, const char *data, size_t len)
+{
+  struct inode              *inode            = filep->f_inode;
+  struct ws2812_dev_s       *dev              = inode->i_private;
+  struct esp_ws2812_dev_s   *priv             =
+      (struct esp_ws2812_dev_s *)dev->private;
+  int                        position         = filep->f_pos;
+  uint32_t                   n_leds           = len / WS2812_RW_PIXEL_SIZE;
+  uint8_t                    colors           = (dev->has_white ? 4 : 3);
+  uint8_t                   *bp               = priv->buf + position;
+  int                        rmt_bytes;
+  int                        n_leds_written;
+  int                        ret;
+
+  /* Check if LED data isn't NULL */
+
+  if (data == NULL)
+    {
+      lederr("esp_ws2812 write failed: NULL data\n");
+      set_errno(EINVAL);
+      return 0;
+    }
+
+  /* Check if the number of LEDs to be updated is valid */
+
+  if (n_leds > dev->nleds)
+    {
+      lederr("esp_ws2812 write failed: invalid len for the LEDs buffer\n");
+      set_errno(EINVAL);
+      return 0;
+    }
+
+  nxmutex_lock(&dev->lock);
+
+  if (len > 0)
+    {
+      /* Check if the lenght to be updated, considering the current position,
+       * is valid. The number of LEDs to be updated should, starting from the
+       * current offset should be less than the LED strip total length.
+       */
+
+      if (((position + len) / WS2812_RW_PIXEL_SIZE) > dev->nleds)
+        {
+          ledwarn("esp_ws2812 write truncated:\n\t\tLED position: %d\n"
+                  "\t\tLED requested to be written: %ld\n"
+                  "\t\tLED strip LED count: %d\n"
+                  "\t\tLED being written: %d\n",
+                  position / WS2812_RW_PIXEL_SIZE,
+                  n_leds,
+                  dev->nleds,
+                  dev->nleds - (position / WS2812_RW_PIXEL_SIZE));
+          n_leds = dev->nleds - (position / WS2812_RW_PIXEL_SIZE);
+        }
+
+      ret = map_leds_to_words(priv,
+                              (struct rgbw_led_s *)data,
+                              n_leds,
+                              (uint32_t *)bp,
+                              dev->has_white);
+      if (ret < 0)
+        {
+          lederr("esp_ws2812 write failed: %d\n", ret);
+          nxmutex_unlock(&dev->lock);
+          set_errno(-ret);
+          return ret;
+        }
+
+      /* Update the file position: each LED color is represented by 8 RMT
+       * items. The position is, then, the number of LEDs to be update times
+       * the size of a LED color in bytes.
+       */
+
+      position += n_leds * WS2812_RW_PIXEL_SIZE;
+
+      filep->f_pos = position;
+    }
+
+  /* Write the buffer to the RMT device */
+
+  rmt_bytes = priv->rmt->ops->write(priv->rmt,
+                                    (const char *)priv->buf,
+                                    priv->buflen);
+
+  /* n_leds_written is the number of LEDs that had their values changed:
+   * Each LED color is represented by 8 RMT items. We also added a last
+   * RMT item to the buffer, so we need to subtract 1 from the total number.
+   * Finally, we divide by the number of colors to get the number of LEDs.
+   */
+
+  n_leds_written = ((rmt_bytes / sizeof(rmt_item32_t)) - 1) / (colors * 8);
+
+  /* Compare n_leds_written with the value representing the full LED strip */
+
+  if (n_leds_written < dev->nleds)
+    {
+      lederr("esp_ws2812 write failed: %d\n", n_leds_written);
+      nxmutex_unlock(&dev->lock);
+      set_errno(-EIO);
+      return -EIO;
+    }
+
+  nxmutex_unlock(&dev->lock);
+
+  /* Return the number of LEDs pixels that had their values changed */
+
+  return n_leds * WS2812_RW_PIXEL_SIZE;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: esp_ws2812_setup
+ *
+ * Description:
+ *   This function sets up a WS2812 device instance. It allocates memory for
+ *   the device structures, initializes the device with the provided
+ *   parameters, and registers the device with the system.
+ *
+ * Input Parameters:
+ *   path         - The device path.
+ *   rmt          - Pointer to the RMT device structure.
+ *   pixel_count  - The number of pixels in the WS2812 strip.
+ *   has_white    - Flag indicating if the WS2812 strip includes a white LED.
+ *
+ * Returned Value:
+ *   Returns a pointer to the WS2812 device structure on successful setup;
+ *   NULL is returned on any failure, with errno set appropriately.
+ *
+ ****************************************************************************/
+
+struct ws2812_dev_s *esp_ws2812_setup(const char       *path,
+                                      struct rmt_dev_s *rmt,
+                                      uint16_t         pixel_count,
+                                      bool             has_white)
+{
+  struct ws2812_dev_s     *dev;
+  struct esp_ws2812_dev_s *priv;
+  int                     err;
+
+  /* Allocate struct holding generic WS2812 device data */
+
+  dev = kmm_zalloc(sizeof(struct ws2812_dev_s));
+
+  if (dev == NULL)
+    {
+      lederr("esp_ws2812 setup: out of memory\n");
+      set_errno(ENOMEM);
+      return NULL;
+    }
+
+  /* Allocate struct holding Espressif's WS2812 (RMT-enabled) device data */
+
+  priv = kmm_zalloc(sizeof(struct esp_ws2812_dev_s));
+
+  if (priv == NULL)
+    {
+      lederr("esp_ws2812 open: out of memory\n");
+      kmm_free(dev);
+      set_errno(ENOMEM);
+      return NULL;
+    }
+
+  priv->rmt = rmt;
+
+  dev->open      = esp_open;
+  dev->close     = esp_close;
+  dev->write     = esp_write;
+  dev->private   = priv;
+  dev->clock     = CONFIG_WS2812_FREQUENCY;
+  dev->port      = priv->rmt->minor;
+  dev->nleds     = pixel_count;
+  dev->has_white = has_white;
+
+  nxmutex_init(&dev->lock);
+
+  ledinfo("register dev: 0x%p\n", dev);
+
+  /* Register the WS2812 RGB addressable LED strip device */
+
+  err = ws2812_register(path, dev);
+
+  if (err != OK)
+    {
+      set_errno(err);
+      return NULL;
+    }
+
+  return (void *)dev;
+}
+
+/****************************************************************************
+ * Name: esp_ws2812_release
+ *
+ * Description:
+ *   This function releases a previously opened WS2812 device instance. It
+ *   checks if the device is currently open, and if not, it frees the private
+ *   data structure and sets the private field of the device to NULL. If the
+ *   device is still open, it returns an error.
+ *
+ * Input Parameters:
+ *   driver - Pointer to the instance of the WS2812 device driver to be
+ *            released.
+ *
+ * Returned Value:
+ *   Returns OK on successful release of the device; a negated errno value
+ *   is returned on any failure.
+ *
+ ****************************************************************************/
+
+int esp_ws2812_release(void * driver)
+{
+  struct ws2812_dev_s *dev = driver;
+  struct esp_ws2812_dev_s *priv;
+  int ret = OK;
+
+  priv = (struct esp_ws2812_dev_s *)dev->private;
+
+  nxmutex_lock(&dev->lock);
+
+  if (priv->open_count == 0)
+    {
+      dev->private = NULL;
+
+      nxmutex_unlock(&dev->lock);
+
+      kmm_free(priv);
+    }
+    else
+    {
+      ret = -EBUSY;
+      nxmutex_unlock(&dev->lock);
+    }
+
+  return ret;
+}
+
+#endif /* CONFIG_WS2812 */
diff --git a/arch/risc-v/src/common/espressif/esp_ws2812.h 
b/arch/risc-v/src/common/espressif/esp_ws2812.h
new file mode 100644
index 0000000000..4c6b62f843
--- /dev/null
+++ b/arch/risc-v/src/common/espressif/esp_ws2812.h
@@ -0,0 +1,100 @@
+/****************************************************************************
+ * arch/risc-v/src/common/espressif/esp_ws2812.h
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_RISC_V_SRC_COMMON_ESPRESSIF_ESP_WS2812_H
+#define __ARCH_RISC_V_SRC_COMMON_ESPRESSIF_ESP_WS2812_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <debug.h>
+#include <stdbool.h>
+
+#ifndef __ASSEMBLY__
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+#ifdef CONFIG_WS2812
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: esp_ws2812_setup
+ *
+ * Description:
+ *   This function sets up a WS2812 device instance. It allocates memory for
+ *   the device structures, initializes the device with the provided
+ *   parameters, and registers the device with the system.
+ *
+ * Input Parameters:
+ *   path         - The device path.
+ *   rmt          - Pointer to the RMT device structure.
+ *   pixel_count  - The number of pixels in the WS2812 strip.
+ *   has_white    - Flag indicating if the WS2812 strip includes a white LED.
+ *
+ * Returned Value:
+ *   Returns a pointer to the WS2812 device structure on successful setup;
+ *   NULL is returned on any failure, with errno set appropriately.
+ *
+ ****************************************************************************/
+
+struct ws2812_dev_s *esp_ws2812_setup(const char       *path,
+                                      struct rmt_dev_s *rmt,
+                                      uint16_t         pixel_count,
+                                      bool             has_white);
+/****************************************************************************
+ * Name: esp_ws2812_release
+ *
+ * Description:
+ *   This function releases a previously opened WS2812 device instance. It
+ *   checks if the device is currently open, and if not, it frees the private
+ *   data structure and sets the private field of the device to NULL. If the
+ *   device is still open, it returns an error.
+ *
+ * Input Parameters:
+ *   driver - Pointer to the instance of the WS2812 device driver to be
+ *            released.
+ *
+ * Returned Value:
+ *   Returns OK on successful release of the device; a negated errno value
+ *   is returned on any failure.
+ *
+ ****************************************************************************/
+
+int esp_ws2812_release(void * driver);
+
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_RISC_V_SRC_COMMON_ESPRESSIF_ESP_WS2812_H */
diff --git a/arch/risc-v/src/esp32c3/hal_esp32c3.mk 
b/arch/risc-v/src/esp32c3/hal_esp32c3.mk
index e877c1a8fe..982bd28c59 100644
--- a/arch/risc-v/src/esp32c3/hal_esp32c3.mk
+++ b/arch/risc-v/src/esp32c3/hal_esp32c3.mk
@@ -105,6 +105,7 @@ CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/timer_hal_iram.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/cache_hal.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/mpu_hal.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/mmu_hal.c
+CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/rmt_hal.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/uart_hal.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/uart_hal_iram.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/wdt_hal_iram.c
@@ -115,6 +116,7 @@ CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/log/log_noos.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/riscv/interrupt.c
 CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/soc/$(CHIP_SERIES)/gpio_periph.c
 CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/soc/$(CHIP_SERIES)/ledc_periph.c
+CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/soc/$(CHIP_SERIES)/rmt_periph.c
 
 ifeq ($(CONFIG_ESPRESSIF_SIMPLE_BOOT),y)
   CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/nuttx/src/bootloader_banner_wrap.c
diff --git a/arch/risc-v/src/esp32c6/hal_esp32c6.mk 
b/arch/risc-v/src/esp32c6/hal_esp32c6.mk
index ffca8ab4f6..065bf55ea4 100644
--- a/arch/risc-v/src/esp32c6/hal_esp32c6.mk
+++ b/arch/risc-v/src/esp32c6/hal_esp32c6.mk
@@ -97,6 +97,7 @@ CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/gpio_hal.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/ledc_hal.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/ledc_hal_iram.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/lp_timer_hal.c
+CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/rmt_hal.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/timer_hal.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/timer_hal_iram.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/uart_hal.c
@@ -109,3 +110,4 @@ CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/log/log_noos.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/riscv/interrupt.c
 CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/soc/$(CHIP_SERIES)/gpio_periph.c
 CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/soc/$(CHIP_SERIES)/ledc_periph.c
+CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/soc/$(CHIP_SERIES)/rmt_periph.c
diff --git a/arch/risc-v/src/esp32h2/hal_esp32h2.mk 
b/arch/risc-v/src/esp32h2/hal_esp32h2.mk
index 5c4edd8cac..78ecfb79f2 100644
--- a/arch/risc-v/src/esp32h2/hal_esp32h2.mk
+++ b/arch/risc-v/src/esp32h2/hal_esp32h2.mk
@@ -96,6 +96,7 @@ CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/gpio_hal.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/ledc_hal.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/ledc_hal_iram.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/lp_timer_hal.c
+CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/rmt_hal.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/timer_hal.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/timer_hal_iram.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/hal/uart_hal.c
@@ -108,3 +109,4 @@ CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/log/log_noos.c
 CHIP_CSRCS += chip/$(ESP_HAL_3RDPARTY_REPO)/components/riscv/interrupt.c
 CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/soc/$(CHIP_SERIES)/gpio_periph.c
 CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/soc/$(CHIP_SERIES)/ledc_periph.c
+CHIP_CSRCS += 
chip/$(ESP_HAL_3RDPARTY_REPO)/components/soc/$(CHIP_SERIES)/rmt_periph.c
diff --git a/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h 
b/boards/risc-v/esp32c3/common/include/esp_board_rmt.h
similarity index 67%
copy from boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h
copy to boards/risc-v/esp32c3/common/include/esp_board_rmt.h
index 97f82fe1d9..03ce6bb942 100644
--- a/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h
+++ b/boards/risc-v/esp32c3/common/include/esp_board_rmt.h
@@ -1,5 +1,5 @@
 /****************************************************************************
- * boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h
+ * boards/risc-v/esp32c3/common/include/esp_board_rmt.h
  *
  * Licensed to the Apache Software Foundation (ASF) under one or more
  * contributor license agreements.  See the NOTICE file distributed with
@@ -18,8 +18,8 @@
  *
  ****************************************************************************/
 
-#ifndef __BOARDS_RISCV_ESP32C3_ESP32C3_GENERIC_SRC_ESP32C3_GENERIC_H
-#define __BOARDS_RISCV_ESP32C3_ESP32C3_GENERIC_SRC_ESP32C3_GENERIC_H
+#ifndef __BOARDS_RISC_V_ESP32C3_COMMON_INCLUDE_ESP_BOARD_RMT_H
+#define __BOARDS_RISC_V_ESP32C3_COMMON_INCLUDE_ESP_BOARD_RMT_H
 
 /****************************************************************************
  * Included Files
@@ -31,57 +31,67 @@
  * Pre-processor Definitions
  ****************************************************************************/
 
-/****************************************************************************
- * Public Types
- ****************************************************************************/
+#ifndef __ASSEMBLY__
 
 /****************************************************************************
  * Public Data
  ****************************************************************************/
 
-#ifndef __ASSEMBLY__
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
 
 /****************************************************************************
  * Public Function Prototypes
  ****************************************************************************/
 
+#ifdef CONFIG_ESP_RMT
+
 /****************************************************************************
- * Name: esp_bringup
+ * Name: board_rmt_rxinitialize
  *
  * Description:
- *   Perform architecture-specific initialization.
- *
- *   CONFIG_BOARD_LATE_INITIALIZE=y :
- *     Called from board_late_initialize().
- *
- *   CONFIG_BOARD_LATE_INITIALIZE=y && CONFIG_BOARDCTL=y :
- *     Called from the NSH library via board_app_initialize().
+ *   Initialize the RMT peripheral and register a RX device.
  *
  * Input Parameters:
- *   None.
+ *   ch  - the RMT's channel that will be used
+ *   pin - The pin used for the RX channel
  *
  * Returned Value:
- *   Zero (OK) is returned on success; A negated errno value is returned on
- *   any failure.
+ *   Zero (OK) on success; a negated errno value on failure.
  *
  ****************************************************************************/
 
-int esp_bringup(void);
+int board_rmt_rxinitialize(int ch, int pin);
 
 /****************************************************************************
- * Name: esp_gpio_init
+ * Name: board_rmt_txinitialize
  *
  * Description:
- *   Configure the GPIO driver.
+ *   Initialize the RMT peripheral and register a TX device.
+ *
+ * Input Parameters:
+ *   ch  - the RMT's channel that will be used
+ *   pin - The pin used for the TX channel
  *
  * Returned Value:
- *   Zero (OK).
+ *   Zero (OK) on success; a negated errno value on failure.
  *
  ****************************************************************************/
 
-#ifdef CONFIG_DEV_GPIO
-int esp_gpio_init(void);
+int board_rmt_txinitialize(int ch, int pin);
+
+#endif /* CONFIG_ESP_RMT */
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
 #endif
 
 #endif /* __ASSEMBLY__ */
-#endif /* __BOARDS_RISCV_ESP32C3_ESP32C3_GENERIC_SRC_ESP32C3_GENERIC_H */
+#endif /* __BOARDS_RISC_V_ESP32C3_COMMON_INCLUDE_ESP_BOARD_RMT_H */
diff --git a/boards/risc-v/esp32c3/common/src/Make.defs 
b/boards/risc-v/esp32c3/common/src/Make.defs
index 0c1d6abbb2..adb8a5c594 100644
--- a/boards/risc-v/esp32c3/common/src/Make.defs
+++ b/boards/risc-v/esp32c3/common/src/Make.defs
@@ -24,6 +24,10 @@ ifeq ($(CONFIG_ESPRESSIF_LEDC),y)
   CSRCS += esp_board_ledc.c
 endif
 
+ifeq ($(CONFIG_ESP_RMT),y)
+  CSRCS += esp_board_rmt.c
+endif
+
 DEPPATH += --dep-path src
 VPATH += :src
 CFLAGS += 
${INCDIR_PREFIX}$(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src$(DELIM)board$(DELIM)src
diff --git a/boards/risc-v/esp32c3/common/src/esp_board_rmt.c 
b/boards/risc-v/esp32c3/common/src/esp_board_rmt.c
new file mode 100644
index 0000000000..528d70581e
--- /dev/null
+++ b/boards/risc-v/esp32c3/common/src/esp_board_rmt.c
@@ -0,0 +1,150 @@
+/****************************************************************************
+ * boards/risc-v/esp32c3/common/src/esp_board_rmt.c
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+#include <stdio.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/rmt/rmtchar.h>
+#ifdef CONFIG_WS2812_NON_SPI_DRIVER
+#include <nuttx/leds/ws2812.h>
+
+#include "espressif/esp_ws2812.h"
+#endif
+
+#include "espressif/esp_rmt.h"
+
+#ifdef CONFIG_ESP_RMT
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: board_rmt_rxinitialize
+ *
+ * Description:
+ *   Initialize the RMT peripheral and register a RX device.
+ *
+ * Input Parameters:
+ *   ch  - the RMT's channel that will be used
+ *   pin - The pin used for the RX channel
+ *
+ * Returned Value:
+ *   Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int board_rmt_rxinitialize(int ch, int pin)
+{
+  int ret;
+
+  struct rmt_dev_s *rmt = esp_rmt_rx_init(ch, pin);
+
+  ret = rmtchar_register(rmt);
+  if (ret < 0)
+    {
+      rmterr("ERROR: rmtchar_register failed: %d\n", ret);
+      return ret;
+    }
+
+  return ret;
+}
+
+/****************************************************************************
+ * Name: board_rmt_txinitialize
+ *
+ * Description:
+ *   Initialize the RMT peripheral and register a TX device.
+ *
+ * Input Parameters:
+ *   ch  - the RMT's channel that will be used
+ *   pin - The pin used for the TX channel
+ *
+ * Returned Value:
+ *   Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int board_rmt_txinitialize(int ch, int pin)
+{
+  int ret;
+  struct rmt_dev_s *rmt;
+#ifdef CONFIG_WS2812_NON_SPI_DRIVER
+  struct ws2812_dev_s *led;
+#endif
+
+  rmt = esp_rmt_tx_init(ch, pin);
+  if (rmt == NULL)
+    {
+      rmterr("ERROR: esp_rmt_tx_init failed\n");
+      return -ENODEV;
+    }
+
+  ret = rmtchar_register(rmt);
+  if (ret < 0)
+    {
+      rmterr("ERROR: rmtchar_register failed: %d\n", ret);
+      return ret;
+    }
+
+#ifdef CONFIG_WS2812_NON_SPI_DRIVER
+  led = esp_ws2812_setup("/dev/leds0", rmt, CONFIG_WS2812_LED_COUNT, false);
+  if (led == NULL)
+    {
+      rmterr("ERROR: esp_ws2812_setup failed\n");
+      return -ENODEV;
+    }
+#endif
+
+  return ret;
+}
+#endif
diff --git a/boards/risc-v/esp32c3/esp32c3-generic/configs/rmt/defconfig 
b/boards/risc-v/esp32c3/esp32c3-generic/configs/rmt/defconfig
new file mode 100644
index 0000000000..e22df83852
--- /dev/null
+++ b/boards/risc-v/esp32c3/esp32c3-generic/configs/rmt/defconfig
@@ -0,0 +1,59 @@
+#
+# This file is autogenerated: PLEASE DO NOT EDIT IT.
+#
+# You can use "make menuconfig" to make any modifications to the installed 
.config file.
+# You can then do "make savedefconfig" to generate a new defconfig file that 
includes your
+# modifications.
+#
+# CONFIG_NDEBUG is not set
+# CONFIG_NSH_ARGCAT is not set
+# CONFIG_NSH_CMDOPT_HEXDUMP is not set
+CONFIG_ARCH="risc-v"
+CONFIG_ARCH_BOARD="esp32c3-generic"
+CONFIG_ARCH_BOARD_COMMON=y
+CONFIG_ARCH_BOARD_ESP32C3_GENERIC=y
+CONFIG_ARCH_CHIP="esp32c3"
+CONFIG_ARCH_CHIP_ESP32C3_GENERIC=y
+CONFIG_ARCH_INTERRUPTSTACK=1536
+CONFIG_ARCH_RISCV=y
+CONFIG_ARCH_STACKDUMP=y
+CONFIG_BOARDCTL_RESET=y
+CONFIG_BOARD_LOOPSPERMSEC=15000
+CONFIG_BUILTIN=y
+CONFIG_DEV_ZERO=y
+CONFIG_ESP_RMT=y
+CONFIG_EXAMPLES_RMTCHAR=y
+CONFIG_EXAMPLES_RMTCHAR_RX=y
+CONFIG_EXAMPLES_RMTCHAR_RX_DEVPATH="/dev/rmt2"
+CONFIG_EXAMPLES_RMTCHAR_TX=y
+CONFIG_EXAMPLES_WS2812=y
+CONFIG_FS_PROCFS=y
+CONFIG_IDLETHREAD_STACKSIZE=2048
+CONFIG_INIT_ENTRYPOINT="nsh_main"
+CONFIG_INTELHEX_BINARY=y
+CONFIG_LIBC_PERROR_STDOUT=y
+CONFIG_LIBC_STRERROR=y
+CONFIG_NFILE_DESCRIPTORS_PER_BLOCK=6
+CONFIG_NSH_ARCHINIT=y
+CONFIG_NSH_BUILTIN_APPS=y
+CONFIG_NSH_FILEIOSIZE=512
+CONFIG_NSH_READLINE=y
+CONFIG_NSH_STRERROR=y
+CONFIG_PREALLOC_TIMERS=0
+CONFIG_RMT=y
+CONFIG_RMTCHAR=y
+CONFIG_RMT_DEFAULT_RX_BUFFER_SIZE=512
+CONFIG_RR_INTERVAL=200
+CONFIG_SCHED_BACKTRACE=y
+CONFIG_SCHED_WAITPID=y
+CONFIG_START_DAY=29
+CONFIG_START_MONTH=11
+CONFIG_START_YEAR=2019
+CONFIG_SYSTEM_DUMPSTACK=y
+CONFIG_SYSTEM_NSH=y
+CONFIG_TESTING_GETPRIME=y
+CONFIG_TESTING_OSTEST=y
+CONFIG_UART0_SERIAL_CONSOLE=y
+CONFIG_WS2812=y
+CONFIG_WS2812_LED_COUNT=100
+CONFIG_WS2812_NON_SPI_DRIVER=y
diff --git a/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h 
b/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h
index 97f82fe1d9..a77eaa3194 100644
--- a/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h
+++ b/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h
@@ -31,6 +31,19 @@
  * Pre-processor Definitions
  ****************************************************************************/
 
+/* RMT gpio */
+
+#define RMT_RXCHANNEL       2
+#define RMT_TXCHANNEL       0
+
+#ifdef CONFIG_RMT_LOOP_TEST_MODE
+#  define RMT_INPUT_PIN     0
+#  define RMT_OUTPUT_PIN    0
+#else
+#  define RMT_INPUT_PIN     2
+#  define RMT_OUTPUT_PIN    8
+#endif
+
 /****************************************************************************
  * Public Types
  ****************************************************************************/
diff --git a/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3_bringup.c 
b/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3_bringup.c
index 8ca8660f9f..04f8cab22b 100644
--- a/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3_bringup.c
+++ b/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3_bringup.c
@@ -60,6 +60,10 @@
 #  include <nuttx/input/buttons.h>
 #endif
 
+#ifdef CONFIG_ESP_RMT
+#  include "esp_board_rmt.h"
+#endif
+
 #include "esp32c3-generic.h"
 
 /****************************************************************************
@@ -147,6 +151,20 @@ int esp_bringup(void)
     }
 #endif
 
+#ifdef CONFIG_ESP_RMT
+  ret = board_rmt_txinitialize(RMT_TXCHANNEL, RMT_OUTPUT_PIN);
+  if (ret < 0)
+    {
+      syslog(LOG_ERR, "ERROR: board_rmt_txinitialize() failed: %d\n", ret);
+    }
+
+  ret = board_rmt_rxinitialize(RMT_RXCHANNEL, RMT_INPUT_PIN);
+  if (ret < 0)
+    {
+      syslog(LOG_ERR, "ERROR: board_rmt_txinitialize() failed: %d\n", ret);
+    }
+#endif
+
 #ifdef CONFIG_RTC_DRIVER
   /* Initialize the RTC driver */
 
diff --git a/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h 
b/boards/risc-v/esp32c6/common/include/esp_board_rmt.h
similarity index 67%
copy from boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h
copy to boards/risc-v/esp32c6/common/include/esp_board_rmt.h
index 97f82fe1d9..cbb3f56f5c 100644
--- a/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h
+++ b/boards/risc-v/esp32c6/common/include/esp_board_rmt.h
@@ -1,5 +1,5 @@
 /****************************************************************************
- * boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h
+ * boards/risc-v/esp32c6/common/include/esp_board_rmt.h
  *
  * Licensed to the Apache Software Foundation (ASF) under one or more
  * contributor license agreements.  See the NOTICE file distributed with
@@ -18,8 +18,8 @@
  *
  ****************************************************************************/
 
-#ifndef __BOARDS_RISCV_ESP32C3_ESP32C3_GENERIC_SRC_ESP32C3_GENERIC_H
-#define __BOARDS_RISCV_ESP32C3_ESP32C3_GENERIC_SRC_ESP32C3_GENERIC_H
+#ifndef __BOARDS_RISC_V_ESP32C6_COMMON_INCLUDE_ESP_BOARD_RMT_H
+#define __BOARDS_RISC_V_ESP32C6_COMMON_INCLUDE_ESP_BOARD_RMT_H
 
 /****************************************************************************
  * Included Files
@@ -31,57 +31,67 @@
  * Pre-processor Definitions
  ****************************************************************************/
 
-/****************************************************************************
- * Public Types
- ****************************************************************************/
+#ifndef __ASSEMBLY__
 
 /****************************************************************************
  * Public Data
  ****************************************************************************/
 
-#ifndef __ASSEMBLY__
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
 
 /****************************************************************************
  * Public Function Prototypes
  ****************************************************************************/
 
+#ifdef CONFIG_ESP_RMT
+
 /****************************************************************************
- * Name: esp_bringup
+ * Name: board_rmt_rxinitialize
  *
  * Description:
- *   Perform architecture-specific initialization.
- *
- *   CONFIG_BOARD_LATE_INITIALIZE=y :
- *     Called from board_late_initialize().
- *
- *   CONFIG_BOARD_LATE_INITIALIZE=y && CONFIG_BOARDCTL=y :
- *     Called from the NSH library via board_app_initialize().
+ *   Initialize the RMT peripheral and register a RX device.
  *
  * Input Parameters:
- *   None.
+ *   ch  - the RMT's channel that will be used
+ *   pin - The pin used for the RX channel
  *
  * Returned Value:
- *   Zero (OK) is returned on success; A negated errno value is returned on
- *   any failure.
+ *   Zero (OK) on success; a negated errno value on failure.
  *
  ****************************************************************************/
 
-int esp_bringup(void);
+int board_rmt_rxinitialize(int ch, int pin);
 
 /****************************************************************************
- * Name: esp_gpio_init
+ * Name: board_rmt_txinitialize
  *
  * Description:
- *   Configure the GPIO driver.
+ *   Initialize the RMT peripheral and register a TX device.
+ *
+ * Input Parameters:
+ *   ch  - the RMT's channel that will be used
+ *   pin - The pin used for the TX channel
  *
  * Returned Value:
- *   Zero (OK).
+ *   Zero (OK) on success; a negated errno value on failure.
  *
  ****************************************************************************/
 
-#ifdef CONFIG_DEV_GPIO
-int esp_gpio_init(void);
+int board_rmt_txinitialize(int ch, int pin);
+
+#endif /* CONFIG_ESP_RMT */
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
 #endif
 
 #endif /* __ASSEMBLY__ */
-#endif /* __BOARDS_RISCV_ESP32C3_ESP32C3_GENERIC_SRC_ESP32C3_GENERIC_H */
+#endif /* __BOARDS_RISC_V_ESP32C6_COMMON_INCLUDE_ESP_BOARD_RMT_H */
diff --git a/boards/risc-v/esp32c6/common/src/Make.defs 
b/boards/risc-v/esp32c6/common/src/Make.defs
index 6581c3adaa..bf8aa770e3 100644
--- a/boards/risc-v/esp32c6/common/src/Make.defs
+++ b/boards/risc-v/esp32c6/common/src/Make.defs
@@ -24,6 +24,10 @@ ifeq ($(CONFIG_ESPRESSIF_LEDC),y)
   CSRCS += esp_board_ledc.c
 endif
 
+ifeq ($(CONFIG_ESP_RMT),y)
+  CSRCS += esp_board_rmt.c
+endif
+
 DEPPATH += --dep-path src
 VPATH += :src
 CFLAGS += 
${INCDIR_PREFIX}$(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src$(DELIM)board$(DELIM)src
diff --git a/boards/risc-v/esp32c6/common/src/esp_board_rmt.c 
b/boards/risc-v/esp32c6/common/src/esp_board_rmt.c
new file mode 100644
index 0000000000..d73ebcd23a
--- /dev/null
+++ b/boards/risc-v/esp32c6/common/src/esp_board_rmt.c
@@ -0,0 +1,150 @@
+/****************************************************************************
+ * boards/risc-v/esp32c6/common/src/esp_board_rmt.c
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+#include <stdio.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/rmt/rmtchar.h>
+#ifdef CONFIG_WS2812_NON_SPI_DRIVER
+#include <nuttx/leds/ws2812.h>
+
+#include "espressif/esp_ws2812.h"
+#endif
+
+#include "espressif/esp_rmt.h"
+
+#ifdef CONFIG_ESP_RMT
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: board_rmt_rxinitialize
+ *
+ * Description:
+ *   Initialize the RMT peripheral and register a RX device.
+ *
+ * Input Parameters:
+ *   ch  - the RMT's channel that will be used
+ *   pin - The pin used for the RX channel
+ *
+ * Returned Value:
+ *   Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int board_rmt_rxinitialize(int ch, int pin)
+{
+  int ret;
+
+  struct rmt_dev_s *rmt = esp_rmt_rx_init(ch, pin);
+
+  ret = rmtchar_register(rmt);
+  if (ret < 0)
+    {
+      rmterr("ERROR: rmtchar_register failed: %d\n", ret);
+      return ret;
+    }
+
+  return ret;
+}
+
+/****************************************************************************
+ * Name: board_rmt_txinitialize
+ *
+ * Description:
+ *   Initialize the RMT peripheral and register a TX device.
+ *
+ * Input Parameters:
+ *   ch  - the RMT's channel that will be used
+ *   pin - The pin used for the TX channel
+ *
+ * Returned Value:
+ *   Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int board_rmt_txinitialize(int ch, int pin)
+{
+  int ret;
+  struct rmt_dev_s *rmt;
+#ifdef CONFIG_WS2812_NON_SPI_DRIVER
+  struct ws2812_dev_s *led;
+#endif
+
+  rmt = esp_rmt_tx_init(ch, pin);
+  if (rmt == NULL)
+    {
+      rmterr("ERROR: esp_rmt_tx_init failed\n");
+      return -ENODEV;
+    }
+
+  ret = rmtchar_register(rmt);
+  if (ret < 0)
+    {
+      rmterr("ERROR: rmtchar_register failed: %d\n", ret);
+      return ret;
+    }
+
+#ifdef CONFIG_WS2812_NON_SPI_DRIVER
+  led = esp_ws2812_setup("/dev/leds0", rmt, CONFIG_WS2812_LED_COUNT, false);
+  if (led == NULL)
+    {
+      rmterr("ERROR: esp_ws2812_setup failed\n");
+      return -ENODEV;
+    }
+#endif
+
+  return ret;
+}
+#endif
diff --git a/boards/risc-v/esp32c6/esp32c6-devkit/configs/rmt/defconfig 
b/boards/risc-v/esp32c6/esp32c6-devkit/configs/rmt/defconfig
new file mode 100644
index 0000000000..742d400eb4
--- /dev/null
+++ b/boards/risc-v/esp32c6/esp32c6-devkit/configs/rmt/defconfig
@@ -0,0 +1,59 @@
+#
+# This file is autogenerated: PLEASE DO NOT EDIT IT.
+#
+# You can use "make menuconfig" to make any modifications to the installed 
.config file.
+# You can then do "make savedefconfig" to generate a new defconfig file that 
includes your
+# modifications.
+#
+# CONFIG_NSH_ARGCAT is not set
+# CONFIG_NSH_CMDOPT_HEXDUMP is not set
+CONFIG_ARCH="risc-v"
+CONFIG_ARCH_BOARD="esp32c6-devkit"
+CONFIG_ARCH_BOARD_COMMON=y
+CONFIG_ARCH_BOARD_ESP32C6_DEVKIT=y
+CONFIG_ARCH_CHIP="esp32c6"
+CONFIG_ARCH_CHIP_ESP32C6=y
+CONFIG_ARCH_INTERRUPTSTACK=2048
+CONFIG_ARCH_RISCV=y
+CONFIG_ARCH_STACKDUMP=y
+CONFIG_BOARDCTL_RESET=y
+CONFIG_BOARD_LOOPSPERMSEC=15000
+CONFIG_BUILTIN=y
+CONFIG_DEV_ZERO=y
+CONFIG_ESPRESSIF_ESP32C6=y
+CONFIG_ESP_RMT=y
+CONFIG_EXAMPLES_RMTCHAR=y
+CONFIG_EXAMPLES_RMTCHAR_RX=y
+CONFIG_EXAMPLES_RMTCHAR_RX_DEVPATH="/dev/rmt2"
+CONFIG_EXAMPLES_RMTCHAR_TX=y
+CONFIG_EXAMPLES_WS2812=y
+CONFIG_FS_PROCFS=y
+CONFIG_IDLETHREAD_STACKSIZE=2048
+CONFIG_INIT_ENTRYPOINT="nsh_main"
+CONFIG_INTELHEX_BINARY=y
+CONFIG_LIBC_PERROR_STDOUT=y
+CONFIG_LIBC_STRERROR=y
+CONFIG_NFILE_DESCRIPTORS_PER_BLOCK=6
+CONFIG_NSH_ARCHINIT=y
+CONFIG_NSH_BUILTIN_APPS=y
+CONFIG_NSH_FILEIOSIZE=512
+CONFIG_NSH_READLINE=y
+CONFIG_NSH_STRERROR=y
+CONFIG_PREALLOC_TIMERS=0
+CONFIG_RMT=y
+CONFIG_RMTCHAR=y
+CONFIG_RMT_DEFAULT_RX_BUFFER_SIZE=512
+CONFIG_RR_INTERVAL=200
+CONFIG_SCHED_BACKTRACE=y
+CONFIG_SCHED_WAITPID=y
+CONFIG_START_DAY=29
+CONFIG_START_MONTH=11
+CONFIG_START_YEAR=2019
+CONFIG_SYSTEM_DUMPSTACK=y
+CONFIG_SYSTEM_NSH=y
+CONFIG_TESTING_GETPRIME=y
+CONFIG_TESTING_OSTEST=y
+CONFIG_UART0_SERIAL_CONSOLE=y
+CONFIG_WS2812=y
+CONFIG_WS2812_LED_COUNT=100
+CONFIG_WS2812_NON_SPI_DRIVER=y
diff --git a/boards/risc-v/esp32c6/esp32c6-devkit/src/esp32c6-devkit.h 
b/boards/risc-v/esp32c6/esp32c6-devkit/src/esp32c6-devkit.h
index ad6766b0e4..b47e5acc64 100644
--- a/boards/risc-v/esp32c6/esp32c6-devkit/src/esp32c6-devkit.h
+++ b/boards/risc-v/esp32c6/esp32c6-devkit/src/esp32c6-devkit.h
@@ -31,6 +31,19 @@
  * Pre-processor Definitions
  ****************************************************************************/
 
+/* RMT gpio */
+
+#define RMT_RXCHANNEL       2
+#define RMT_TXCHANNEL       0
+
+#ifdef CONFIG_RMT_LOOP_TEST_MODE
+#  define RMT_INPUT_PIN     0
+#  define RMT_OUTPUT_PIN    0
+#else
+#  define RMT_INPUT_PIN     2
+#  define RMT_OUTPUT_PIN    8
+#endif
+
 /****************************************************************************
  * Public Types
  ****************************************************************************/
diff --git a/boards/risc-v/esp32c6/esp32c6-devkit/src/esp32c6_bringup.c 
b/boards/risc-v/esp32c6/esp32c6-devkit/src/esp32c6_bringup.c
index 642c27b27b..596df3a9f1 100644
--- a/boards/risc-v/esp32c6/esp32c6-devkit/src/esp32c6_bringup.c
+++ b/boards/risc-v/esp32c6/esp32c6-devkit/src/esp32c6_bringup.c
@@ -60,6 +60,10 @@
 #  include <nuttx/input/buttons.h>
 #endif
 
+#ifdef CONFIG_ESP_RMT
+#  include "esp_board_rmt.h"
+#endif
+
 #include "esp32c6-devkit.h"
 
 /****************************************************************************
@@ -147,6 +151,20 @@ int esp_bringup(void)
     }
 #endif
 
+#ifdef CONFIG_ESP_RMT
+  ret = board_rmt_txinitialize(RMT_TXCHANNEL, RMT_OUTPUT_PIN);
+  if (ret < 0)
+    {
+      syslog(LOG_ERR, "ERROR: board_rmt_txinitialize() failed: %d\n", ret);
+    }
+
+  ret = board_rmt_rxinitialize(RMT_RXCHANNEL, RMT_INPUT_PIN);
+  if (ret < 0)
+    {
+      syslog(LOG_ERR, "ERROR: board_rmt_txinitialize() failed: %d\n", ret);
+    }
+#endif
+
 #ifdef CONFIG_RTC_DRIVER
   /* Initialize the RTC driver */
 
diff --git a/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h 
b/boards/risc-v/esp32h2/common/include/esp_board_rmt.h
similarity index 67%
copy from boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h
copy to boards/risc-v/esp32h2/common/include/esp_board_rmt.h
index 97f82fe1d9..4106b0d5d3 100644
--- a/boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h
+++ b/boards/risc-v/esp32h2/common/include/esp_board_rmt.h
@@ -1,5 +1,5 @@
 /****************************************************************************
- * boards/risc-v/esp32c3/esp32c3-generic/src/esp32c3-generic.h
+ * boards/risc-v/esp32h2/common/include/esp_board_rmt.h
  *
  * Licensed to the Apache Software Foundation (ASF) under one or more
  * contributor license agreements.  See the NOTICE file distributed with
@@ -18,8 +18,8 @@
  *
  ****************************************************************************/
 
-#ifndef __BOARDS_RISCV_ESP32C3_ESP32C3_GENERIC_SRC_ESP32C3_GENERIC_H
-#define __BOARDS_RISCV_ESP32C3_ESP32C3_GENERIC_SRC_ESP32C3_GENERIC_H
+#ifndef __BOARDS_RISC_V_ESP32H2_COMMON_INCLUDE_ESP_BOARD_RMT_H
+#define __BOARDS_RISC_V_ESP32H2_COMMON_INCLUDE_ESP_BOARD_RMT_H
 
 /****************************************************************************
  * Included Files
@@ -31,57 +31,67 @@
  * Pre-processor Definitions
  ****************************************************************************/
 
-/****************************************************************************
- * Public Types
- ****************************************************************************/
+#ifndef __ASSEMBLY__
 
 /****************************************************************************
  * Public Data
  ****************************************************************************/
 
-#ifndef __ASSEMBLY__
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
 
 /****************************************************************************
  * Public Function Prototypes
  ****************************************************************************/
 
+#ifdef CONFIG_ESP_RMT
+
 /****************************************************************************
- * Name: esp_bringup
+ * Name: board_rmt_rxinitialize
  *
  * Description:
- *   Perform architecture-specific initialization.
- *
- *   CONFIG_BOARD_LATE_INITIALIZE=y :
- *     Called from board_late_initialize().
- *
- *   CONFIG_BOARD_LATE_INITIALIZE=y && CONFIG_BOARDCTL=y :
- *     Called from the NSH library via board_app_initialize().
+ *   Initialize the RMT peripheral and register a RX device.
  *
  * Input Parameters:
- *   None.
+ *   ch  - the RMT's channel that will be used
+ *   pin - The pin used for the RX channel
  *
  * Returned Value:
- *   Zero (OK) is returned on success; A negated errno value is returned on
- *   any failure.
+ *   Zero (OK) on success; a negated errno value on failure.
  *
  ****************************************************************************/
 
-int esp_bringup(void);
+int board_rmt_rxinitialize(int ch, int pin);
 
 /****************************************************************************
- * Name: esp_gpio_init
+ * Name: board_rmt_txinitialize
  *
  * Description:
- *   Configure the GPIO driver.
+ *   Initialize the RMT peripheral and register a TX device.
+ *
+ * Input Parameters:
+ *   ch  - the RMT's channel that will be used
+ *   pin - The pin used for the TX channel
  *
  * Returned Value:
- *   Zero (OK).
+ *   Zero (OK) on success; a negated errno value on failure.
  *
  ****************************************************************************/
 
-#ifdef CONFIG_DEV_GPIO
-int esp_gpio_init(void);
+int board_rmt_txinitialize(int ch, int pin);
+
+#endif /* CONFIG_ESP_RMT */
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
 #endif
 
 #endif /* __ASSEMBLY__ */
-#endif /* __BOARDS_RISCV_ESP32C3_ESP32C3_GENERIC_SRC_ESP32C3_GENERIC_H */
+#endif /* __BOARDS_RISC_V_ESP32H2_COMMON_INCLUDE_ESP_BOARD_RMT_H */
diff --git a/boards/risc-v/esp32h2/common/src/Make.defs 
b/boards/risc-v/esp32h2/common/src/Make.defs
index 2dee42cd04..90b594c2e4 100644
--- a/boards/risc-v/esp32h2/common/src/Make.defs
+++ b/boards/risc-v/esp32h2/common/src/Make.defs
@@ -24,6 +24,10 @@ ifeq ($(CONFIG_ESPRESSIF_LEDC),y)
   CSRCS += esp_board_ledc.c
 endif
 
+ifeq ($(CONFIG_ESP_RMT),y)
+  CSRCS += esp_board_rmt.c
+endif
+
 DEPPATH += --dep-path src
 VPATH += :src
 CFLAGS += 
${INCDIR_PREFIX}$(TOPDIR)$(DELIM)arch$(DELIM)$(CONFIG_ARCH)$(DELIM)src$(DELIM)board$(DELIM)src
diff --git a/boards/risc-v/esp32h2/common/src/esp_board_rmt.c 
b/boards/risc-v/esp32h2/common/src/esp_board_rmt.c
new file mode 100644
index 0000000000..3948444336
--- /dev/null
+++ b/boards/risc-v/esp32h2/common/src/esp_board_rmt.c
@@ -0,0 +1,150 @@
+/****************************************************************************
+ * boards/risc-v/esp32h2/common/src/esp_board_rmt.c
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+#include <stdio.h>
+
+#include <nuttx/kmalloc.h>
+#include <nuttx/rmt/rmtchar.h>
+#ifdef CONFIG_WS2812_NON_SPI_DRIVER
+#include <nuttx/leds/ws2812.h>
+
+#include "espressif/esp_ws2812.h"
+#endif
+
+#include "espressif/esp_rmt.h"
+
+#ifdef CONFIG_ESP_RMT
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: board_rmt_rxinitialize
+ *
+ * Description:
+ *   Initialize the RMT peripheral and register a RX device.
+ *
+ * Input Parameters:
+ *   ch  - the RMT's channel that will be used
+ *   pin - The pin used for the RX channel
+ *
+ * Returned Value:
+ *   Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int board_rmt_rxinitialize(int ch, int pin)
+{
+  int ret;
+
+  struct rmt_dev_s *rmt = esp_rmt_rx_init(ch, pin);
+
+  ret = rmtchar_register(rmt);
+  if (ret < 0)
+    {
+      rmterr("ERROR: rmtchar_register failed: %d\n", ret);
+      return ret;
+    }
+
+  return ret;
+}
+
+/****************************************************************************
+ * Name: board_rmt_txinitialize
+ *
+ * Description:
+ *   Initialize the RMT peripheral and register a TX device.
+ *
+ * Input Parameters:
+ *   ch  - the RMT's channel that will be used
+ *   pin - The pin used for the TX channel
+ *
+ * Returned Value:
+ *   Zero (OK) on success; a negated errno value on failure.
+ *
+ ****************************************************************************/
+
+int board_rmt_txinitialize(int ch, int pin)
+{
+  int ret;
+  struct rmt_dev_s *rmt;
+#ifdef CONFIG_WS2812_NON_SPI_DRIVER
+  struct ws2812_dev_s *led;
+#endif
+
+  rmt = esp_rmt_tx_init(ch, pin);
+  if (rmt == NULL)
+    {
+      rmterr("ERROR: esp_rmt_tx_init failed\n");
+      return -ENODEV;
+    }
+
+  ret = rmtchar_register(rmt);
+  if (ret < 0)
+    {
+      rmterr("ERROR: rmtchar_register failed: %d\n", ret);
+      return ret;
+    }
+
+#ifdef CONFIG_WS2812_NON_SPI_DRIVER
+  led = esp_ws2812_setup("/dev/leds0", rmt, CONFIG_WS2812_LED_COUNT, false);
+  if (led == NULL)
+    {
+      rmterr("ERROR: esp_ws2812_setup failed\n");
+      return -ENODEV;
+    }
+#endif
+
+  return ret;
+}
+#endif
diff --git a/boards/risc-v/esp32h2/esp32h2-devkit/configs/rmt/defconfig 
b/boards/risc-v/esp32h2/esp32h2-devkit/configs/rmt/defconfig
new file mode 100644
index 0000000000..a4ef3497e0
--- /dev/null
+++ b/boards/risc-v/esp32h2/esp32h2-devkit/configs/rmt/defconfig
@@ -0,0 +1,59 @@
+#
+# This file is autogenerated: PLEASE DO NOT EDIT IT.
+#
+# You can use "make menuconfig" to make any modifications to the installed 
.config file.
+# You can then do "make savedefconfig" to generate a new defconfig file that 
includes your
+# modifications.
+#
+# CONFIG_NSH_ARGCAT is not set
+# CONFIG_NSH_CMDOPT_HEXDUMP is not set
+CONFIG_ARCH="risc-v"
+CONFIG_ARCH_BOARD="esp32h2-devkit"
+CONFIG_ARCH_BOARD_COMMON=y
+CONFIG_ARCH_BOARD_ESP32H2_DEVKIT=y
+CONFIG_ARCH_CHIP="esp32h2"
+CONFIG_ARCH_CHIP_ESP32H2=y
+CONFIG_ARCH_INTERRUPTSTACK=2048
+CONFIG_ARCH_RISCV=y
+CONFIG_ARCH_STACKDUMP=y
+CONFIG_BOARDCTL_RESET=y
+CONFIG_BOARD_LOOPSPERMSEC=15000
+CONFIG_BUILTIN=y
+CONFIG_DEV_ZERO=y
+CONFIG_ESPRESSIF_ESP32H2=y
+CONFIG_ESP_RMT=y
+CONFIG_EXAMPLES_RMTCHAR=y
+CONFIG_EXAMPLES_RMTCHAR_RX=y
+CONFIG_EXAMPLES_RMTCHAR_RX_DEVPATH="/dev/rmt2"
+CONFIG_EXAMPLES_RMTCHAR_TX=y
+CONFIG_EXAMPLES_WS2812=y
+CONFIG_FS_PROCFS=y
+CONFIG_IDLETHREAD_STACKSIZE=2048
+CONFIG_INIT_ENTRYPOINT="nsh_main"
+CONFIG_INTELHEX_BINARY=y
+CONFIG_LIBC_PERROR_STDOUT=y
+CONFIG_LIBC_STRERROR=y
+CONFIG_NFILE_DESCRIPTORS_PER_BLOCK=6
+CONFIG_NSH_ARCHINIT=y
+CONFIG_NSH_BUILTIN_APPS=y
+CONFIG_NSH_FILEIOSIZE=512
+CONFIG_NSH_READLINE=y
+CONFIG_NSH_STRERROR=y
+CONFIG_PREALLOC_TIMERS=0
+CONFIG_RMT=y
+CONFIG_RMTCHAR=y
+CONFIG_RMT_DEFAULT_RX_BUFFER_SIZE=512
+CONFIG_RR_INTERVAL=200
+CONFIG_SCHED_BACKTRACE=y
+CONFIG_SCHED_WAITPID=y
+CONFIG_START_DAY=29
+CONFIG_START_MONTH=11
+CONFIG_START_YEAR=2019
+CONFIG_SYSTEM_DUMPSTACK=y
+CONFIG_SYSTEM_NSH=y
+CONFIG_TESTING_GETPRIME=y
+CONFIG_TESTING_OSTEST=y
+CONFIG_UART0_SERIAL_CONSOLE=y
+CONFIG_WS2812=y
+CONFIG_WS2812_LED_COUNT=100
+CONFIG_WS2812_NON_SPI_DRIVER=y
diff --git a/boards/risc-v/esp32h2/esp32h2-devkit/src/esp32h2-devkit.h 
b/boards/risc-v/esp32h2/esp32h2-devkit/src/esp32h2-devkit.h
index 03fcbe1f1c..9e64ed4bce 100644
--- a/boards/risc-v/esp32h2/esp32h2-devkit/src/esp32h2-devkit.h
+++ b/boards/risc-v/esp32h2/esp32h2-devkit/src/esp32h2-devkit.h
@@ -31,6 +31,19 @@
  * Pre-processor Definitions
  ****************************************************************************/
 
+/* RMT gpio */
+
+#define RMT_RXCHANNEL       2
+#define RMT_TXCHANNEL       0
+
+#ifdef CONFIG_RMT_LOOP_TEST_MODE
+#  define RMT_INPUT_PIN     0
+#  define RMT_OUTPUT_PIN    0
+#else
+#  define RMT_INPUT_PIN     2
+#  define RMT_OUTPUT_PIN    8
+#endif
+
 /****************************************************************************
  * Public Types
  ****************************************************************************/
diff --git a/boards/risc-v/esp32h2/esp32h2-devkit/src/esp32h2_bringup.c 
b/boards/risc-v/esp32h2/esp32h2-devkit/src/esp32h2_bringup.c
index d597e8ba51..03123200c5 100644
--- a/boards/risc-v/esp32h2/esp32h2-devkit/src/esp32h2_bringup.c
+++ b/boards/risc-v/esp32h2/esp32h2-devkit/src/esp32h2_bringup.c
@@ -60,6 +60,10 @@
 #  include <nuttx/input/buttons.h>
 #endif
 
+#ifdef CONFIG_ESP_RMT
+#  include "esp_board_rmt.h"
+#endif
+
 #include "esp32h2-devkit.h"
 
 /****************************************************************************
@@ -147,6 +151,20 @@ int esp_bringup(void)
     }
 #endif
 
+#ifdef CONFIG_ESP_RMT
+  ret = board_rmt_txinitialize(RMT_TXCHANNEL, RMT_OUTPUT_PIN);
+  if (ret < 0)
+    {
+      syslog(LOG_ERR, "ERROR: board_rmt_txinitialize() failed: %d\n", ret);
+    }
+
+  ret = board_rmt_rxinitialize(RMT_RXCHANNEL, RMT_INPUT_PIN);
+  if (ret < 0)
+    {
+      syslog(LOG_ERR, "ERROR: board_rmt_txinitialize() failed: %d\n", ret);
+    }
+#endif
+
 #ifdef CONFIG_RTC_DRIVER
   /* Initialize the RTC driver */
 


Reply via email to