drivers: esp32: Update for shared intc

Drivers update to use shared interrupt allocator for Xtensa
and RISCV devices.

Signed-off-by: Raffael Rostagno <raffael.rostagno@espressif.com>
Signed-off-by: Sylvio Alves <sylvio.alves@espressif.com>
diff --git a/drivers/counter/counter_esp32_rtc.c b/drivers/counter/counter_esp32_rtc.c
index ebbdd20..bf751f6 100644
--- a/drivers/counter/counter_esp32_rtc.c
+++ b/drivers/counter/counter_esp32_rtc.c
@@ -1,15 +1,11 @@
 /*
- * Copyright (c) 2022 Espressif Systems (Shanghai) Co., Ltd.
+ * Copyright (c) 2022-2025 Espressif Systems (Shanghai) Co., Ltd.
  *
  * SPDX-License-Identifier: Apache-2.0
  */
 
 #define DT_DRV_COMPAT espressif_esp32_rtc_timer
 
-/*
- * Include esp-idf headers first to avoid
- * redefining BIT() macro
- */
 #include "soc/rtc_cntl_reg.h"
 #include "soc/rtc.h"
 #include <esp_rom_sys.h>
@@ -21,22 +17,11 @@
 #include <zephyr/kernel.h>
 #include <zephyr/drivers/clock_control.h>
 #include <zephyr/drivers/clock_control/esp32_clock_control.h>
-
-#if defined(CONFIG_SOC_SERIES_ESP32C2) || defined(CONFIG_SOC_SERIES_ESP32C3)
-#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
-#else
 #include <zephyr/drivers/interrupt_controller/intc_esp32.h>
-#endif
 
 #include <zephyr/logging/log.h>
 LOG_MODULE_REGISTER(esp32_counter_rtc, CONFIG_COUNTER_LOG_LEVEL);
 
-#if defined(CONFIG_SOC_SERIES_ESP32C2) || defined(CONFIG_SOC_SERIES_ESP32C3)
-#define ESP32_COUNTER_RTC_ISR_HANDLER isr_handler_t
-#else
-#define ESP32_COUNTER_RTC_ISR_HANDLER intr_handler_t
-#endif
-
 static void counter_esp32_isr(void *arg);
 
 struct counter_esp32_config {
@@ -65,9 +50,10 @@
 			       &data->clk_src_freq);
 
 	flags = ESP_PRIO_TO_FLAGS(cfg->irq_priority) | ESP_INT_FLAGS_CHECK(cfg->irq_flags) |
-		ESP_INTR_FLAG_SHARED;
+			     ESP_INTR_FLAG_SHARED;
+
 	ret = esp_intr_alloc(cfg->irq_source, flags,
-			     (ESP32_COUNTER_RTC_ISR_HANDLER)counter_esp32_isr, (void *)dev, NULL);
+			     (intr_handler_t)counter_esp32_isr, (void *)dev, NULL);
 
 	if (ret != 0) {
 		LOG_ERR("could not allocate interrupt (err %d)", ret);
@@ -246,6 +232,6 @@
 		      NULL,
 		      &counter_data,
 		      &counter_config,
-		      POST_KERNEL,
+		      PRE_KERNEL_2,
 		      CONFIG_COUNTER_INIT_PRIORITY,
 		      &rtc_timer_esp32_api);
diff --git a/drivers/counter/counter_esp32_tmr.c b/drivers/counter/counter_esp32_tmr.c
index 3131b45..45143dc 100644
--- a/drivers/counter/counter_esp32_tmr.c
+++ b/drivers/counter/counter_esp32_tmr.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2024 Espressif Systems (Shanghai) Co., Ltd.
+ * Copyright (c) 2024-2025 Espressif Systems (Shanghai) Co., Ltd.
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -14,22 +14,12 @@
 #include <zephyr/drivers/counter.h>
 #include <zephyr/drivers/clock_control.h>
 #include <zephyr/kernel.h>
-#if defined(CONFIG_RISCV)
-#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
-#else
 #include <zephyr/drivers/interrupt_controller/intc_esp32.h>
-#endif
 #include <zephyr/device.h>
 #include <zephyr/logging/log.h>
 
 LOG_MODULE_REGISTER(esp32_counter, CONFIG_COUNTER_LOG_LEVEL);
 
