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


The following commit(s) were added to refs/heads/master by this push:
     new c8b7950bd4d risc-v/espressif/uart: Update common source code functions
c8b7950bd4d is described below

commit c8b7950bd4d85cad1a2b3474e44cb8b8c07bf993
Author: Tiago Medicci Serrano <[email protected]>
AuthorDate: Wed Sep 24 10:25:50 2025 -0300

    risc-v/espressif/uart: Update common source code functions
    
    Updates the common source code for the UART peripheral used by
    Espressif's RISC-Vs SoCs. This enables newer SoCs to be supported
    in the future while maintaining backwards compatibility.
    
    Signed-off-by: Tiago Medicci Serrano <[email protected]>
---
 arch/risc-v/src/common/espressif/esp_lowputc.c   | 139 ++++++++++++++++-------
 arch/risc-v/src/common/espressif/esp_lowputc.h   |  32 +++---
 arch/risc-v/src/common/espressif/esp_serial.c    |  71 ++++++++----
 arch/risc-v/src/common/espressif/esp_usbserial.c |  24 ++--
 arch/risc-v/src/esp32c3/hal_esp32c3.mk           |   2 +-
 arch/risc-v/src/esp32h2/hal_esp32h2.mk           |   2 +-
 6 files changed, 169 insertions(+), 101 deletions(-)

diff --git a/arch/risc-v/src/common/espressif/esp_lowputc.c 
b/arch/risc-v/src/common/espressif/esp_lowputc.c
index b358c990537..af400264e8f 100644
--- a/arch/risc-v/src/common/espressif/esp_lowputc.c
+++ b/arch/risc-v/src/common/espressif/esp_lowputc.c
@@ -47,8 +47,11 @@
 #include "esp_irq.h"
 #include "esp_lowputc.h"
 #include "esp_usbserial.h"
+#include "esp_private/critical_section.h"
+#include "esp_private/uart_share_hw_ctrl.h"
 
 #include "hal/uart_hal.h"
+#include "soc/uart_periph.h"
 #include "periph_ctrl.h"
 #include "soc/gpio_sig_map.h"
 #ifdef CONFIG_ESPRESSIF_LP_UART
@@ -71,6 +74,18 @@
 #  define ESP_LP_UART0_ID     UART_NUM_MAX
 #endif /* CONFIG_ESPRESSIF_LP_UART */
 
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define UART_CONTEXT_INIT_DEF(uart_num) \
+{ \
+  .port_id = uart_num, \
+  .hal.dev = UART_LL_GET_HW(uart_num), \
+  INIT_CRIT_SECTION_LOCK_IN_STRUCT(spinlock) \
+  .hw_enabled = false, \
+}
+
 /****************************************************************************
  * Private Types
  ****************************************************************************/
