drivers: adc: esp32: split adc_esp32.c between 2 files

Splits driver source code between adc_esp32.c and adc_esp32_dma.c to
improve maintenance

Signed-off-by: Marcio Ribeiro <marcio.ribeiro@espressif.com>
diff --git a/drivers/adc/CMakeLists.txt b/drivers/adc/CMakeLists.txt
index 08b8cc8..db3a7ae 100644
--- a/drivers/adc/CMakeLists.txt
+++ b/drivers/adc/CMakeLists.txt
@@ -43,6 +43,7 @@
 zephyr_library_sources_ifdef(CONFIG_ADC_RPI_PICO	adc_rpi_pico.c)
 zephyr_library_sources_ifdef(CONFIG_ADC_XMC4XXX		adc_xmc4xxx.c)
 zephyr_library_sources_ifdef(CONFIG_ADC_ESP32		adc_esp32.c)
+zephyr_library_sources_ifdef(CONFIG_ADC_ESP32_DMA	adc_esp32_dma.c)
 zephyr_library_sources_ifdef(CONFIG_ADC_GECKO_ADC   	adc_gecko.c)
 zephyr_library_sources_ifdef(CONFIG_ADC_GECKO_IADC   	iadc_gecko.c)
 zephyr_library_sources_ifdef(CONFIG_ADC_SILABS_SIWX91X 	adc_silabs_siwx91x.c)
diff --git a/drivers/adc/adc_esp32.c b/drivers/adc/adc_esp32.c
index 3bfbcb0..424e43b 100644
--- a/drivers/adc/adc_esp32.c
+++ b/drivers/adc/adc_esp32.c
@@ -6,66 +6,13 @@
 
 #define DT_DRV_COMPAT espressif_esp32_adc
 
-#include <errno.h>
-#include <hal/adc_hal.h>
-#include <hal/adc_oneshot_hal.h>
-#include <hal/adc_types.h>
-#include <soc/adc_periph.h>
-#include <esp_adc/adc_cali.h>
-#include <esp_adc/adc_cali_scheme.h>
 #include <esp_clk_tree.h>
-#include <esp_private/periph_ctrl.h>
 #include <esp_private/sar_periph_ctrl.h>
 #include <esp_private/adc_share_hw_ctrl.h>
 
-#if defined(CONFIG_ADC_ESP32_DMA)
-#if SOC_GDMA_SUPPORTED
-#include <zephyr/drivers/dma.h>
-#include <zephyr/drivers/dma/dma_esp32.h>
-#else
-#include <zephyr/drivers/interrupt_controller/intc_esp32.h>
+#include "adc_esp32.h"
 
-#if CONFIG_SOC_SERIES_ESP32
-#include <zephyr/dt-bindings/interrupt-controller/esp-xtensa-intmux.h>
-
-#define ADC_DMA_I2S_HOST                 0
-#define ADC_DMA_INTR_MASK                ADC_HAL_DMA_INTR_MASK
-#define ADC_DMA_DEV                      I2S_LL_GET_HW(ADC_DMA_I2S_HOST)
-#define ADC_DMA_CHANNEL                  0
-#define adc_dma_check_event(dev, mask)   (i2s_ll_get_intr_status(dev) & mask)
-#define adc_dma_digi_clr_intr(dev, mask) i2s_ll_clear_intr_status(dev, mask)
-
-#define I2S0_NODE_ID    DT_NODELABEL(i2s0)
-#define I2S0_DEV        ((const struct device *)DEVICE_DT_GET_OR_NULL(I2S0_NODE_ID))
-#define I2S0_CLK_DEV    ((const struct device *)DEVICE_DT_GET(DT_CLOCKS_CTLR(I2S0_NODE_ID)))
-#define I2S0_CLK_SUBSYS ((clock_control_subsys_t)DT_CLOCKS_CELL(I2S0_NODE_ID, offset))
-#endif /* CONFIG_SOC_SERIES_ESP32 */
-
-#if CONFIG_SOC_SERIES_ESP32S2
-#include <zephyr/dt-bindings/interrupt-controller/esp32s2-xtensa-intmux.h>
-
-#define ADC_DMA_SPI_HOST                 SPI3_HOST
-#define ADC_DMA_INTR_MASK                ADC_HAL_DMA_INTR_MASK
-#define ADC_DMA_DEV                      SPI_LL_GET_HW(ADC_DMA_SPI_HOST)
-#define ADC_DMA_CHANNEL                  (DT_PROP(DT_NODELABEL(spi3), dma_host) + 1)
-#define adc_dma_check_event(dev, mask)   spi_ll_get_intr(dev, mask)
-#define adc_dma_digi_clr_intr(dev, mask) spi_ll_clear_intr(dev, mask)
-
-#define SPI3_NODE_ID        DT_NODELABEL(spi3)
-#define SPI3_DEV            ((const struct device *)DEVICE_DT_GET_OR_NULL(SPI3_NODE_ID))
-#define SPI3_CLK_DEV        ((const struct device *)DEVICE_DT_GET(DT_CLOCKS_CTLR(SPI3_NODE_ID)))
-#define SPI3_CLK_SUBSYS     ((clock_control_subsys_t)DT_CLOCKS_CELL(SPI3_NODE_ID, offset))
-#define SPI3_DMA_CLK_SUBSYS ((clock_control_subsys_t)DT_PROP(SPI3_NODE_ID, dma_clk))
-#endif /* CONFIG_SOC_SERIES_ESP32 */
-
-#endif /* SOC_GDMA_SUPPORTED */
-#endif /* defined(CONFIG_ADC_ESP32_DMA) */
-
-#include <zephyr/kernel.h>
-#include <zephyr/device.h>
-#include <zephyr/drivers/adc.h>
 #include <zephyr/drivers/gpio.h>
-#include <zephyr/drivers/clock_control.h>
 
 #include <zephyr/logging/log.h>
 LOG_MODULE_REGISTER(adc_esp32, CONFIG_ADC_LOG_LEVEL);
@@ -78,39 +25,8 @@
 /* Default internal reference voltage */
 #define ADC_ESP32_DEFAULT_VREF_INTERNAL (1100)
 
-#define ADC_DMA_BUFFER_SIZE DMA_DESCRIPTOR_BUFFER_MAX_SIZE_4B_ALIGNED
-
 #define ADC_CLIP_MVOLT_12DB	2550
 