-#if defined(CONFIG_RISCV)
-#define ISR_HANDLER isr_handler_t
-#else
-#define ISR_HANDLER intr_handler_t
-#endif
-
 static void counter_esp32_isr(void *arg);
 
 typedef bool (*timer_isr_t)(void *);
@@ -97,7 +87,7 @@
 	int ret = esp_intr_alloc(cfg->irq_source,
 				 ESP_PRIO_TO_FLAGS(cfg->irq_priority) |
 					 ESP_INT_FLAGS_CHECK(cfg->irq_flags),
-				 (ISR_HANDLER)counter_esp32_isr, (void *)dev, NULL);
+				 (intr_handler_t)counter_esp32_isr, (void *)dev, NULL);
 
 	if (ret != 0) {
 		LOG_ERR("could not allocate interrupt (err %d)", ret);
diff --git a/drivers/dma/dma_esp32_gdma.c b/drivers/dma/dma_esp32_gdma.c
index 5f7c888..945b1e2 100644
--- a/drivers/dma/dma_esp32_gdma.c
+++ b/drivers/dma/dma_esp32_gdma.c
@@ -16,22 +16,13 @@
 
 #include <soc.h>
 #include <esp_memory_utils.h>
+#include <soc/soc_memory_types.h>
 #include <errno.h>
 #include <zephyr/kernel.h>
 #include <zephyr/drivers/dma.h>
 #include <zephyr/drivers/dma/dma_esp32.h>
 #include <zephyr/drivers/clock_control.h>
-#if defined(CONFIG_SOC_SERIES_ESP32C3) || defined(CONFIG_SOC_SERIES_ESP32C6)
-#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
-#else
 #include <zephyr/drivers/interrupt_controller/intc_esp32.h>
-#endif
-
-#if defined(CONFIG_SOC_SERIES_ESP32C3) || defined(CONFIG_SOC_SERIES_ESP32C6)
-#define ISR_HANDLER isr_handler_t
-#else
-#define ISR_HANDLER intr_handler_t
-#endif
 
 #define DMA_MAX_CHANNEL SOC_GDMA_PAIRS_PER_GROUP
 
@@ -61,7 +52,10 @@
 	int periph_id;
 	dma_callback_t cb;
 	void *user_data;
-	dma_descriptor_t desc_list[CONFIG_DMA_ESP32_MAX_DESCRIPTOR_NUM];
+	dma_descriptor_t desc;
+#if defined(CONFIG_SOC_SERIES_ESP32S3)
+	intr_handle_t *intr_handle;
+#endif
 };
 
 struct dma_esp32_config {
@@ -546,7 +540,7 @@
 		int ret = esp_intr_alloc(irq_cfg[i].irq_source,
 			ESP_PRIO_TO_FLAGS(irq_cfg[i].irq_priority) |
 				ESP_INT_FLAGS_CHECK(irq_cfg[i].irq_flags) | ESP_INTR_FLAG_IRAM,
-			(ISR_HANDLER)config->irq_handlers[i],
+			(intr_handler_t)config->irq_handlers[i],
 			(void *)dev,
 			NULL);
 		if (ret != 0) {
diff --git a/drivers/gpio/gpio_esp32.c b/drivers/gpio/gpio_esp32.c
index 9460d3c..98b22d7 100644
--- a/drivers/gpio/gpio_esp32.c
+++ b/drivers/gpio/gpio_esp32.c
@@ -1,6 +1,6 @@
 /*
  * Copyright (c) 2017 Intel Corporation
- * Copyright (c) 2021 Espressif Systems (Shanghai) Co., Ltd.
+ * Copyright (c) 2021-2025 Espressif Systems (Shanghai) Co., Ltd.
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -20,13 +20,7 @@
 #include <zephyr/device.h>
 #include <zephyr/drivers/gpio.h>
 #include <zephyr/dt-bindings/gpio/espressif-esp32-gpio.h>
-#if defined(CONFIG_SOC_SERIES_ESP32C2) || \
-	defined(CONFIG_SOC_SERIES_ESP32C3) || \
-	defined(CONFIG_SOC_SERIES_ESP32C6)
-#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
-#else
 #include <zephyr/drivers/interrupt_controller/intc_esp32.h>
-#endif
 #include <zephyr/kernel.h>
 #include <zephyr/sys/util.h>
 
@@ -42,7 +36,6 @@
 #define out_w1tc out_w1tc.val
 /* arch_curr_cpu() is not available for riscv based chips */
 #define CPU_ID()  0
-#define ISR_HANDLER isr_handler_t
 #elif CONFIG_SOC_SERIES_ESP32C3
 /* gpio structs in esp32c3 series are different from xtensa ones */
 #define out out.data
@@ -51,7 +44,6 @@
 #define out_w1tc out_w1tc.val
 /* arch_curr_cpu() is not available for riscv based chips */
 #define CPU_ID()  0
-#define ISR_HANDLER isr_handler_t
 #elif defined(CONFIG_SOC_SERIES_ESP32C6)
 /* gpio structs in esp32c6 are also different */
 #define out out.out_data_orig
@@ -60,10 +52,8 @@
 #define out_w1tc out_w1tc.val
 /* arch_curr_cpu() is not available for riscv based chips */
 #define CPU_ID()  0
-#define ISR_HANDLER isr_handler_t
 #else
 #define CPU_ID() arch_curr_cpu()->id
-#define ISR_HANDLER intr_handler_t
 #endif
 
 #ifndef SOC_GPIO_SUPPORT_RTC_INDEPENDENT
@@ -482,8 +472,9 @@
 	if (!isr_connected) {
 		int ret = esp_intr_alloc(DT_IRQ_BY_IDX(DT_NODELABEL(gpio0), 0, irq),
 			ESP_PRIO_TO_FLAGS(DT_IRQ_BY_IDX(DT_NODELABEL(gpio0), 0, priority)) |
-			ESP_INT_FLAGS_CHECK(DT_IRQ_BY_IDX(DT_NODELABEL(gpio0), 0, flags)),
-			(ISR_HANDLER)gpio_esp32_isr,
+			ESP_INT_FLAGS_CHECK(DT_IRQ_BY_IDX(DT_NODELABEL(gpio0), 0, flags)) |
+				ESP_INTR_FLAG_IRAM,
+			(intr_handler_t)gpio_esp32_isr,
 			(void *)dev,
 			NULL);
 
diff --git a/drivers/pwm/pwm_mc_esp32.c b/drivers/pwm/pwm_mc_esp32.c
index b7bb59f..2e15355 100644
--- a/drivers/pwm/pwm_mc_esp32.c
+++ b/drivers/pwm/pwm_mc_esp32.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2024 Espressif Systems (Shanghai) Co., Ltd.
+ * Copyright (c) 2024-2025 Espressif Systems (Shanghai) Co., Ltd.
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -19,21 +19,11 @@
 #include <zephyr/drivers/clock_control.h>
 #include <esp_clk_tree.h>
 #ifdef CONFIG_PWM_CAPTURE
-#if defined(CONFIG_RISCV)
-#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
-#else
 #include <zephyr/drivers/interrupt_controller/intc_esp32.h>
-#endif
 #endif /* CONFIG_PWM_CAPTURE */
 #include <zephyr/logging/log.h>
 LOG_MODULE_REGISTER(mcpwm_esp32, CONFIG_PWM_LOG_LEVEL);
 
-#if defined(CONFIG_RISCV)
-#define ISR_HANDLER isr_handler_t
-#else
-#define ISR_HANDLER intr_handler_t
-#endif
-
 #ifdef CONFIG_PWM_CAPTURE
 #define SKIP_IRQ_NUM        4U
 #define CAP_INT_MASK        7U
@@ -554,7 +544,7 @@
 				ESP_PRIO_TO_FLAGS(DT_INST_IRQ_BY_IDX(idx, 0, priority)) |          \
 				ESP_INT_FLAGS_CHECK(DT_INST_IRQ_BY_IDX(idx, 0, flags)) |          \
 					ESP_INTR_FLAG_IRAM,                                        \
-				(ISR_HANDLER)mcpwm_esp32_isr, (void *)dev, NULL);                  \
+				(intr_handler_t)mcpwm_esp32_isr, (void *)dev, NULL);               \
 		return ret;                                                                \
 	}
 #define CAPTURE_INIT(idx) .irq_config_func = mcpwm_esp32_irq_config_func_##idx