@@ -90,22 +105,17 @@ static uart_hal_context_t g_uart0_hal =
 
 struct esp_uart_s g_uart0_config =
 {
-  .source = UART0_INTR_SOURCE,
   .cpuint = -ENOMEM,
   .int_pri = ESP_IRQ_PRIORITY_DEFAULT,
   .id = 0,
-  .irq = ESP_IRQ_UART0,
   .baud = CONFIG_UART0_BAUD,
   .stop_b2 =  CONFIG_UART0_2STOP,
   .bits = CONFIG_UART0_BITS,
   .parity = CONFIG_UART0_PARITY,
   .txpin = CONFIG_ESPRESSIF_UART0_TXPIN,
-  .txsig = U0TXD_OUT_IDX,
   .rxpin = CONFIG_ESPRESSIF_UART0_RXPIN,
-  .rxsig = U0RXD_IN_IDX,
 #ifdef CONFIG_SERIAL_IFLOWCONTROL
   .rtspin = CONFIG_ESPRESSIF_UART0_RTSPIN,
-  .rtssig = U0RTS_OUT_IDX,
 #ifdef CONFIG_UART0_IFLOWCONTROL
   .iflow  = true,    /* input flow control (RTS) enabled */
 #else
@@ -114,7 +124,6 @@ struct esp_uart_s g_uart0_config =
 #endif
 #ifdef CONFIG_SERIAL_OFLOWCONTROL
   .ctspin = CONFIG_ESPRESSIF_UART0_CTSPIN,
-  .ctssig = U0CTS_IN_IDX,
 #ifdef CONFIG_UART0_OFLOWCONTROL
   .oflow  = true,    /* output flow control (CTS) enabled */
 #else
@@ -145,22 +154,17 @@ static uart_hal_context_t g_uart1_hal =
 
 struct esp_uart_s g_uart1_config =
 {
-  .source = UART1_INTR_SOURCE,
   .cpuint = -ENOMEM,
   .int_pri = ESP_IRQ_PRIORITY_DEFAULT,
   .id = 1,
-  .irq = ESP_IRQ_UART1,
   .baud = CONFIG_UART1_BAUD,
   .stop_b2 = CONFIG_UART1_2STOP,
   .bits = CONFIG_UART1_BITS,
   .parity = CONFIG_UART1_PARITY,
   .txpin = CONFIG_ESPRESSIF_UART1_TXPIN,
-  .txsig = U1TXD_OUT_IDX,
   .rxpin = CONFIG_ESPRESSIF_UART1_RXPIN,
-  .rxsig = U1RXD_IN_IDX,
 #ifdef CONFIG_SERIAL_IFLOWCONTROL
   .rtspin = CONFIG_ESPRESSIF_UART1_RTSPIN,
-  .rtssig = U1RTS_OUT_IDX,
 #ifdef CONFIG_UART1_IFLOWCONTROL
   .iflow  = true,    /* input flow control (RTS) enabled */
 #else
@@ -169,7 +173,6 @@ struct esp_uart_s g_uart1_config =
 #endif
 #ifdef CONFIG_SERIAL_OFLOWCONTROL
   .ctspin = CONFIG_ESPRESSIF_UART1_CTSPIN,
-  .ctssig = U1CTS_IN_IDX,
 #ifdef CONFIG_UART1_OFLOWCONTROL
   .oflow  = true,    /* output flow control (CTS) enabled */
 #else
@@ -200,22 +203,17 @@ static uart_hal_context_t g_lp_uart0_hal =
 
 struct esp_uart_s g_lp_uart0_config =
 {
-  .source = LP_UART_INTR_SOURCE,
   .cpuint = -ENOMEM,
   .int_pri = ESP_IRQ_PRIORITY_DEFAULT,
   .id = ESP_LP_UART0_ID,
-  .irq = ESP_IRQ_LP_UART,
   .baud = CONFIG_LPUART0_BAUD,
   .stop_b2 = CONFIG_LPUART0_2STOP,
   .bits = CONFIG_LPUART0_BITS,
   .parity = CONFIG_LPUART0_PARITY,
   .txpin = LP_UART_DEFAULT_TX_GPIO_NUM,
-  .txsig = LP_U0TXD_MUX_FUNC,
   .rxpin = LP_UART_DEFAULT_RX_GPIO_NUM,
-  .rxsig = LP_U0RXD_MUX_FUNC,
 #ifdef CONFIG_SERIAL_IFLOWCONTROL
   .rtspin = LP_UART_DEFAULT_RTS_GPIO_NUM,
-  .rtssig = LP_U0RTS_MUX_FUNC,
 #ifdef CONFIG_LPUART0_IFLOWCONTROL
   .iflow  = true,    /* input flow control (RTS) enabled */
 #else
@@ -224,7 +222,6 @@ struct esp_uart_s g_lp_uart0_config =
 #endif
 #ifdef CONFIG_SERIAL_OFLOWCONTROL
   .ctspin = LP_UART_DEFAULT_CTS_GPIO_NUM,
-  .ctssig = LP_U0CTS_MUX_FUNC,
 #ifdef CONFIG_LPUART0_OFLOWCONTROL
   .oflow  = true,    /* output flow control (CTS) enabled */
 #else
@@ -240,6 +237,28 @@ struct esp_uart_s g_lp_uart0_config =
 
 #endif /* HAVE_UART_DEVICE */
 
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+uart_context_t g_uart_context[UART_NUM_MAX] =
+{
+  UART_CONTEXT_INIT_DEF(UART_NUM_0),
+  UART_CONTEXT_INIT_DEF(UART_NUM_1),
+#if SOC_UART_HP_NUM > 2
+  UART_CONTEXT_INIT_DEF(UART_NUM_2),
+#endif
+#if SOC_UART_HP_NUM > 3
+  UART_CONTEXT_INIT_DEF(UART_NUM_3),
+#endif
+#if SOC_UART_HP_NUM > 4
+  UART_CONTEXT_INIT_DEF(UART_NUM_4),
+#endif
+#if (SOC_UART_LP_NUM >= 1)
+  UART_CONTEXT_INIT_DEF(LP_UART_NUM_0),
+#endif
+};
+
 /****************************************************************************
  * Private Functions
  ****************************************************************************/
@@ -295,6 +314,51 @@ static void esp_lowputc_lp_uart_config_io(const struct 
esp_uart_s *priv,
  * Public Functions
  ****************************************************************************/
 
+bool esp_lowputc_uart_module_enable(const struct esp_uart_s *priv)
+{
+  int uart_num = priv->id;
+  bool newly_enabled = false;
+  mutex_t lock;
+
+  nxmutex_init(&lock);
+
+  g_uart_context[uart_num].mutex = (_lock_t)&lock;
+
+  _lock_acquire(&(g_uart_context[uart_num].mutex));
+
+  if (g_uart_context[uart_num].hw_enabled != true)
+    {
+      if (uart_num < SOC_UART_HP_NUM)
+        {
+          HP_UART_BUS_CLK_ATOMIC()
+            {
+              uart_ll_enable_bus_clock(uart_num, true);
+            }
+
+          if (uart_num != CONFIG_ESP_CONSOLE_UART_NUM)
+            {
+              HP_UART_BUS_CLK_ATOMIC()
+                {
+                  uart_ll_reset_register(uart_num);
+                }
+
+              HP_UART_SRC_CLK_ATOMIC()
+                {
+                  uart_ll_sclk_enable(g_uart_context[uart_num].hal.dev);
+                }
+            }
+        }
+
+      g_uart_context[uart_num].hw_enabled = true;
+      newly_enabled = true;
+    }
+
+  _lock_release(&(g_uart_context[uart_num].mutex));
+  nxmutex_destroy(&lock);
+  g_uart_context[uart_num].mutex = NULL;
+  return newly_enabled;
+}
+
 /****************************************************************************
  * Name: esp_lowputc_send_byte
  *
@@ -313,25 +377,6 @@ void esp_lowputc_send_byte(const struct esp_uart_s *priv, 
char byte)
   uart_hal_write_txfifo(priv->hal, (const uint8_t *)&byte, 1, &write_size);
 }
 
-/****************************************************************************
- * Name: esp_lowputc_enable_sysclk
- *
- * Description:
- *   Enable clock for the UART using the System register.
- *
- * Parameters:
- *   priv           - Pointer to the private driver struct.
- *
- ****************************************************************************/
-
-void esp_lowputc_enable_sysclk(const struct esp_uart_s *priv)
-{
-  if (priv->id < ESP_LP_UART0_ID)
-    {
-      periph_module_enable(PERIPH_UART0_MODULE + priv->id);
-    }
-}
-
 /****************************************************************************
  * Name: esp_lowputc_disable_all_uart_int
  *
@@ -410,24 +455,32 @@ void esp_lowputc_config_pins(const struct esp_uart_s 
*priv)
   if (priv->id < ESP_LP_UART0_ID)
     {
       esp_configgpio(priv->rxpin, INPUT | PULLUP);
-      esp_gpio_matrix_in(priv->rxpin, priv->rxsig, 0);
+      esp_gpio_matrix_in(priv->rxpin,
+                         UART_PERIPH_SIGNAL(priv->id, SOC_UART_RX_PIN_IDX),
+                         0);
 
       esp_configgpio(priv->txpin, OUTPUT);
-      esp_gpio_matrix_out(priv->txpin, priv->txsig, 0, 0);
+      esp_gpio_matrix_out(priv->txpin,
+                          UART_PERIPH_SIGNAL(priv->id, SOC_UART_TX_PIN_IDX),
+                          0, 0);
 
 #ifdef CONFIG_SERIAL_IFLOWCONTROL
       if (priv->iflow)
         {
+          uint32_t sig = UART_PERIPH_SIGNAL(priv->id, SOC_UART_RTS_PIN_IDX);
+
           esp_configgpio(priv->rtspin, OUTPUT);
-          esp_gpio_matrix_out(priv->rtspin, priv->rtssig, 0, 0);
+          esp_gpio_matrix_out(priv->rtspin, sig, 0, 0);
         }
 
 #endif
 #ifdef CONFIG_SERIAL_OFLOWCONTROL
       if (priv->oflow)
         {
+          uint32_t sig = UART_PERIPH_SIGNAL(priv->id, SOC_UART_CTS_PIN_IDX);
+
           esp_configgpio(priv->ctspin, INPUT | PULLUP);
-          esp_gpio_matrix_in(priv->ctspin, priv->ctssig, 0);
+          esp_gpio_matrix_in(priv->ctspin, sig, 0);
         }
 #endif
 
@@ -546,12 +599,12 @@ void esp_lowsetup(void)
 #ifndef CONFIG_SUPPRESS_UART_CONFIG
 
 #ifdef CONFIG_ESPRESSIF_UART0
-  esp_lowputc_enable_sysclk(&g_uart0_config);
+  esp_lowputc_uart_module_enable(&g_uart0_config);
   esp_lowputc_config_pins(&g_uart0_config);
 #endif
 
 #ifdef CONFIG_ESPRESSIF_UART1
-  esp_lowputc_enable_sysclk(&g_uart1_config);
+  esp_lowputc_uart_module_enable(&g_uart1_config);
   esp_lowputc_config_pins(&g_uart1_config);
 #endif
 
diff --git a/arch/risc-v/src/common/espressif/esp_lowputc.h 
b/arch/risc-v/src/common/espressif/esp_lowputc.h
index 382b22152cb..036ef41a425 100644
--- a/arch/risc-v/src/common/espressif/esp_lowputc.h
+++ b/arch/risc-v/src/common/espressif/esp_lowputc.h
@@ -35,6 +35,7 @@
 #include <stdint.h>
 #include <string.h>
 #include <sys/types.h>
+#include <sys/lock.h>
 #include <unistd.h>
 
 #include <nuttx/arch.h>
@@ -44,6 +45,7 @@
 #include "chip.h"
 #include "esp_irq.h"
 #include "hal/uart_hal.h"
+#include "esp_private/critical_section.h"
 
 /****************************************************************************
  * Public Types
@@ -53,27 +55,21 @@
 
 struct esp_uart_s
 {
-  int                 source;    /* UART interrupt source */
   int                 cpuint;    /* CPU interrupt assigned to this UART */
   irq_priority_t      int_pri;   /* UART Interrupt Priority */
   int                 id;        /* UART ID */
-  int                 irq;       /* IRQ associated with this UART */
   uint32_t            baud;      /* Configured baud rate */
   bool                stop_b2;   /* Flag for using 2 stop bits */
   uint8_t             bits;      /* Data length (5 to 8 bits) */
   uint8_t             parity;    /* 0=no parity, 1=odd, 2=even */
   uint8_t             txpin;     /* TX pin */
-  uint8_t             txsig;     /* TX signal */
   uint8_t             rxpin;     /* RX pin */
-  uint8_t             rxsig;     /* RX signal */
 #ifdef CONFIG_SERIAL_IFLOWCONTROL
   uint8_t             rtspin;    /* RTS pin number */
-  uint8_t             rtssig;    /* RTS signal */
   bool                iflow;     /* Input flow control (RTS) enabled */
 #endif
 #ifdef CONFIG_SERIAL_OFLOWCONTROL
   uint8_t             ctspin;    /* CTS pin number */
-  uint8_t             ctssig;    /* CTS signal */
   bool                oflow;     /* Output flow control (CTS) enabled */
 #endif
 #ifdef HAVE_RS485
@@ -85,6 +81,15 @@ struct esp_uart_s
   spinlock_t          lock;      /* Spinlock */
 };
 
+typedef struct
+{
+  _lock_t mutex;                 /* Protect uart_module_enable, 
uart_module_disable, retention, etc. */
+  uart_port_t port_id;
+  uart_hal_context_t hal;        /* UART hal context */
+  DECLARE_CRIT_SECTION_LOCK_IN_STRUCT(spinlock)
+  bool hw_enabled;
+} uart_context_t;
+
 extern struct esp_uart_s g_uart0_config;
 extern struct esp_uart_s g_uart1_config;
 extern struct esp_uart_s g_lp_uart0_config;
@@ -108,19 +113,6 @@ extern struct esp_uart_s g_lp_uart0_config;
 void esp_lowputc_send_byte(const struct esp_uart_s *priv,
                            char byte);
 
-/****************************************************************************
- * Name: esp_lowputc_enable_sysclk
- *
- * Description:
- *   Enable clock for the UART using the System register.
- *
- * Parameters:
- *   priv           - Pointer to the private driver struct.
- *
- ****************************************************************************/
-
-void esp_lowputc_enable_sysclk(const struct esp_uart_s *priv);
-
 /****************************************************************************
  * Name: esp_lowputc_disable_all_uart_int
  *
@@ -193,4 +185,6 @@ void esp_lowputc_restore_pins(const struct esp_uart_s 
*priv);
 
 void esp_lowsetup(void);
 
+bool esp_lowputc_uart_module_enable(const struct esp_uart_s *priv);
+
 #endif /* __ARCH_RISCV_SRC_COMMON_ESPRESSIF_ESP_LOWPUTC_H */
diff --git a/arch/risc-v/src/common/espressif/esp_serial.c 
b/arch/risc-v/src/common/espressif/esp_serial.c
index 25b37c09601..56ce7f62c98 100644
--- a/arch/risc-v/src/common/espressif/esp_serial.c
+++ b/arch/risc-v/src/common/espressif/esp_serial.c
@@ -55,7 +55,10 @@
 #endif
 
 #include "esp_clk_tree.h"
+#include "esp_private/uart_share_hw_ctrl.h"
+#include "esp_private/esp_clk_tree_common.h"
 #include "hal/uart_hal.h"
+#include "soc/uart_periph.h"
 #include "soc/clk_tree_defs.h"
 #include "periph_ctrl.h"
 
@@ -306,6 +309,12 @@ static uart_dev_t g_lp_uart0_dev =
 
 #endif /* CONFIG_ESPRESSIF_UART */
 
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+extern uart_context_t g_uart_context[UART_NUM_MAX];
+
 /****************************************************************************
  * Private Functions
  ****************************************************************************/
@@ -453,15 +462,21 @@ static void set_stop_length(const struct esp_uart_s *priv)
 static int esp_setup(uart_dev_t *dev)
 {
   struct esp_uart_s *priv = dev->priv;
+  soc_module_clk_t src_clk;
   uint32_t sclk_freq;
+  bool success = false;
 
   /* Enable the UART Clock */
 
-  esp_lowputc_enable_sysclk(priv);
+  esp_lowputc_uart_module_enable(priv);
+
+  uart_hal_get_sclk(priv->hal, &src_clk);
+
+  esp_clk_tree_src_get_freq_hz(src_clk,
+                               ESP_CLK_TREE_SRC_FREQ_PRECISION_CACHED,
+                               &sclk_freq);
 
-  esp_clk_tree_src_get_freq_hz((soc_module_clk_t)priv->clk_src,
-                           ESP_CLK_TREE_SRC_FREQ_PRECISION_CACHED,
-                           &sclk_freq);
+  esp_os_enter_critical(&(g_uart_context[priv->id].spinlock));
 
   /* Initialize UART module */
 #ifdef CONFIG_ESPRESSIF_LP_UART
@@ -479,25 +494,18 @@ static int esp_setup(uart_dev_t *dev)
 #endif
 
   uart_hal_init(priv->hal, priv->id);
+
   uart_hal_set_mode(priv->hal, UART_MODE_UART);
-  if (priv->id < ESP_LP_UART0_ID)
-    {
-      uart_hal_set_sclk(priv->hal, UART_SCLK_DEFAULT);
-      uart_hal_set_baudrate(priv->hal, priv->baud, sclk_freq);
-    }
-#ifdef CONFIG_ESPRESSIF_LP_UART
-  else
-    {
-      /* Override protocol parameters from the configuration */
 
-      if (!lp_uart_ll_set_baudrate(priv->hal->dev, priv->baud, sclk_freq))
+  if (priv->id < SOC_UART_HP_NUM)
+    {
+      esp_clk_tree_enable_src(UART_SCLK_XTAL, true);
+      HP_UART_SRC_CLK_ATOMIC()
         {
-          /* Unachievable baud rate */
-
-          return ESP_FAIL;
+          uart_hal_set_sclk(priv->hal, UART_SCLK_XTAL);
+          success = uart_hal_set_baudrate(priv->hal, priv->baud, sclk_freq);
         }
     }
-#endif
 
   uart_hal_set_parity(priv->hal, priv->parity);
   set_data_length(priv);
@@ -559,6 +567,13 @@ static int esp_setup(uart_dev_t *dev)
   else
 #endif
 
+  esp_os_exit_critical(&(g_uart_context[priv->id].spinlock));
+
+  if (success == false)
+    {
+      return -EIO;
+    }
+
   /* Clear FIFOs */
 
   uart_hal_rxfifo_rst(priv->hal);
@@ -619,24 +634,27 @@ static int esp_attach(uart_dev_t *dev)
 {
   struct esp_uart_s *priv = dev->priv;
   int ret;
+  int source;
 
   DEBUGASSERT(priv->cpuint == -ENOMEM);
 
   /* Set up to receive peripheral interrupts */
 
-  priv->cpuint = esp_setup_irq(priv->source, priv->int_pri,
+  source = uart_periph_signal[priv->id].irq;
+
+  priv->cpuint = esp_setup_irq(source, priv->int_pri,
                                ESP_IRQ_TRIGGER_LEVEL);
 
   /* Attach and enable the IRQ */
 
-  ret = irq_attach(priv->irq, uart_handler, dev);
+  ret = irq_attach(ESP_SOURCE2IRQ(source), uart_handler, dev);
   if (ret == OK)
     {
-      up_enable_irq(priv->irq);
+      up_enable_irq(ESP_SOURCE2IRQ(source));
     }
   else
     {
-      up_disable_irq(priv->irq);
+      up_disable_irq(ESP_SOURCE2IRQ(source));
     }
 
   return ret;
@@ -661,17 +679,20 @@ static int esp_attach(uart_dev_t *dev)
 static void esp_detach(uart_dev_t *dev)
 {
   struct esp_uart_s *priv = dev->priv;
+  int source;
 
   DEBUGASSERT(priv->cpuint != -ENOMEM);
 
+  source = uart_periph_signal[priv->id].irq;
+
   /* Disable and detach the CPU interrupt */
 
-  up_disable_irq(priv->irq);
-  irq_detach(priv->irq);
+  up_disable_irq(ESP_SOURCE2IRQ(source));
+  irq_detach(ESP_SOURCE2IRQ(source));
 
   /* Disassociate the peripheral interrupt from the CPU interrupt */
 
-  esp_teardown_irq(priv->source, priv->cpuint);
+  esp_teardown_irq(source, priv->cpuint);
   priv->cpuint = -ENOMEM;
 }
 
diff --git a/arch/risc-v/src/common/espressif/esp_usbserial.c 
b/arch/risc-v/src/common/espressif/esp_usbserial.c
index 93fc98edd82..5d7a6072f09 100644
--- a/arch/risc-v/src/common/espressif/esp_usbserial.c
+++ b/arch/risc-v/src/common/espressif/esp_usbserial.c
@@ -106,8 +106,8 @@ static char g_txbuffer[ESP_USBCDC_BUFFERSIZE];
 
 static struct esp_priv_s g_usbserial_priv =
 {
-  .source = USB_SERIAL_JTAG_INTR_SOURCE,
-  .irq    = ESP_IRQ_USB_SERIAL_JTAG,
+  .source = ETS_USB_SERIAL_JTAG_INTR_SOURCE,
+  .irq    = ESP_SOURCE2IRQ(ETS_USB_SERIAL_JTAG_INTR_SOURCE),
   .cpuint = -ENOMEM,
 };
 
@@ -167,23 +167,23 @@ uart_dev_t g_uart_usbserial =
 static int esp_interrupt(int irq, void *context, void *arg)
 {
   struct uart_dev_s *dev = (struct uart_dev_s *)arg;
-  uint32_t tx_mask = USB_SERIAL_JTAG_SERIAL_IN_EMPTY_INT_ST;
-  uint32_t rx_mask = USB_SERIAL_JTAG_SERIAL_OUT_RECV_PKT_INT_ST;
   uint32_t int_status = usb_serial_jtag_ll_get_intsts_mask();
 
   /* Send buffer has room and can accept new data. */
 
-  if ((int_status & tx_mask) != 0)
+  if ((int_status & USB_SERIAL_JTAG_INTR_SERIAL_IN_EMPTY) != 0)
     {
-      usb_serial_jtag_ll_clr_intsts_mask(tx_mask);
+      usb_serial_jtag_ll_clr_intsts_mask(
+        USB_SERIAL_JTAG_INTR_SERIAL_IN_EMPTY);
       uart_xmitchars(dev);
     }
 
   /* Data from the host are available to read. */
 
-  if ((int_status & rx_mask) != 0)
+  if ((int_status & USB_SERIAL_JTAG_INTR_SERIAL_OUT_RECV_PKT) != 0)
     {
-      usb_serial_jtag_ll_clr_intsts_mask(rx_mask);
+      usb_serial_jtag_ll_clr_intsts_mask(
+        USB_SERIAL_JTAG_INTR_SERIAL_OUT_RECV_PKT);
       uart_recvchars(dev);
     }
 
@@ -230,12 +230,12 @@ static void esp_txint(struct uart_dev_s *dev, bool enable)
   if (enable)
     {
       usb_serial_jtag_ll_ena_intr_mask(
-        USB_SERIAL_JTAG_SERIAL_IN_EMPTY_INT_ENA);
+        USB_SERIAL_JTAG_INTR_SERIAL_IN_EMPTY);
     }
   else
     {
       usb_serial_jtag_ll_disable_intr_mask(
-        USB_SERIAL_JTAG_SERIAL_IN_EMPTY_INT_ENA);
+        USB_SERIAL_JTAG_INTR_SERIAL_IN_EMPTY);
     }
 }
 
@@ -252,12 +252,12 @@ static void esp_rxint(struct uart_dev_s *dev, bool enable)
   if (enable)
     {
       usb_serial_jtag_ll_ena_intr_mask(
-        USB_SERIAL_JTAG_SERIAL_OUT_RECV_PKT_INT_ENA);
+        USB_SERIAL_JTAG_INTR_SERIAL_OUT_RECV_PKT);
     }
   else
     {
       usb_serial_jtag_ll_disable_intr_mask(
-        USB_SERIAL_JTAG_SERIAL_OUT_RECV_PKT_INT_ENA);
+        USB_SERIAL_JTAG_INTR_SERIAL_OUT_RECV_PKT);
     }
 }
 
diff --git a/arch/risc-v/src/esp32c3/hal_esp32c3.mk 
b/arch/risc-v/src/esp32c3/hal_esp32c3.mk
index ab374b20d26..e1ab63a76dc 100644
--- a/arch/risc-v/src/esp32c3/hal_esp32c3.mk
+++ b/arch/risc-v/src/esp32c3/hal_esp32c3.mk
@@ -197,6 +197,7 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)temperature_sensor_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)timer_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)twai_periph.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)${CHIP_SERIES}$(DELIM)uart_periph.c
 
 ifeq ($(CONFIG_ESPRESSIF_SIMPLE_BOOT),y)
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)nuttx$(DELIM)src$(DELIM)bootloader_banner_wrap.c
@@ -217,7 +218,6 @@ ifeq ($(CONFIG_ESPRESSIF_SIMPLE_BOOT),y)
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)bootloader_sha.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)${CHIP_SERIES}$(DELIM)bootloader_soc.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)flash_encrypt.c
-  CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)${CHIP_SERIES}$(DELIM)uart_periph.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_uart.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_sys.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_spiflash.c
diff --git a/arch/risc-v/src/esp32h2/hal_esp32h2.mk 
b/arch/risc-v/src/esp32h2/hal_esp32h2.mk
index 7b64943679b..019ea4ffb80 100644
--- a/arch/risc-v/src/esp32h2/hal_esp32h2.mk
+++ b/arch/risc-v/src/esp32h2/hal_esp32h2.mk
@@ -199,6 +199,7 @@ CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)temperature_sensor_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)timer_periph.c
 CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)twai_periph.c
+CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)$(CHIP_SERIES)$(DELIM)uart_periph.c
 
 ifeq ($(CONFIG_ESPRESSIF_SIMPLE_BOOT),y)
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)nuttx$(DELIM)src$(DELIM)bootloader_banner_wrap.c
@@ -219,7 +220,6 @@ ifeq ($(CONFIG_ESPRESSIF_SIMPLE_BOOT),y)
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)${CHIP_SERIES}$(DELIM)bootloader_soc.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)flash_encrypt.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)bootloader_support$(DELIM)src$(DELIM)bootloader_sha.c
-  CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)soc$(DELIM)${CHIP_SERIES}$(DELIM)uart_periph.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_uart.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_sys.c
   CHIP_CSRCS += 
chip$(DELIM)$(ESP_HAL_3RDPARTY_REPO)$(DELIM)components$(DELIM)esp_rom$(DELIM)patches$(DELIM)esp_rom_spiflash.c

Reply via email to