-struct adc_esp32_conf {
-	const struct device *clock_dev;
-	const clock_control_subsys_t clock_subsys;
-	adc_unit_t unit;
-	uint8_t channel_count;
-	const struct device *gpio_port;
-#if defined(CONFIG_ADC_ESP32_DMA) && SOC_GDMA_SUPPORTED
-	const struct device *dma_dev;
-	uint8_t dma_channel;
-#endif /* defined(CONFIG_ADC_ESP32_DMA) && SOC_GDMA_SUPPORTED */
-};
-
-struct adc_esp32_data {
-	adc_oneshot_hal_ctx_t hal;
-	adc_atten_t attenuation[SOC_ADC_MAX_CHANNEL_NUM];
-	uint8_t resolution[SOC_ADC_MAX_CHANNEL_NUM];
-	adc_cali_handle_t cal_handle[SOC_ADC_MAX_CHANNEL_NUM];
-	uint16_t meas_ref_internal;
-	uint16_t *buffer;
-#ifdef CONFIG_ADC_ESP32_DMA
-	adc_hal_dma_ctx_t adc_hal_dma_ctx;
-	uint8_t *dma_buffer;
-	struct k_sem dma_conv_wait_lock;
-#if !SOC_GDMA_SUPPORTED
-	struct intr_handle_data_t *irq_handle;
-#endif /* !SOC_GDMA_SUPPORTED */
-#endif /* CONFIG_ADC_ESP32_DMA */
-};
-
 static void adc_hw_calibration(adc_unit_t unit)
 {
 #if SOC_ADC_CALIBRATION_V1_SUPPORTED
@@ -183,261 +99,6 @@
 	*val_mv = (*val_mv * num) / den;
 }
 
-#else
-
-#if SOC_GDMA_SUPPORTED
-
-static void IRAM_ATTR adc_esp32_dma_conv_done(const struct device *dma_dev, void *user_data,
-					      uint32_t channel, int status)
-{
-	ARG_UNUSED(dma_dev);
-	ARG_UNUSED(status);
-
-	const struct device *dev = user_data;
-	struct adc_esp32_data *data = dev->data;
-
-	k_sem_give(&data->dma_conv_wait_lock);
-}
-
-static int adc_esp32_dma_start(const struct device *dev, uint8_t *buf, size_t len)
-{
-	const struct adc_esp32_conf *conf = dev->config;
-	int err = 0;
-
-	struct dma_config dma_cfg = {0};
-	struct dma_status dma_status = {0};
-	struct dma_block_config dma_blk = {0};
-
-	err = dma_get_status(conf->dma_dev, conf->dma_channel, &dma_status);
-	if (err) {
-		LOG_ERR("Unable to get dma channel[%u] status (%d)",
-			(unsigned int)conf->dma_channel, err);
-		return -EINVAL;
-	}
-
-	if (dma_status.busy) {
-		LOG_ERR("dma channel[%u] is busy!", (unsigned int)conf->dma_channel);
-		return -EBUSY;
-	}
-
-	unsigned int key = irq_lock();
-
-	dma_cfg.channel_direction = PERIPHERAL_TO_MEMORY;
-	dma_cfg.dma_callback = adc_esp32_dma_conv_done;
-	dma_cfg.user_data = (void *)dev;
-	dma_cfg.dma_slot = ESP_GDMA_TRIG_PERIPH_ADC0;
-	dma_cfg.block_count = 1;
-	dma_cfg.head_block = &dma_blk;
-	dma_blk.block_size = len;
-	dma_blk.dest_address = (uint32_t)buf;
-
-	err = dma_config(conf->dma_dev, conf->dma_channel, &dma_cfg);
-	if (err) {
-		LOG_ERR("Error configuring dma (%d)", err);
-		goto unlock;
-	}
-
-	err = dma_start(conf->dma_dev, conf->dma_channel);
-	if (err) {
-		LOG_ERR("Error starting dma (%d)", err);
-		goto unlock;
-	}
-
-unlock:
-	irq_unlock(key);
-	return err;
-}
-
-static int adc_esp32_dma_stop(const struct device *dev)
-{
-	const struct adc_esp32_conf *conf = dev->config;
-	unsigned int key = irq_lock();
-	int err = 0;
-
-	err = dma_stop(conf->dma_dev, conf->dma_channel);
-	if (err) {
-		LOG_ERR("Error stopping dma (%d)", err);
-	}
-
-	irq_unlock(key);
-	return err;
-}
-
-#else
-
-static IRAM_ATTR void adc_esp32_dma_intr_handler(void *arg)
-{
-	if (arg == NULL) {
-		return;
-	}
-
-	const struct device *dev = arg;
-	struct adc_esp32_data *data = dev->data;
-
-	bool conv_completed = adc_dma_check_event(ADC_DMA_DEV, ADC_DMA_INTR_MASK);
-
-	if (conv_completed) {
-		adc_dma_digi_clr_intr(ADC_DMA_DEV, ADC_DMA_INTR_MASK);
-
-		k_sem_give(&data->dma_conv_wait_lock);
-	}
-}
-
-#endif /* SOC_GDMA_SUPPORTED */
-
-static int adc_esp32_fill_digi_ctrlr_cfg(const struct device *dev, const struct adc_sequence *seq,
-					 uint32_t sample_freq_hz,
-					 adc_digi_pattern_config_t *pattern_config,
-					 adc_hal_digi_ctrlr_cfg_t *adc_hal_digi_ctrlr_cfg,
-					 uint32_t *pattern_len, uint32_t *unit_attenuation)
-{
-	const struct adc_esp32_conf *conf = dev->config;
-	struct adc_esp32_data *data = dev->data;
-
-	adc_digi_pattern_config_t *adc_digi_pattern_config = pattern_config;
-	const uint32_t unit_atten_uninit = 999;
-	uint32_t channel_mask = 1, channels_copy = seq->channels;
-
-	*pattern_len = 0;
-	*unit_attenuation = unit_atten_uninit;
-	for (uint8_t channel_id = 0; channel_id < conf->channel_count; channel_id++) {
-		if (channels_copy & channel_mask) {
-			if (*unit_attenuation == unit_atten_uninit) {
-				*unit_attenuation = data->attenuation[channel_id];
-			} else if (*unit_attenuation != data->attenuation[channel_id]) {
-				LOG_ERR("Channel[%u] attenuation different of unit[%u] attenuation",
-					(unsigned int)channel_id, (unsigned int)conf->unit);
-				return -EINVAL;
-			}
-
-			adc_digi_pattern_config->atten = data->attenuation[channel_id];
-			adc_digi_pattern_config->channel = channel_id;
-			adc_digi_pattern_config->unit = conf->unit;
-			adc_digi_pattern_config->bit_width = seq->resolution;
-			adc_digi_pattern_config++;
-
-			*pattern_len += 1;
-			if (*pattern_len > SOC_ADC_PATT_LEN_MAX) {
-				LOG_ERR("Max pattern len is %d", SOC_ADC_PATT_LEN_MAX);
-				return -EINVAL;
-			}
-
-			channels_copy &= ~channel_mask;
-			if (!channels_copy) {
-				break;
-			}
-		}
-		channel_mask <<= 1;
-	}
-
-	soc_module_clk_t clk_src = ADC_DIGI_CLK_SRC_DEFAULT;
-	uint32_t clk_src_freq_hz = 0;
-
-	int err = esp_clk_tree_src_get_freq_hz(clk_src, ESP_CLK_TREE_SRC_FREQ_PRECISION_CACHED,
-				     &clk_src_freq_hz);
-	if (err != ESP_OK) {
-		return -1;
-	}
-
-	adc_hal_digi_ctrlr_cfg->conv_mode =
-		(conf->unit == ADC_UNIT_1) ? ADC_CONV_SINGLE_UNIT_1 : ADC_CONV_SINGLE_UNIT_2;
-	adc_hal_digi_ctrlr_cfg->clk_src = clk_src;
-	adc_hal_digi_ctrlr_cfg->clk_src_freq_hz = clk_src_freq_hz;
-	adc_hal_digi_ctrlr_cfg->sample_freq_hz = sample_freq_hz;
-	adc_hal_digi_ctrlr_cfg->adc_pattern = pattern_config;
-	adc_hal_digi_ctrlr_cfg->adc_pattern_len = *pattern_len;
-
-	return 0;
-}
-
-static void adc_esp32_digi_start(const struct device *dev,
-				 adc_hal_digi_ctrlr_cfg_t *adc_hal_digi_ctrlr_cfg,
-				 uint32_t number_of_adc_samples, uint32_t unit_attenuation)
-
-{
-	const struct adc_esp32_conf *conf = dev->config;
-	struct adc_esp32_data *data = dev->data;
-
-	periph_module_reset(PERIPH_SARADC_MODULE);
-	sar_periph_ctrl_adc_continuous_power_acquire();
-	adc_lock_acquire(conf->unit);
-
-#if SOC_ADC_CALIBRATION_V1_SUPPORTED
-	adc_set_hw_calibration_code(conf->unit, unit_attenuation);
-#endif /* SOC_ADC_CALIBRATION_V1_SUPPORTED */
-
-#if SOC_ADC_ARBITER_SUPPORTED
-	if (conf->unit == ADC_UNIT_2) {
-		adc_arbiter_t config = ADC_ARBITER_CONFIG_DEFAULT();
-
-		adc_hal_arbiter_config(&config);
-	}
-#endif /* SOC_ADC_ARBITER_SUPPORTED */
-
-	adc_hal_dma_config_t adc_hal_dma_config = {
-#if !SOC_GDMA_SUPPORTED
-		.dev = (void *)ADC_DMA_DEV,
-		.eof_desc_num = 1,
-		.dma_chan = ADC_DMA_CHANNEL,
-		.eof_step = 1,
-#endif /* !SOC_GDMA_SUPPORTED */
-		.eof_num = number_of_adc_samples
-	};
-
-	adc_hal_dma_ctx_config(&data->adc_hal_dma_ctx, &adc_hal_dma_config);
-	adc_hal_set_controller(conf->unit, ADC_HAL_CONTINUOUS_READ_MODE);
-	adc_hal_digi_init(&data->adc_hal_dma_ctx);
-	adc_hal_digi_controller_config(&data->adc_hal_dma_ctx, adc_hal_digi_ctrlr_cfg);
-	adc_hal_digi_start(&data->adc_hal_dma_ctx, data->dma_buffer);
-}
-
-static void adc_esp32_digi_stop(const struct device *dev)
-{
-	const struct adc_esp32_conf *conf = dev->config;
-	struct adc_esp32_data *data = dev->data;
-
-	adc_hal_digi_dis_intr(&data->adc_hal_dma_ctx, ADC_HAL_DMA_INTR_MASK);
-	adc_hal_digi_clr_intr(&data->adc_hal_dma_ctx, ADC_HAL_DMA_INTR_MASK);
-	adc_hal_digi_stop(&data->adc_hal_dma_ctx);
-
-#if ADC_LL_WORKAROUND_CLEAR_EOF_COUNTER
-	periph_module_reset(PERIPH_SARADC_MODULE);
-	adc_ll_digi_dma_clr_eof();
-#endif
-
-	adc_hal_digi_deinit(&data->adc_hal_dma_ctx);
-	adc_lock_release(conf->unit);
-	sar_periph_ctrl_adc_continuous_power_release();
-}
-
-static void adc_esp32_fill_seq_buffer(const void *seq_buffer, const void *dma_buffer,
-				      uint32_t number_of_samples)
-{
-	uint16_t *sample = (uint16_t *)seq_buffer;
-	adc_digi_output_data_t *digi_data = (adc_digi_output_data_t *)dma_buffer;
-
-	for (uint32_t k = 0; k < number_of_samples; k++) {
-#if SOC_GDMA_SUPPORTED
-		*sample++ = (uint16_t)(digi_data++)->type2.data;
-#else
-		*sample++ = (uint16_t)(digi_data++)->type1.data;
-#endif /* SOC_GDMA_SUPPORTED */
-	}
-}
-
-static int adc_esp32_wait_for_dma_conv_done(const struct device *dev)
-{
-	struct adc_esp32_data *data = dev->data;
-	int err = 0;
-
-	err = k_sem_take(&data->dma_conv_wait_lock, K_FOREVER);
-	if (err) {
-		LOG_ERR("Error taking dma_conv_wait_lock (%d)", err);
-	}
-
-	return err;
-}
-
 #endif /* CONFIG_ADC_ESP32_DMA */
 
 static int adc_esp32_read(const struct device *dev, const struct adc_sequence *seq)