diff --git a/drivers/serial/serial_esp32_usb.c b/drivers/serial/serial_esp32_usb.c
index 79ea1a1..de278ee 100644
--- a/drivers/serial/serial_esp32_usb.c
+++ b/drivers/serial/serial_esp32_usb.c
@@ -1,5 +1,6 @@
 /*
  * Copyright (c) 2022 Libre Solar Technologies GmbH
+ * Copyright (c) 2025 Espressif Systems (Shanghai) Co., Ltd.
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -13,21 +14,11 @@
 #include <errno.h>
 #include <soc.h>
 #include <zephyr/drivers/uart.h>
-#if defined(CONFIG_SOC_SERIES_ESP32C3) || defined(CONFIG_SOC_SERIES_ESP32C6)
-#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
-#else
 #include <zephyr/drivers/interrupt_controller/intc_esp32.h>
-#endif
 #include <zephyr/drivers/clock_control.h>
 #include <zephyr/sys/util.h>
 #include <esp_attr.h>
 
-#if defined(CONFIG_SOC_SERIES_ESP32C3) || defined(CONFIG_SOC_SERIES_ESP32C6)
-#define ISR_HANDLER isr_handler_t
-#else
-#define ISR_HANDLER intr_handler_t
-#endif
-
 /*
  * Timeout after which the poll_out function stops waiting for space in the tx fifo.
  *
@@ -113,7 +104,7 @@
 	ret = esp_intr_alloc(config->irq_source,
 			ESP_PRIO_TO_FLAGS(config->irq_priority) |
 			ESP_INT_FLAGS_CHECK(config->irq_flags),
-			(ISR_HANDLER)serial_esp32_usb_isr,
+			(intr_handler_t)serial_esp32_usb_isr,
 			(void *)dev, NULL);
 #endif
 	return ret;
diff --git a/drivers/serial/uart_esp32.c b/drivers/serial/uart_esp32.c
index 47d652b..2638b25 100644
--- a/drivers/serial/uart_esp32.c
+++ b/drivers/serial/uart_esp32.c
@@ -1,6 +1,6 @@
 /*
  * Copyright (c) 2019 Mohamed ElShahawi (extremegtx@hotmail.com)
- * Copyright (c) 2023 Espressif Systems (Shanghai) Co., Ltd.
+ * Copyright (c) 2023-2025 Espressif Systems (Shanghai) Co., Ltd.
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -51,13 +51,7 @@
 #include <soc.h>
 #include <zephyr/drivers/uart.h>
 
-#if defined(CONFIG_SOC_SERIES_ESP32C2) || \
-	defined(CONFIG_SOC_SERIES_ESP32C3) || \
-	defined(CONFIG_SOC_SERIES_ESP32C6)
-#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
-#else
 #include <zephyr/drivers/interrupt_controller/intc_esp32.h>
-#endif
 
 #include <zephyr/drivers/clock_control.h>
 #include <errno.h>
@@ -67,14 +61,6 @@
 
 LOG_MODULE_REGISTER(uart_esp32, CONFIG_UART_LOG_LEVEL);
 
-#if defined(CONFIG_SOC_SERIES_ESP32C2) || \
-	defined(CONFIG_SOC_SERIES_ESP32C3) || \
-	defined(CONFIG_SOC_SERIES_ESP32C6)
-#define ISR_HANDLER isr_handler_t
-#else
-#define ISR_HANDLER intr_handler_t
-#endif
-
 struct uart_esp32_config {
 	const struct device *clock_dev;
 	const struct pinctrl_dev_config *pcfg;
@@ -962,7 +948,7 @@
 	ret = esp_intr_alloc(config->irq_source,
 			ESP_PRIO_TO_FLAGS(config->irq_priority) |
 			ESP_INT_FLAGS_CHECK(config->irq_flags),
-			(ISR_HANDLER)uart_esp32_isr,
+			(intr_handler_t)uart_esp32_isr,
 			(void *)dev,
 			NULL);
 	if (ret < 0) {
@@ -1071,7 +1057,7 @@
 		ESP_UART_UHCI_INIT(idx)};                                                          \
                                                                                                    \
 	DEVICE_DT_INST_DEFINE(idx, uart_esp32_init, NULL, &uart_esp32_data_##idx,                  \
-			      &uart_esp32_cfg_port_##idx, PRE_KERNEL_1,                            \
+			      &uart_esp32_cfg_port_##idx, PRE_KERNEL_2,                            \
 			      CONFIG_SERIAL_INIT_PRIORITY, &uart_esp32_api);
 
 DT_INST_FOREACH_STATUS_OKAY(ESP32_UART_INIT);
diff --git a/drivers/spi/spi_esp32_spim.c b/drivers/spi/spi_esp32_spim.c
index 8ad679b..f672d26 100644
--- a/drivers/spi/spi_esp32_spim.c
+++ b/drivers/spi/spi_esp32_spim.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2020 Espressif Systems (Shanghai) Co., Ltd.
+ * Copyright (c) 2020-2025 Espressif Systems (Shanghai) Co., Ltd.
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -17,13 +17,7 @@
 #include <soc.h>
 #include <esp_memory_utils.h>
 #include <zephyr/drivers/spi.h>
-#include <zephyr/drivers/spi/rtio.h>
-#if defined(CONFIG_SOC_SERIES_ESP32C2) || defined(CONFIG_SOC_SERIES_ESP32C3) ||                    \
-	defined(CONFIG_SOC_SERIES_ESP32C6)
-#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
-#else
 #include <zephyr/drivers/interrupt_controller/intc_esp32.h>
-#endif
 #ifdef SOC_GDMA_SUPPORTED
 #include <hal/gdma_hal.h>
 #include <hal/gdma_ll.h>
@@ -32,13 +26,6 @@
 #include "spi_context.h"
 #include "spi_esp32_spim.h"
 
-#if defined(CONFIG_SOC_SERIES_ESP32C2) || defined(CONFIG_SOC_SERIES_ESP32C3) ||                    \
-	defined(CONFIG_SOC_SERIES_ESP32C6)
-#define ISR_HANDLER isr_handler_t
-#else
-#define ISR_HANDLER intr_handler_t
-#endif
-
 #define SPI_DMA_MAX_BUFFER_SIZE 4092
 
 static bool spi_esp32_transfer_ongoing(struct spi_esp32_data *data)
@@ -250,7 +237,7 @@
 	err = esp_intr_alloc(cfg->irq_source,
 			ESP_PRIO_TO_FLAGS(cfg->irq_priority) |
 			ESP_INT_FLAGS_CHECK(cfg->irq_flags) | ESP_INTR_FLAG_IRAM,
-			(ISR_HANDLER)spi_esp32_isr,
+			(intr_handler_t)spi_esp32_isr,
 			(void *)dev,
 			NULL);
 
diff --git a/drivers/timer/esp32_sys_timer.c b/drivers/timer/esp32_sys_timer.c
index bb36445..46bc178 100644
--- a/drivers/timer/esp32_sys_timer.c
+++ b/drivers/timer/esp32_sys_timer.c
@@ -1,8 +1,9 @@
 /*
- * Copyright (c) 2021 Espressif Systems (Shanghai) Co., Ltd.
+ * Copyright (c) 2021-2025 Espressif Systems (Shanghai) Co., Ltd.
  *
  * SPDX-License-Identifier: Apache-2.0
  */
