[PATCH v2 6/8] iio: adc: ad4030: Add SPI offload support

Marcelo Schmitt posted 8 patches 1 week, 6 days ago
There is a newer version of this series
[PATCH v2 6/8] iio: adc: ad4030: Add SPI offload support
Posted by Marcelo Schmitt 1 week, 6 days ago
AD4030 and similar ADCs can capture data at sample rates up to 2 mega
samples per second (MSPS). Not all SPI controllers are able to achieve such
high throughputs and even when the controller is fast enough to run
transfers at the required speed, it may be costly to the CPU to handle
transfer data at such high sample rates. Add SPI offload support for AD4030
and similar ADCs to enable data capture at maximum sample rates.

Co-developed-by: Sergiu Cuciurean <sergiu.cuciurean@analog.com>
Signed-off-by: Sergiu Cuciurean <sergiu.cuciurean@analog.com>
Co-developed-by: Nuno Sa <nuno.sa@analog.com>
Signed-off-by: Nuno Sa <nuno.sa@analog.com>
Co-developed-by: Trevor Gamblin <tgamblin@baylibre.com>
Signed-off-by: Trevor Gamblin <tgamblin@baylibre.com>
Co-developed-by: Axel Haslam <ahaslam@baylibre.com>
Signed-off-by: Axel Haslam <ahaslam@baylibre.com>
Signed-off-by: Marcelo Schmitt <marcelo.schmitt@analog.com>
---
Most of the code for SPI offload support is based on work from Sergiu Cuciurean,
Nuno Sa, Axel Haslam, and Trevor Gamblin. Thus, this patch comes with many
co-developed-by tags. I also draw inspiration from other drivers supporting SPI
offload, many of them written by David Lechner.

Change log v1 -> v2
- Dropped all clock-modes and DDR related stuff for now as those will require
  further changes to the SPI subsystem or to SPI controller drivers.
- Update the modes register with proper output data mode bits when sample
  averaging (oversampling_ratio) is set.
- Lock on device state mutex before updating oversampling and sampling frequency.
- Made sampling_frequency shared by all channels.
- Better checking the requested sampling frequency is valid.
- Adjusted to SPI offload data capture preparation and stop procedures.
- Error out if try to get/set sampling frequency without offload trigger.
- Depend on PWM so build always succeed.
- Drop unmatched/unbalanced call to iio_device_release_direct().
- No longer shadowing error codes.

Suggestions to v1 that I did not comply to:
[SPI]
> I would be tempted to put the loop check here [in drivers/spi/spi-offload-trigger-pwm.c]:
> 
> 	offload_offset_ns = periodic->offset_ns;
> 
> 	do {
> 		wf.offset_ns = offload_offset_ns;
> 		ret = pwm_round_waveform_might_sleep(st->pwm, &wf);
> 		if (ret)
> 			return ret;
> 		offload_offset_ns += 10;
> 
> 	} while (wf.offset_ns < periodic->offset_ns);
> 
> 	wf.duty_offset_ns = periodic->offset_ns;
> 
> instead of in the ADC driver so that all future callers don't have to
> repeat this.

Not sure implementing the PWM trigger phase approximation/rounding/setup within
spi-offload-trigger-pwm is actually desirable. The PWM phase
approximation/rounding/setup done in AD4030 iterates over the configuration of a
second PWM (the PWM connected to the CNV pin). I haven't seen any other device
that would use such double PWM setup schema so pushing an additional argument to
spi_offload_trigger_pwm_validate() doesn't seem worth it.

[IIO]
> Why using slower speed for offload?
Looks like it's the same max speed for both register access and data sample.
So, just reusing the existing define for the max transfer speed.

 drivers/iio/adc/Kconfig  |   3 +
 drivers/iio/adc/ad4030.c | 485 +++++++++++++++++++++++++++++++++++----
 2 files changed, 445 insertions(+), 43 deletions(-)

diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig
index 58a14e6833f6..2a44fcaccf54 100644
--- a/drivers/iio/adc/Kconfig
+++ b/drivers/iio/adc/Kconfig
@@ -60,8 +60,11 @@ config AD4030
 	tristate "Analog Devices AD4030 ADC Driver"
 	depends on SPI
 	depends on GPIOLIB
+	depends on PWM
 	select REGMAP
 	select IIO_BUFFER
+	select IIO_BUFFER_DMA
+	select IIO_BUFFER_DMAENGINE
 	select IIO_TRIGGERED_BUFFER
 	help
 	  Say yes here to build support for Analog Devices AD4030 and AD4630 high speed
diff --git a/drivers/iio/adc/ad4030.c b/drivers/iio/adc/ad4030.c
index aa0e27321869..52805c779934 100644
--- a/drivers/iio/adc/ad4030.c
+++ b/drivers/iio/adc/ad4030.c
@@ -14,15 +14,25 @@
  */
 
 #include <linux/bitfield.h>
+#include <linux/cleanup.h>
 #include <linux/clk.h>
+#include <linux/dmaengine.h>
+#include <linux/iio/buffer-dmaengine.h>
 #include <linux/iio/iio.h>
 #include <linux/iio/trigger_consumer.h>
 #include <linux/iio/triggered_buffer.h>
+#include <linux/limits.h>
+#include <linux/log2.h>
+#include <linux/math64.h>
+#include <linux/minmax.h>
+#include <linux/pwm.h>
 #include <linux/regmap.h>
 #include <linux/regulator/consumer.h>
+#include <linux/spi/offload/consumer.h>
 #include <linux/spi/spi.h>
 #include <linux/unaligned.h>
 #include <linux/units.h>
+#include <linux/types.h>
 
 #define AD4030_REG_INTERFACE_CONFIG_A			0x00
 #define     AD4030_REG_INTERFACE_CONFIG_A_SW_RESET	(BIT(0) | BIT(7))
@@ -111,6 +121,8 @@
 #define AD4632_TCYC_NS			2000
 #define AD4632_TCYC_ADJUSTED_NS		(AD4632_TCYC_NS - AD4030_TCNVL_NS)
 #define AD4030_TRESET_COM_DELAY_MS	750