@@ -456,22 +117,18 @@
 		LOG_ERR("Multi-channel readings not supported");
 		return -ENOTSUP;
 	}
-#endif /* CONFIG_ADC_ESP32_DMA */
 
-	if (seq->options) {
-		if (seq->options->extra_samplings) {
-			LOG_ERR("Extra samplings not supported");
-			return -ENOTSUP;
-		}
-
-#ifndef CONFIG_ADC_ESP32_DMA
-		if (seq->options->interval_us) {
-			LOG_ERR("Interval between samplings not supported");
-			return -ENOTSUP;
-		}
-#endif /* CONFIG_ADC_ESP32_DMA */
+	if (seq->options && seq->options->extra_samplings) {
+		LOG_ERR("Extra samplings not supported");
+		return -ENOTSUP;
 	}
 
+	if (seq->options && seq->options->interval_us) {
+		LOG_ERR("Interval between samplings not supported");
+		return -ENOTSUP;
+	}
+#endif /* CONFIG_ADC_ESP32_DMA */
+
 	if (!VALID_RESOLUTION(seq->resolution)) {
 		LOG_ERR("unsupported resolution (%d)", seq->resolution);
 		return -ENOTSUP;
@@ -485,10 +142,30 @@
 
 	data->resolution[channel_id] = seq->resolution;
 
-#ifndef CONFIG_ADC_ESP32_DMA
+#ifdef CONFIG_ADC_ESP32_DMA
+	int err = adc_esp32_dma_read(dev, seq);
 
+	if (err < 0) {
+		return err;
+	}
+#else
 	uint32_t acq_raw;
 
+	if (seq->channels > BIT(channel_id)) {
+		LOG_ERR("Multi-channel readings not supported");
+		return -ENOTSUP;
+	}
+
+	if (seq->options && seq->options->extra_samplings) {
+		LOG_ERR("Extra samplings not supported");
+		return -ENOTSUP;
+	}
+
+	if (seq->options && seq->options->interval_us) {
+		LOG_ERR("Interval between samplings not supported");
+		return -ENOTSUP;
+	}
+
 	adc_oneshot_hal_setup(&data->hal, channel_id);
 
 #if SOC_ADC_CALIBRATION_V1_SUPPORTED
@@ -507,11 +184,10 @@
 				data->hal.unit, channel_id, acq_raw, acq_mv);
 
 #if CONFIG_SOC_SERIES_ESP32
-		if (data->attenuation[channel_id] == ADC_ATTEN_DB_12) {
-			if (acq_mv > ADC_CLIP_MVOLT_12DB) {
+			if (data->attenuation[channel_id] == ADC_ATTEN_DB_12 &&
+			    acq_mv > ADC_CLIP_MVOLT_12DB) {
 				acq_mv = ADC_CLIP_MVOLT_12DB;
 			}
-		}
 #endif /* CONFIG_SOC_SERIES_ESP32 */
 
 			/* Fit according to selected attenuation */
@@ -528,80 +204,6 @@
 	/* Store result */
 	data->buffer = (uint16_t *)seq->buffer;
 	data->buffer[0] = acq_raw;
-
-#else /* CONFIG_ADC_ESP32_DMA */
-
-	int err = 0;
-	uint32_t adc_pattern_len, unit_attenuation;
-	adc_hal_digi_ctrlr_cfg_t adc_hal_digi_ctrlr_cfg;
-	adc_digi_pattern_config_t adc_digi_pattern_config[SOC_ADC_MAX_CHANNEL_NUM];
-
-	const struct adc_sequence_options *options = seq->options;
-	uint32_t sample_freq_hz = SOC_ADC_SAMPLE_FREQ_THRES_HIGH, number_of_samplings = 1;
-
-	if (options && options->interval_us) {
-		sample_freq_hz = MHZ(1) / options->interval_us;
-		if (sample_freq_hz < SOC_ADC_SAMPLE_FREQ_THRES_LOW ||
-		    sample_freq_hz > SOC_ADC_SAMPLE_FREQ_THRES_HIGH) {
-			LOG_ERR("ADC sampling frequency out of range: %uHz", sample_freq_hz);
-			return -EINVAL;
-		}
-	}
-
-	err = adc_esp32_fill_digi_ctrlr_cfg(dev, seq, sample_freq_hz, adc_digi_pattern_config,
-					    &adc_hal_digi_ctrlr_cfg, &adc_pattern_len,
-					    &unit_attenuation);
-	if (err || adc_pattern_len == 0) {
-		return -EINVAL;
-	}
-
-	if (options != NULL) {
-		number_of_samplings = seq->buffer_size / (adc_pattern_len * sizeof(uint16_t));
-	}
-
-	if (!number_of_samplings) {
-		LOG_ERR("buffer_size insufficient to store at least one set of samples!");
-		return -EINVAL;
-	}
-
-	uint32_t number_of_adc_samples = number_of_samplings * adc_pattern_len;
-	uint32_t number_of_adc_dma_data_bytes =
-		number_of_adc_samples * SOC_ADC_DIGI_DATA_BYTES_PER_CONV;
-
-	if (number_of_adc_dma_data_bytes > ADC_DMA_BUFFER_SIZE) {
-		LOG_ERR("dma buffer size insufficient to store a complete sequence!");
-		return -EINVAL;
-	}
-
-	adc_esp32_digi_start(dev, &adc_hal_digi_ctrlr_cfg, number_of_adc_samples, unit_attenuation);
-
-#if SOC_GDMA_SUPPORTED
-	err = adc_esp32_dma_start(dev, data->dma_buffer, number_of_adc_dma_data_bytes);
-#else
-	err = esp_intr_enable(data->irq_handle);
-#endif /* SOC_GDMA_SUPPORTED */
-	if (err) {
-		return err;
-	}
-
-	err = adc_esp32_wait_for_dma_conv_done(dev);
-	if (err) {
-		return err;
-	}
-
-#if SOC_GDMA_SUPPORTED
-	err = adc_esp32_dma_stop(dev);
-#else
-	err = esp_intr_disable(data->irq_handle);
-#endif /* SOC_GDMA_SUPPORTED */
-	if (err) {
-		return err;
-	}
-
-	adc_esp32_digi_stop(dev);
-
-	adc_esp32_fill_seq_buffer(seq->buffer, data->dma_buffer, number_of_adc_samples);
-
 #endif /* CONFIG_ADC_ESP32_DMA */
 
 	return 0;
@@ -623,6 +225,7 @@
 {
 	const struct adc_esp32_conf *conf = (const struct adc_esp32_conf *)dev->config;
 	struct adc_esp32_data *data = (struct adc_esp32_data *)dev->data;
+	int err;
 
 	if (cfg->channel_id >= conf->channel_count) {
 		LOG_ERR("Unsupported channel id '%d'", cfg->channel_id);
@@ -649,7 +252,13 @@
 		return -ENOTSUP;
 	}
 
-#ifndef CONFIG_ADC_ESP32_DMA
+#ifdef CONFIG_ADC_ESP32_DMA
+	err = adc_esp32_dma_channel_setup(dev, cfg);
+
+	if (err < 0) {
+		return err;
+	}
+#else
 	adc_atten_t old_atten = data->attenuation[cfg->channel_id];
 
 	adc_oneshot_hal_chan_cfg_t config = {
@@ -705,11 +314,6 @@
 						    &data->cal_handle[cfg->channel_id]);
 #endif /* ADC_CALI_SCHEME_LINE_FITTING_SUPPORTED */
 	}
-#else
-	if (!SOC_ADC_DIG_SUPPORTED_UNIT(conf->unit)) {
-		LOG_ERR("ADC2 dma mode is no longer supported, please use ADC1!");
-		return -EINVAL;
-	}
 #endif /* CONFIG_ADC_ESP32_DMA */
 
 	/* GPIO config for ADC mode */
@@ -727,7 +331,7 @@
 		.pin = io_num,
 	};
 
-	int err = gpio_pin_configure_dt(&gpio, GPIO_DISCONNECTED);
+	err = gpio_pin_configure_dt(&gpio, GPIO_DISCONNECTED);
 
 	if (err) {
 		LOG_ERR("Error disconnecting io (%d)", io_num);
@@ -760,7 +364,13 @@
 		return -ENODEV;
 	}
 
-#ifndef CONFIG_ADC_ESP32_DMA
+#ifdef CONFIG_ADC_ESP32_DMA
+	int err = adc_esp32_dma_init(dev);
+
+	if (err < 0) {
+		return err;
+	}
+#else
 	adc_oneshot_hal_cfg_t config = {
 		.unit = conf->unit,
 		.work_mode = ADC_HAL_SINGLE_READ_MODE,
@@ -771,74 +381,6 @@
 	adc_oneshot_hal_init(&data->hal, &config);
 
 	sar_periph_ctrl_adc_oneshot_power_acquire();
-#else
-
-	if (k_sem_init(&data->dma_conv_wait_lock, 0, 1)) {
-		LOG_ERR("dma_conv_wait_lock initialization failed!");
-		return -EINVAL;
-	}
-
-	data->adc_hal_dma_ctx.rx_desc = k_aligned_alloc(sizeof(uint32_t), sizeof(dma_descriptor_t));
-	if (!data->adc_hal_dma_ctx.rx_desc) {
-		LOG_ERR("rx_desc allocation failed!");
-		return -ENOMEM;
-	}
-	LOG_DBG("rx_desc = 0x%08X", (unsigned int)data->adc_hal_dma_ctx.rx_desc);
-
-	data->dma_buffer = k_aligned_alloc(sizeof(uint32_t), ADC_DMA_BUFFER_SIZE);
-	if (!data->dma_buffer) {
-		LOG_ERR("dma buffer allocation failed!");
-		k_free(data->adc_hal_dma_ctx.rx_desc);
-		return -ENOMEM;
-	}
-	LOG_DBG("data->dma_buffer = 0x%08X", (unsigned int)data->dma_buffer);
-
-#ifdef CONFIG_SOC_SERIES_ESP32
-	const struct device *i2s0_dev = I2S0_DEV;
-
-	if (i2s0_dev != NULL) {
-		LOG_ERR("I2S0 not available for ADC_ESP32_DMA");
-		return -ENODEV;
-	}
-
-	if (!device_is_ready(I2S0_CLK_DEV)) {
-		return -ENODEV;
-	}
-
-	clock_control_on(I2S0_CLK_DEV, I2S0_CLK_SUBSYS);
-	i2s_ll_enable_clock(ADC_DMA_DEV);
-
-	int err = esp_intr_alloc(I2S0_INTR_SOURCE, ESP_INTR_FLAG_IRAM | ESP_INTR_FLAG_INTRDISABLED,
-				 adc_esp32_dma_intr_handler, (void *)dev, &(data->irq_handle));
-	if (err != 0) {
-		LOG_ERR("Could not allocate interrupt (err %d)", err);
-		return err;
-	}
-#endif /* CONFIG_SOC_SERIES_ESP32S2 */
-
-#ifdef CONFIG_SOC_SERIES_ESP32S2
-	const struct device *spi3_dev = SPI3_DEV;
-
-	if (spi3_dev != NULL) {
-		LOG_ERR("SPI3 not available for ADC_ESP32_DMA");
-		return -ENODEV;
-	}
-
-	if (!device_is_ready(SPI3_CLK_DEV)) {
-		return -ENODEV;
-	}
-
-	clock_control_on(SPI3_CLK_DEV, SPI3_CLK_SUBSYS);
-	clock_control_on(SPI3_CLK_DEV, SPI3_DMA_CLK_SUBSYS);
-
-	int err = esp_intr_alloc(SPI3_DMA_INTR_SOURCE,
-				 ESP_INTR_FLAG_IRAM | ESP_INTR_FLAG_INTRDISABLED,
-				 adc_esp32_dma_intr_handler, (void *)dev, &(data->irq_handle));
-	if (err != 0) {
-		LOG_ERR("Could not allocate interrupt (err %d)", err);
-		return err;
-	}
-#endif /* CONFIG_SOC_SERIES_ESP32S2 */
 #endif /* CONFIG_ADC_ESP32_DMA */
 
 	for (uint8_t i = 0; i < SOC_ADC_MAX_CHANNEL_NUM; i++) {
@@ -864,17 +406,13 @@
 	.ref_internal = ADC_ESP32_DEFAULT_VREF_INTERNAL,
 };
 
-#ifdef CONFIG_ADC_ESP32_DMA
-#if SOC_GDMA_SUPPORTED
+#if defined(CONFIG_ADC_ESP32_DMA) && SOC_GDMA_SUPPORTED
 #define ADC_ESP32_CONF_INIT(n)                                                                     \
 	.dma_dev = DEVICE_DT_GET(DT_INST_DMAS_CTLR_BY_IDX(n, 0)),                                  \
 	.dma_channel = DT_INST_DMAS_CELL_BY_IDX(n, 0, channel)
 #else
 #define ADC_ESP32_CONF_INIT(n)
-#endif /* SOC_GDMA_SUPPORTED */
-#else
-#define ADC_ESP32_CONF_INIT(n)
-#endif /* CONFIG_ADC_ESP32_DMA */
+#endif /* defined(SOC_GDMA_SUPPORTED) && SOC_GDMA_SUPPORTED */
 
 #define ADC_ESP32_CHECK_CHANNEL_REF(chan)                                                          \
 	BUILD_ASSERT(DT_ENUM_HAS_VALUE(chan, zephyr_reference, adc_ref_internal),                  \
diff --git a/drivers/adc/adc_esp32.h b/drivers/adc/adc_esp32.h
new file mode 100644
index 0000000..7aefbc8
--- /dev/null
+++ b/drivers/adc/adc_esp32.h
@@ -0,0 +1,49 @@
+/*
+ * Copyright (c) 2025 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#include <hal/adc_hal.h>
+#include <hal/adc_oneshot_hal.h>
+#include <hal/adc_types.h>
+#include <esp_adc/adc_cali.h>
+
+#include <zephyr/kernel.h>
+#include <zephyr/drivers/adc.h>
+#include <zephyr/drivers/clock_control.h>
+
+struct adc_esp32_conf {
+	const struct device *clock_dev;
+	const clock_control_subsys_t clock_subsys;
+	adc_unit_t unit;
+	uint8_t channel_count;
+	const struct device *gpio_port;
+#if defined(CONFIG_ADC_ESP32_DMA) && SOC_GDMA_SUPPORTED
+	const struct device *dma_dev;
+	uint8_t dma_channel;
+#endif /* defined(CONFIG_ADC_ESP32_DMA) && SOC_GDMA_SUPPORTED */
+};
+
+struct adc_esp32_data {
+	adc_oneshot_hal_ctx_t hal;
+	adc_atten_t attenuation[SOC_ADC_MAX_CHANNEL_NUM];
+	uint8_t resolution[SOC_ADC_MAX_CHANNEL_NUM];
+	adc_cali_handle_t cal_handle[SOC_ADC_MAX_CHANNEL_NUM];
+	uint16_t meas_ref_internal;
+	uint16_t *buffer;
+#ifdef CONFIG_ADC_ESP32_DMA
+	adc_hal_dma_ctx_t adc_hal_dma_ctx;
+	uint8_t *dma_buffer;
+	struct k_sem dma_conv_wait_lock;
+#if !SOC_GDMA_SUPPORTED
+	struct intr_handle_data_t *irq_handle;
+#endif /* !SOC_GDMA_SUPPORTED */
+#endif /* CONFIG_ADC_ESP32_DMA */
+};
+
+int adc_esp32_dma_read(const struct device *dev, const struct adc_sequence *seq);
+
+int adc_esp32_dma_channel_setup(const struct device *dev, const struct adc_channel_cfg *cfg);
+
+int adc_esp32_dma_init(const struct device *dev);
diff --git a/drivers/adc/adc_esp32_dma.c b/drivers/adc/adc_esp32_dma.c
new file mode 100644
index 0000000..2c5b26c
--- /dev/null
+++ b/drivers/adc/adc_esp32_dma.c
@@ -0,0 +1,435 @@
+/*
+ * Copyright (c) 2025 Espressif Systems (Shanghai) CO LTD
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#define DT_DRV_COMPAT espressif_esp32_adc
+
+#include <esp_adc/adc_cali.h>
+#include <esp_clk_tree.h>
+#include <esp_private/periph_ctrl.h>
+#include <esp_private/sar_periph_ctrl.h>
+#include <esp_private/adc_share_hw_ctrl.h>
+
+#include "adc_esp32.h"
+
+#include <zephyr/logging/log.h>
+LOG_MODULE_REGISTER(adc_esp32_dma, CONFIG_ADC_LOG_LEVEL);
+
+#if SOC_GDMA_SUPPORTED
+#include <zephyr/drivers/dma.h>
+#include <zephyr/drivers/dma/dma_esp32.h>
+#elif defined(CONFIG_SOC_SERIES_ESP32)
+#include <zephyr/dt-bindings/clock/esp32_clock.h>
+#include <zephyr/dt-bindings/interrupt-controller/esp-xtensa-intmux.h>
+#include <zephyr/drivers/interrupt_controller/intc_esp32.h>
+#define ADC_DMA_I2S_HOST 0
+#elif defined(CONFIG_SOC_SERIES_ESP32S2)
+#include <zephyr/dt-bindings/clock/esp32s2_clock.h>
+#include <zephyr/dt-bindings/interrupt-controller/esp32s2-xtensa-intmux.h>
+#include <zephyr/drivers/interrupt_controller/intc_esp32.h>
+#endif /* SOC_GDMA_SUPPORTED */
+
+#define ADC_DMA_BUFFER_SIZE        DMA_DESCRIPTOR_BUFFER_MAX_SIZE_4B_ALIGNED
+#define ADC_DMA_MAX_CONV_DONE_TIME 1000
+
+#define UNIT_ATTEN_UNINIT UINT32_MAX
+
+#if SOC_GDMA_SUPPORTED
+
+static void IRAM_ATTR adc_esp32_dma_conv_done(const struct device *dma_dev, void *user_data,
+					      uint32_t channel, int status)
+{
+	ARG_UNUSED(dma_dev);
+	ARG_UNUSED(status);
+
+	const struct device *dev = user_data;
+	struct adc_esp32_data *data = dev->data;
+
+	k_sem_give(&data->dma_conv_wait_lock);
+}
+
+static int adc_esp32_dma_start(const struct device *dev, uint8_t *buf, size_t len)
+{
+	const struct adc_esp32_conf *conf = dev->config;
+	int err;
+
+	struct dma_config dma_cfg = {0};
+	struct dma_status dma_status = {0};
+	struct dma_block_config dma_blk = {0};
+
+	err = dma_get_status(conf->dma_dev, conf->dma_channel, &dma_status);
+	if (err) {
+		LOG_ERR("Unable to get dma channel[%u] status (%d)",
+			(unsigned int)conf->dma_channel, err);
+		return -EINVAL;
+	}
+
+	if (dma_status.busy) {
+		LOG_ERR("dma channel[%u] is busy!", (unsigned int)conf->dma_channel);
+		return -EBUSY;
+	}
+
+	dma_cfg.channel_direction = PERIPHERAL_TO_MEMORY;
+	dma_cfg.dma_callback = adc_esp32_dma_conv_done;
+	dma_cfg.user_data = (void *)dev;
+	dma_cfg.dma_slot = ESP_GDMA_TRIG_PERIPH_ADC0;
+	dma_cfg.block_count = 1;
+	dma_cfg.head_block = &dma_blk;
+	dma_blk.block_size = len;
+	dma_blk.dest_address = (uint32_t)buf;
+
+	err = dma_config(conf->dma_dev, conf->dma_channel, &dma_cfg);
+	if (err) {
+		LOG_ERR("Error configuring dma (%d)", err);
+		return err;
+	}
+
+	err = dma_start(conf->dma_dev, conf->dma_channel);
+	if (err) {
+		LOG_ERR("Error starting dma (%d)", err);
+		return err;
+	}
+
+	return 0;
+}
+
+static int adc_esp32_dma_stop(const struct device *dev)
+{
+	const struct adc_esp32_conf *conf = dev->config;
+	int err;
+
+	err = dma_stop(conf->dma_dev, conf->dma_channel);
+	if (err) {
+		LOG_ERR("Error stopping dma (%d)", err);
+	}
+
+	return err;
+}
+
+#else
+
+static IRAM_ATTR void adc_esp32_dma_intr_handler(void *arg)
+{
+	const struct device *dev = arg;
+	struct adc_esp32_data *data = dev->data;
+
+#if defined(CONFIG_SOC_SERIES_ESP32)
+	if (i2s_ll_get_intr_status(I2S_LL_GET_HW(ADC_DMA_I2S_HOST)) & ADC_HAL_DMA_INTR_MASK) {
+		i2s_ll_clear_intr_status(I2S_LL_GET_HW(ADC_DMA_I2S_HOST), ADC_HAL_DMA_INTR_MASK);
+#elif defined(CONFIG_SOC_SERIES_ESP32S2)
+	if (spi_ll_get_intr(SPI_LL_GET_HW(SPI3_HOST), ADC_HAL_DMA_INTR_MASK)) {
+		spi_ll_clear_intr(SPI_LL_GET_HW(SPI3_HOST), ADC_HAL_DMA_INTR_MASK);
+#endif /* defined(CONFIG_SOC_SERIES_ESP32) */
+		k_sem_give(&data->dma_conv_wait_lock);
+	}
+}
+
+#endif /* SOC_GDMA_SUPPORTED */
+
+static int adc_esp32_fill_digi_ctrlr_cfg(const struct device *dev, const struct adc_sequence *seq,
+					 uint32_t sample_freq_hz,
+					 adc_digi_pattern_config_t *pattern_config,
+					 adc_hal_digi_ctrlr_cfg_t *adc_hal_digi_ctrlr_cfg,
+					 uint32_t *pattern_len, uint32_t *unit_attenuation)
+{
+	const struct adc_esp32_conf *conf = dev->config;
+	struct adc_esp32_data *data = dev->data;
+
+	adc_digi_pattern_config_t *adc_digi_pattern_config = pattern_config;
+	uint32_t channel_mask = 1, channels_copy = seq->channels;
+
+	*pattern_len = 0;
+	*unit_attenuation = UNIT_ATTEN_UNINIT;
+	for (uint8_t channel_id = 0; channel_id < conf->channel_count; channel_id++) {
+		if (channels_copy & channel_mask) {
+			if (*unit_attenuation == UNIT_ATTEN_UNINIT) {
+				*unit_attenuation = data->attenuation[channel_id];
+			}
+
+			if (*unit_attenuation != data->attenuation[channel_id]) {
+				LOG_ERR("Channel[%u] attenuation different of unit[%u] attenuation",
+					(unsigned int)channel_id, (unsigned int)conf->unit);
+				return -EINVAL;
+			}
+
+			adc_digi_pattern_config->atten = data->attenuation[channel_id];
+			adc_digi_pattern_config->channel = channel_id;
+			adc_digi_pattern_config->unit = conf->unit;
+			adc_digi_pattern_config->bit_width = seq->resolution;
+			adc_digi_pattern_config++;
+
+			*pattern_len += 1;
+			if (*pattern_len > SOC_ADC_PATT_LEN_MAX) {
+				LOG_ERR("Max pattern len is %d", SOC_ADC_PATT_LEN_MAX);
+				return -EINVAL;
+			}
+
+			channels_copy &= ~channel_mask;
+			if (!channels_copy) {
+				break;
+			}
+		}
+		channel_mask <<= 1;
+	}
+
+	soc_module_clk_t clk_src = ADC_DIGI_CLK_SRC_DEFAULT;
+	uint32_t clk_src_freq_hz = 0;
+
+	int err = esp_clk_tree_src_get_freq_hz(clk_src, ESP_CLK_TREE_SRC_FREQ_PRECISION_CACHED,
+					       &clk_src_freq_hz);
+	if (err != ESP_OK) {
+		return -EIO;
+	}
+
+	adc_hal_digi_ctrlr_cfg->conv_mode =
+		(conf->unit == ADC_UNIT_1) ? ADC_CONV_SINGLE_UNIT_1 : ADC_CONV_SINGLE_UNIT_2;
+	adc_hal_digi_ctrlr_cfg->clk_src = clk_src;
+	adc_hal_digi_ctrlr_cfg->clk_src_freq_hz = clk_src_freq_hz;
+	adc_hal_digi_ctrlr_cfg->sample_freq_hz = sample_freq_hz;
+	adc_hal_digi_ctrlr_cfg->adc_pattern = pattern_config;
+	adc_hal_digi_ctrlr_cfg->adc_pattern_len = *pattern_len;
+
+	return 0;
+}
+
+static void adc_esp32_digi_start(const struct device *dev,
+				 adc_hal_digi_ctrlr_cfg_t *adc_hal_digi_ctrlr_cfg,
+				 uint32_t number_of_adc_samples, uint32_t unit_attenuation)
+{
+	const struct adc_esp32_conf *conf = dev->config;
+	struct adc_esp32_data *data = dev->data;
+
+	periph_module_reset(PERIPH_SARADC_MODULE);
+	sar_periph_ctrl_adc_continuous_power_acquire();
+	adc_lock_acquire(conf->unit);
+
+#if SOC_ADC_CALIBRATION_V1_SUPPORTED
+	adc_set_hw_calibration_code(conf->unit, unit_attenuation);
+#endif /* SOC_ADC_CALIBRATION_V1_SUPPORTED */
+
+#if SOC_ADC_ARBITER_SUPPORTED
+	if (conf->unit == ADC_UNIT_2) {
+		adc_arbiter_t config = ADC_ARBITER_CONFIG_DEFAULT();
+
+		adc_hal_arbiter_config(&config);
+	}
+#endif /* SOC_ADC_ARBITER_SUPPORTED */
+
+	adc_hal_dma_config_t adc_hal_dma_config = {
+#if defined(CONFIG_SOC_SERIES_ESP32)
+		.dev = (void *)I2S_LL_GET_HW(ADC_DMA_I2S_HOST),
+		.eof_desc_num = 1,
+		.eof_step = 1,
+#elif defined(CONFIG_SOC_SERIES_ESP32S2)
+		.dev = (void *)SPI_LL_GET_HW(SPI3_HOST),
+		.eof_desc_num = 1,
+		.eof_step = 1,
+#endif /* defined(CONFIG_SOC_SERIES_ESP32) */
+		.eof_num = number_of_adc_samples,
+	};
+
+	adc_hal_dma_ctx_config(&data->adc_hal_dma_ctx, &adc_hal_dma_config);
+	adc_hal_set_controller(conf->unit, ADC_HAL_CONTINUOUS_READ_MODE);
+	adc_hal_digi_init(&data->adc_hal_dma_ctx);
+	adc_hal_digi_controller_config(&data->adc_hal_dma_ctx, adc_hal_digi_ctrlr_cfg);
+	adc_hal_digi_start(&data->adc_hal_dma_ctx, data->dma_buffer);
+}
+
+static void adc_esp32_digi_stop(const struct device *dev)
+{
+	const struct adc_esp32_conf *conf = dev->config;
+	struct adc_esp32_data *data = dev->data;
+
+	adc_hal_digi_dis_intr(&data->adc_hal_dma_ctx, ADC_HAL_DMA_INTR_MASK);
+	adc_hal_digi_clr_intr(&data->adc_hal_dma_ctx, ADC_HAL_DMA_INTR_MASK);
+	adc_hal_digi_stop(&data->adc_hal_dma_ctx);
+
+#if ADC_LL_WORKAROUND_CLEAR_EOF_COUNTER
+	periph_module_reset(PERIPH_SARADC_MODULE);
+	adc_ll_digi_dma_clr_eof();
+#endif
+
+	adc_hal_digi_deinit(&data->adc_hal_dma_ctx);
+	adc_lock_release(conf->unit);
+	sar_periph_ctrl_adc_continuous_power_release();
+}
+
+static void adc_esp32_fill_seq_buffer(const void *seq_buffer, const void *dma_buffer,
+				      uint32_t number_of_samples)
+{
+	uint16_t *sample = (uint16_t *)seq_buffer;
+	adc_digi_output_data_t *digi_data = (adc_digi_output_data_t *)dma_buffer;
+
+	for (uint32_t k = 0; k < number_of_samples; k++) {
+#if SOC_GDMA_SUPPORTED
+		*sample++ = (uint16_t)(digi_data++)->type2.data;
+#else
+		*sample++ = (uint16_t)(digi_data++)->type1.data;
+#endif /* SOC_GDMA_SUPPORTED */
+	}
+}
+
+static int adc_esp32_wait_for_dma_conv_done(const struct device *dev)
+{
+	struct adc_esp32_data *data = dev->data;
+	int err = 0;
+
+	err = k_sem_take(&data->dma_conv_wait_lock, K_MSEC(ADC_DMA_MAX_CONV_DONE_TIME));
+	if (err) {
+		LOG_ERR("Error taking dma_conv_wait_lock (%d)", err);
+	}
+
+	return err;
+}
+
+int adc_esp32_dma_read(const struct device *dev, const struct adc_sequence *seq)
+{
+	struct adc_esp32_data *data = dev->data;
+	int err = 0;
+	uint32_t adc_pattern_len, unit_attenuation;
+	adc_hal_digi_ctrlr_cfg_t adc_hal_digi_ctrlr_cfg;
+	adc_digi_pattern_config_t adc_digi_pattern_config[SOC_ADC_MAX_CHANNEL_NUM];
+
+	const struct adc_sequence_options *options = seq->options;
+	uint32_t sample_freq_hz = SOC_ADC_SAMPLE_FREQ_THRES_HIGH, number_of_samplings = 1;
+
+	if (options && options->callback) {
+		return -ENOTSUP;
+	}
+
+	if (options && options->interval_us) {
+		sample_freq_hz = MHZ(1) / options->interval_us;
+		if (sample_freq_hz < SOC_ADC_SAMPLE_FREQ_THRES_LOW ||
+		    sample_freq_hz > SOC_ADC_SAMPLE_FREQ_THRES_HIGH) {
+			LOG_ERR("ADC sampling frequency out of range: %uHz", sample_freq_hz);
+			return -EINVAL;
+		}
+	}
+
+	err = adc_esp32_fill_digi_ctrlr_cfg(dev, seq, sample_freq_hz, adc_digi_pattern_config,
+					    &adc_hal_digi_ctrlr_cfg, &adc_pattern_len,
+					    &unit_attenuation);
+	if (err || adc_pattern_len == 0) {
+		return -EINVAL;
+	}
+
+	if (options != NULL) {
+		number_of_samplings = options->extra_samplings + 1;
+	}
+
+	if (seq->buffer_size < (number_of_samplings * sizeof(uint16_t))) {
+		LOG_ERR("buffer size is not enough to store all samples!");
+		return -EINVAL;
+	}
+
+	uint32_t number_of_adc_samples = number_of_samplings * adc_pattern_len;
+	uint32_t number_of_adc_dma_data_bytes =
+		number_of_adc_samples * SOC_ADC_DIGI_DATA_BYTES_PER_CONV;
+
+	if (number_of_adc_dma_data_bytes > ADC_DMA_BUFFER_SIZE) {
+		LOG_ERR("dma buffer size insufficient to store a complete sequence!");
+		return -EINVAL;
+	}
+
+#if SOC_GDMA_SUPPORTED
+	err = adc_esp32_dma_start(dev, data->dma_buffer, number_of_adc_dma_data_bytes);
+#else
+	err = esp_intr_enable(data->irq_handle);
+#endif /* SOC_GDMA_SUPPORTED */
+	if (err) {
+		return err;
+	}
+
+	adc_esp32_digi_start(dev, &adc_hal_digi_ctrlr_cfg, number_of_adc_samples, unit_attenuation);
+
+	err = adc_esp32_wait_for_dma_conv_done(dev);
+	if (err) {
+		return err;
+	}
+
+	adc_esp32_digi_stop(dev);
+
+#if SOC_GDMA_SUPPORTED
+	err = adc_esp32_dma_stop(dev);
+#else
+	err = esp_intr_disable(data->irq_handle);
+#endif /* SOC_GDMA_SUPPORTED */
+	if (err) {
+		return err;
+	}
+
+	adc_esp32_fill_seq_buffer(seq->buffer, data->dma_buffer, number_of_adc_samples);
+
+	return 0;
+}
+
+int adc_esp32_dma_channel_setup(const struct device *dev, const struct adc_channel_cfg *cfg)
+{
+	__maybe_unused const struct adc_esp32_conf *conf =
+		(const struct adc_esp32_conf *)dev->config;
+
+	if (!SOC_ADC_DIG_SUPPORTED_UNIT(conf->unit)) {
+		LOG_ERR("ADC2 dma mode is no longer supported, please use ADC1!");
+		return -EINVAL;
+	}
+
+	return 0;
+}
+
+int adc_esp32_dma_init(const struct device *dev)
+{
+	struct adc_esp32_data *data = (struct adc_esp32_data *)dev->data;
+
+	if (k_sem_init(&data->dma_conv_wait_lock, 0, 1)) {
+		LOG_ERR("dma_conv_wait_lock initialization failed!");
+		return -EINVAL;
+	}
+
+	data->adc_hal_dma_ctx.rx_desc = k_aligned_alloc(sizeof(uint32_t), sizeof(dma_descriptor_t));
+	if (!data->adc_hal_dma_ctx.rx_desc) {
+		LOG_ERR("rx_desc allocation failed!");
+		return -ENOMEM;
+	}
+	LOG_DBG("rx_desc = 0x%08X", (unsigned int)data->adc_hal_dma_ctx.rx_desc);
+
+	data->dma_buffer = k_aligned_alloc(sizeof(uint32_t), ADC_DMA_BUFFER_SIZE);
+	if (!data->dma_buffer) {
+		LOG_ERR("dma buffer allocation failed!");
+		k_free(data->adc_hal_dma_ctx.rx_desc);
+		return -ENOMEM;
+	}
+	LOG_DBG("data->dma_buffer = 0x%08X", (unsigned int)data->dma_buffer);
+
+#ifdef CONFIG_SOC_SERIES_ESP32
+	periph_module_enable(PERIPH_I2S0_MODULE);
+	i2s_ll_enable_clock(I2S_LL_GET_HW(ADC_DMA_I2S_HOST));
+
+	int err = esp_intr_alloc(I2S0_INTR_SOURCE, ESP_INTR_FLAG_IRAM | ESP_INTR_FLAG_INTRDISABLED,
+				 adc_esp32_dma_intr_handler, (void *)dev, &(data->irq_handle));
+	if (err != 0) {
+		LOG_ERR("Could not allocate interrupt (err %d)", err);
+		k_free(data->adc_hal_dma_ctx.rx_desc);
+		k_free(data->dma_buffer);
+		return err;
+	}
+#endif /* CONFIG_SOC_SERIES_ESP32 */
+
+#ifdef CONFIG_SOC_SERIES_ESP32S2
+	periph_module_enable(PERIPH_HSPI_MODULE);
+	periph_module_enable(PERIPH_SPI3_DMA_MODULE);
+
+	int err = esp_intr_alloc(SPI3_DMA_INTR_SOURCE,
+				 ESP_INTR_FLAG_IRAM | ESP_INTR_FLAG_INTRDISABLED,
+				 adc_esp32_dma_intr_handler, (void *)dev, &(data->irq_handle));
+	if (err != 0) {
+		LOG_ERR("Could not allocate interrupt (err %d)", err);
+		k_free(data->adc_hal_dma_ctx.rx_desc);
+		k_free(data->dma_buffer);
+		return err;
+	}
+#endif /* CONFIG_SOC_SERIES_ESP32S2 */
+
+	return 0;
+}
diff --git a/drivers/i2s/i2s_esp32.c b/drivers/i2s/i2s_esp32.c
index ab29e02..d813b50 100644
--- a/drivers/i2s/i2s_esp32.c
+++ b/drivers/i2s/i2s_esp32.c
@@ -28,6 +28,11 @@
 #error "DMA peripheral is not enabled!"
 #endif /* SOC_GDMA_SUPPORTED */
 
+#if defined(CONFIG_SOC_SERIES_ESP32) && defined(CONFIG_ADC_ESP32_DMA) &&                           \
+	DT_NODE_HAS_STATUS_OKAY(DT_NODELABEL(i2s0))
+#error "i2s0 must be disabled if ADC_ESP32_DMA is enabled for ESP32"
+#endif
+
 LOG_MODULE_REGISTER(i2s_esp32, CONFIG_I2S_LOG_LEVEL);
 
 #define I2S_ESP32_CLK_SRC             I2S_CLK_SRC_DEFAULT
diff --git a/drivers/spi/spi_esp32_spim.c b/drivers/spi/spi_esp32_spim.c
index 6a61868..b96d11a 100644
--- a/drivers/spi/spi_esp32_spim.c
+++ b/drivers/spi/spi_esp32_spim.c
@@ -27,6 +27,11 @@
 #include "spi_context.h"
 #include "spi_esp32_spim.h"
 
+#if defined(CONFIG_SOC_SERIES_ESP32S2) && defined(CONFIG_ADC_ESP32_DMA) &&                         \
+	DT_NODE_HAS_STATUS_OKAY(DT_NODELABEL(spi3)) && DT_PROP(DT_NODELABEL(spi3), dma_enabled)
+#error "spi3 must not have dma-enabled if ADC_ESP32_DMA is enabled for ESP32-S2"
+#endif
+
 #define SPI_DMA_MAX_BUFFER_SIZE 4092
 
 #define SPI_DMA_RX 0