+
 #include <soc/soc_caps.h>
 #include <soc/soc.h>
 
@@ -12,7 +13,7 @@
 #include <rom/ets_sys.h>
 #include <esp_attr.h>
 
-#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
+#include <zephyr/drivers/interrupt_controller/intc_esp32.h>
 #include <zephyr/drivers/timer/system_timer.h>
 #include <zephyr/sys_clock.h>
 #include <soc.h>
@@ -56,7 +57,7 @@
 	return systimer_hal_get_counter_value(&systimer_hal, SYSTIMER_COUNTER_OS_TICK);
 }
 
-static void sys_timer_isr(const void *arg)
+static void sys_timer_isr(void *arg)
 {
 	ARG_UNUSED(arg);
 	systimer_ll_clear_alarm_int(systimer_hal.dev, SYSTIMER_ALARM_OS_TICK_CORE0);
@@ -167,5 +168,5 @@
 	return 0;
 }
 
-SYS_INIT(sys_clock_driver_init, PRE_KERNEL_1,
+SYS_INIT(sys_clock_driver_init, PRE_KERNEL_2,
 	 CONFIG_SYSTEM_CLOCK_INIT_PRIORITY);
diff --git a/drivers/watchdog/wdt_esp32.c b/drivers/watchdog/wdt_esp32.c
index 66caa75..acaf7d7 100644
--- a/drivers/watchdog/wdt_esp32.c
+++ b/drivers/watchdog/wdt_esp32.c
@@ -1,12 +1,12 @@
 /*
  * Copyright (C) 2017 Intel Corporation
+ * Copyright (c) 2025 Espressif Systems (Shanghai) Co., Ltd.
  *
  * SPDX-License-Identifier: Apache-2.0
  */
 
 #define DT_DRV_COMPAT espressif_esp32_watchdog
 
-/* Include esp-idf headers first to avoid redefining BIT() macro */
 #if defined(CONFIG_SOC_SERIES_ESP32C6)
 #include <soc/lp_aon_reg.h>
 #else
@@ -19,22 +19,12 @@
 #include <string.h>
 #include <zephyr/drivers/watchdog.h>
 #include <zephyr/drivers/clock_control.h>
-#if defined(CONFIG_SOC_SERIES_ESP32C3) || defined(CONFIG_SOC_SERIES_ESP32C6)
-#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
-#else
 #include <zephyr/drivers/interrupt_controller/intc_esp32.h>
-#endif
 #include <zephyr/device.h>
 
 #include <zephyr/logging/log.h>
 LOG_MODULE_REGISTER(wdt_esp32, CONFIG_WDT_LOG_LEVEL);
 
-#if defined(CONFIG_SOC_SERIES_ESP32C3) || defined(CONFIG_SOC_SERIES_ESP32C6)
-#define ISR_HANDLER isr_handler_t
-#else
-#define ISR_HANDLER intr_handler_t
-#endif
-
 #define MWDT_TICK_PRESCALER		40000
 #define MWDT_TICKS_PER_US		500
 
@@ -170,7 +160,7 @@
 	wdt_hal_init(&data->hal, config->wdt_inst, MWDT_TICK_PRESCALER, true);
 
 	flags = ESP_PRIO_TO_FLAGS(config->irq_priority) | ESP_INT_FLAGS_CHECK(config->irq_flags);
-	ret = esp_intr_alloc(config->irq_source, flags, (ISR_HANDLER)wdt_esp32_isr, (void *)dev,
+	ret = esp_intr_alloc(config->irq_source, flags, (intr_handler_t)wdt_esp32_isr, (void *)dev,
 			     NULL);
 
 	if (ret != 0) {
diff --git a/drivers/watchdog/xt_wdt_esp32.c b/drivers/watchdog/xt_wdt_esp32.c
index 3c6fd8e..29b7555 100644
--- a/drivers/watchdog/xt_wdt_esp32.c
+++ b/drivers/watchdog/xt_wdt_esp32.c
@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2024 Espressif Systems (Shanghai) Co., Ltd.
+ * Copyright (c) 2024-2025 Espressif Systems (Shanghai) Co., Ltd.
  *
  * SPDX-License-Identifier: Apache-2.0
  */
@@ -14,22 +14,12 @@
 #include <zephyr/drivers/clock_control.h>
 #include <zephyr/drivers/clock_control/esp32_clock_control.h>
 
-#ifndef CONFIG_SOC_SERIES_ESP32C3
 #include <zephyr/drivers/interrupt_controller/intc_esp32.h>
-#else
-#include <zephyr/drivers/interrupt_controller/intc_esp32c3.h>
-#endif
 #include <zephyr/device.h>
 #include <zephyr/logging/log.h>
 
 LOG_MODULE_REGISTER(xt_wdt_esp32, CONFIG_WDT_LOG_LEVEL);
 
-#ifdef CONFIG_SOC_SERIES_ESP32C3
-#define ISR_HANDLER isr_handler_t
-#else
-#define ISR_HANDLER intr_handler_t
-#endif
-
 #define ESP32_XT_WDT_MAX_TIMEOUT 255
 
 struct esp32_xt_wdt_data {
@@ -134,7 +124,7 @@
 
 	flags = ESP_PRIO_TO_FLAGS(cfg->irq_priority) | ESP_INT_FLAGS_CHECK(cfg->irq_flags) |
 		ESP_INTR_FLAG_SHARED;
-	err = esp_intr_alloc(cfg->irq_source, flags, (ISR_HANDLER)esp32_xt_wdt_isr, (void *)dev,
+	err = esp_intr_alloc(cfg->irq_source, flags, (intr_handler_t)esp32_xt_wdt_isr, (void *)dev,
 			     NULL);
 	if (err) {
 		LOG_ERR("Failed to register ISR\n");