+/* Datasheet says 9.8ns, so use the closest integer value */
+#define AD4030_TQUIET_CNV_DELAY_NS	10
 
 enum ad4030_out_mode {
 	AD4030_OUT_DATA_MD_DIFF,
@@ -136,11 +148,13 @@ struct ad4030_chip_info {
 	const char *name;
 	const unsigned long *available_masks;
 	const struct iio_chan_spec channels[AD4030_MAX_IIO_CHANNEL_NB];
+	const struct iio_chan_spec offload_channels[AD4030_MAX_IIO_CHANNEL_NB];
 	u8 grade;
 	u8 precision_bits;
 	/* Number of hardware channels */
 	int num_voltage_inputs;
 	unsigned int tcyc_ns;
+	unsigned int max_sample_rate_hz;
 };
 
 struct ad4030_state {
@@ -153,6 +167,15 @@ struct ad4030_state {
 	int offset_avail[3];
 	unsigned int avg_log2;
 	enum ad4030_out_mode mode;
+	struct mutex lock; /* Protect read-modify-write and multi write sequences */
+	/* Offload sampling */
+	struct spi_transfer offload_xfer;
+	struct spi_message offload_msg;
+	struct spi_offload *offload;
+	struct spi_offload_trigger *offload_trigger;
+	struct spi_offload_trigger_config offload_trigger_config;
+	struct pwm_device *cnv_trigger;
+	struct pwm_waveform cnv_wf;
 
 	/*
 	 * DMA (thus cache coherency maintenance) requires the transfer buffers
@@ -209,8 +232,9 @@ struct ad4030_state {
  * - voltage0-voltage1
  * - voltage2-voltage3
  */
-#define AD4030_CHAN_DIFF(_idx, _scan_type) {				\
+#define __AD4030_CHAN_DIFF(_idx, _scan_type, _offload) {		\
 	.info_mask_shared_by_all =					\
+		(_offload ? BIT(IIO_CHAN_INFO_SAMP_FREQ) : 0) |		\
 		BIT(IIO_CHAN_INFO_OVERSAMPLING_RATIO),			\
 	.info_mask_shared_by_all_available =				\
 		BIT(IIO_CHAN_INFO_OVERSAMPLING_RATIO),			\
@@ -232,6 +256,12 @@ struct ad4030_state {
 	.num_ext_scan_type = ARRAY_SIZE(_scan_type),			\
 }
 
+#define AD4030_CHAN_DIFF(_idx, _scan_type)				\
+	__AD4030_CHAN_DIFF(_idx, _scan_type, 0)
+
+#define AD4030_OFFLOAD_CHAN_DIFF(_idx, _scan_type)			\
+	__AD4030_CHAN_DIFF(_idx, _scan_type, 1)
+
 static const int ad4030_average_modes[] = {
 	BIT(0),					/* No averaging/oversampling */
 	BIT(1), BIT(2), BIT(3), BIT(4),		/* 2 to 16 */
@@ -240,6 +270,11 @@ static const int ad4030_average_modes[] = {
 	BIT(13), BIT(14), BIT(15), BIT(16),	/* 8192 to 65536 */
 };
 
+static const struct spi_offload_config ad4030_offload_config = {
+	.capability_flags = SPI_OFFLOAD_CAP_TRIGGER |
+			    SPI_OFFLOAD_CAP_RX_STREAM_DMA,
+};
+
 static int ad4030_enter_config_mode(struct ad4030_state *st)
 {
 	st->tx_data[0] = AD4030_REG_ACCESS;
@@ -453,6 +488,106 @@ static int ad4030_get_chan_calibbias(struct iio_dev *indio_dev,
 	}
 }
 
+static void ad4030_get_sampling_freq(struct ad4030_state *st, int *freq)
+{
+	struct spi_offload_trigger_config *config = &st->offload_trigger_config;
+
+	/*
+	 * Conversion data is fetched from the device when the offload transfer
+	 * is triggered. Thus, provide the SPI offload trigger frequency as the
+	 * sampling frequency.
+	 */
+	*freq = config->periodic.frequency_hz;
+}
+
+static int __ad4030_set_sampling_freq(struct ad4030_state *st,
+				      unsigned int freq, unsigned int avg_log2)
+{
+	struct spi_offload_trigger_config *config = &st->offload_trigger_config;
+	struct pwm_waveform cnv_wf = { };
+	u64 target = AD4030_TCNVH_NS;
+	u64 offload_period_ns;
+	u64 offload_offset_ns;
+	int ret;
+
+	/*
+	 * When averaging/oversampling over N samples, we fire the offload
+	 * trigger once at every N pulses of the CNV signal. Conversely, the CNV
+	 * signal needs to be N times faster than the offload trigger. Take that
+	 * into account to correctly re-evaluate both the PWM waveform connected
+	 * to CNV and the SPI offload trigger.
+	 */
+	if (st->mode == AD4030_OUT_DATA_MD_30_AVERAGED_DIFF)
+		freq <<= avg_log2;
+
+	cnv_wf.period_length_ns = DIV_ROUND_CLOSEST(NSEC_PER_SEC, freq);
+	/*
+	 * The datasheet lists a minimum time of 9.8 ns, but no maximum. If the
+	 * rounded PWM's value is less than 10, increase the target value by 10
+	 * and attempt to round the waveform again, until the value is at least
+	 * 10 ns. Use a separate variable to represent the target in case the
+	 * rounding is severe enough to keep putting the first few results under
+	 * the minimum 10ns condition checked by the while loop.
+	 */
+	do {
+		cnv_wf.duty_length_ns = target;
+		ret = pwm_round_waveform_might_sleep(st->cnv_trigger, &cnv_wf);
+		if (ret)
+			return ret;
+		target += AD4030_TCNVH_NS;
+	} while (cnv_wf.duty_length_ns < AD4030_TCNVH_NS);
+
+	if (!in_range(cnv_wf.period_length_ns, AD4030_TCYC_NS, INT_MAX))
+		return -EINVAL;
+
+	offload_period_ns = cnv_wf.period_length_ns;
+	if (st->mode == AD4030_OUT_DATA_MD_30_AVERAGED_DIFF)
+		offload_period_ns <<= avg_log2;
+
+	config->periodic.frequency_hz =  DIV_ROUND_UP_ULL(NSEC_PER_SEC,
+							  offload_period_ns);
+
+	/*
+	 * The hardware does the capture on zone 2 (when SPI trigger PWM
+	 * is used). This means that the SPI trigger signal should happen at
+	 * tsync + tquiet_con_delay being tsync the conversion signal period
+	 * and tquiet_con_delay 9.8ns. Hence set the PWM phase accordingly.
+	 *
+	 * The PWM waveform API only supports nanosecond resolution right now,
+	 * so round this setting to the closest available value.
+	 */
+	offload_offset_ns = AD4030_TQUIET_CNV_DELAY_NS;
+	do {
+		config->periodic.offset_ns = offload_offset_ns;
+		ret = spi_offload_trigger_validate(st->offload_trigger, config);
+		if (ret)
+			return ret;
+		offload_offset_ns += AD4030_TQUIET_CNV_DELAY_NS;
+	} while (config->periodic.offset_ns < AD4030_TQUIET_CNV_DELAY_NS);
+
+	st->cnv_wf = cnv_wf;
+
+	return 0;
+}
+
+static int ad4030_set_sampling_freq(struct iio_dev *indio_dev, int freq)
+{
+	struct ad4030_state *st = iio_priv(indio_dev);
+
+	/*
+	 * We have no control over the sampling frequency without SPI offload
+	 * triggering.
+	 */
+	if (!st->offload_trigger)
+		return -ENODEV;
+
+	if (!in_range(freq, 1, st->chip->max_sample_rate_hz))
+		return -EINVAL;
+
+	guard(mutex)(&st->lock);
+	return __ad4030_set_sampling_freq(st, freq, st->avg_log2);
+}
+
 static int ad4030_set_chan_calibscale(struct iio_dev *indio_dev,
 				      struct iio_chan_spec const *chan,
 				      int gain_int,
@@ -507,27 +642,6 @@ static int ad4030_set_chan_calibbias(struct iio_dev *indio_dev,
 				 st->tx_data, AD4030_REG_OFFSET_BYTES_NB);
 }
 
-static int ad4030_set_avg_frame_len(struct iio_dev *dev, int avg_val)
-{
-	struct ad4030_state *st = iio_priv(dev);
-	unsigned int avg_log2 = ilog2(avg_val);
-	unsigned int last_avg_idx = ARRAY_SIZE(ad4030_average_modes) - 1;
-	int ret;
-
-	if (avg_val < 0 || avg_val > ad4030_average_modes[last_avg_idx])
-		return -EINVAL;
-
-	ret = regmap_write(st->regmap, AD4030_REG_AVG,
-			   AD4030_REG_AVG_MASK_AVG_SYNC |
-			   FIELD_PREP(AD4030_REG_AVG_MASK_AVG_VAL, avg_log2));
-	if (ret)
-		return ret;
-
-	st->avg_log2 = avg_log2;
-
-	return 0;
-}
-
 static bool ad4030_is_common_byte_asked(struct ad4030_state *st,
 					unsigned int mask)
 {
@@ -536,11 +650,10 @@ static bool ad4030_is_common_byte_asked(struct ad4030_state *st,
 		AD4030_DUAL_COMMON_BYTE_CHANNELS_MASK);
 }
 
-static int ad4030_set_mode(struct iio_dev *indio_dev, unsigned long mask)
+static int ad4030_set_mode(struct ad4030_state *st, unsigned long mask,
+			   unsigned int avg_log2)
 {
-	struct ad4030_state *st = iio_priv(indio_dev);
-
-	if (st->avg_log2 > 0) {
+	if (avg_log2 > 0) {
 		st->mode = AD4030_OUT_DATA_MD_30_AVERAGED_DIFF;
 	} else if (ad4030_is_common_byte_asked(st, mask)) {
 		switch (st->chip->precision_bits) {
@@ -564,6 +677,50 @@ static int ad4030_set_mode(struct iio_dev *indio_dev, unsigned long mask)
 				  st->mode);
 }
 
+static int ad4030_set_avg_frame_len(struct iio_dev *dev, unsigned long mask, int avg_val)
+{
+	struct ad4030_state *st = iio_priv(dev);
+	unsigned int avg_log2 = ilog2(avg_val);
+	unsigned int last_avg_idx = ARRAY_SIZE(ad4030_average_modes) - 1;
+	int freq;
+	int ret;
+
+	if (avg_val < 0 || avg_val > ad4030_average_modes[last_avg_idx])
+		return -EINVAL;
+
+	guard(mutex)(&st->lock);
+	ret = ad4030_set_mode(st, mask, avg_log2);
+	if (ret)
+		return ret;
+
+	if (st->offload_trigger) {
+		/*
+		 * The sample averaging and sampling frequency configurations
+		 * are mutually dependent one from another. That's because the
+		 * effective data sample rate is fCNV / 2^N, where N is the
+		 * number of samples being averaged.
+		 *
+		 * When SPI offload is supported and we have control over the
+		 * sample rate, the conversion start signal (CNV) and the SPI
+		 * offload trigger frequencies must be re-evaluated so data is
+		 * fetched only after 'avg_val' conversions.
+		 */
+		ad4030_get_sampling_freq(st, &freq);
+		ret = __ad4030_set_sampling_freq(st, freq, avg_log2);
+		if (ret)
+			return ret;
+	}
+
+	ret = regmap_write(st->regmap, AD4030_REG_AVG,
+			   AD4030_REG_AVG_MASK_AVG_SYNC |
+			   FIELD_PREP(AD4030_REG_AVG_MASK_AVG_VAL, avg_log2));
+	if (ret)
+		return ret;
+
+	st->avg_log2 = avg_log2;
+	return 0;
+}
+
 /*
  * Descramble 2 32bits numbers out of a 64bits. The bits are interleaved:
  * 1 bit for first number, 1 bit for the second, and so on...
@@ -672,7 +829,7 @@ static int ad4030_single_conversion(struct iio_dev *indio_dev,
 	struct ad4030_state *st = iio_priv(indio_dev);
 	int ret;
 
-	ret = ad4030_set_mode(indio_dev, BIT(chan->scan_index));
+	ret = ad4030_set_mode(st, BIT(chan->scan_index), st->avg_log2);
 	if (ret)
 		return ret;
 
@@ -769,6 +926,13 @@ static int ad4030_read_raw_dispatch(struct iio_dev *indio_dev,
 		*val = BIT(st->avg_log2);
 		return IIO_VAL_INT;
 
+	case IIO_CHAN_INFO_SAMP_FREQ:
+		if (!st->offload_trigger)
+			return -ENODEV;
+
+		ad4030_get_sampling_freq(st, val);
+		return IIO_VAL_INT;
+
 	default:
 		return -EINVAL;
 	}
@@ -807,7 +971,10 @@ static int ad4030_write_raw_dispatch(struct iio_dev *indio_dev,
 		return ad4030_set_chan_calibbias(indio_dev, chan, val);
 
 	case IIO_CHAN_INFO_OVERSAMPLING_RATIO:
-		return ad4030_set_avg_frame_len(indio_dev, val);
+		return ad4030_set_avg_frame_len(indio_dev, BIT(chan->scan_index), val);
+
+	case IIO_CHAN_INFO_SAMP_FREQ:
+		return ad4030_set_sampling_freq(indio_dev, val);
 
 	default:
 		return -EINVAL;
@@ -869,7 +1036,9 @@ static int ad4030_get_current_scan_type(const struct iio_dev *indio_dev,
 static int ad4030_update_scan_mode(struct iio_dev *indio_dev,
 				   const unsigned long *scan_mask)
 {
-	return ad4030_set_mode(indio_dev, *scan_mask);
+	struct ad4030_state *st = iio_priv(indio_dev);
+
+	return ad4030_set_mode(st, *scan_mask, st->avg_log2);
 }
 
 static const struct iio_info ad4030_iio_info = {
@@ -898,6 +1067,88 @@ static const struct iio_buffer_setup_ops ad4030_buffer_setup_ops = {
 	.validate_scan_mask = ad4030_validate_scan_mask,
 };
 
+static void ad4030_prepare_offload_msg(struct iio_dev *indio_dev)
+{
+	struct ad4030_state *st = iio_priv(indio_dev);
+	u8 offload_bpw;
+
+	if (st->mode == AD4030_OUT_DATA_MD_30_AVERAGED_DIFF)
+		offload_bpw = 32;
+	else
+		offload_bpw = st->chip->precision_bits;
+
+	st->offload_xfer.speed_hz = AD4030_SPI_MAX_REG_XFER_SPEED;
+	st->offload_xfer.bits_per_word = roundup_pow_of_two(offload_bpw);
+	st->offload_xfer.len = spi_bpw_to_bytes(offload_bpw);
+	st->offload_xfer.offload_flags = SPI_OFFLOAD_XFER_RX_STREAM;
+	spi_message_init_with_transfers(&st->offload_msg, &st->offload_xfer, 1);
+}
+
+static int ad4030_offload_buffer_postenable(struct iio_dev *indio_dev)
+{
+	struct ad4030_state *st = iio_priv(indio_dev);
+	int ret;
+
+	ret = regmap_write(st->regmap, AD4030_REG_EXIT_CFG_MODE, BIT(0));
+	if (ret)
+		return ret;
+
+	ad4030_prepare_offload_msg(indio_dev);
+	st->offload_msg.offload = st->offload;
+	ret = spi_optimize_message(st->spi, &st->offload_msg);
+	if (ret)
+		goto out_reset_mode;
+
+	ret = pwm_set_waveform_might_sleep(st->cnv_trigger, &st->cnv_wf, false);
+	if (ret)
+		goto out_unoptimize;
+
+	ret = spi_offload_trigger_enable(st->offload, st->offload_trigger,
+					 &st->offload_trigger_config);
+	if (ret)
+		goto out_pwm_disable;
+
+	return 0;
+
+out_pwm_disable:
+	pwm_disable(st->cnv_trigger);
+out_unoptimize:
+	spi_unoptimize_message(&st->offload_msg);
+out_reset_mode:
+	/* reenter register configuration mode */
+	ret = ad4030_enter_config_mode(st);
+	if (ret)
+		dev_err(&st->spi->dev,
+			"couldn't reenter register configuration mode\n");
+	return ret;
+}
+
+static int ad4030_offload_buffer_predisable(struct iio_dev *indio_dev)
+{
+	struct ad4030_state *st = iio_priv(indio_dev);
+	int ret;
+
+	spi_offload_trigger_disable(st->offload, st->offload_trigger);
+
+	pwm_disable(st->cnv_trigger);
+
+	spi_unoptimize_message(&st->offload_msg);
+
+	/* reenter register configuration mode */
+	ret = ad4030_enter_config_mode(st);
+	if (ret)
+		dev_err(&st->spi->dev,
+			"couldn't reenter register configuration mode\n");
+
+	return ret;
+}
+
+static const struct iio_buffer_setup_ops ad4030_offload_buffer_setup_ops = {
+	.postenable = &ad4030_offload_buffer_postenable,
+	.predisable = &ad4030_offload_buffer_predisable,
+	.validate_scan_mask = ad4030_validate_scan_mask,
+};
+
 static int ad4030_regulators_get(struct ad4030_state *st)
 {
 	struct device *dev = &st->spi->dev;
@@ -967,6 +1218,24 @@ static int ad4030_detect_chip_info(const struct ad4030_state *st)
 	return 0;
 }
 
+static int ad4030_pwm_get(struct ad4030_state *st)
+{
+	struct device *dev = &st->spi->dev;
+
+	st->cnv_trigger = devm_pwm_get(dev, NULL);
+	if (IS_ERR(st->cnv_trigger))
+		return dev_err_probe(dev, PTR_ERR(st->cnv_trigger),
+				     "Failed to get CNV PWM\n");
+
+	/*
+	 * Preemptively disable the PWM, since we only want to enable it with
+	 * the buffer.
+	 */
+	pwm_disable(st->cnv_trigger);
+
+	return 0;
+}
+
 static int ad4030_config(struct ad4030_state *st)
 {
 	int ret;
@@ -994,6 +1263,31 @@ static int ad4030_config(struct ad4030_state *st)
 	return 0;
 }
 
+static int ad4030_spi_offload_setup(struct iio_dev *indio_dev,
+				    struct ad4030_state *st)
+{
+	struct device *dev = &st->spi->dev;
+	struct dma_chan *rx_dma;
+
+	indio_dev->setup_ops = &ad4030_offload_buffer_setup_ops;
+
+	st->offload_trigger = devm_spi_offload_trigger_get(dev, st->offload,
+							   SPI_OFFLOAD_TRIGGER_PERIODIC);
+	if (IS_ERR(st->offload_trigger))
+		return dev_err_probe(dev, PTR_ERR(st->offload_trigger),
+				     "failed to get offload trigger\n");
+
+	st->offload_trigger_config.type = SPI_OFFLOAD_TRIGGER_PERIODIC;
+
+	rx_dma = devm_spi_offload_rx_stream_request_dma_chan(dev, st->offload);
+	if (IS_ERR(rx_dma))
+		return dev_err_probe(dev, PTR_ERR(rx_dma),
+				     "failed to get offload RX DMA\n");
+
+	return devm_iio_dmaengine_buffer_setup_with_handle(dev, indio_dev, rx_dma,
+							   IIO_BUFFER_DIRECTION_IN);
+}
+
 static int ad4030_probe(struct spi_device *spi)
 {
 	struct device *dev = &spi->dev;
@@ -1018,6 +1312,10 @@ static int ad4030_probe(struct spi_device *spi)
 	if (!st->chip)
 		return -EINVAL;
 
+	ret = devm_mutex_init(dev, &st->lock);
+	if (ret)
+		return ret;
+
 	ret = ad4030_regulators_get(st);
 	if (ret)
 		return ret;
@@ -1045,24 +1343,57 @@ static int ad4030_probe(struct spi_device *spi)
 		return dev_err_probe(dev, PTR_ERR(st->cnv_gpio),
 				     "Failed to get cnv gpio\n");
 
-	/*
-	 * One hardware channel is split in two software channels when using
-	 * common byte mode. Add one more channel for the timestamp.
-	 */
-	indio_dev->num_channels = 2 * st->chip->num_voltage_inputs + 1;
 	indio_dev->name = st->chip->name;
 	indio_dev->modes = INDIO_DIRECT_MODE;
 	indio_dev->info = &ad4030_iio_info;
-	indio_dev->channels = st->chip->channels;
-	indio_dev->available_scan_masks = st->chip->available_masks;
 
-	ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
-					      iio_pollfunc_store_time,
-					      ad4030_trigger_handler,
-					      &ad4030_buffer_setup_ops);
-	if (ret)
-		return dev_err_probe(dev, ret,
-				     "Failed to setup triggered buffer\n");
+	st->offload = devm_spi_offload_get(dev, spi, &ad4030_offload_config);
+	ret = PTR_ERR_OR_ZERO(st->offload);
+	if (ret && ret != -ENODEV)
+		return dev_err_probe(dev, ret, "failed to get offload\n");
+
+	/* Fall back to low speed usage when no SPI offload is available. */
+	if (ret == -ENODEV) {
+		/*
+		 * One hardware channel is split in two software channels when
+		 * using common byte mode. Add one more channel for the timestamp.
+		 */
+		indio_dev->num_channels = 2 * st->chip->num_voltage_inputs + 1;
+		indio_dev->channels = st->chip->channels;
+		indio_dev->available_scan_masks = st->chip->available_masks;
+
+		ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
+						      iio_pollfunc_store_time,
+						      ad4030_trigger_handler,
+						      &ad4030_buffer_setup_ops);
+		if (ret)
+			return dev_err_probe(dev, ret,
+					     "Failed to setup triggered buffer\n");
+	} else {
+		/*
+		 * One hardware channel is split in two software channels when
+		 * using common byte mode. Offloaded SPI transfers can't support
+		 * software timestamp so no additional timestamp channel is added.
+		 */
+		indio_dev->num_channels = 2 * st->chip->num_voltage_inputs;
+		indio_dev->channels = st->chip->offload_channels;
+		indio_dev->available_scan_masks = st->chip->available_masks;
+		ret = ad4030_spi_offload_setup(indio_dev, st);
+		if (ret)
+			return dev_err_probe(dev, ret,
+					     "Failed to setup SPI offload\n");
+
+		ret = ad4030_pwm_get(st);
+		if (ret)
+			return dev_err_probe(&spi->dev, ret,
+					     "Failed to get PWM: %d\n", ret);
+
+		ret = __ad4030_set_sampling_freq(st, st->chip->max_sample_rate_hz,
+						 st->avg_log2);
+		if (ret)
+			return dev_err_probe(&spi->dev, ret,
+					     "Failed to set offload samp freq\n");
+	}
 
 	return devm_iio_device_register(dev, indio_dev);
 }
@@ -1100,6 +1431,23 @@ static const struct iio_scan_type ad4030_24_scan_types[] = {
 	},
 };
 
+static const struct iio_scan_type ad4030_24_offload_scan_types[] = {
+	[AD4030_SCAN_TYPE_NORMAL] = {
+		.sign = 's',
+		.storagebits = 32,
+		.realbits = 24,
+		.shift = 0,
+		.endianness = IIO_CPU,
+	},
+	[AD4030_SCAN_TYPE_AVG] = {
+		.sign = 's',
+		.storagebits = 32,
+		.realbits = 30,
+		.shift = 2,
+		.endianness = IIO_CPU,
+	},
+};
+
 static const struct iio_scan_type ad4030_16_scan_types[] = {
 	[AD4030_SCAN_TYPE_NORMAL] = {
 		.sign = 's',
@@ -1117,6 +1465,23 @@ static const struct iio_scan_type ad4030_16_scan_types[] = {
 	}
 };
 
+static const struct iio_scan_type ad4030_16_offload_scan_types[] = {
+	[AD4030_SCAN_TYPE_NORMAL] = {
+		.sign = 's',
+		.storagebits = 32,
+		.realbits = 16,
+		.shift = 0,
+		.endianness = IIO_CPU,
+	},
+	[AD4030_SCAN_TYPE_AVG] = {
+		.sign = 's',
+		.storagebits = 32,
+		.realbits = 30,
+		.shift = 2,
+		.endianness = IIO_CPU,
+	},
+};
+
 static const struct ad4030_chip_info ad4030_24_chip_info = {
 	.name = "ad4030-24",
 	.available_masks = ad4030_channel_masks,
@@ -1125,10 +1490,15 @@ static const struct ad4030_chip_info ad4030_24_chip_info = {
 		AD4030_CHAN_CMO(1, 0),
 		IIO_CHAN_SOFT_TIMESTAMP(2),
 	},
+	.offload_channels = {
+		AD4030_OFFLOAD_CHAN_DIFF(0, ad4030_24_offload_scan_types),
+		AD4030_CHAN_CMO(1, 0),
+	},
 	.grade = AD4030_REG_CHIP_GRADE_AD4030_24_GRADE,
 	.precision_bits = 24,
 	.num_voltage_inputs = 1,
 	.tcyc_ns = AD4030_TCYC_ADJUSTED_NS,
+	.max_sample_rate_hz = 2 * HZ_PER_MHZ,
 };
 
 static const struct ad4030_chip_info ad4630_16_chip_info = {
@@ -1141,10 +1511,17 @@ static const struct ad4030_chip_info ad4630_16_chip_info = {
 		AD4030_CHAN_CMO(3, 1),
 		IIO_CHAN_SOFT_TIMESTAMP(4),
 	},
+	.offload_channels = {
+		AD4030_OFFLOAD_CHAN_DIFF(0, ad4030_16_offload_scan_types),
+		AD4030_OFFLOAD_CHAN_DIFF(1, ad4030_16_offload_scan_types),
+		AD4030_CHAN_CMO(2, 0),
+		AD4030_CHAN_CMO(3, 1),
+	},
 	.grade = AD4030_REG_CHIP_GRADE_AD4630_16_GRADE,
 	.precision_bits = 16,
 	.num_voltage_inputs = 2,
 	.tcyc_ns = AD4030_TCYC_ADJUSTED_NS,
+	.max_sample_rate_hz = 2 * HZ_PER_MHZ,
 };
 
 static const struct ad4030_chip_info ad4630_24_chip_info = {
@@ -1157,10 +1534,17 @@ static const struct ad4030_chip_info ad4630_24_chip_info = {
 		AD4030_CHAN_CMO(3, 1),
 		IIO_CHAN_SOFT_TIMESTAMP(4),
 	},
+	.offload_channels = {
+		AD4030_OFFLOAD_CHAN_DIFF(0, ad4030_24_offload_scan_types),
+		AD4030_OFFLOAD_CHAN_DIFF(1, ad4030_24_offload_scan_types),
+		AD4030_CHAN_CMO(2, 0),
+		AD4030_CHAN_CMO(3, 1),
+	},
 	.grade = AD4030_REG_CHIP_GRADE_AD4630_24_GRADE,
 	.precision_bits = 24,
 	.num_voltage_inputs = 2,
 	.tcyc_ns = AD4030_TCYC_ADJUSTED_NS,
+	.max_sample_rate_hz = 2 * HZ_PER_MHZ,
 };
 
 static const struct ad4030_chip_info ad4632_16_chip_info = {
@@ -1173,10 +1557,17 @@ static const struct ad4030_chip_info ad4632_16_chip_info = {
 		AD4030_CHAN_CMO(3, 1),
 		IIO_CHAN_SOFT_TIMESTAMP(4),
 	},
+	.offload_channels = {
+		AD4030_OFFLOAD_CHAN_DIFF(0, ad4030_16_offload_scan_types),
+		AD4030_OFFLOAD_CHAN_DIFF(1, ad4030_16_offload_scan_types),
+		AD4030_CHAN_CMO(2, 0),
+		AD4030_CHAN_CMO(3, 1),
+	},
 	.grade = AD4030_REG_CHIP_GRADE_AD4632_16_GRADE,
 	.precision_bits = 16,
 	.num_voltage_inputs = 2,
 	.tcyc_ns = AD4632_TCYC_ADJUSTED_NS,
+	.max_sample_rate_hz = 500 * HZ_PER_KHZ,
 };
 
 static const struct ad4030_chip_info ad4632_24_chip_info = {
@@ -1189,10 +1580,17 @@ static const struct ad4030_chip_info ad4632_24_chip_info = {
 		AD4030_CHAN_CMO(3, 1),
 		IIO_CHAN_SOFT_TIMESTAMP(4),
 	},
+	.offload_channels = {
+		AD4030_OFFLOAD_CHAN_DIFF(0, ad4030_24_offload_scan_types),
+		AD4030_OFFLOAD_CHAN_DIFF(1, ad4030_24_offload_scan_types),
+		AD4030_CHAN_CMO(2, 0),
+		AD4030_CHAN_CMO(3, 1),
+	},
 	.grade = AD4030_REG_CHIP_GRADE_AD4632_24_GRADE,
 	.precision_bits = 24,
 	.num_voltage_inputs = 2,
 	.tcyc_ns = AD4632_TCYC_ADJUSTED_NS,
+	.max_sample_rate_hz = 500 * HZ_PER_KHZ,
 };
 
 static const struct spi_device_id ad4030_id_table[] = {
@@ -1228,3 +1626,4 @@ module_spi_driver(ad4030_driver);
 MODULE_AUTHOR("Esteban Blanc <eblanc@baylibre.com>");
 MODULE_DESCRIPTION("Analog Devices AD4630 ADC family driver");
 MODULE_LICENSE("GPL");
+MODULE_IMPORT_NS("IIO_DMAENGINE_BUFFER");
-- 
2.50.1
Re: [PATCH v2 6/8] iio: adc: ad4030: Add SPI offload support
Posted by David Lechner 1 week, 2 days ago
On 9/18/25 12:39 PM, Marcelo Schmitt wrote:
> AD4030 and similar ADCs can capture data at sample rates up to 2 mega
> samples per second (MSPS). Not all SPI controllers are able to achieve such
> high throughputs and even when the controller is fast enough to run
> transfers at the required speed, it may be costly to the CPU to handle
> transfer data at such high sample rates. Add SPI offload support for AD4030
> and similar ADCs to enable data capture at maximum sample rates.

I tried testing this with AD4630-24 but didn't have luck in actually
capturing data. I'm 100% sure the problem is with the FPGA. And the
evaluation board doesn't have any place to attach a logic analyzer for
debugging. That means that I wasn't able to reliabably test this code
yet. But I don't expect my problems to be solved any time soon, so I
don't want to let that hold up progress. I would have really liked to
have been able to see the actual timings over the wire to make sure
we got all of that correct.

> 
> Co-developed-by: Sergiu Cuciurean <sergiu.cuciurean@analog.com>
> Signed-off-by: Sergiu Cuciurean <sergiu.cuciurean@analog.com>
> Co-developed-by: Nuno Sa <nuno.sa@analog.com>
> Signed-off-by: Nuno Sa <nuno.sa@analog.com>
> Co-developed-by: Trevor Gamblin <tgamblin@baylibre.com>
> Signed-off-by: Trevor Gamblin <tgamblin@baylibre.com>
> Co-developed-by: Axel Haslam <ahaslam@baylibre.com>
> Signed-off-by: Axel Haslam <ahaslam@baylibre.com>
> Signed-off-by: Marcelo Schmitt <marcelo.schmitt@analog.com>
> ---
> Most of the code for SPI offload support is based on work from Sergiu Cuciurean,
> Nuno Sa, Axel Haslam, and Trevor Gamblin. Thus, this patch comes with many
> co-developed-by tags. I also draw inspiration from other drivers supporting SPI
> offload, many of them written by David Lechner.
> 
> Change log v1 -> v2
> - Dropped all clock-modes and DDR related stuff for now as those will require
>   further changes to the SPI subsystem or to SPI controller drivers.
> - Update the modes register with proper output data mode bits when sample
>   averaging (oversampling_ratio) is set.
> - Lock on device state mutex before updating oversampling and sampling frequency.
> - Made sampling_frequency shared by all channels.
> - Better checking the requested sampling frequency is valid.
> - Adjusted to SPI offload data capture preparation and stop procedures.
> - Error out if try to get/set sampling frequency without offload trigger.
> - Depend on PWM so build always succeed.
> - Drop unmatched/unbalanced call to iio_device_release_direct().
> - No longer shadowing error codes.
> 
> Suggestions to v1 that I did not comply to:
> [SPI]
>> I would be tempted to put the loop check here [in drivers/spi/spi-offload-trigger-pwm.c]:
>>
>> 	offload_offset_ns = periodic->offset_ns;
>>
>> 	do {
>> 		wf.offset_ns = offload_offset_ns;
>> 		ret = pwm_round_waveform_might_sleep(st->pwm, &wf);
>> 		if (ret)
>> 			return ret;
>> 		offload_offset_ns += 10;
>>
>> 	} while (wf.offset_ns < periodic->offset_ns);
>>
>> 	wf.duty_offset_ns = periodic->offset_ns;
>>
>> instead of in the ADC driver so that all future callers don't have to
>> repeat this.
> 
> Not sure implementing the PWM trigger phase approximation/rounding/setup within
> spi-offload-trigger-pwm is actually desirable. The PWM phase
> approximation/rounding/setup done in AD4030 iterates over the configuration of a
> second PWM (the PWM connected to the CNV pin). I haven't seen any other device
> that would use such double PWM setup schema so pushing an additional argument to
> spi_offload_trigger_pwm_validate() doesn't seem worth it.

I think you are right that spi_offload_trigger_pwm_validate() is not the
correct place for this. If we end up repeating this code a lot, we can
make a helper function for it in a place that makes sense at that time.

> 
> [IIO]
>> Why using slower speed for offload?
> Looks like it's the same max speed for both register access and data sample.
> So, just reusing the existing define for the max transfer speed.

I don't follow. The "REG" in AD4030_SPI_MAX_REG_XFER_SPEED stands for
"register". The actual max speed for reading sample data should be coming
from the devicetree since it is faster and depends on the wiring and VIO
voltage. It could be as much as 102 MHz.

Unrelated to this series, I still think 80 MHz is faster that it needs
to be for AD4030_SPI_MAX_REG_XFER_SPEED. It is fine to do them slower,
e.g. at 10 MHz to reduce the risk of errors and also makes it easier to
debug using a logic analyzer.

> 
>  drivers/iio/adc/Kconfig  |   3 +
>  drivers/iio/adc/ad4030.c | 485 +++++++++++++++++++++++++++++++++++----
>  2 files changed, 445 insertions(+), 43 deletions(-)
> 
> diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig
> index 58a14e6833f6..2a44fcaccf54 100644
> --- a/drivers/iio/adc/Kconfig
> +++ b/drivers/iio/adc/Kconfig
> @@ -60,8 +60,11 @@ config AD4030
>  	tristate "Analog Devices AD4030 ADC Driver"
>  	depends on SPI
>  	depends on GPIOLIB
> +	depends on PWM

PWM is currently only required when using offload, so not a strict depedency.

>  	select REGMAP
>  	select IIO_BUFFER
> +	select IIO_BUFFER_DMA
> +	select IIO_BUFFER_DMAENGINE
>  	select IIO_TRIGGERED_BUFFER
>  	help
>  	  Say yes here to build support for Analog Devices AD4030 and AD4630 high speed
> diff --git a/drivers/iio/adc/ad4030.c b/drivers/iio/adc/ad4030.c
> index aa0e27321869..52805c779934 100644
> --- a/drivers/iio/adc/ad4030.c
> +++ b/drivers/iio/adc/ad4030.c
> @@ -14,15 +14,25 @@
>   */
>  
>  #include <linux/bitfield.h>
> +#include <linux/cleanup.h>
>  #include <linux/clk.h>
> +#include <linux/dmaengine.h>
> +#include <linux/iio/buffer-dmaengine.h>
>  #include <linux/iio/iio.h>
>  #include <linux/iio/trigger_consumer.h>
>  #include <linux/iio/triggered_buffer.h>
> +#include <linux/limits.h>
> +#include <linux/log2.h>
> +#include <linux/math64.h>
> +#include <linux/minmax.h>
> +#include <linux/pwm.h>
>  #include <linux/regmap.h>
>  #include <linux/regulator/consumer.h>
> +#include <linux/spi/offload/consumer.h>
>  #include <linux/spi/spi.h>
>  #include <linux/unaligned.h>
>  #include <linux/units.h>
> +#include <linux/types.h>
>  
>  #define AD4030_REG_INTERFACE_CONFIG_A			0x00
>  #define     AD4030_REG_INTERFACE_CONFIG_A_SW_RESET	(BIT(0) | BIT(7))
> @@ -111,6 +121,8 @@
>  #define AD4632_TCYC_NS			2000
>  #define AD4632_TCYC_ADJUSTED_NS		(AD4632_TCYC_NS - AD4030_TCNVL_NS)
>  #define AD4030_TRESET_COM_DELAY_MS	750
> +/* Datasheet says 9.8ns, so use the closest integer value */
> +#define AD4030_TQUIET_CNV_DELAY_NS	10
>  
>  enum ad4030_out_mode {
>  	AD4030_OUT_DATA_MD_DIFF,
> @@ -136,11 +148,13 @@ struct ad4030_chip_info {
>  	const char *name;
>  	const unsigned long *available_masks;
>  	const struct iio_chan_spec channels[AD4030_MAX_IIO_CHANNEL_NB];
> +	const struct iio_chan_spec offload_channels[AD4030_MAX_IIO_CHANNEL_NB];
>  	u8 grade;
>  	u8 precision_bits;
>  	/* Number of hardware channels */
>  	int num_voltage_inputs;
>  	unsigned int tcyc_ns;
> +	unsigned int max_sample_rate_hz;
>  };
>  
>  struct ad4030_state {
> @@ -153,6 +167,15 @@ struct ad4030_state {
>  	int offset_avail[3];
>  	unsigned int avg_log2;
>  	enum ad4030_out_mode mode;
> +	struct mutex lock; /* Protect read-modify-write and multi write sequences */
> +	/* Offload sampling */
> +	struct spi_transfer offload_xfer;
> +	struct spi_message offload_msg;
> +	struct spi_offload *offload;
> +	struct spi_offload_trigger *offload_trigger;
> +	struct spi_offload_trigger_config offload_trigger_config;
> +	struct pwm_device *cnv_trigger;
> +	struct pwm_waveform cnv_wf;
>  
>  	/*
>  	 * DMA (thus cache coherency maintenance) requires the transfer buffers
> @@ -209,8 +232,9 @@ struct ad4030_state {
>   * - voltage0-voltage1
>   * - voltage2-voltage3
>   */
> -#define AD4030_CHAN_DIFF(_idx, _scan_type) {				\
> +#define __AD4030_CHAN_DIFF(_idx, _scan_type, _offload) {		\
>  	.info_mask_shared_by_all =					\
> +		(_offload ? BIT(IIO_CHAN_INFO_SAMP_FREQ) : 0) |		\
>  		BIT(IIO_CHAN_INFO_OVERSAMPLING_RATIO),			\
>  	.info_mask_shared_by_all_available =				\
>  		BIT(IIO_CHAN_INFO_OVERSAMPLING_RATIO),			\
> @@ -232,6 +256,12 @@ struct ad4030_state {
>  	.num_ext_scan_type = ARRAY_SIZE(_scan_type),			\
>  }
>  
> +#define AD4030_CHAN_DIFF(_idx, _scan_type)				\
> +	__AD4030_CHAN_DIFF(_idx, _scan_type, 0)
> +
> +#define AD4030_OFFLOAD_CHAN_DIFF(_idx, _scan_type)			\
> +	__AD4030_CHAN_DIFF(_idx, _scan_type, 1)
> +
>  static const int ad4030_average_modes[] = {
>  	BIT(0),					/* No averaging/oversampling */
>  	BIT(1), BIT(2), BIT(3), BIT(4),		/* 2 to 16 */
> @@ -240,6 +270,11 @@ static const int ad4030_average_modes[] = {
>  	BIT(13), BIT(14), BIT(15), BIT(16),	/* 8192 to 65536 */
>  };
>  
> +static const struct spi_offload_config ad4030_offload_config = {
> +	.capability_flags = SPI_OFFLOAD_CAP_TRIGGER |
> +			    SPI_OFFLOAD_CAP_RX_STREAM_DMA,
> +};
> +
>  static int ad4030_enter_config_mode(struct ad4030_state *st)
>  {
>  	st->tx_data[0] = AD4030_REG_ACCESS;
> @@ -453,6 +488,106 @@ static int ad4030_get_chan_calibbias(struct iio_dev *indio_dev,
>  	}
>  }
>  
> +static void ad4030_get_sampling_freq(struct ad4030_state *st, int *freq)
> +{
> +	struct spi_offload_trigger_config *config = &st->offload_trigger_config;
> +
> +	/*
> +	 * Conversion data is fetched from the device when the offload transfer
> +	 * is triggered. Thus, provide the SPI offload trigger frequency as the
> +	 * sampling frequency.
> +	 */
> +	*freq = config->periodic.frequency_hz;
> +}
> +
> +static int __ad4030_set_sampling_freq(struct ad4030_state *st,
> +				      unsigned int freq, unsigned int avg_log2)

This has more to do with the converstion trigger frequency (when CNV is
toggled) that it does with sample rate (when we read sample data). When
oversampling is in use, the conversion rate is higher than the sample rate.
So I would be tempted to call this function ad4030_update_conversion_rate().

> +{
> +	struct spi_offload_trigger_config *config = &st->offload_trigger_config;
> +	struct pwm_waveform cnv_wf = { };
> +	u64 target = AD4030_TCNVH_NS;
> +	u64 offload_period_ns;
> +	u64 offload_offset_ns;
> +	int ret;
> +
> +	/*
> +	 * When averaging/oversampling over N samples, we fire the offload
> +	 * trigger once at every N pulses of the CNV signal. Conversely, the CNV
> +	 * signal needs to be N times faster than the offload trigger. Take that
> +	 * into account to correctly re-evaluate both the PWM waveform connected
> +	 * to CNV and the SPI offload trigger.
> +	 */
> +	if (st->mode == AD4030_OUT_DATA_MD_30_AVERAGED_DIFF)

I think we could drop the condition here. If oversampling is disabled (oversampling
ratio == 1) then avg_log2 should be 0. st->mode may be left in a different state
from a single conversion, so can't be relied upon to decide if oversampling is
enabled or not.

> +		freq <<= avg_log2;
> +
> +	cnv_wf.period_length_ns = DIV_ROUND_CLOSEST(NSEC_PER_SEC, freq);
> +	/*
> +	 * The datasheet lists a minimum time of 9.8 ns, but no maximum. If the
> +	 * rounded PWM's value is less than 10, increase the target value by 10
> +	 * and attempt to round the waveform again, until the value is at least
> +	 * 10 ns. Use a separate variable to represent the target in case the
> +	 * rounding is severe enough to keep putting the first few results under
> +	 * the minimum 10ns condition checked by the while loop.
> +	 */
> +	do {
> +		cnv_wf.duty_length_ns = target;
> +		ret = pwm_round_waveform_might_sleep(st->cnv_trigger, &cnv_wf);
> +		if (ret)
> +			return ret;
> +		target += AD4030_TCNVH_NS;
> +	} while (cnv_wf.duty_length_ns < AD4030_TCNVH_NS);
> +
> +	if (!in_range(cnv_wf.period_length_ns, AD4030_TCYC_NS, INT_MAX))
> +		return -EINVAL;

I hit this error during testing with the default max_sample_rate_hz assigned
in probe. We could have a loop for this too to try to get the closest valid
period rather than erroring if the exact value isn't available.

> +
> +	offload_period_ns = cnv_wf.period_length_ns;
> +	if (st->mode == AD4030_OUT_DATA_MD_30_AVERAGED_DIFF)

Same as above about dropping this condition.

> +		offload_period_ns <<= avg_log2;
> +
> +	config->periodic.frequency_hz =  DIV_ROUND_UP_ULL(NSEC_PER_SEC,
> +							  offload_period_ns);
> +
> +	/*
> +	 * The hardware does the capture on zone 2 (when SPI trigger PWM
> +	 * is used). This means that the SPI trigger signal should happen at
> +	 * tsync + tquiet_con_delay being tsync the conversion signal period
> +	 * and tquiet_con_delay 9.8ns. Hence set the PWM phase accordingly.
> +	 *
> +	 * The PWM waveform API only supports nanosecond resolution right now,
> +	 * so round this setting to the closest available value.
> +	 */
> +	offload_offset_ns = AD4030_TQUIET_CNV_DELAY_NS;
> +	do {
> +		config->periodic.offset_ns = offload_offset_ns;
> +		ret = spi_offload_trigger_validate(st->offload_trigger, config);
> +		if (ret)
> +			return ret;
> +		offload_offset_ns += AD4030_TQUIET_CNV_DELAY_NS;
> +	} while (config->periodic.offset_ns < AD4030_TQUIET_CNV_DELAY_NS);
> +
> +	st->cnv_wf = cnv_wf;
> +
> +	return 0;
> +}
> +
> +static int ad4030_set_sampling_freq(struct iio_dev *indio_dev, int freq)
> +{
> +	struct ad4030_state *st = iio_priv(indio_dev);
> +
> +	/*
> +	 * We have no control over the sampling frequency without SPI offload
> +	 * triggering.
> +	 */
> +	if (!st->offload_trigger)
> +		return -ENODEV;
> +
> +	if (!in_range(freq, 1, st->chip->max_sample_rate_hz))
> +		return -EINVAL;
> +
> +	guard(mutex)(&st->lock);

Why not iio_device_claim_direct() instead of a new lock? We wouldn't
want to change the sampling frequency during a buffered read anyway.
This driver already uses iio_device_claim_direct() to protect other
register access.

> +	return __ad4030_set_sampling_freq(st, freq, st->avg_log2);
> +}
> +
>  static int ad4030_set_chan_calibscale(struct iio_dev *indio_dev,
>  				      struct iio_chan_spec const *chan,
>  				      int gain_int,
> @@ -507,27 +642,6 @@ static int ad4030_set_chan_calibbias(struct iio_dev *indio_dev,
>  				 st->tx_data, AD4030_REG_OFFSET_BYTES_NB);
>  }
>  
> -static int ad4030_set_avg_frame_len(struct iio_dev *dev, int avg_val)
> -{
> -	struct ad4030_state *st = iio_priv(dev);
> -	unsigned int avg_log2 = ilog2(avg_val);
> -	unsigned int last_avg_idx = ARRAY_SIZE(ad4030_average_modes) - 1;
> -	int ret;
> -
> -	if (avg_val < 0 || avg_val > ad4030_average_modes[last_avg_idx])
> -		return -EINVAL;
> -
> -	ret = regmap_write(st->regmap, AD4030_REG_AVG,
> -			   AD4030_REG_AVG_MASK_AVG_SYNC |
> -			   FIELD_PREP(AD4030_REG_AVG_MASK_AVG_VAL, avg_log2));
> -	if (ret)
> -		return ret;
> -
> -	st->avg_log2 = avg_log2;
> -
> -	return 0;
> -}
> -
>  static bool ad4030_is_common_byte_asked(struct ad4030_state *st,
>  					unsigned int mask)
>  {
> @@ -536,11 +650,10 @@ static bool ad4030_is_common_byte_asked(struct ad4030_state *st,
>  		AD4030_DUAL_COMMON_BYTE_CHANNELS_MASK);
>  }
>  
> -static int ad4030_set_mode(struct iio_dev *indio_dev, unsigned long mask)
> +static int ad4030_set_mode(struct ad4030_state *st, unsigned long mask,
> +			   unsigned int avg_log2)
>  {
> -	struct ad4030_state *st = iio_priv(indio_dev);
> -
> -	if (st->avg_log2 > 0) {
> +	if (avg_log2 > 0) {
>  		st->mode = AD4030_OUT_DATA_MD_30_AVERAGED_DIFF;
>  	} else if (ad4030_is_common_byte_asked(st, mask)) {
>  		switch (st->chip->precision_bits) {
> @@ -564,6 +677,50 @@ static int ad4030_set_mode(struct iio_dev *indio_dev, unsigned long mask)
>  				  st->mode);
>  }
>  
> +static int ad4030_set_avg_frame_len(struct iio_dev *dev, unsigned long mask, int avg_val)
> +{
> +	struct ad4030_state *st = iio_priv(dev);
> +	unsigned int avg_log2 = ilog2(avg_val);
> +	unsigned int last_avg_idx = ARRAY_SIZE(ad4030_average_modes) - 1;
> +	int freq;
> +	int ret;
> +
> +	if (avg_val < 0 || avg_val > ad4030_average_modes[last_avg_idx])
> +		return -EINVAL;
> +
> +	guard(mutex)(&st->lock);
> +	ret = ad4030_set_mode(st, mask, avg_log2);

Not sure it makes sense to set the mode here. The mode gets set again anyway
(possibly with a different mask) just before doing a single conversion or when
starting a buffered read. So this doesn't really have any useful effect AFAICT.

> +	if (ret)
> +		return ret;
> +
> +	if (st->offload_trigger) {
> +		/*
> +		 * The sample averaging and sampling frequency configurations
> +		 * are mutually dependent one from another. That's because the
> +		 * effective data sample rate is fCNV / 2^N, where N is the
> +		 * number of samples being averaged.
> +		 *
> +		 * When SPI offload is supported and we have control over the
> +		 * sample rate, the conversion start signal (CNV) and the SPI
> +		 * offload trigger frequencies must be re-evaluated so data is
> +		 * fetched only after 'avg_val' conversions.
> +		 */
> +		ad4030_get_sampling_freq(st, &freq);
> +		ret = __ad4030_set_sampling_freq(st, freq, avg_log2);

This looks a bit strange to "get" the sample rate and then "set" it to the
same value we just got. This is what inspired the suggestion to reanme
 __ad4030_set_sampling_freq().

> +		if (ret)
> +			return ret;
> +	}
> +
> +	ret = regmap_write(st->regmap, AD4030_REG_AVG,
> +			   AD4030_REG_AVG_MASK_AVG_SYNC |
> +			   FIELD_PREP(AD4030_REG_AVG_MASK_AVG_VAL, avg_log2));
> +	if (ret)
> +		return ret;
> +
> +	st->avg_log2 = avg_log2;
> +	return 0;
> +}
> +
>  /*
>   * Descramble 2 32bits numbers out of a 64bits. The bits are interleaved:
>   * 1 bit for first number, 1 bit for the second, and so on...
> @@ -672,7 +829,7 @@ static int ad4030_single_conversion(struct iio_dev *indio_dev,
>  	struct ad4030_state *st = iio_priv(indio_dev);
>  	int ret;
>  
> -	ret = ad4030_set_mode(indio_dev, BIT(chan->scan_index));
> +	ret = ad4030_set_mode(st, BIT(chan->scan_index), st->avg_log2);
>  	if (ret)
>  		return ret;
>  
> @@ -769,6 +926,13 @@ static int ad4030_read_raw_dispatch(struct iio_dev *indio_dev,
>  		*val = BIT(st->avg_log2);
>  		return IIO_VAL_INT;
>  
> +	case IIO_CHAN_INFO_SAMP_FREQ:
> +		if (!st->offload_trigger)
> +			return -ENODEV;
> +
> +		ad4030_get_sampling_freq(st, val);
> +		return IIO_VAL_INT;
> +
>  	default:
>  		return -EINVAL;
>  	}
> @@ -807,7 +971,10 @@ static int ad4030_write_raw_dispatch(struct iio_dev *indio_dev,
>  		return ad4030_set_chan_calibbias(indio_dev, chan, val);
>  
>  	case IIO_CHAN_INFO_OVERSAMPLING_RATIO:
> -		return ad4030_set_avg_frame_len(indio_dev, val);
> +		return ad4030_set_avg_frame_len(indio_dev, BIT(chan->scan_index), val);
> +
> +	case IIO_CHAN_INFO_SAMP_FREQ:
> +		return ad4030_set_sampling_freq(indio_dev, val);
>  
>  	default:
>  		return -EINVAL;
> @@ -869,7 +1036,9 @@ static int ad4030_get_current_scan_type(const struct iio_dev *indio_dev,
>  static int ad4030_update_scan_mode(struct iio_dev *indio_dev,
>  				   const unsigned long *scan_mask)
>  {
> -	return ad4030_set_mode(indio_dev, *scan_mask);
> +	struct ad4030_state *st = iio_priv(indio_dev);
> +
> +	return ad4030_set_mode(st, *scan_mask, st->avg_log2);
>  }
>  
>  static const struct iio_info ad4030_iio_info = {
> @@ -898,6 +1067,88 @@ static const struct iio_buffer_setup_ops ad4030_buffer_setup_ops = {
>  	.validate_scan_mask = ad4030_validate_scan_mask,
>  };
>  
> +static void ad4030_prepare_offload_msg(struct iio_dev *indio_dev)
> +{
> +	struct ad4030_state *st = iio_priv(indio_dev);
> +	u8 offload_bpw;
> +
> +	if (st->mode == AD4030_OUT_DATA_MD_30_AVERAGED_DIFF)
> +		offload_bpw = 32;
> +	else
> +		offload_bpw = st->chip->precision_bits;
> +

> +	st->offload_xfer.speed_hz = AD4030_SPI_MAX_REG_XFER_SPEED;

As mentioned at the beginning, drop this line and let it use the max
speed from the devicetree.

> +	st->offload_xfer.bits_per_word = roundup_pow_of_two(offload_bpw);

Why roundup_pow_of_two()? The SPI controller can do 24 bits per word.
And if we are reading both a 24-bit value and the common mode voltage,
this would cause both to be read in 1 word.

Speaking of which, I think this will need a possible second xfer with
bpw=8 if we want to read the common mode voltage.

Or, if the intention was to not allow it, we need different scan masks.
But I don't see a reason why we could not allow it.

Or, if this is making a assumptions about extra hardware being present
to move bits around between reading them over the SPI bus and pushing the
values to DMA, then there should be some comments about that. More on that
below.

> +	st->offload_xfer.len = spi_bpw_to_bytes(offload_bpw);
> +	st->offload_xfer.offload_flags = SPI_OFFLOAD_XFER_RX_STREAM;
> +	spi_message_init_with_transfers(&st->offload_msg, &st->offload_xfer, 1);
> +}
> +
> +static int ad4030_offload_buffer_postenable(struct iio_dev *indio_dev)
> +{
> +	struct ad4030_state *st = iio_priv(indio_dev);
> +	int ret;
> +
> +	ret = regmap_write(st->regmap, AD4030_REG_EXIT_CFG_MODE, BIT(0));
> +	if (ret)
> +		return ret;
> +
> +	ad4030_prepare_offload_msg(indio_dev);
> +	st->offload_msg.offload = st->offload;
> +	ret = spi_optimize_message(st->spi, &st->offload_msg);
> +	if (ret)
> +		goto out_reset_mode;
> +
> +	ret = pwm_set_waveform_might_sleep(st->cnv_trigger, &st->cnv_wf, false);
> +	if (ret)
> +		goto out_unoptimize;
> +
> +	ret = spi_offload_trigger_enable(st->offload, st->offload_trigger,
> +					 &st->offload_trigger_config);
> +	if (ret)
> +		goto out_pwm_disable;
> +
> +	return 0;
> +
> +out_pwm_disable:
> +	pwm_disable(st->cnv_trigger);
> +out_unoptimize:
> +	spi_unoptimize_message(&st->offload_msg);
> +out_reset_mode:
> +	/* reenter register configuration mode */
> +	ret = ad4030_enter_config_mode(st);

This overwrites the original error in `ret` and could result in the function
returning sucessfully when it should have returned an error. To fix, we can
introduce a ret2 variable for checking the return value while unwinding after
an error (and should print ret2 in the dev_err(), otherwise that info gets
lost).

> +	if (ret)
> +		dev_err(&st->spi->dev,
> +			"couldn't reenter register configuration mode\n");
> +	return ret;
> +}
> +
> +static int ad4030_offload_buffer_predisable(struct iio_dev *indio_dev)
> +{
> +	struct ad4030_state *st = iio_priv(indio_dev);
> +	int ret;
> +
> +	spi_offload_trigger_disable(st->offload, st->offload_trigger);
> +
> +	pwm_disable(st->cnv_trigger);
> +
> +	spi_unoptimize_message(&st->offload_msg);
> +
> +	/* reenter register configuration mode */
> +	ret = ad4030_enter_config_mode(st);
> +	if (ret)
> +		dev_err(&st->spi->dev,
> +			"couldn't reenter register configuration mode\n");
> +
> +	return ret;
> +}
> +
> +static const struct iio_buffer_setup_ops ad4030_offload_buffer_setup_ops = {
> +	.postenable = &ad4030_offload_buffer_postenable,
> +	.predisable = &ad4030_offload_buffer_predisable,
> +	.validate_scan_mask = ad4030_validate_scan_mask,
> +};
> +
>  static int ad4030_regulators_get(struct ad4030_state *st)
>  {
>  	struct device *dev = &st->spi->dev;
> @@ -967,6 +1218,24 @@ static int ad4030_detect_chip_info(const struct ad4030_state *st)
>  	return 0;
>  }
>  
> +static int ad4030_pwm_get(struct ad4030_state *st)
> +{
> +	struct device *dev = &st->spi->dev;
> +
> +	st->cnv_trigger = devm_pwm_get(dev, NULL);
> +	if (IS_ERR(st->cnv_trigger))
> +		return dev_err_probe(dev, PTR_ERR(st->cnv_trigger),
> +				     "Failed to get CNV PWM\n");
> +
> +	/*
> +	 * Preemptively disable the PWM, since we only want to enable it with
> +	 * the buffer.
> +	 */
> +	pwm_disable(st->cnv_trigger);
> +
> +	return 0;
> +}
> +
>  static int ad4030_config(struct ad4030_state *st)
>  {
>  	int ret;
> @@ -994,6 +1263,31 @@ static int ad4030_config(struct ad4030_state *st)
>  	return 0;
>  }
>  
> +static int ad4030_spi_offload_setup(struct iio_dev *indio_dev,
> +				    struct ad4030_state *st)
> +{
> +	struct device *dev = &st->spi->dev;
> +	struct dma_chan *rx_dma;
> +
> +	indio_dev->setup_ops = &ad4030_offload_buffer_setup_ops;
> +
> +	st->offload_trigger = devm_spi_offload_trigger_get(dev, st->offload,
> +							   SPI_OFFLOAD_TRIGGER_PERIODIC);
> +	if (IS_ERR(st->offload_trigger))
> +		return dev_err_probe(dev, PTR_ERR(st->offload_trigger),
> +				     "failed to get offload trigger\n");
> +
> +	st->offload_trigger_config.type = SPI_OFFLOAD_TRIGGER_PERIODIC;

If we want to be really strict/generic here, we should not be allowing
chips with num_voltage_inputs == 2 and a single SPI bus/deserializer (i.e.
channel data is interleaved). In this case, extra hardware is required
to do the de-interleaving (i.e. the spi_axis_reorder IP block).

We could take the easy way out and just always assume that is there.
In that case, we should makes some comments here about such assumptions.

Or we could actually describe it properly in the devicetree and check
for that here. This came up during the discussions when I was upstreaming
SPI offload support. It would look something like this...

In the devicetree, instead of having the DMA connected to the SPI controller,
we now have a separate IP block with it's own node between them.

/* spi_axis_reorder IP block */
reorder: offload-stream-sink@4000000 {
	compatible = "adi,axi-spi-reorder";
	reg = <0x4000000 0x1000>;
	clocks = <&spi_clk>;
	dmas = <&adc_dma>;
};

spi@5000000 {
	compatible = "adi,axi-spi-engine-1.00.a
	reg = <0x4000000 0x1000>;
	clocks = <&clkc 15>, <&spi_clk>;
	clock-name "s_axi_aclk", "spi_clk";

	trigger-sources = <&pwm_trigger>;
	offload-streams = <&reorder>;
	offload-stream-names = "offload0-rx";

	...
};

Then here in the driver, we would need a different (non-existing)
API to get the DMA from this offload-stream rather than calling
devm_spi_offload_rx_stream_request_dma_chan(). Or extend the SPI
controller to handle that.

Or 3rd option: If easy way is not acceptable and "right way" is too much
work, we could just return error here for num_voltage_inputs == 2 until
we add support for SPI controllers with two buses/deserializers.

> +
> +	rx_dma = devm_spi_offload_rx_stream_request_dma_chan(dev, st->offload);
> +	if (IS_ERR(rx_dma))
> +		return dev_err_probe(dev, PTR_ERR(rx_dma),
> +				     "failed to get offload RX DMA\n");
> +
> +	return devm_iio_dmaengine_buffer_setup_with_handle(dev, indio_dev, rx_dma,
> +							   IIO_BUFFER_DIRECTION_IN);
> +}
> +
>  static int ad4030_probe(struct spi_device *spi)
>  {
>  	struct device *dev = &spi->dev;
> @@ -1018,6 +1312,10 @@ static int ad4030_probe(struct spi_device *spi)
>  	if (!st->chip)
>  		return -EINVAL;
>  
> +	ret = devm_mutex_init(dev, &st->lock);
> +	if (ret)
> +		return ret;
> +
>  	ret = ad4030_regulators_get(st);
>  	if (ret)
>  		return ret;
> @@ -1045,24 +1343,57 @@ static int ad4030_probe(struct spi_device *spi)
>  		return dev_err_probe(dev, PTR_ERR(st->cnv_gpio),
>  				     "Failed to get cnv gpio\n");
>  
> -	/*
> -	 * One hardware channel is split in two software channels when using
> -	 * common byte mode. Add one more channel for the timestamp.
> -	 */
> -	indio_dev->num_channels = 2 * st->chip->num_voltage_inputs + 1;
>  	indio_dev->name = st->chip->name;
>  	indio_dev->modes = INDIO_DIRECT_MODE;
>  	indio_dev->info = &ad4030_iio_info;
> -	indio_dev->channels = st->chip->channels;
> -	indio_dev->available_scan_masks = st->chip->available_masks;
>  
> -	ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
> -					      iio_pollfunc_store_time,
> -					      ad4030_trigger_handler,
> -					      &ad4030_buffer_setup_ops);
> -	if (ret)
> -		return dev_err_probe(dev, ret,
> -				     "Failed to setup triggered buffer\n");
> +	st->offload = devm_spi_offload_get(dev, spi, &ad4030_offload_config);
> +	ret = PTR_ERR_OR_ZERO(st->offload);
> +	if (ret && ret != -ENODEV)
> +		return dev_err_probe(dev, ret, "failed to get offload\n");
> +
> +	/* Fall back to low speed usage when no SPI offload is available. */
> +	if (ret == -ENODEV) {
> +		/*
> +		 * One hardware channel is split in two software channels when
> +		 * using common byte mode. Add one more channel for the timestamp.
> +		 */
> +		indio_dev->num_channels = 2 * st->chip->num_voltage_inputs + 1;
> +		indio_dev->channels = st->chip->channels;
> +		indio_dev->available_scan_masks = st->chip->available_masks;
> +
> +		ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
> +						      iio_pollfunc_store_time,
> +						      ad4030_trigger_handler,
> +						      &ad4030_buffer_setup_ops);
> +		if (ret)
> +			return dev_err_probe(dev, ret,
> +					     "Failed to setup triggered buffer\n");
> +	} else {
> +		/*
> +		 * One hardware channel is split in two software channels when
> +		 * using common byte mode. Offloaded SPI transfers can't support
> +		 * software timestamp so no additional timestamp channel is added.
> +		 */
> +		indio_dev->num_channels = 2 * st->chip->num_voltage_inputs;
> +		indio_dev->channels = st->chip->offload_channels;
> +		indio_dev->available_scan_masks = st->chip->available_masks;

It looks like scan_masks are the same in both cases, so we could leave that
outside of the if statement.

> +		ret = ad4030_spi_offload_setup(indio_dev, st);
> +		if (ret)
> +			return dev_err_probe(dev, ret,
> +					     "Failed to setup SPI offload\n");
> +
> +		ret = ad4030_pwm_get(st);
> +		if (ret)
> +			return dev_err_probe(&spi->dev, ret,
> +					     "Failed to get PWM: %d\n", ret);
> +
> +		ret = __ad4030_set_sampling_freq(st, st->chip->max_sample_rate_hz,

Max sample rate probably isn't the best choice for a default since it only works
under very specific conditions. In another driver, we picked a rate that would
still work even if we maxed out the oversampling ratio and had only one serial
line. As mentioned above, the driver failed to probe for me because of this and
I had to change the inital rate.

> +						 st->avg_log2);
> +		if (ret)
> +			return dev_err_probe(&spi->dev, ret,
> +					     "Failed to set offload samp freq\n");
> +	}
>  
>  	return devm_iio_device_register(dev, indio_dev);
>  }
Re: [PATCH v2 6/8] iio: adc: ad4030: Add SPI offload support
Posted by Marcelo Schmitt 1 week, 1 day ago
Hi David, thanks for the insightful review.

On 09/22, David Lechner wrote:
> On 9/18/25 12:39 PM, Marcelo Schmitt wrote:
> > AD4030 and similar ADCs can capture data at sample rates up to 2 mega
> > samples per second (MSPS). Not all SPI controllers are able to achieve such
> > high throughputs and even when the controller is fast enough to run
> > transfers at the required speed, it may be costly to the CPU to handle
> > transfer data at such high sample rates. Add SPI offload support for AD4030
> > and similar ADCs to enable data capture at maximum sample rates.
> 
> I tried testing this with AD4630-24 but didn't have luck in actually
> capturing data. I'm 100% sure the problem is with the FPGA. And the
> evaluation board doesn't have any place to attach a logic analyzer for
> debugging. That means that I wasn't able to reliabably test this code
> yet. But I don't expect my problems to be solved any time soon, so I
> don't want to let that hold up progress. I would have really liked to
> have been able to see the actual timings over the wire to make sure
> we got all of that correct.
> 
Even if you hook up probes to the SPI lines, you might not be able to logic
analyze the transfers at frequencies like 100 MHz or even at 80 MHz unless you
have a very fast logic analyzer or oscilloscope. To debug these signals we
usually change the HDL verilog to add ILA debug cores to record the signals on
the FPGA. I'll see if I can get or build the project with those ILA cores set.
Another thing is getting the correct combination of HDL + device tree because
we have a few possible HDL build configurations (for number of lanes, clock mode,
DDR/DTR, and capture zone) and the device tree must be coherent with what runs
on the FPGA. I'll send you some of boot files I was using during my tests.

> > ---
...
> > [IIO]
> >> Why using slower speed for offload?
> > Looks like it's the same max speed for both register access and data sample.
> > So, just reusing the existing define for the max transfer speed.
> 
> I don't follow. The "REG" in AD4030_SPI_MAX_REG_XFER_SPEED stands for
> "register". The actual max speed for reading sample data should be coming
> from the devicetree since it is faster and depends on the wiring and VIO
> voltage. It could be as much as 102 MHz.
> 
I have finally I noticed the SPI compatible mode timings. Sure, will adapt to
use faster sample rate when possible.


> Unrelated to this series, I still think 80 MHz is faster that it needs
> to be for AD4030_SPI_MAX_REG_XFER_SPEED. It is fine to do them slower,
> e.g. at 10 MHz to reduce the risk of errors and also makes it easier to
> debug using a logic analyzer.

Sure, will do that.

> 
> > 
> >  drivers/iio/adc/Kconfig  |   3 +
> >  drivers/iio/adc/ad4030.c | 485 +++++++++++++++++++++++++++++++++++----
> >  2 files changed, 445 insertions(+), 43 deletions(-)
> > 
> > diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig
> > index 58a14e6833f6..2a44fcaccf54 100644
...
> > +	cnv_wf.period_length_ns = DIV_ROUND_CLOSEST(NSEC_PER_SEC, freq);
> > +	/*
> > +	 * The datasheet lists a minimum time of 9.8 ns, but no maximum. If the
> > +	 * rounded PWM's value is less than 10, increase the target value by 10
> > +	 * and attempt to round the waveform again, until the value is at least
> > +	 * 10 ns. Use a separate variable to represent the target in case the
> > +	 * rounding is severe enough to keep putting the first few results under
> > +	 * the minimum 10ns condition checked by the while loop.
> > +	 */
> > +	do {
> > +		cnv_wf.duty_length_ns = target;
> > +		ret = pwm_round_waveform_might_sleep(st->cnv_trigger, &cnv_wf);
> > +		if (ret)
> > +			return ret;
> > +		target += AD4030_TCNVH_NS;
> > +	} while (cnv_wf.duty_length_ns < AD4030_TCNVH_NS);
> > +
> > +	if (!in_range(cnv_wf.period_length_ns, AD4030_TCYC_NS, INT_MAX))
> > +		return -EINVAL;
> 
> I hit this error during testing with the default max_sample_rate_hz assigned
> in probe. We could have a loop for this too to try to get the closest valid
> period rather than erroring if the exact value isn't available.
> 
Yes, this makes sense. Though, looping to try to get a suitable period wouldn't
potentially also change the duty_length we settled above?

> > +
> > +	offload_period_ns = cnv_wf.period_length_ns;
> > +	if (st->mode == AD4030_OUT_DATA_MD_30_AVERAGED_DIFF)
> 
...
> > +static int ad4030_set_sampling_freq(struct iio_dev *indio_dev, int freq)
> > +{
> > +	struct ad4030_state *st = iio_priv(indio_dev);
> > +
> > +	/*
> > +	 * We have no control over the sampling frequency without SPI offload
> > +	 * triggering.
> > +	 */
> > +	if (!st->offload_trigger)
> > +		return -ENODEV;
> > +
> > +	if (!in_range(freq, 1, st->chip->max_sample_rate_hz))
> > +		return -EINVAL;
> > +
> > +	guard(mutex)(&st->lock);
> 
> Why not iio_device_claim_direct() instead of a new lock? We wouldn't
> want to change the sampling frequency during a buffered read anyway.
> This driver already uses iio_device_claim_direct() to protect other
> register access.

The new lock is to protect concurrent updates of the oversampling and sampling
frequency. Since, oversampling and the sampling frequency properties are
mutually dependent one from another, a simultaneous write to those attributes
could lead to an invalid oversamp + samp freq configuration.

> 
> > +	return __ad4030_set_sampling_freq(st, freq, st->avg_log2);
> > +}
> > +
...
> > +static void ad4030_prepare_offload_msg(struct iio_dev *indio_dev)
> > +{
> > +	struct ad4030_state *st = iio_priv(indio_dev);
> > +	u8 offload_bpw;
> > +
> > +	if (st->mode == AD4030_OUT_DATA_MD_30_AVERAGED_DIFF)
> > +		offload_bpw = 32;
> > +	else
> > +		offload_bpw = st->chip->precision_bits;
> > +
> 
> > +	st->offload_xfer.speed_hz = AD4030_SPI_MAX_REG_XFER_SPEED;
> 
> As mentioned at the beginning, drop this line and let it use the max
> speed from the devicetree.
> 
> > +	st->offload_xfer.bits_per_word = roundup_pow_of_two(offload_bpw);
> 
> Why roundup_pow_of_two()? The SPI controller can do 24 bits per word.
> And if we are reading both a 24-bit value and the common mode voltage,
> this would cause both to be read in 1 word.
> 
> Speaking of which, I think this will need a possible second xfer with
> bpw=8 if we want to read the common mode voltage.
> 
> Or, if the intention was to not allow it, we need different scan masks.
> But I don't see a reason why we could not allow it.
> 
Nothing says we couldn't support offloading transfers with
differential + common-mode data, at least in theory. So, I didn't felt like it
should be prevented. Though, offloading differential + common-mode data is
a configuration I couldn't really test with ADAQ4216 because the HDL is ... peculiar.


> Or, if this is making a assumptions about extra hardware being present
> to move bits around between reading them over the SPI bus and pushing the
> values to DMA, then there should be some comments about that. More on that
> below.
> 
> > +	st->offload_xfer.len = spi_bpw_to_bytes(offload_bpw);
> > +	st->offload_xfer.offload_flags = SPI_OFFLOAD_XFER_RX_STREAM;
> > +	spi_message_init_with_transfers(&st->offload_msg, &st->offload_xfer, 1);
> > +}
> > +
...
> > +static int ad4030_spi_offload_setup(struct iio_dev *indio_dev,
> > +				    struct ad4030_state *st)
> > +{
> > +	struct device *dev = &st->spi->dev;
> > +	struct dma_chan *rx_dma;
> > +
> > +	indio_dev->setup_ops = &ad4030_offload_buffer_setup_ops;
> > +
> > +	st->offload_trigger = devm_spi_offload_trigger_get(dev, st->offload,
> > +							   SPI_OFFLOAD_TRIGGER_PERIODIC);
> > +	if (IS_ERR(st->offload_trigger))
> > +		return dev_err_probe(dev, PTR_ERR(st->offload_trigger),
> > +				     "failed to get offload trigger\n");
> > +
> > +	st->offload_trigger_config.type = SPI_OFFLOAD_TRIGGER_PERIODIC;
> 
> If we want to be really strict/generic here, we should not be allowing
> chips with num_voltage_inputs == 2 and a single SPI bus/deserializer (i.e.
> channel data is interleaved). In this case, extra hardware is required
> to do the de-interleaving (i.e. the spi_axis_reorder IP block).

By channel data is interleaved you mean data from both channels going out on
SDO0 (LANE_MD == 0b11)? In that case, yes, I think so. Only the ADC driver would
know about data being interleaved and it would not be able to descramble it when
data gets pushed up through DMA.

> 
> We could take the easy way out and just always assume that is there.
> In that case, we should makes some comments here about such assumptions.
> 
> Or we could actually describe it properly in the devicetree and check
> for that here. This came up during the discussions when I was upstreaming
> SPI offload support. It would look something like this...
> 
> In the devicetree, instead of having the DMA connected to the SPI controller,
> we now have a separate IP block with it's own node between them.
> 
> /* spi_axis_reorder IP block */
> reorder: offload-stream-sink@4000000 {
> 	compatible = "adi,axi-spi-reorder";
> 	reg = <0x4000000 0x1000>;
> 	clocks = <&spi_clk>;
> 	dmas = <&adc_dma>;
> };
> 
> spi@5000000 {
> 	compatible = "adi,axi-spi-engine-1.00.a
> 	reg = <0x4000000 0x1000>;
> 	clocks = <&clkc 15>, <&spi_clk>;
> 	clock-name "s_axi_aclk", "spi_clk";
> 
> 	trigger-sources = <&pwm_trigger>;
> 	offload-streams = <&reorder>;
> 	offload-stream-names = "offload0-rx";
> 
> 	...
> };
> 
> Then here in the driver, we would need a different (non-existing)
> API to get the DMA from this offload-stream rather than calling
> devm_spi_offload_rx_stream_request_dma_chan(). Or extend the SPI
> controller to handle that.
> 
> Or 3rd option: If easy way is not acceptable and "right way" is too much
> work, we could just return error here for num_voltage_inputs == 2 until
> we add support for SPI controllers with two buses/deserializers.
> 
3rd option sounds more reasonable for the moment.
I think this might, alternatively, be supported as something associated with
spi-rx/tx-bus-width dt property. The question we seem to be trying to answer is,
how data coming from a multi-line bus is expected to be delivered?


> > +
> > +	rx_dma = devm_spi_offload_rx_stream_request_dma_chan(dev, st->offload);
> > +	if (IS_ERR(rx_dma))
> > +		return dev_err_probe(dev, PTR_ERR(rx_dma),
> > +				     "failed to get offload RX DMA\n");
> > +
> > +	return devm_iio_dmaengine_buffer_setup_with_handle(dev, indio_dev, rx_dma,
> > +							   IIO_BUFFER_DIRECTION_IN);
> > +}
> > +

Thanks,
Marcelo
Re: [PATCH v2 6/8] iio: adc: ad4030: Add SPI offload support
Posted by David Lechner 1 week, 1 day ago
On 9/23/25 10:27 AM, Marcelo Schmitt wrote:
> Hi David, thanks for the insightful review.
> 
> On 09/22, David Lechner wrote:
>> On 9/18/25 12:39 PM, Marcelo Schmitt wrote:

...

>>> +	cnv_wf.period_length_ns = DIV_ROUND_CLOSEST(NSEC_PER_SEC, freq);
>>> +	/*
>>> +	 * The datasheet lists a minimum time of 9.8 ns, but no maximum. If the
>>> +	 * rounded PWM's value is less than 10, increase the target value by 10
>>> +	 * and attempt to round the waveform again, until the value is at least
>>> +	 * 10 ns. Use a separate variable to represent the target in case the
>>> +	 * rounding is severe enough to keep putting the first few results under
>>> +	 * the minimum 10ns condition checked by the while loop.
>>> +	 */
>>> +	do {
>>> +		cnv_wf.duty_length_ns = target;
>>> +		ret = pwm_round_waveform_might_sleep(st->cnv_trigger, &cnv_wf);
>>> +		if (ret)
>>> +			return ret;
>>> +		target += AD4030_TCNVH_NS;
>>> +	} while (cnv_wf.duty_length_ns < AD4030_TCNVH_NS);
>>> +
>>> +	if (!in_range(cnv_wf.period_length_ns, AD4030_TCYC_NS, INT_MAX))
>>> +		return -EINVAL;
>>
>> I hit this error during testing with the default max_sample_rate_hz assigned
>> in probe. We could have a loop for this too to try to get the closest valid
>> period rather than erroring if the exact value isn't available.
>>
> Yes, this makes sense. Though, looping to try to get a suitable period wouldn't
> potentially also change the duty_length we settled above?

I didn't think too hard about it or debug too deep. So it might be fine the
way it is. We'll just want to make sure that when testing with a 2 MSPS part
that we can get the max sample rate without error. The ZedBoard has some funny
rounding due to clocks being divided by 3, so it could just be a case of
having to to put in 1.998 MHz to actually get 2 MHz or something like
that because of the lack of accuracy due to rounding.

> 
>>> +
>>> +	offload_period_ns = cnv_wf.period_length_ns;
>>> +	if (st->mode == AD4030_OUT_DATA_MD_30_AVERAGED_DIFF)
>>
> ...
>>> +static int ad4030_set_sampling_freq(struct iio_dev *indio_dev, int freq)
>>> +{
>>> +	struct ad4030_state *st = iio_priv(indio_dev);
>>> +
>>> +	/*
>>> +	 * We have no control over the sampling frequency without SPI offload
>>> +	 * triggering.
>>> +	 */
>>> +	if (!st->offload_trigger)
>>> +		return -ENODEV;
>>> +
>>> +	if (!in_range(freq, 1, st->chip->max_sample_rate_hz))
>>> +		return -EINVAL;
>>> +
>>> +	guard(mutex)(&st->lock);
>>
>> Why not iio_device_claim_direct() instead of a new lock? We wouldn't
>> want to change the sampling frequency during a buffered read anyway.
>> This driver already uses iio_device_claim_direct() to protect other
>> register access.
> 
> The new lock is to protect concurrent updates of the oversampling and sampling
> frequency. Since, oversampling and the sampling frequency properties are
> mutually dependent one from another, a simultaneous write to those attributes
> could lead to an invalid oversamp + samp freq configuration.

I understand the need for the protection. And using iio_device_claim_direct()
seems like it could do the job without the need for an additional lock.
Re: [PATCH v2 6/8] iio: adc: ad4030: Add SPI offload support
Posted by Nuno Sá 1 week, 6 days ago
On Thu, 2025-09-18 at 14:39 -0300, Marcelo Schmitt wrote:
> AD4030 and similar ADCs can capture data at sample rates up to 2 mega
> samples per second (MSPS). Not all SPI controllers are able to achieve such
> high throughputs and even when the controller is fast enough to run
> transfers at the required speed, it may be costly to the CPU to handle
> transfer data at such high sample rates. Add SPI offload support for AD4030
> and similar ADCs to enable data capture at maximum sample rates.
> 
> Co-developed-by: Sergiu Cuciurean <sergiu.cuciurean@analog.com>
> Signed-off-by: Sergiu Cuciurean <sergiu.cuciurean@analog.com>
> Co-developed-by: Nuno Sa <nuno.sa@analog.com>
> Signed-off-by: Nuno Sa <nuno.sa@analog.com>
> Co-developed-by: Trevor Gamblin <tgamblin@baylibre.com>
> Signed-off-by: Trevor Gamblin <tgamblin@baylibre.com>
> Co-developed-by: Axel Haslam <ahaslam@baylibre.com>
> Signed-off-by: Axel Haslam <ahaslam@baylibre.com>
> Signed-off-by: Marcelo Schmitt <marcelo.schmitt@analog.com>
> ---
> Most of the code for SPI offload support is based on work from Sergiu
> Cuciurean,
> Nuno Sa, Axel Haslam, and Trevor Gamblin. Thus, this patch comes with many
> co-developed-by tags. I also draw inspiration from other drivers supporting
> SPI
> offload, many of them written by David Lechner.

As far as I'm concerned, you can drop me (and I guess Sergiu) of the list. The
support I added was for the legacy offload support we had in ADI tree which was
very different from what we have today. Ditto for the PWM waveform API. So I
don't think it makes sense for me to take credit for this one :)

- Nuno Sá
> 
> Change log v1 -> v2
> - Dropped all clock-modes and DDR related stuff for now as those will require
>   further changes to the SPI subsystem or to SPI controller drivers.
> - Update the modes register with proper output data mode bits when sample
>   averaging (oversampling_ratio) is set.
> - Lock on device state mutex before updating oversampling and sampling
> frequency.
> - Made sampling_frequency shared by all channels.
> - Better checking the requested sampling frequency is valid.
> - Adjusted to SPI offload data capture preparation and stop procedures.
> - Error out if try to get/set sampling frequency without offload trigger.
> - Depend on PWM so build always succeed.
> - Drop unmatched/unbalanced call to iio_device_release_direct().
> - No longer shadowing error codes.
> 
> Suggestions to v1 that I did not comply to:
> [SPI]
> > I would be tempted to put the loop check here [in drivers/spi/spi-offload-
> > trigger-pwm.c]:
> > 
> > 	offload_offset_ns = periodic->offset_ns;
> > 
> > 	do {
> > 		wf.offset_ns = offload_offset_ns;
> > 		ret = pwm_round_waveform_might_sleep(st->pwm, &wf);
> > 		if (ret)
> > 			return ret;
> > 		offload_offset_ns += 10;
> > 
> > 	} while (wf.offset_ns < periodic->offset_ns);
> > 
> > 	wf.duty_offset_ns = periodic->offset_ns;
> > 
> > instead of in the ADC driver so that all future callers don't have to
> > repeat this.
> 
> Not sure implementing the PWM trigger phase approximation/rounding/setup
> within
> spi-offload-trigger-pwm is actually desirable. The PWM phase
> approximation/rounding/setup done in AD4030 iterates over the configuration of
> a
> second PWM (the PWM connected to the CNV pin). I haven't seen any other device
> that would use such double PWM setup schema so pushing an additional argument
> to
> spi_offload_trigger_pwm_validate() doesn't seem worth it.
> 
> [IIO]
> > Why using slower speed for offload?
> Looks like it's the same max speed for both register access and data sample.
> So, just reusing the existing define for the max transfer speed.
> 
>  drivers/iio/adc/Kconfig  |   3 +
>  drivers/iio/adc/ad4030.c | 485 +++++++++++++++++++++++++++++++++++----
>  2 files changed, 445 insertions(+), 43 deletions(-)
> 
> diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig
> index 58a14e6833f6..2a44fcaccf54 100644
> --- a/drivers/iio/adc/Kconfig
> +++ b/drivers/iio/adc/Kconfig
> @@ -60,8 +60,11 @@ config AD4030
>  	tristate "Analog Devices AD4030 ADC Driver"
>  	depends on SPI
>  	depends on GPIOLIB
> +	depends on PWM
>  	select REGMAP
>  	select IIO_BUFFER
> +	select IIO_BUFFER_DMA
> +	select IIO_BUFFER_DMAENGINE
>  	select IIO_TRIGGERED_BUFFER
>  	help
>  	  Say yes here to build support for Analog Devices AD4030 and AD4630
> high speed
> diff --git a/drivers/iio/adc/ad4030.c b/drivers/iio/adc/ad4030.c
> index aa0e27321869..52805c779934 100644
> --- a/drivers/iio/adc/ad4030.c
> +++ b/drivers/iio/adc/ad4030.c
> @@ -14,15 +14,25 @@
>   */
>  
>  #include <linux/bitfield.h>
> +#include <linux/cleanup.h>
>  #include <linux/clk.h>
> +#include <linux/dmaengine.h>
> +#include <linux/iio/buffer-dmaengine.h>
>  #include <linux/iio/iio.h>
>  #include <linux/iio/trigger_consumer.h>
>  #include <linux/iio/triggered_buffer.h>
> +#include <linux/limits.h>
> +#include <linux/log2.h>
> +#include <linux/math64.h>
> +#include <linux/minmax.h>
> +#include <linux/pwm.h>
>  #include <linux/regmap.h>
>  #include <linux/regulator/consumer.h>
> +#include <linux/spi/offload/consumer.h>
>  #include <linux/spi/spi.h>
>  #include <linux/unaligned.h>
>  #include <linux/units.h>
> +#include <linux/types.h>
>  
>  #define AD4030_REG_INTERFACE_CONFIG_A			0x00
>  #define     AD4030_REG_INTERFACE_CONFIG_A_SW_RESET	(BIT(0) | BIT(7))
> @@ -111,6 +121,8 @@
>  #define AD4632_TCYC_NS			2000
>  #define AD4632_TCYC_ADJUSTED_NS		(AD4632_TCYC_NS -
> AD4030_TCNVL_NS)
>  #define AD4030_TRESET_COM_DELAY_MS	750
> +/* Datasheet says 9.8ns, so use the closest integer value */
> +#define AD4030_TQUIET_CNV_DELAY_NS	10
>  
>  enum ad4030_out_mode {
>  	AD4030_OUT_DATA_MD_DIFF,
> @@ -136,11 +148,13 @@ struct ad4030_chip_info {
>  	const char *name;
>  	const unsigned long *available_masks;
>  	const struct iio_chan_spec channels[AD4030_MAX_IIO_CHANNEL_NB];
> +	const struct iio_chan_spec
> offload_channels[AD4030_MAX_IIO_CHANNEL_NB];
>  	u8 grade;
>  	u8 precision_bits;
>  	/* Number of hardware channels */
>  	int num_voltage_inputs;
>  	unsigned int tcyc_ns;
> +	unsigned int max_sample_rate_hz;
>  };
>  
>  struct ad4030_state {
> @@ -153,6 +167,15 @@ struct ad4030_state {
>  	int offset_avail[3];
>  	unsigned int avg_log2;
>  	enum ad4030_out_mode mode;
> +	struct mutex lock; /* Protect read-modify-write and multi write
> sequences */
> +	/* Offload sampling */
> +	struct spi_transfer offload_xfer;
> +	struct spi_message offload_msg;
> +	struct spi_offload *offload;
> +	struct spi_offload_trigger *offload_trigger;
> +	struct spi_offload_trigger_config offload_trigger_config;
> +	struct pwm_device *cnv_trigger;
> +	struct pwm_waveform cnv_wf;
>  
>  	/*
>  	 * DMA (thus cache coherency maintenance) requires the transfer
> buffers
> @@ -209,8 +232,9 @@ struct ad4030_state {
>   * - voltage0-voltage1
>   * - voltage2-voltage3
>   */
> -#define AD4030_CHAN_DIFF(_idx, _scan_type) {				\
> +#define __AD4030_CHAN_DIFF(_idx, _scan_type, _offload) {		\
>  	.info_mask_shared_by_all =					\
> +		(_offload ? BIT(IIO_CHAN_INFO_SAMP_FREQ) : 0)
> |		\
>  		BIT(IIO_CHAN_INFO_OVERSAMPLING_RATIO),			\
>  	.info_mask_shared_by_all_available =				\
>  		BIT(IIO_CHAN_INFO_OVERSAMPLING_RATIO),			\
> @@ -232,6 +256,12 @@ struct ad4030_state {
>  	.num_ext_scan_type = ARRAY_SIZE(_scan_type),			\
>  }
>  
> +#define AD4030_CHAN_DIFF(_idx, _scan_type)				\
> +	__AD4030_CHAN_DIFF(_idx, _scan_type, 0)
> +
> +#define AD4030_OFFLOAD_CHAN_DIFF(_idx, _scan_type)			\
> +	__AD4030_CHAN_DIFF(_idx, _scan_type, 1)
> +
>  static const int ad4030_average_modes[] = {
>  	BIT(0),					/* No
> averaging/oversampling */
>  	BIT(1), BIT(2), BIT(3), BIT(4),		/* 2 to 16 */
> @@ -240,6 +270,11 @@ static const int ad4030_average_modes[] = {
>  	BIT(13), BIT(14), BIT(15), BIT(16),	/* 8192 to 65536 */
>  };
>  
> +static const struct spi_offload_config ad4030_offload_config = {
> +	.capability_flags = SPI_OFFLOAD_CAP_TRIGGER |
> +			    SPI_OFFLOAD_CAP_RX_STREAM_DMA,
> +};
> +
>  static int ad4030_enter_config_mode(struct ad4030_state *st)
>  {
>  	st->tx_data[0] = AD4030_REG_ACCESS;
> @@ -453,6 +488,106 @@ static int ad4030_get_chan_calibbias(struct iio_dev
> *indio_dev,
>  	}
>  }
>  
> +static void ad4030_get_sampling_freq(struct ad4030_state *st, int *freq)
> +{
> +	struct spi_offload_trigger_config *config = &st-
> >offload_trigger_config;
> +
> +	/*
> +	 * Conversion data is fetched from the device when the offload
> transfer
> +	 * is triggered. Thus, provide the SPI offload trigger frequency as
> the
> +	 * sampling frequency.
> +	 */
> +	*freq = config->periodic.frequency_hz;
> +}
> +
> +static int __ad4030_set_sampling_freq(struct ad4030_state *st,
> +				      unsigned int freq, unsigned int
> avg_log2)
> +{
> +	struct spi_offload_trigger_config *config = &st-
> >offload_trigger_config;
> +	struct pwm_waveform cnv_wf = { };
> +	u64 target = AD4030_TCNVH_NS;
> +	u64 offload_period_ns;
> +	u64 offload_offset_ns;
> +	int ret;
> +
> +	/*
> +	 * When averaging/oversampling over N samples, we fire the offload
> +	 * trigger once at every N pulses of the CNV signal. Conversely, the
> CNV
> +	 * signal needs to be N times faster than the offload trigger. Take
> that
> +	 * into account to correctly re-evaluate both the PWM waveform
> connected
> +	 * to CNV and the SPI offload trigger.
> +	 */
> +	if (st->mode == AD4030_OUT_DATA_MD_30_AVERAGED_DIFF)
> +		freq <<= avg_log2;
> +
> +	cnv_wf.period_length_ns = DIV_ROUND_CLOSEST(NSEC_PER_SEC, freq);
> +	/*
> +	 * The datasheet lists a minimum time of 9.8 ns, but no maximum. If
> the
> +	 * rounded PWM's value is less than 10, increase the target value by
> 10
> +	 * and attempt to round the waveform again, until the value is at
> least
> +	 * 10 ns. Use a separate variable to represent the target in case the
> +	 * rounding is severe enough to keep putting the first few results
> under
> +	 * the minimum 10ns condition checked by the while loop.
> +	 */
> +	do {
> +		cnv_wf.duty_length_ns = target;
> +		ret = pwm_round_waveform_might_sleep(st->cnv_trigger,
> &cnv_wf);
> +		if (ret)
> +			return ret;
> +		target += AD4030_TCNVH_NS;
> +	} while (cnv_wf.duty_length_ns < AD4030_TCNVH_NS);
> +
> +	if (!in_range(cnv_wf.period_length_ns, AD4030_TCYC_NS, INT_MAX))
> +		return -EINVAL;
> +
> +	offload_period_ns = cnv_wf.period_length_ns;
> +	if (st->mode == AD4030_OUT_DATA_MD_30_AVERAGED_DIFF)
> +		offload_period_ns <<= avg_log2;
> +
> +	config->periodic.frequency_hz =  DIV_ROUND_UP_ULL(NSEC_PER_SEC,
> +							  offload_period_ns);
> +
> +	/*
> +	 * The hardware does the capture on zone 2 (when SPI trigger PWM
> +	 * is used). This means that the SPI trigger signal should happen at
> +	 * tsync + tquiet_con_delay being tsync the conversion signal period
> +	 * and tquiet_con_delay 9.8ns. Hence set the PWM phase accordingly.
> +	 *
> +	 * The PWM waveform API only supports nanosecond resolution right
> now,
> +	 * so round this setting to the closest available value.
> +	 */
> +	offload_offset_ns = AD4030_TQUIET_CNV_DELAY_NS;
> +	do {
> +		config->periodic.offset_ns = offload_offset_ns;
> +		ret = spi_offload_trigger_validate(st->offload_trigger,
> config);
> +		if (ret)
> +			return ret;
> +		offload_offset_ns += AD4030_TQUIET_CNV_DELAY_NS;
> +	} while (config->periodic.offset_ns < AD4030_TQUIET_CNV_DELAY_NS);
> +
> +	st->cnv_wf = cnv_wf;
> +
> +	return 0;
> +}
> +
> +static int ad4030_set_sampling_freq(struct iio_dev *indio_dev, int freq)
> +{
> +	struct ad4030_state *st = iio_priv(indio_dev);
> +
> +	/*
> +	 * We have no control over the sampling frequency without SPI offload
> +	 * triggering.
> +	 */
> +	if (!st->offload_trigger)
> +		return -ENODEV;
> +
> +	if (!in_range(freq, 1, st->chip->max_sample_rate_hz))
> +		return -EINVAL;
> +
> +	guard(mutex)(&st->lock);
> +	return __ad4030_set_sampling_freq(st, freq, st->avg_log2);
> +}
> +
>  static int ad4030_set_chan_calibscale(struct iio_dev *indio_dev,
>  				      struct iio_chan_spec const *chan,
>  				      int gain_int,
> @@ -507,27 +642,6 @@ static int ad4030_set_chan_calibbias(struct iio_dev
> *indio_dev,
>  				 st->tx_data, AD4030_REG_OFFSET_BYTES_NB);
>  }
>  
> -static int ad4030_set_avg_frame_len(struct iio_dev *dev, int avg_val)
> -{
> -	struct ad4030_state *st = iio_priv(dev);
> -	unsigned int avg_log2 = ilog2(avg_val);
> -	unsigned int last_avg_idx = ARRAY_SIZE(ad4030_average_modes) - 1;
> -	int ret;
> -
> -	if (avg_val < 0 || avg_val > ad4030_average_modes[last_avg_idx])
> -		return -EINVAL;
> -
> -	ret = regmap_write(st->regmap, AD4030_REG_AVG,
> -			   AD4030_REG_AVG_MASK_AVG_SYNC |
> -			   FIELD_PREP(AD4030_REG_AVG_MASK_AVG_VAL,
> avg_log2));
> -	if (ret)
> -		return ret;
> -
> -	st->avg_log2 = avg_log2;
> -
> -	return 0;
> -}
> -
>  static bool ad4030_is_common_byte_asked(struct ad4030_state *st,
>  					unsigned int mask)
>  {
> @@ -536,11 +650,10 @@ static bool ad4030_is_common_byte_asked(struct
> ad4030_state *st,
>  		AD4030_DUAL_COMMON_BYTE_CHANNELS_MASK);
>  }
>  
> -static int ad4030_set_mode(struct iio_dev *indio_dev, unsigned long mask)
> +static int ad4030_set_mode(struct ad4030_state *st, unsigned long mask,
> +			   unsigned int avg_log2)
>  {
> -	struct ad4030_state *st = iio_priv(indio_dev);
> -
> -	if (st->avg_log2 > 0) {
> +	if (avg_log2 > 0) {
>  		st->mode = AD4030_OUT_DATA_MD_30_AVERAGED_DIFF;
>  	} else if (ad4030_is_common_byte_asked(st, mask)) {
>  		switch (st->chip->precision_bits) {
> @@ -564,6 +677,50 @@ static int ad4030_set_mode(struct iio_dev *indio_dev,
> unsigned long mask)
>  				  st->mode);
>  }
>  
> +static int ad4030_set_avg_frame_len(struct iio_dev *dev, unsigned long mask,
> int avg_val)
> +{
> +	struct ad4030_state *st = iio_priv(dev);
> +	unsigned int avg_log2 = ilog2(avg_val);
> +	unsigned int last_avg_idx = ARRAY_SIZE(ad4030_average_modes) - 1;
> +	int freq;
> +	int ret;
> +
> +	if (avg_val < 0 || avg_val > ad4030_average_modes[last_avg_idx])
> +		return -EINVAL;
> +
> +	guard(mutex)(&st->lock);
> +	ret = ad4030_set_mode(st, mask, avg_log2);
> +	if (ret)
> +		return ret;
> +
> +	if (st->offload_trigger) {
> +		/*
> +		 * The sample averaging and sampling frequency configurations
> +		 * are mutually dependent one from another. That's because
> the
> +		 * effective data sample rate is fCNV / 2^N, where N is the
> +		 * number of samples being averaged.
> +		 *
> +		 * When SPI offload is supported and we have control over the
> +		 * sample rate, the conversion start signal (CNV) and the SPI
> +		 * offload trigger frequencies must be re-evaluated so data
> is
> +		 * fetched only after 'avg_val' conversions.
> +		 */
> +		ad4030_get_sampling_freq(st, &freq);
> +		ret = __ad4030_set_sampling_freq(st, freq, avg_log2);
> +		if (ret)
> +			return ret;
> +	}
> +
> +	ret = regmap_write(st->regmap, AD4030_REG_AVG,
> +			   AD4030_REG_AVG_MASK_AVG_SYNC |
> +			   FIELD_PREP(AD4030_REG_AVG_MASK_AVG_VAL,
> avg_log2));
> +	if (ret)
> +		return ret;
> +
> +	st->avg_log2 = avg_log2;
> +	return 0;
> +}
> +
>  /*
>   * Descramble 2 32bits numbers out of a 64bits. The bits are interleaved:
>   * 1 bit for first number, 1 bit for the second, and so on...
> @@ -672,7 +829,7 @@ static int ad4030_single_conversion(struct iio_dev
> *indio_dev,
>  	struct ad4030_state *st = iio_priv(indio_dev);
>  	int ret;
>  
> -	ret = ad4030_set_mode(indio_dev, BIT(chan->scan_index));
> +	ret = ad4030_set_mode(st, BIT(chan->scan_index), st->avg_log2);
>  	if (ret)
>  		return ret;
>  
> @@ -769,6 +926,13 @@ static int ad4030_read_raw_dispatch(struct iio_dev
> *indio_dev,
>  		*val = BIT(st->avg_log2);
>  		return IIO_VAL_INT;
>  
> +	case IIO_CHAN_INFO_SAMP_FREQ:
> +		if (!st->offload_trigger)
> +			return -ENODEV;
> +
> +		ad4030_get_sampling_freq(st, val);
> +		return IIO_VAL_INT;
> +
>  	default:
>  		return -EINVAL;
>  	}
> @@ -807,7 +971,10 @@ static int ad4030_write_raw_dispatch(struct iio_dev
> *indio_dev,
>  		return ad4030_set_chan_calibbias(indio_dev, chan, val);
>  
>  	case IIO_CHAN_INFO_OVERSAMPLING_RATIO:
> -		return ad4030_set_avg_frame_len(indio_dev, val);
> +		return ad4030_set_avg_frame_len(indio_dev, BIT(chan-
> >scan_index), val);
> +
> +	case IIO_CHAN_INFO_SAMP_FREQ:
> +		return ad4030_set_sampling_freq(indio_dev, val);
>  
>  	default:
>  		return -EINVAL;
> @@ -869,7 +1036,9 @@ static int ad4030_get_current_scan_type(const struct
> iio_dev *indio_dev,
>  static int ad4030_update_scan_mode(struct iio_dev *indio_dev,
>  				   const unsigned long *scan_mask)
>  {
> -	return ad4030_set_mode(indio_dev, *scan_mask);
> +	struct ad4030_state *st = iio_priv(indio_dev);
> +
> +	return ad4030_set_mode(st, *scan_mask, st->avg_log2);
>  }
>  
>  static const struct iio_info ad4030_iio_info = {
> @@ -898,6 +1067,88 @@ static const struct iio_buffer_setup_ops
> ad4030_buffer_setup_ops = {
>  	.validate_scan_mask = ad4030_validate_scan_mask,
>  };
>  
> +static void ad4030_prepare_offload_msg(struct iio_dev *indio_dev)
> +{
> +	struct ad4030_state *st = iio_priv(indio_dev);
> +	u8 offload_bpw;
> +
> +	if (st->mode == AD4030_OUT_DATA_MD_30_AVERAGED_DIFF)
> +		offload_bpw = 32;
> +	else
> +		offload_bpw = st->chip->precision_bits;
> +
> +	st->offload_xfer.speed_hz = AD4030_SPI_MAX_REG_XFER_SPEED;
> +	st->offload_xfer.bits_per_word = roundup_pow_of_two(offload_bpw);
> +	st->offload_xfer.len = spi_bpw_to_bytes(offload_bpw);
> +	st->offload_xfer.offload_flags = SPI_OFFLOAD_XFER_RX_STREAM;
> +	spi_message_init_with_transfers(&st->offload_msg, &st->offload_xfer,
> 1);
> +}
> +
> +static int ad4030_offload_buffer_postenable(struct iio_dev *indio_dev)
> +{
> +	struct ad4030_state *st = iio_priv(indio_dev);
> +	int ret;
> +
> +	ret = regmap_write(st->regmap, AD4030_REG_EXIT_CFG_MODE, BIT(0));
> +	if (ret)
> +		return ret;
> +
> +	ad4030_prepare_offload_msg(indio_dev);
> +	st->offload_msg.offload = st->offload;
> +	ret = spi_optimize_message(st->spi, &st->offload_msg);
> +	if (ret)
> +		goto out_reset_mode;
> +
> +	ret = pwm_set_waveform_might_sleep(st->cnv_trigger, &st->cnv_wf,
> false);
> +	if (ret)
> +		goto out_unoptimize;
> +
> +	ret = spi_offload_trigger_enable(st->offload, st->offload_trigger,
> +					 &st->offload_trigger_config);
> +	if (ret)
> +		goto out_pwm_disable;
> +
> +	return 0;
> +
> +out_pwm_disable:
> +	pwm_disable(st->cnv_trigger);
> +out_unoptimize:
> +	spi_unoptimize_message(&st->offload_msg);
> +out_reset_mode:
> +	/* reenter register configuration mode */
> +	ret = ad4030_enter_config_mode(st);
> +	if (ret)
> +		dev_err(&st->spi->dev,
> +			"couldn't reenter register configuration mode\n");
> +	return ret;
> +}
> +
> +static int ad4030_offload_buffer_predisable(struct iio_dev *indio_dev)
> +{
> +	struct ad4030_state *st = iio_priv(indio_dev);
> +	int ret;
> +
> +	spi_offload_trigger_disable(st->offload, st->offload_trigger);
> +
> +	pwm_disable(st->cnv_trigger);
> +
> +	spi_unoptimize_message(&st->offload_msg);
> +
> +	/* reenter register configuration mode */
> +	ret = ad4030_enter_config_mode(st);
> +	if (ret)
> +		dev_err(&st->spi->dev,
> +			"couldn't reenter register configuration mode\n");
> +
> +	return ret;
> +}
> +
> +static const struct iio_buffer_setup_ops ad4030_offload_buffer_setup_ops = {
> +	.postenable = &ad4030_offload_buffer_postenable,
> +	.predisable = &ad4030_offload_buffer_predisable,
> +	.validate_scan_mask = ad4030_validate_scan_mask,
> +};
> +
>  static int ad4030_regulators_get(struct ad4030_state *st)
>  {
>  	struct device *dev = &st->spi->dev;
> @@ -967,6 +1218,24 @@ static int ad4030_detect_chip_info(const struct
> ad4030_state *st)
>  	return 0;
>  }
>  
> +static int ad4030_pwm_get(struct ad4030_state *st)
> +{
> +	struct device *dev = &st->spi->dev;
> +
> +	st->cnv_trigger = devm_pwm_get(dev, NULL);
> +	if (IS_ERR(st->cnv_trigger))
> +		return dev_err_probe(dev, PTR_ERR(st->cnv_trigger),
> +				     "Failed to get CNV PWM\n");
> +
> +	/*
> +	 * Preemptively disable the PWM, since we only want to enable it with
> +	 * the buffer.
> +	 */
> +	pwm_disable(st->cnv_trigger);
> +
> +	return 0;
> +}
> +
>  static int ad4030_config(struct ad4030_state *st)
>  {
>  	int ret;
> @@ -994,6 +1263,31 @@ static int ad4030_config(struct ad4030_state *st)
>  	return 0;
>  }
>  
> +static int ad4030_spi_offload_setup(struct iio_dev *indio_dev,
> +				    struct ad4030_state *st)
> +{
> +	struct device *dev = &st->spi->dev;
> +	struct dma_chan *rx_dma;
> +
> +	indio_dev->setup_ops = &ad4030_offload_buffer_setup_ops;
> +
> +	st->offload_trigger = devm_spi_offload_trigger_get(dev, st->offload,
> +							  
> SPI_OFFLOAD_TRIGGER_PERIODIC);
> +	if (IS_ERR(st->offload_trigger))
> +		return dev_err_probe(dev, PTR_ERR(st->offload_trigger),
> +				     "failed to get offload trigger\n");
> +
> +	st->offload_trigger_config.type = SPI_OFFLOAD_TRIGGER_PERIODIC;
> +
> +	rx_dma = devm_spi_offload_rx_stream_request_dma_chan(dev, st-
> >offload);
> +	if (IS_ERR(rx_dma))
> +		return dev_err_probe(dev, PTR_ERR(rx_dma),
> +				     "failed to get offload RX DMA\n");
> +
> +	return devm_iio_dmaengine_buffer_setup_with_handle(dev, indio_dev,
> rx_dma,
> +							  
> IIO_BUFFER_DIRECTION_IN);
> +}
> +
>  static int ad4030_probe(struct spi_device *spi)
>  {
>  	struct device *dev = &spi->dev;
> @@ -1018,6 +1312,10 @@ static int ad4030_probe(struct spi_device *spi)
>  	if (!st->chip)
>  		return -EINVAL;
>  
> +	ret = devm_mutex_init(dev, &st->lock);
> +	if (ret)
> +		return ret;
> +
>  	ret = ad4030_regulators_get(st);
>  	if (ret)
>  		return ret;
> @@ -1045,24 +1343,57 @@ static int ad4030_probe(struct spi_device *spi)
>  		return dev_err_probe(dev, PTR_ERR(st->cnv_gpio),
>  				     "Failed to get cnv gpio\n");
>  
> -	/*
> -	 * One hardware channel is split in two software channels when using
> -	 * common byte mode. Add one more channel for the timestamp.
> -	 */
> -	indio_dev->num_channels = 2 * st->chip->num_voltage_inputs + 1;
>  	indio_dev->name = st->chip->name;
>  	indio_dev->modes = INDIO_DIRECT_MODE;
>  	indio_dev->info = &ad4030_iio_info;
> -	indio_dev->channels = st->chip->channels;
> -	indio_dev->available_scan_masks = st->chip->available_masks;
>  
> -	ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
> -					      iio_pollfunc_store_time,
> -					      ad4030_trigger_handler,
> -					      &ad4030_buffer_setup_ops);
> -	if (ret)
> -		return dev_err_probe(dev, ret,
> -				     "Failed to setup triggered buffer\n");
> +	st->offload = devm_spi_offload_get(dev, spi, &ad4030_offload_config);
> +	ret = PTR_ERR_OR_ZERO(st->offload);
> +	if (ret && ret != -ENODEV)
> +		return dev_err_probe(dev, ret, "failed to get offload\n");
> +
> +	/* Fall back to low speed usage when no SPI offload is available. */
> +	if (ret == -ENODEV) {
> +		/*
> +		 * One hardware channel is split in two software channels
> when
> +		 * using common byte mode. Add one more channel for the
> timestamp.
> +		 */
> +		indio_dev->num_channels = 2 * st->chip->num_voltage_inputs +
> 1;
> +		indio_dev->channels = st->chip->channels;
> +		indio_dev->available_scan_masks = st->chip->available_masks;
> +
> +		ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
> +						     
> iio_pollfunc_store_time,
> +						      ad4030_trigger_handler,
> +						     
> &ad4030_buffer_setup_ops);
> +		if (ret)
> +			return dev_err_probe(dev, ret,
> +					     "Failed to setup triggered
> buffer\n");
> +	} else {
> +		/*
> +		 * One hardware channel is split in two software channels
> when
> +		 * using common byte mode. Offloaded SPI transfers can't
> support
> +		 * software timestamp so no additional timestamp channel is
> added.
> +		 */
> +		indio_dev->num_channels = 2 * st->chip->num_voltage_inputs;
> +		indio_dev->channels = st->chip->offload_channels;
> +		indio_dev->available_scan_masks = st->chip->available_masks;
> +		ret = ad4030_spi_offload_setup(indio_dev, st);
> +		if (ret)
> +			return dev_err_probe(dev, ret,
> +					     "Failed to setup SPI
> offload\n");
> +
> +		ret = ad4030_pwm_get(st);
> +		if (ret)
> +			return dev_err_probe(&spi->dev, ret,
> +					     "Failed to get PWM: %d\n", ret);
> +
> +		ret = __ad4030_set_sampling_freq(st, st->chip-
> >max_sample_rate_hz,
> +						 st->avg_log2);
> +		if (ret)
> +			return dev_err_probe(&spi->dev, ret,
> +					     "Failed to set offload samp
> freq\n");
> +	}
>  
>  	return devm_iio_device_register(dev, indio_dev);
>  }
> @@ -1100,6 +1431,23 @@ static const struct iio_scan_type
> ad4030_24_scan_types[] = {
>  	},
>  };
>  
> +static const struct iio_scan_type ad4030_24_offload_scan_types[] = {
> +	[AD4030_SCAN_TYPE_NORMAL] = {
> +		.sign = 's',
> +		.storagebits = 32,
> +		.realbits = 24,
> +		.shift = 0,
> +		.endianness = IIO_CPU,
> +	},
> +	[AD4030_SCAN_TYPE_AVG] = {
> +		.sign = 's',
> +		.storagebits = 32,
> +		.realbits = 30,
> +		.shift = 2,
> +		.endianness = IIO_CPU,
> +	},
> +};
> +
>  static const struct iio_scan_type ad4030_16_scan_types[] = {
>  	[AD4030_SCAN_TYPE_NORMAL] = {
>  		.sign = 's',
> @@ -1117,6 +1465,23 @@ static const struct iio_scan_type
> ad4030_16_scan_types[] = {
>  	}
>  };
>  
> +static const struct iio_scan_type ad4030_16_offload_scan_types[] = {
> +	[AD4030_SCAN_TYPE_NORMAL] = {
> +		.sign = 's',
> +		.storagebits = 32,
> +		.realbits = 16,
> +		.shift = 0,
> +		.endianness = IIO_CPU,
> +	},
> +	[AD4030_SCAN_TYPE_AVG] = {
> +		.sign = 's',
> +		.storagebits = 32,
> +		.realbits = 30,
> +		.shift = 2,
> +		.endianness = IIO_CPU,
> +	},
> +};
> +
>  static const struct ad4030_chip_info ad4030_24_chip_info = {
>  	.name = "ad4030-24",
>  	.available_masks = ad4030_channel_masks,
> @@ -1125,10 +1490,15 @@ static const struct ad4030_chip_info
> ad4030_24_chip_info = {
>  		AD4030_CHAN_CMO(1, 0),
>  		IIO_CHAN_SOFT_TIMESTAMP(2),
>  	},
> +	.offload_channels = {
> +		AD4030_OFFLOAD_CHAN_DIFF(0, ad4030_24_offload_scan_types),
> +		AD4030_CHAN_CMO(1, 0),
> +	},
>  	.grade = AD4030_REG_CHIP_GRADE_AD4030_24_GRADE,
>  	.precision_bits = 24,
>  	.num_voltage_inputs = 1,
>  	.tcyc_ns = AD4030_TCYC_ADJUSTED_NS,
> +	.max_sample_rate_hz = 2 * HZ_PER_MHZ,
>  };
>  
>  static const struct ad4030_chip_info ad4630_16_chip_info = {
> @@ -1141,10 +1511,17 @@ static const struct ad4030_chip_info
> ad4630_16_chip_info = {
>  		AD4030_CHAN_CMO(3, 1),
>  		IIO_CHAN_SOFT_TIMESTAMP(4),
>  	},
> +	.offload_channels = {
> +		AD4030_OFFLOAD_CHAN_DIFF(0, ad4030_16_offload_scan_types),
> +		AD4030_OFFLOAD_CHAN_DIFF(1, ad4030_16_offload_scan_types),
> +		AD4030_CHAN_CMO(2, 0),
> +		AD4030_CHAN_CMO(3, 1),
> +	},
>  	.grade = AD4030_REG_CHIP_GRADE_AD4630_16_GRADE,
>  	.precision_bits = 16,
>  	.num_voltage_inputs = 2,
>  	.tcyc_ns = AD4030_TCYC_ADJUSTED_NS,
> +	.max_sample_rate_hz = 2 * HZ_PER_MHZ,
>  };
>  
>  static const struct ad4030_chip_info ad4630_24_chip_info = {
> @@ -1157,10 +1534,17 @@ static const struct ad4030_chip_info
> ad4630_24_chip_info = {
>  		AD4030_CHAN_CMO(3, 1),
>  		IIO_CHAN_SOFT_TIMESTAMP(4),
>  	},
> +	.offload_channels = {
> +		AD4030_OFFLOAD_CHAN_DIFF(0, ad4030_24_offload_scan_types),
> +		AD4030_OFFLOAD_CHAN_DIFF(1, ad4030_24_offload_scan_types),
> +		AD4030_CHAN_CMO(2, 0),
> +		AD4030_CHAN_CMO(3, 1),
> +	},
>  	.grade = AD4030_REG_CHIP_GRADE_AD4630_24_GRADE,
>  	.precision_bits = 24,
>  	.num_voltage_inputs = 2,
>  	.tcyc_ns = AD4030_TCYC_ADJUSTED_NS,
> +	.max_sample_rate_hz = 2 * HZ_PER_MHZ,
>  };
>  
>  static const struct ad4030_chip_info ad4632_16_chip_info = {
> @@ -1173,10 +1557,17 @@ static const struct ad4030_chip_info
> ad4632_16_chip_info = {
>  		AD4030_CHAN_CMO(3, 1),
>  		IIO_CHAN_SOFT_TIMESTAMP(4),
>  	},
> +	.offload_channels = {
> +		AD4030_OFFLOAD_CHAN_DIFF(0, ad4030_16_offload_scan_types),
> +		AD4030_OFFLOAD_CHAN_DIFF(1, ad4030_16_offload_scan_types),
> +		AD4030_CHAN_CMO(2, 0),
> +		AD4030_CHAN_CMO(3, 1),
> +	},
>  	.grade = AD4030_REG_CHIP_GRADE_AD4632_16_GRADE,
>  	.precision_bits = 16,
>  	.num_voltage_inputs = 2,
>  	.tcyc_ns = AD4632_TCYC_ADJUSTED_NS,
> +	.max_sample_rate_hz = 500 * HZ_PER_KHZ,
>  };
>  
>  static const struct ad4030_chip_info ad4632_24_chip_info = {
> @@ -1189,10 +1580,17 @@ static const struct ad4030_chip_info
> ad4632_24_chip_info = {
>  		AD4030_CHAN_CMO(3, 1),
>  		IIO_CHAN_SOFT_TIMESTAMP(4),
>  	},
> +	.offload_channels = {
> +		AD4030_OFFLOAD_CHAN_DIFF(0, ad4030_24_offload_scan_types),
> +		AD4030_OFFLOAD_CHAN_DIFF(1, ad4030_24_offload_scan_types),
> +		AD4030_CHAN_CMO(2, 0),
> +		AD4030_CHAN_CMO(3, 1),
> +	},
>  	.grade = AD4030_REG_CHIP_GRADE_AD4632_24_GRADE,
>  	.precision_bits = 24,
>  	.num_voltage_inputs = 2,
>  	.tcyc_ns = AD4632_TCYC_ADJUSTED_NS,
> +	.max_sample_rate_hz = 500 * HZ_PER_KHZ,
>  };
>  
>  static const struct spi_device_id ad4030_id_table[] = {
> @@ -1228,3 +1626,4 @@ module_spi_driver(ad4030_driver);
>  MODULE_AUTHOR("Esteban Blanc <eblanc@baylibre.com>");
>  MODULE_DESCRIPTION("Analog Devices AD4630 ADC family driver");
>  MODULE_LICENSE("GPL");
> +MODULE_IMPORT_NS("IIO_DMAENGINE_BUFFER");