[PATCH v3 2/2] iio: adc: Add ti-ads1018 driver

Kurt Borja posted 2 patches 2 days, 17 hours ago
[PATCH v3 2/2] iio: adc: Add ti-ads1018 driver
Posted by Kurt Borja 2 days, 17 hours ago
Add ti-ads1018 driver for Texas Instruments ADS1018 and ADS1118 SPI
analog-to-digital converters.

These chips' MOSI pin is shared with a data-ready interrupt. Defining
this interrupt in devicetree is optional, therefore we only create an
IIO trigger if one is found.

Handling this interrupt requires some considerations. When enabling the
trigger the CS line is tied low (active), thus we need to hold
spi_bus_lock() too, to avoid state corruption. This is done inside the
set_trigger_state() callback, to let users use other triggers without
wasting a bus lock.

Signed-off-by: Kurt Borja <kuurtb@gmail.com>
---
 MAINTAINERS                  |   1 +
 drivers/iio/adc/Kconfig      |  12 +
 drivers/iio/adc/Makefile     |   1 +
 drivers/iio/adc/ti-ads1018.c | 811 +++++++++++++++++++++++++++++++++++++++++++
 4 files changed, 825 insertions(+)

diff --git a/MAINTAINERS b/MAINTAINERS
index 3d5295b5d6eb..b3822cbff2c6 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -25651,6 +25651,7 @@ M:	Kurt Borja <kuurtb@gmail.com>
 L:	linux-iio@vger.kernel.org
 S:	Maintained
 F:	Documentation/devicetree/bindings/iio/adc/ti,ads1018.yaml
+F:	drivers/iio/adc/ti-ads1018.c
 
 TI ADS7924 ADC DRIVER
 M:	Hugo Villeneuve <hvilleneuve@dimonoff.com>
diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig
index 58da8255525e..aa3f7023c64b 100644
--- a/drivers/iio/adc/Kconfig
+++ b/drivers/iio/adc/Kconfig
@@ -1664,6 +1664,18 @@ config TI_ADS1015
 	  This driver can also be built as a module. If so, the module will be
 	  called ti-ads1015.
 
+config TI_ADS1018
+       tristate "Texas Instruments ADS1018 ADC"
+       depends on SPI
+       select IIO_BUFFER
+       select IIO_TRIGGERED_BUFFER
+       help
+         If you say yes here you get support for Texas Instruments ADS1018 and
+         ADS1118 ADC chips.
+
+         This driver can also be built as a module. If so, the module will be
+         called ti-ads1018.
+
 config TI_ADS1100
 	tristate "Texas Instruments ADS1100 and ADS1000 ADC"
 	depends on I2C
diff --git a/drivers/iio/adc/Makefile b/drivers/iio/adc/Makefile
index 7cc8f9a12f76..72ef79becdec 100644
--- a/drivers/iio/adc/Makefile
+++ b/drivers/iio/adc/Makefile
@@ -145,6 +145,7 @@ obj-$(CONFIG_TI_ADC12138) += ti-adc12138.o
 obj-$(CONFIG_TI_ADC128S052) += ti-adc128s052.o
 obj-$(CONFIG_TI_ADC161S626) += ti-adc161s626.o
 obj-$(CONFIG_TI_ADS1015) += ti-ads1015.o
+obj-$(CONFIG_TI_ADS1018) += ti-ads1018.o
 obj-$(CONFIG_TI_ADS1100) += ti-ads1100.o
 obj-$(CONFIG_TI_ADS1119) += ti-ads1119.o
 obj-$(CONFIG_TI_ADS124S08) += ti-ads124s08.o
diff --git a/drivers/iio/adc/ti-ads1018.c b/drivers/iio/adc/ti-ads1018.c
new file mode 100644
index 000000000000..2e851a1addfd
--- /dev/null
+++ b/drivers/iio/adc/ti-ads1018.c
@@ -0,0 +1,811 @@
+// SPDX-License-Identifier: GPL-2.0-or-later
+/*
+ * Texas Instruments ADS1018 ADC driver
+ *
+ * Copyright (C) 2025 Kurt Borja <kuurtb@gmail.com>
+ */
+
+#include <linux/array_size.h>
+#include <linux/bitfield.h>
+#include <linux/bitmap.h>
+#include <linux/byteorder/generic.h>
+#include <linux/dev_printk.h>
+#include <linux/gpio/consumer.h>
+#include <linux/interrupt.h>
+#include <linux/math.h>
+#include <linux/mod_devicetable.h>
+#include <linux/module.h>
+#include <linux/spi/spi.h>
+#include <linux/types.h>
+#include <linux/units.h>
+
+#include <linux/iio/buffer.h>
+#include <linux/iio/iio.h>
+#include <linux/iio/trigger.h>
+#include <linux/iio/trigger_consumer.h>
+#include <linux/iio/triggered_buffer.h>
+
+#define ADS1018_CFG_DEFAULT		0x058b
+
+#define ADS1018_CFG_OS_TRIG		BIT(15)
+#define ADS1018_CFG_TS_MODE_EN		BIT(4)
+#define ADS1018_CFG_PULL_UP		BIT(3)
+#define ADS1018_CFG_NOP			BIT(1)
+#define ADS1018_CFG_VALID		(ADS1018_CFG_PULL_UP | ADS1018_CFG_NOP)
+
+#define ADS1018_CFG_MUX_MASK		GENMASK(14, 12)
+
+#define ADS1018_CFG_PGA_MASK		GENMASK(11, 9)
+#define ADS1018_PGA_DEFAULT		2
+
+#define ADS1018_CFG_MODE_MASK		GENMASK(8, 8)
+#define ADS1018_MODE_CONTINUOUS		0
+#define ADS1018_MODE_ONESHOT		1
+
+#define ADS1018_CFG_DRATE_MASK		GENMASK(7, 5)
+#define ADS1018_DRATE_DEFAULT		4
+
+#define ADS1018_CHANNELS_MAX		10
+
+struct ads1018_chan_data {
+	u8 pga_mode;
+	u8 data_rate_mode;
+};
+
+struct ads1018_chip_info {
+	const char *name;
+
+	const struct iio_chan_spec *channels;
+	unsigned long num_channels;
+
+	/* IIO_VAL_INT */
+	const unsigned int *data_rate_mode_to_hz;
+	unsigned long num_data_rate_mode_to_hz;
+
+	/* IIO_VAL_INT_PLUS_NANO */
+	const unsigned int (*pga_mode_to_gain)[2];
+	unsigned long num_pga_mode_to_gain;
+
+	/* IIO_VAL_INT_PLUS_MICRO */
+	const int temp_scale[2];
+};
+
+struct ads1018 {
+	struct spi_device *spi;
+	struct iio_trigger *indio_trig;
+
+	struct gpio_desc *drdy_gpiod;
+	int drdy_irq;
+
+	bool restore_mode;
+
+	struct ads1018_chan_data chan_data[ADS1018_CHANNELS_MAX];
+	const struct ads1018_chip_info *chip_info;
+
+	struct spi_message msg_read;
+	struct spi_transfer xfer;
+	__be16 tx_buf[2] __aligned(IIO_DMA_MINALIGN);
+	__be16 rx_buf[2];
+};
+
+#define ADS1018_VOLT_DIFF_CHAN(_addr, _chan, _chan2, _realbits) {		\
+	.type = IIO_VOLTAGE,							\
+	.channel = _chan,							\
+	.channel2 = _chan2,							\
+	.scan_index = _addr,							\
+	.scan_type = {								\
+		.sign = 's',							\
+		.realbits = _realbits,						\
+		.storagebits = 16,						\
+		.shift = 16 - _realbits,					\
+		.endianness = IIO_BE,						\
+	},									\
+	.info_mask_separate = BIT(IIO_CHAN_INFO_RAW) |				\
+			      BIT(IIO_CHAN_INFO_SCALE) |			\
+			      BIT(IIO_CHAN_INFO_SAMP_FREQ),			\
+	.info_mask_shared_by_type_available = BIT(IIO_CHAN_INFO_SCALE),		\
+	.info_mask_shared_by_all_available = BIT(IIO_CHAN_INFO_SAMP_FREQ),	\
+	.indexed = true,							\
+	.differential = true,							\
+}
+
+#define ADS1018_VOLT_CHAN(_addr, _chan, _realbits) {				\
+	.type = IIO_VOLTAGE,							\
+	.channel = _chan,							\
+	.scan_index = _addr,							\
+	.scan_type = {								\
+		.sign = 's',							\
+		.realbits = _realbits,						\
+		.storagebits = 16,						\
+		.shift = 16 - _realbits,					\
+		.endianness = IIO_BE,						\
+	},									\
+	.info_mask_separate = BIT(IIO_CHAN_INFO_RAW) |				\
+			      BIT(IIO_CHAN_INFO_SCALE) |			\
+			      BIT(IIO_CHAN_INFO_SAMP_FREQ),			\
+	.info_mask_shared_by_type_available = BIT(IIO_CHAN_INFO_SCALE),		\
+	.info_mask_shared_by_all_available = BIT(IIO_CHAN_INFO_SAMP_FREQ),	\
+	.indexed = true,							\
+}
+
+#define ADS1018_TEMP_CHAN(_addr, _realbits) {					\
+	.type = IIO_TEMP,							\
+	.channel = 0,								\
+	.scan_index = _addr,							\
+	.scan_type = {								\
+		.sign = 's',							\
+		.realbits = _realbits,						\
+		.storagebits = 16,						\
+		.shift = 16 - _realbits,					\
+		.endianness = IIO_BE,						\
+	},									\
+	.info_mask_separate = BIT(IIO_CHAN_INFO_RAW) |				\
+			      BIT(IIO_CHAN_INFO_SCALE) |			\
+			      BIT(IIO_CHAN_INFO_SAMP_FREQ),			\
+	.info_mask_shared_by_all_available = BIT(IIO_CHAN_INFO_SAMP_FREQ),	\
+}
+
+static const struct iio_chan_spec ads1118_iio_channels[] = {
+	ADS1018_VOLT_DIFF_CHAN(0, 0, 1, 16),
+	ADS1018_VOLT_DIFF_CHAN(1, 0, 3, 16),
+	ADS1018_VOLT_DIFF_CHAN(2, 1, 3, 16),
+	ADS1018_VOLT_DIFF_CHAN(3, 2, 3, 16),
+	ADS1018_VOLT_CHAN(4, 0, 16),
+	ADS1018_VOLT_CHAN(5, 1, 16),
+	ADS1018_VOLT_CHAN(6, 2, 16),
+	ADS1018_VOLT_CHAN(7, 3, 16),
+	ADS1018_TEMP_CHAN(8, 14),
+	IIO_CHAN_SOFT_TIMESTAMP(9),
+};
+
+static const struct iio_chan_spec ads1018_iio_channels[] = {
+	ADS1018_VOLT_DIFF_CHAN(0, 0, 1, 12),
+	ADS1018_VOLT_DIFF_CHAN(1, 0, 3, 12),
+	ADS1018_VOLT_DIFF_CHAN(2, 1, 3, 12),
+	ADS1018_VOLT_DIFF_CHAN(3, 2, 3, 12),
+	ADS1018_VOLT_CHAN(4, 0, 12),
+	ADS1018_VOLT_CHAN(5, 1, 12),
+	ADS1018_VOLT_CHAN(6, 2, 12),
+	ADS1018_VOLT_CHAN(7, 3, 12),
+	ADS1018_TEMP_CHAN(8, 12),
+	IIO_CHAN_SOFT_TIMESTAMP(9),
+};
+
+/**
+ * ads1018_get_data_rate_mode - Get current data-rate mode for a channel.
+ * @ad1018: Device data
+ * @address: Channel address
+ *
+ * Context: Expects iio_device_claim_direct() is held.
+ *
+ * Return: Current data-rate mode for the channel at @address.
+ */
+static u8 ads1018_get_data_rate_mode(struct ads1018 *ads1018, unsigned int address)
+{
+	return ads1018->chan_data[address].data_rate_mode;
+}
+
+/**
+ * ads1018_get_pga_mode - Get current PGA mode for a channel.
+ * @ad1018: Device data
+ * @address: Channel address
+ *
+ * Context: Expects iio_device_claim_direct() is held.
+ *
+ * Return: Current PGA mode for the channel at @address.
+ */
+static u8 ads1018_get_pga_mode(struct ads1018 *ads1018, unsigned int address)
+{
+	return ads1018->chan_data[address].pga_mode;
+}
+
+/**
+ * ads1018_set_data_rate_mode - Set a data-rate mode for a channel.
+ * @ad1018: Device data
+ * @address: Channel address
+ * @val: New data-rate mode for channel at @address.
+ *
+ * Context: Expects iio_device_claim_direct() is held.
+ *
+ * Lazily set a new data-rate mode for a channel.
+ */
+static void ads1018_set_data_rate_mode(struct ads1018 *ads1018, unsigned int address,
+				       u8 val)
+{
+	ads1018->chan_data[address].data_rate_mode = val;
+}
+
+/**
+ * ads1018_set_pga_mode - Set a PGA mode for a channel.
+ * @ad1018: Device data
+ * @address: Channel address
+ * @val: New PGA mode for channel at @address.
+ *
+ * Context: Expects iio_device_claim_direct() is held.
+ *
+ * Lazily set a new PGA mode for a channel.
+ */
+static void ads1018_set_pga_mode(struct ads1018 *ads1018, unsigned int address,
+				 u8 val)
+{
+	ads1018->chan_data[address].pga_mode = val;
+}
+
+/**
+ * ads1018_calc_delay - Calculates an appropriate delay for a single-shot
+ *			reading
+ * @ad1018: Device data
+ *
+ * Calculates an appropriate delay for a single shot reading, assuming the
+ * device's maximum data-rate is used.
+ *
+ * Context: Expects iio_device_claim_direct() is held.
+ *
+ * Return: Delay in microseconds.
+ */
+static unsigned long ads1018_calc_delay(struct ads1018 *ads1018)
+{
+	const struct ads1018_chip_info *chip_info = ads1018->chip_info;
+	unsigned long max_drate_mode = chip_info->num_data_rate_mode_to_hz - 1;
+	unsigned int hz = chip_info->data_rate_mode_to_hz[max_drate_mode];
+
+	/* We subtract 10% data-rate error */
+	hz -= DIV_ROUND_UP(hz, 10);
+
+	/* Calculate time per sample in microseconds */
+	return DIV_ROUND_UP(MICROHZ_PER_HZ, hz);
+}
+
+/**
+ * ads1018_read_unlocked - Reads a conversion value from the device
+ * @ad1018: Device data
+ * @cnv: ADC Conversion value
+ * @hold_cs: Keep CS line asserted after the SPI transfer
+ *
+ * Reads the most recent ADC conversion value, without updating the
+ * device's configuration.
+ *
+ * Context: Expects spi_bus_lock() is held.
+ *
+ * Return: 0 on success, negative errno on error.
+ */
+static int ads1018_read_unlocked(struct ads1018 *ads1018, __be16 *cnv, bool hold_cs)
+{
+	int ret;
+
+	ads1018->xfer.cs_change = hold_cs;
+
+	ret = spi_sync_locked(ads1018->spi, &ads1018->msg_read);
+	if (ret)
+		return ret;
+
+	if (cnv)
+		*cnv = ads1018->rx_buf[0];
+
+	return 0;
+}
+
+/**
+ * ads1018_oneshot - Performs a one-shot reading sequence
+ * @ad1018: Device data
+ * @cfg: New configuration for the device
+ * @cnv: Conversion value
+ *
+ * Writes a new configuration, waits an appropriate delay (assuming the new
+ * configuration uses the maximum data-rate) and then reads the most recent
+ * conversion.
+ *
+ * Context: Expects iio_device_claim_direct() is held.
+ *
+ * Return: 0 on success, negative errno on error.
+ */
+static int ads1018_oneshot(struct ads1018 *ads1018, u16 cfg, u16 *cnv)
+{
+	struct spi_transfer xfer[2] = {
+		{
+			.tx_buf = ads1018->tx_buf,
+			.len = sizeof(ads1018->tx_buf),
+			.delay = {
+				.value = ads1018_calc_delay(ads1018),
+				.unit = SPI_DELAY_UNIT_USECS,
+			},
+		},
+		{
+			.rx_buf = ads1018->rx_buf,
+			.len = sizeof(ads1018->rx_buf),
+		},
+	};
+	int ret;
+
+	ads1018->tx_buf[0] = cpu_to_be16(cfg);
+	ads1018->tx_buf[1] = 0;
+
+	ret = spi_sync_transfer(ads1018->spi, xfer, ARRAY_SIZE(xfer));
+	if (ret)
+		return ret;
+
+	*cnv = be16_to_cpu(ads1018->rx_buf[0]);
+
+	return 0;
+}
+
+static int
+ads1018_read_raw_unlocked(struct iio_dev *indio_dev, struct iio_chan_spec const *chan,
+			  int *val, int *val2, long mask)
+{
+	struct ads1018 *ads1018 = iio_priv(indio_dev);
+	const struct ads1018_chip_info *chip_info = ads1018->chip_info;
+	u8 drate_mode = ads1018_get_data_rate_mode(ads1018, chan->scan_index);
+	u8 pga_mode = ads1018_get_pga_mode(ads1018, chan->scan_index);
+	u8 max_drate_mode = chip_info->num_data_rate_mode_to_hz - 1;
+	u16 cnv, cfg;
+	int ret;
+
+	switch (mask) {
+	case IIO_CHAN_INFO_RAW:
+		cfg = ADS1018_CFG_VALID | ADS1018_CFG_OS_TRIG;
+		cfg |= FIELD_PREP(ADS1018_CFG_MUX_MASK, chan->scan_index);
+		cfg |= FIELD_PREP(ADS1018_CFG_PGA_MASK, pga_mode);
+		cfg |= FIELD_PREP(ADS1018_CFG_MODE_MASK, ADS1018_MODE_ONESHOT);
+		cfg |= FIELD_PREP(ADS1018_CFG_DRATE_MASK, max_drate_mode);
+
+		if (chan->type == IIO_TEMP)
+			cfg |= ADS1018_CFG_TS_MODE_EN;
+
+		ret = ads1018_oneshot(ads1018, cfg, &cnv);
+		if (ret)
+			return ret;
+
+		cnv >>= chan->scan_type.shift;
+		*val = sign_extend32(cnv, chan->scan_type.realbits - 1);
+
+		return IIO_VAL_INT;
+
+	case IIO_CHAN_INFO_SCALE:
+		switch (chan->type) {
+		case IIO_VOLTAGE:
+			*val = chip_info->pga_mode_to_gain[pga_mode][0];
+			*val2 = chip_info->pga_mode_to_gain[pga_mode][1];
+			return IIO_VAL_INT_PLUS_NANO;
+
+		case IIO_TEMP:
+			*val = chip_info->temp_scale[0];
+			*val2 = chip_info->temp_scale[1];
+			return IIO_VAL_INT_PLUS_MICRO;
+
+		default:
+			return -EOPNOTSUPP;
+		}
+
+	case IIO_CHAN_INFO_SAMP_FREQ:
+		*val = chip_info->data_rate_mode_to_hz[drate_mode];
+		return IIO_VAL_INT;
+
+	default:
+		return -EOPNOTSUPP;
+	}
+}
+
+static int
+ads1018_read_raw(struct iio_dev *indio_dev, struct iio_chan_spec const *chan,
+		 int *val, int *val2, long mask)
+{
+	int ret;
+
+	if (!iio_device_claim_direct(indio_dev))
+		return -EBUSY;
+	ret = ads1018_read_raw_unlocked(indio_dev, chan, val, val2, mask);
+	iio_device_release_direct(indio_dev);
+
+	return ret;
+}
+
+static int
+ads1018_read_avail(struct iio_dev *indio_dev, struct iio_chan_spec const *chan,
+		   const int **vals, int *type, int *length, long mask)
+{
+	struct ads1018 *ads1018 = iio_priv(indio_dev);
+
+	switch (mask) {
+	case IIO_CHAN_INFO_SCALE:
+		*type = IIO_VAL_INT_PLUS_NANO;
+		*vals = (const int *)ads1018->chip_info->pga_mode_to_gain;
+		*length = ads1018->chip_info->num_pga_mode_to_gain * 2;
+		return IIO_AVAIL_LIST;
+
+	case IIO_CHAN_INFO_SAMP_FREQ:
+		*type = IIO_VAL_INT;
+		*vals = ads1018->chip_info->data_rate_mode_to_hz;
+		*length = ads1018->chip_info->num_data_rate_mode_to_hz;
+		return IIO_AVAIL_LIST;
+
+	default:
+		return -EOPNOTSUPP;
+	}
+}
+
+static int
+ads1018_write_raw_unlocked(struct iio_dev *indio_dev, struct iio_chan_spec const *chan,
+			   int val, int val2, long mask)
+{
+	struct ads1018 *ads1018 = iio_priv(indio_dev);
+	const struct ads1018_chip_info *info = ads1018->chip_info;
+	unsigned int i;
+
+	switch (mask) {
+	case IIO_CHAN_INFO_SCALE:
+		for (i = 0; i < info->num_pga_mode_to_gain; i++) {
+			if (val == info->pga_mode_to_gain[i][0] &&
+			    val2 == info->pga_mode_to_gain[i][1])
+				break;
+		}
+
+		if (i == info->num_pga_mode_to_gain)
+			return -EINVAL;
+
+		ads1018_set_pga_mode(ads1018, chan->scan_index, i);
+		return 0;
+
+	case IIO_CHAN_INFO_SAMP_FREQ:
+		for (i = 0; i < info->num_data_rate_mode_to_hz; i++) {
+			if (val == info->data_rate_mode_to_hz[i])
+				break;
+		}
+
+		if (i == info->num_data_rate_mode_to_hz)
+			return -EINVAL;
+
+		ads1018_set_data_rate_mode(ads1018, chan->scan_index, i);
+		return 0;
+
+	default:
+		return -EOPNOTSUPP;
+	}
+}
+
+static int
+ads1018_write_raw(struct iio_dev *indio_dev, struct iio_chan_spec const *chan,
+		  int val, int val2, long mask)
+{
+	int ret;
+
+	if (!iio_device_claim_direct(indio_dev))
+		return -EBUSY;
+	ret = ads1018_write_raw_unlocked(indio_dev, chan, val, val2, mask);
+	iio_device_release_direct(indio_dev);
+
+	return ret;
+}
+
+static int
+ads1018_write_raw_get_fmt(struct iio_dev *indio_dev,
+			  struct iio_chan_spec const *chan, long mask)
+{
+	switch (mask) {
+	case IIO_CHAN_INFO_SCALE:
+		return IIO_VAL_INT_PLUS_NANO;
+	default:
+		return IIO_VAL_INT_PLUS_MICRO;
+	}
+}
+
+static const struct iio_info ads1018_iio_info = {
+	.read_raw = ads1018_read_raw,
+	.read_avail = ads1018_read_avail,
+	.write_raw = ads1018_write_raw,
+	.write_raw_get_fmt = ads1018_write_raw_get_fmt,
+};
+
+static void ads1018_set_trigger_enable(struct ads1018 *ads1018)
+{
+	spi_bus_lock(ads1018->spi->controller);
+	ads1018_read_unlocked(ads1018, NULL, true);
+	enable_irq(ads1018->drdy_irq);
+}
+
+static void ads1018_set_trigger_disable(struct ads1018 *ads1018)
+{
+	disable_irq(ads1018->drdy_irq);
+	ads1018_read_unlocked(ads1018, NULL, false);
+	spi_bus_unlock(ads1018->spi->controller);
+}
+
+static int ads1018_set_trigger_state(struct iio_trigger *trig, bool state)
+{
+	struct ads1018 *ads1018 = iio_trigger_get_drvdata(trig);
+
+	/*
+	 * We need to lock the SPI bus and tie CS low (hold_cs) to catch
+	 * data-ready interrupts, otherwise the MISO line enters a Hi-Z state.
+	 */
+
+	if (state)
+		ads1018_set_trigger_enable(ads1018);
+	else
+		ads1018_set_trigger_disable(ads1018);
+
+	return 0;
+}
+
+static const struct iio_trigger_ops ads1018_trigger_ops = {
+	.set_trigger_state = ads1018_set_trigger_state,
+	.validate_device = iio_trigger_validate_own_device,
+};
+
+static int ads1018_buffer_preenable(struct iio_dev *indio_dev)
+{
+	struct ads1018 *ads1018 = iio_priv(indio_dev);
+	const struct ads1018_chip_info *chip_info = ads1018->chip_info;
+	unsigned int pga, drate, addr;
+	u16 cfg;
+
+	addr = find_first_bit(indio_dev->active_scan_mask, iio_get_masklength(indio_dev));
+	pga = ads1018_get_pga_mode(ads1018, addr);
+	drate = ads1018_get_data_rate_mode(ads1018, addr);
+
+	cfg = ADS1018_CFG_VALID;
+	cfg |= FIELD_PREP(ADS1018_CFG_MUX_MASK, addr);
+	cfg |= FIELD_PREP(ADS1018_CFG_PGA_MASK, pga);
+	cfg |= FIELD_PREP(ADS1018_CFG_MODE_MASK, ADS1018_MODE_CONTINUOUS);
+	cfg |= FIELD_PREP(ADS1018_CFG_DRATE_MASK, drate);
+
+	if (chip_info->channels[addr].type == IIO_TEMP)
+		cfg |= ADS1018_CFG_TS_MODE_EN;
+
+	ads1018->tx_buf[0] = cpu_to_be16(cfg);
+	ads1018->tx_buf[1] = 0;
+
+	return spi_write(ads1018->spi, ads1018->tx_buf, sizeof(ads1018->tx_buf));
+}
+
+static int ads1018_buffer_postdisable(struct iio_dev *indio_dev)
+{
+	struct ads1018 *ads1018 = iio_priv(indio_dev);
+
+	ads1018->tx_buf[0] = cpu_to_be16(ADS1018_CFG_DEFAULT);
+	ads1018->tx_buf[1] = 0;
+
+	return spi_write(ads1018->spi, ads1018->tx_buf, sizeof(ads1018->tx_buf));
+}
+
+static const struct iio_buffer_setup_ops ads1018_buffer_ops = {
+	.preenable = ads1018_buffer_preenable,
+	.postdisable = ads1018_buffer_postdisable,
+	.validate_scan_mask = iio_validate_scan_mask_onehot,
+};
+
+static irqreturn_t ads1018_irq_handler(int irq, void *dev_id)
+{
+	struct ads1018 *ads1018 = dev_id;
+
+	/*
+	 * We need to check if the "drdy" pin is actually active or if it's a
+	 * pending interrupt triggered by the SPI transfer.
+	 */
+	if (ads1018->drdy_gpiod && !gpiod_get_value(ads1018->drdy_gpiod))
+		return IRQ_HANDLED;
+
+	iio_trigger_poll(ads1018->indio_trig);
+
+	return IRQ_HANDLED;
+}
+
+static irqreturn_t ads1018_trigger_handler(int irq, void *p)
+{
+	struct iio_poll_func *pf = p;
+	struct iio_dev *indio_dev = pf->indio_dev;
+	struct ads1018 *ads1018 = iio_priv(indio_dev);
+	struct {
+		__be16 conv;
+		aligned_s64 ts;
+	} scan = {};
+	int ret;
+
+	if (iio_device_claim_buffer_mode(indio_dev))
+		goto out_notify_done;
+
+	if (iio_trigger_using_own(indio_dev)) {
+		disable_irq(ads1018->drdy_irq);
+		ret = ads1018_read_unlocked(ads1018, &scan.conv, true);
+		enable_irq(ads1018->drdy_irq);
+	} else {
+		ret = spi_read(ads1018->spi, ads1018->rx_buf, sizeof(ads1018->rx_buf));
+		scan.conv = ads1018->rx_buf[0];
+	}
+
+	iio_device_release_buffer_mode(indio_dev);
+
+	if (ret)
+		goto out_notify_done;
+
+	iio_push_to_buffers_with_ts(indio_dev, &scan, sizeof(scan), pf->timestamp);
+
+out_notify_done:
+	iio_trigger_notify_done(ads1018->indio_trig);
+
+	return IRQ_HANDLED;
+}
+
+static int ads1018_trigger_setup(struct iio_dev *indio_dev)
+{
+	struct ads1018 *ads1018 = iio_priv(indio_dev);
+	struct spi_device *spi = ads1018->spi;
+	struct device *dev = &spi->dev;
+	const char *con_id = "drdy";
+	int ret;
+
+	ads1018->drdy_gpiod = devm_gpiod_get_optional(dev, con_id, GPIOD_IN);
+	if (IS_ERR(ads1018->drdy_gpiod))
+		return dev_err_probe(dev, PTR_ERR(ads1018->drdy_gpiod),
+				     "Failed to get %s GPIO.\n", con_id);
+
+	/* First try to get IRQ from SPI core, then from GPIO */
+	if (spi->irq > 0)
+		ads1018->drdy_irq = spi->irq;
+	else if (ads1018->drdy_gpiod)
+		ads1018->drdy_irq = gpiod_to_irq(ads1018->drdy_gpiod);
+	if (ads1018->drdy_irq < 0)
+		return dev_err_probe(dev, ads1018->drdy_irq,
+				     "Failed to get IRQ from %s GPIO.\n", con_id);
+
+	/* An IRQ line is only an optional requirement for the IIO trigger */
+	if (ads1018->drdy_irq == 0)
+		return 0;
+
+	ads1018->indio_trig = devm_iio_trigger_alloc(dev, "%s-dev%d-drdy", indio_dev->name,
+						     iio_device_id(indio_dev));
+	if (!ads1018->indio_trig)
+		return -ENOMEM;
+
+	iio_trigger_set_drvdata(ads1018->indio_trig, ads1018);
+	ads1018->indio_trig->ops = &ads1018_trigger_ops;
+
+	ret = devm_iio_trigger_register(dev, ads1018->indio_trig);
+	if (ret)
+		return ret;
+
+	/*
+	 * The "data-ready" IRQ line is shared with the MOSI pin, thus we need
+	 * to keep it disabled until we actually request data.
+	 */
+	return devm_request_irq(dev, ads1018->drdy_irq, ads1018_irq_handler,
+				IRQF_NO_AUTOEN, ads1018->chip_info->name, ads1018);
+}
+
+static int ads1018_spi_probe(struct spi_device *spi)
+{
+	const struct ads1018_chip_info *info = spi_get_device_match_data(spi);
+	struct iio_dev *indio_dev;
+	struct ads1018 *ads1018;
+	int ret;
+
+	indio_dev = devm_iio_device_alloc(&spi->dev, sizeof(*ads1018));
+	if (!indio_dev)
+		return -ENOMEM;
+
+	ads1018 = iio_priv(indio_dev);
+	ads1018->spi = spi;
+	ads1018->chip_info = info;
+	spi_set_drvdata(spi, ads1018);
+
+	indio_dev->modes = INDIO_DIRECT_MODE;
+	indio_dev->name = info->name;
+	indio_dev->info = &ads1018_iio_info;
+	indio_dev->channels = info->channels;
+	indio_dev->num_channels = info->num_channels;
+
+	for (unsigned int i = 0; i < ADS1018_CHANNELS_MAX; i++) {
+		ads1018->chan_data[i].data_rate_mode = ADS1018_DRATE_DEFAULT;
+		ads1018->chan_data[i].pga_mode = ADS1018_PGA_DEFAULT;
+	}
+
+	ads1018->xfer.rx_buf = ads1018->rx_buf;
+	ads1018->xfer.len = sizeof(ads1018->rx_buf);
+	spi_message_init_with_transfers(&ads1018->msg_read, &ads1018->xfer, 1);
+
+	ret = ads1018_trigger_setup(indio_dev);
+	if (ret)
+		return ret;
+
+	ret = devm_iio_triggered_buffer_setup(&spi->dev, indio_dev, iio_pollfunc_store_time,
+					      ads1018_trigger_handler, &ads1018_buffer_ops);
+	if (ret)
+		return ret;
+
+	return devm_iio_device_register(&spi->dev, indio_dev);
+}
+
+/**
+ * ADS1018_FSR_TO_SCALE - Converts FSR into scale
+ * @_fsr: Full-scale range in millivolts
+ * @_res: ADC resolution
+ *
+ * Return: Scale in IIO_VAL_INT_PLUS_NANO format
+ */
+#define ADS1018_FSR_TO_SCALE(_fsr, _res) \
+	{ 0, ((_fsr) * (MICRO >> 6)) / BIT((_res) - 6) }
+
+static const unsigned int ads1018_gain_table[][2] = {
+	ADS1018_FSR_TO_SCALE(6144, 11),
+	ADS1018_FSR_TO_SCALE(4096, 11),
+	ADS1018_FSR_TO_SCALE(2048, 11),
+	ADS1018_FSR_TO_SCALE(1024, 11),
+	ADS1018_FSR_TO_SCALE(512, 11),
+	ADS1018_FSR_TO_SCALE(256, 11),
+};
+
+static const unsigned int ads1118_gain_table[][2] = {
+	ADS1018_FSR_TO_SCALE(6144, 15),
+	ADS1018_FSR_TO_SCALE(4096, 15),
+	ADS1018_FSR_TO_SCALE(2048, 15),
+	ADS1018_FSR_TO_SCALE(1024, 15),
+	ADS1018_FSR_TO_SCALE(512, 15),
+	ADS1018_FSR_TO_SCALE(256, 15),
+};
+
+static const unsigned int ads1018_data_rate_table[] = {
+	128, 250, 490, 920, 1600, 2400, 3300,
+};
+
+static const unsigned int ads1118_data_rate_table[] = {
+	8, 16, 32, 64, 128, 250, 475, 860,
+};
+
+static const struct ads1018_chip_info ads1018_chip_info = {
+	.name = "ads1018",
+
+	.channels = ads1018_iio_channels,
+	.num_channels = ARRAY_SIZE(ads1018_iio_channels),
+
+	.pga_mode_to_gain = ads1018_gain_table,
+	.num_pga_mode_to_gain = ARRAY_SIZE(ads1018_gain_table),
+
+	.data_rate_mode_to_hz = ads1018_data_rate_table,
+	.num_data_rate_mode_to_hz = ARRAY_SIZE(ads1018_data_rate_table),
+
+	.temp_scale = { 0, 125000 },
+};
+
+static const struct ads1018_chip_info ads1118_chip_info = {
+	.name = "ads1118",
+
+	.channels = ads1118_iio_channels,
+	.num_channels = ARRAY_SIZE(ads1118_iio_channels),
+
+	.pga_mode_to_gain = ads1118_gain_table,
+	.num_pga_mode_to_gain = ARRAY_SIZE(ads1118_gain_table),
+
+	.data_rate_mode_to_hz = ads1118_data_rate_table,
+	.num_data_rate_mode_to_hz = ARRAY_SIZE(ads1118_data_rate_table),
+
+	.temp_scale = { 0, 31250 },
+};
+
+static const struct of_device_id ads1018_of_match[] = {
+	{ .compatible = "ti,ads1018", .data = &ads1018_chip_info },
+	{ .compatible = "ti,ads1118", .data = &ads1118_chip_info },
+	{ }
+};
+MODULE_DEVICE_TABLE(of, ads1018_of_match);
+
+static const struct spi_device_id ads1018_spi_match[] = {
+	{ "ads1018", (kernel_ulong_t)&ads1018_chip_info },
+	{ "ads1118", (kernel_ulong_t)&ads1118_chip_info },
+	{ }
+};
+MODULE_DEVICE_TABLE(spi, ads1018_spi_match);
+
+static struct spi_driver ads1018_spi_driver = {
+	.driver = {
+		.name = "ads1018",
+		.of_match_table = ads1018_of_match,
+	},
+	.probe = ads1018_spi_probe,
+	.id_table = ads1018_spi_match,
+};
+
+module_spi_driver(ads1018_spi_driver);
+
+MODULE_DESCRIPTION("Texas Instruments ADS1018 ADC Driver");
+MODULE_LICENSE("GPL");
+MODULE_AUTHOR("Kurt Borja <kuurtb@gmail.com>");

-- 
2.52.0
Re: [PATCH v3 2/2] iio: adc: Add ti-ads1018 driver
Posted by kernel test robot 2 days, 4 hours ago
Hi Kurt,

kernel test robot noticed the following build warnings:

[auto build test WARNING on f9e05791642810a0cf6237d39fafd6fec5e0b4bb]

url:    https://github.com/intel-lab-lkp/linux/commits/Kurt-Borja/dt-bindings-iio-adc-Add-TI-ADS1018-ADS1118/20251129-120153
base:   f9e05791642810a0cf6237d39fafd6fec5e0b4bb
patch link:    https://lore.kernel.org/r/20251128-ads1x18-v3-2-a6ebab815b2d%40gmail.com
patch subject: [PATCH v3 2/2] iio: adc: Add ti-ads1018 driver
config: loongarch-allmodconfig (https://download.01.org/0day-ci/archive/20251130/202511300040.bsFH07WD-lkp@intel.com/config)
compiler: clang version 19.1.7 (https://github.com/llvm/llvm-project cd708029e0b2869e80abe31ddb175f7c35361f90)
reproduce (this is a W=1 build): (https://download.01.org/0day-ci/archive/20251130/202511300040.bsFH07WD-lkp@intel.com/reproduce)

If you fix the issue in a separate patch/commit (i.e. not just a new version of
the same patch/commit), kindly add following tags
| Reported-by: kernel test robot <lkp@intel.com>
| Closes: https://lore.kernel.org/oe-kbuild-all/202511300040.bsFH07WD-lkp@intel.com/

All warnings (new ones prefixed by >>):

>> Warning: drivers/iio/adc/ti-ads1018.c:183 function parameter 'ads1018' not described in 'ads1018_get_data_rate_mode'
>> Warning: drivers/iio/adc/ti-ads1018.c:197 function parameter 'ads1018' not described in 'ads1018_get_pga_mode'
>> Warning: drivers/iio/adc/ti-ads1018.c:213 function parameter 'ads1018' not described in 'ads1018_set_data_rate_mode'
>> Warning: drivers/iio/adc/ti-ads1018.c:229 function parameter 'ads1018' not described in 'ads1018_set_pga_mode'
>> Warning: drivers/iio/adc/ti-ads1018.c:246 function parameter 'ads1018' not described in 'ads1018_calc_delay'
>> Warning: drivers/iio/adc/ti-ads1018.c:272 function parameter 'ads1018' not described in 'ads1018_read_unlocked'
>> Warning: drivers/iio/adc/ti-ads1018.c:302 function parameter 'ads1018' not described in 'ads1018_oneshot'

-- 
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki
Re: [PATCH v3 2/2] iio: adc: Add ti-ads1018 driver
Posted by Andy Shevchenko 2 days, 7 hours ago
On Fri, Nov 28, 2025 at 10:47:13PM -0500, Kurt Borja wrote:
> Add ti-ads1018 driver for Texas Instruments ADS1018 and ADS1118 SPI
> analog-to-digital converters.
> 
> These chips' MOSI pin is shared with a data-ready interrupt. Defining
> this interrupt in devicetree is optional, therefore we only create an
> IIO trigger if one is found.
> 
> Handling this interrupt requires some considerations. When enabling the
> trigger the CS line is tied low (active), thus we need to hold
> spi_bus_lock() too, to avoid state corruption. This is done inside the
> set_trigger_state() callback, to let users use other triggers without
> wasting a bus lock.

Thank you for the update, my comments below.

...

> +#include <linux/array_size.h>
> +#include <linux/bitfield.h>
> +#include <linux/bitmap.h>

> +#include <linux/byteorder/generic.h>

Must be asm/byteorder.h after the linux/* generic group...

> +#include <linux/dev_printk.h>
> +#include <linux/gpio/consumer.h>
> +#include <linux/interrupt.h>
> +#include <linux/math.h>
> +#include <linux/mod_devicetable.h>
> +#include <linux/module.h>
> +#include <linux/spi/spi.h>
> +#include <linux/types.h>
> +#include <linux/units.h>
> +

...here

#include <asm/byteorder.h>
+ blank line.

...

> +static void ads1018_set_data_rate_mode(struct ads1018 *ads1018, unsigned int address,
> +				       u8 val)

It's a bit too long.

static void ads1018_set_data_rate_mode(struct ads1018 *ads1018,
				       unsigned int address, u8 val)

...

> +static void ads1018_set_pga_mode(struct ads1018 *ads1018, unsigned int address,
> +				 u8 val)

This is not so, but I would resplit logically, either

static void ads1018_set_pga_mode(struct ads1018 *ads1018, unsigned int address, u8 val)

(however it's significantly longer than 80 limit)

OR

static void ads1018_set_pga_mode(struct ads1018 *ads1018,
				 unsigned int address, u8 val)

(better and consistent with the above).

...

> +/**
> + * ads1018_calc_delay - Calculates an appropriate delay for a single-shot
> + *			reading

Having this on a single line is fine I suppose.

> + * @ad1018: Device data
> + *
> + * Calculates an appropriate delay for a single shot reading, assuming the
> + * device's maximum data-rate is used.
> + *
> + * Context: Expects iio_device_claim_direct() is held.
> + *
> + * Return: Delay in microseconds.

Does 0 have any special meaning?

> + */

...

> +	/* We subtract 10% data-rate error */
> +	hz -= DIV_ROUND_UP(hz, 10);

Hmm... For delays I expect to see adding 10% to have a good margin.

...

> + * Context: Expects spi_bus_lock() is held.

Do we have a lockdep assert for this?

...

> +static int ads1018_read_unlocked(struct ads1018 *ads1018, __be16 *cnv, bool hold_cs)

Hmm... Don't we want to return value in CPU order? I don't know the answer
here, and IIRC IIO triggers might be actually good with endianess conversion
done, if required, in user space.

...

> + * Context: Expects iio_device_claim_direct() is held.

Jonathan et al., do we have lockdep assert available for this?
I really prefer to see the code for it, while comment is good,
it is not good enough.

...

> +static int
> +ads1018_write_raw_unlocked(struct iio_dev *indio_dev, struct iio_chan_spec const *chan,
> +			   int val, int val2, long mask)
> +{
> +	struct ads1018 *ads1018 = iio_priv(indio_dev);
> +	const struct ads1018_chip_info *info = ads1018->chip_info;
> +	unsigned int i;
> +
> +	switch (mask) {
> +	case IIO_CHAN_INFO_SCALE:
> +		for (i = 0; i < info->num_pga_mode_to_gain; i++) {
> +			if (val == info->pga_mode_to_gain[i][0] &&
> +			    val2 == info->pga_mode_to_gain[i][1])
> +				break;
> +		}

> +

You can remove this blank line as the condition is tighten with the for-loop.
But up to you, I'm fine with either.

> +		if (i == info->num_pga_mode_to_gain)
> +			return -EINVAL;
> +
> +		ads1018_set_pga_mode(ads1018, chan->scan_index, i);
> +		return 0;
> +
> +	case IIO_CHAN_INFO_SAMP_FREQ:
> +		for (i = 0; i < info->num_data_rate_mode_to_hz; i++) {
> +			if (val == info->data_rate_mode_to_hz[i])
> +				break;
> +		}

> +

Ditto.

> +		if (i == info->num_data_rate_mode_to_hz)
> +			return -EINVAL;
> +
> +		ads1018_set_data_rate_mode(ads1018, chan->scan_index, i);
> +		return 0;
> +
> +	default:
> +		return -EOPNOTSUPP;
> +	}
> +}

...

> +	if (iio_device_claim_buffer_mode(indio_dev))
> +		goto out_notify_done;
> +
> +	if (iio_trigger_using_own(indio_dev)) {
> +		disable_irq(ads1018->drdy_irq);
> +		ret = ads1018_read_unlocked(ads1018, &scan.conv, true);
> +		enable_irq(ads1018->drdy_irq);
> +	} else {
> +		ret = spi_read(ads1018->spi, ads1018->rx_buf, sizeof(ads1018->rx_buf));
> +		scan.conv = ads1018->rx_buf[0];
> +	}
> +
> +	iio_device_release_buffer_mode(indio_dev);
> +
> +	if (ret)
> +		goto out_notify_done;
> +
> +	iio_push_to_buffers_with_ts(indio_dev, &scan, sizeof(scan), pf->timestamp);
> +
> +out_notify_done:
> +	iio_trigger_notify_done(ads1018->indio_trig);

Jonathan et al., maybe we need an ACQUIRE() class for this? It will solve
the conditional scoped guard case, no?

...

> +static int ads1018_trigger_setup(struct iio_dev *indio_dev)
> +{
> +	struct ads1018 *ads1018 = iio_priv(indio_dev);
> +	struct spi_device *spi = ads1018->spi;
> +	struct device *dev = &spi->dev;
> +	const char *con_id = "drdy";
> +	int ret;
> +
> +	ads1018->drdy_gpiod = devm_gpiod_get_optional(dev, con_id, GPIOD_IN);
> +	if (IS_ERR(ads1018->drdy_gpiod))
> +		return dev_err_probe(dev, PTR_ERR(ads1018->drdy_gpiod),
> +				     "Failed to get %s GPIO.\n", con_id);
> +
> +	/* First try to get IRQ from SPI core, then from GPIO */
> +	if (spi->irq > 0)
> +		ads1018->drdy_irq = spi->irq;
> +	else if (ads1018->drdy_gpiod)
> +		ads1018->drdy_irq = gpiod_to_irq(ads1018->drdy_gpiod);
> +	if (ads1018->drdy_irq < 0)
> +		return dev_err_probe(dev, ads1018->drdy_irq,
> +				     "Failed to get IRQ from %s GPIO.\n", con_id);
> +
> +	/* An IRQ line is only an optional requirement for the IIO trigger */
> +	if (ads1018->drdy_irq == 0)
> +		return 0;
> +
> +	ads1018->indio_trig = devm_iio_trigger_alloc(dev, "%s-dev%d-drdy", indio_dev->name,
> +						     iio_device_id(indio_dev));

	ads1018->indio_trig = devm_iio_trigger_alloc(dev, "%s-dev%d-%s",
						     indio_dev->name,
						     iio_device_id(indio_dev),
						     con_id);

This also will be kept below 80 limit.

> +	if (!ads1018->indio_trig)
> +		return -ENOMEM;
> +
> +	iio_trigger_set_drvdata(ads1018->indio_trig, ads1018);
> +	ads1018->indio_trig->ops = &ads1018_trigger_ops;
> +
> +	ret = devm_iio_trigger_register(dev, ads1018->indio_trig);
> +	if (ret)
> +		return ret;
> +
> +	/*
> +	 * The "data-ready" IRQ line is shared with the MOSI pin, thus we need
> +	 * to keep it disabled until we actually request data.
> +	 */
> +	return devm_request_irq(dev, ads1018->drdy_irq, ads1018_irq_handler,
> +				IRQF_NO_AUTOEN, ads1018->chip_info->name, ads1018);
> +}

...

> +static int ads1018_spi_probe(struct spi_device *spi)
> +{
> +	const struct ads1018_chip_info *info = spi_get_device_match_data(spi);

	struct device *dev = &spi->dev;

> +	struct iio_dev *indio_dev;
> +	struct ads1018 *ads1018;
> +	int ret;
> +
> +	indio_dev = devm_iio_device_alloc(&spi->dev, sizeof(*ads1018));
> +	if (!indio_dev)
> +		return -ENOMEM;
> +
> +	ads1018 = iio_priv(indio_dev);
> +	ads1018->spi = spi;
> +	ads1018->chip_info = info;
> +	spi_set_drvdata(spi, ads1018);
> +
> +	indio_dev->modes = INDIO_DIRECT_MODE;
> +	indio_dev->name = info->name;
> +	indio_dev->info = &ads1018_iio_info;
> +	indio_dev->channels = info->channels;
> +	indio_dev->num_channels = info->num_channels;
> +
> +	for (unsigned int i = 0; i < ADS1018_CHANNELS_MAX; i++) {
> +		ads1018->chan_data[i].data_rate_mode = ADS1018_DRATE_DEFAULT;
> +		ads1018->chan_data[i].pga_mode = ADS1018_PGA_DEFAULT;
> +	}
> +
> +	ads1018->xfer.rx_buf = ads1018->rx_buf;
> +	ads1018->xfer.len = sizeof(ads1018->rx_buf);
> +	spi_message_init_with_transfers(&ads1018->msg_read, &ads1018->xfer, 1);
> +
> +	ret = ads1018_trigger_setup(indio_dev);
> +	if (ret)
> +		return ret;

> +	ret = devm_iio_triggered_buffer_setup(&spi->dev, indio_dev, iio_pollfunc_store_time,
> +					      ads1018_trigger_handler, &ads1018_buffer_ops);

Too long. With the above done

	ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
					      iio_pollfunc_store_time,
					      ads1018_trigger_handler,
					      &ads1018_buffer_ops);

> +	if (ret)
> +		return ret;
> +
> +	return devm_iio_device_register(&spi->dev, indio_dev);
> +}

...

> +/**
> + * ADS1018_FSR_TO_SCALE - Converts FSR into scale
> + * @_fsr: Full-scale range in millivolts
> + * @_res: ADC resolution

Add here something like this:

*
* The macro is crafted to avoid potential overflows on 32-bit machines.
* This imposes restrictions to the possible values for @_fsr (less
* than 274878), and @_res (great or equal to 6 bits).
*

> + * Return: Scale in IIO_VAL_INT_PLUS_NANO format
> + */
> +#define ADS1018_FSR_TO_SCALE(_fsr, _res) \
> +	{ 0, ((_fsr) * (MICRO >> 6)) / BIT((_res) - 6) }

-- 
With Best Regards,
Andy Shevchenko
Re: [PATCH v3 2/2] iio: adc: Add ti-ads1018 driver
Posted by Kurt Borja 1 day, 17 hours ago
On Sat Nov 29, 2025 at 9:21 AM -05, Andy Shevchenko wrote:

...

>> + * @ad1018: Device data
>> + *
>> + * Calculates an appropriate delay for a single shot reading, assuming the
>> + * device's maximum data-rate is used.
>> + *
>> + * Context: Expects iio_device_claim_direct() is held.
>> + *
>> + * Return: Delay in microseconds.
>
> Does 0 have any special meaning?

This function is never 0.

...

>> +	/* We subtract 10% data-rate error */
>> +	hz -= DIV_ROUND_UP(hz, 10);
>
> Hmm... For delays I expect to see adding 10% to have a good margin.

hz goes in the denomitor bellow, so less hz is more delay. Makes sense
because worst case sample rate is less sample rate.

...

>> + * Context: Expects spi_bus_lock() is held.
>
> Do we have a lockdep assert for this?

Lockdep checks lock is held on the same thread right?

Thinking about it, this context is wrong because we don't hold the bus
lock on the same thread. Rather we hold it to avoid other devices from
transfering while we hold our CS line.

I should probably remove this context and mention this peculiarity in
the long description.

...

>> +static int ads1018_read_unlocked(struct ads1018 *ads1018, __be16 *cnv, bool hold_cs)
>
> Hmm... Don't we want to return value in CPU order? I don't know the answer
> here, and IIRC IIO triggers might be actually good with endianess conversion
> done, if required, in user space.

I specified IIO_BE endianness in each channel's .scan_type, so this
works. However, I don't have issue especifying IIO_CPU and just
returning CPU order values.

...

>> + * Context: Expects iio_device_claim_direct() is held.
>
> Jonathan et al., do we have lockdep assert available for this?
> I really prefer to see the code for it, while comment is good,
> it is not good enough.

This would be nice.

...

>> +	if (iio_device_claim_buffer_mode(indio_dev))
>> +		goto out_notify_done;
>> +
>> +	if (iio_trigger_using_own(indio_dev)) {
>> +		disable_irq(ads1018->drdy_irq);
>> +		ret = ads1018_read_unlocked(ads1018, &scan.conv, true);
>> +		enable_irq(ads1018->drdy_irq);
>> +	} else {
>> +		ret = spi_read(ads1018->spi, ads1018->rx_buf, sizeof(ads1018->rx_buf));
>> +		scan.conv = ads1018->rx_buf[0];
>> +	}
>> +
>> +	iio_device_release_buffer_mode(indio_dev);
>> +
>> +	if (ret)
>> +		goto out_notify_done;
>> +
>> +	iio_push_to_buffers_with_ts(indio_dev, &scan, sizeof(scan), pf->timestamp);
>> +
>> +out_notify_done:
>> +	iio_trigger_notify_done(ads1018->indio_trig);
>
> Jonathan et al., maybe we need an ACQUIRE() class for this? It will solve
> the conditional scoped guard case, no?

...

If no one prefers to do it, I can submit a patch implementing this. Same
for the lockdep issue above.

>> +/**
>> + * ADS1018_FSR_TO_SCALE - Converts FSR into scale
>> + * @_fsr: Full-scale range in millivolts
>> + * @_res: ADC resolution
>
> Add here something like this:
>
> *
> * The macro is crafted to avoid potential overflows on 32-bit machines.
> * This imposes restrictions to the possible values for @_fsr (less
> * than 274878), and @_res (great or equal to 6 bits).
> *

Sure.

I'll address the rest of the comments in v4. Thanks, Andy!


-- 
 ~ Kurt
Re: [PATCH v3 2/2] iio: adc: Add ti-ads1018 driver
Posted by David Lechner 5 hours ago
On 11/29/25 9:31 PM, Kurt Borja wrote:
> On Sat Nov 29, 2025 at 9:21 AM -05, Andy Shevchenko wrote:
> 

...

> 
>>> +static int ads1018_read_unlocked(struct ads1018 *ads1018, __be16 *cnv, bool hold_cs)
>>
>> Hmm... Don't we want to return value in CPU order? I don't know the answer
>> here, and IIRC IIO triggers might be actually good with endianess conversion
>> done, if required, in user space.
> 
> I specified IIO_BE endianness in each channel's .scan_type, so this
> works. However, I don't have issue especifying IIO_CPU and just
> returning CPU order values.
> 

Usually, we want to change the data as little as possible, so leaving
it as IIO_BE is fine.

> ...
> 
>>> + * Context: Expects iio_device_claim_direct() is held.
>>
>> Jonathan et al., do we have lockdep assert available for this?
>> I really prefer to see the code for it, while comment is good,
>> it is not good enough.
> 
> This would be nice.
> 
> ...
> 
>>> +	if (iio_device_claim_buffer_mode(indio_dev))
>>> +		goto out_notify_done;
>>> +
>>> +	if (iio_trigger_using_own(indio_dev)) {
>>> +		disable_irq(ads1018->drdy_irq);
>>> +		ret = ads1018_read_unlocked(ads1018, &scan.conv, true);
>>> +		enable_irq(ads1018->drdy_irq);
>>> +	} else {
>>> +		ret = spi_read(ads1018->spi, ads1018->rx_buf, sizeof(ads1018->rx_buf));
>>> +		scan.conv = ads1018->rx_buf[0];
>>> +	}
>>> +
>>> +	iio_device_release_buffer_mode(indio_dev);
>>> +
>>> +	if (ret)
>>> +		goto out_notify_done;
>>> +
>>> +	iio_push_to_buffers_with_ts(indio_dev, &scan, sizeof(scan), pf->timestamp);
>>> +
>>> +out_notify_done:
>>> +	iio_trigger_notify_done(ads1018->indio_trig);
>>
>> Jonathan et al., maybe we need an ACQUIRE() class for this? It will solve
>> the conditional scoped guard case, no?

No, ACQUIRE() is not scoped, just conditional. I don't think it
will improve anything here.

> 
> ...
> 
> If no one prefers to do it, I can submit a patch implementing this. Same
> for the lockdep issue above.
>
Re: [PATCH v3 2/2] iio: adc: Add ti-ads1018 driver
Posted by Kurt Borja an hour ago
On Mon Dec 1, 2025 at 11:07 AM -05, David Lechner wrote:

...

>>>> +	if (iio_device_claim_buffer_mode(indio_dev))
>>>> +		goto out_notify_done;
>>>> +
>>>> +	if (iio_trigger_using_own(indio_dev)) {
>>>> +		disable_irq(ads1018->drdy_irq);
>>>> +		ret = ads1018_read_unlocked(ads1018, &scan.conv, true);
>>>> +		enable_irq(ads1018->drdy_irq);
>>>> +	} else {
>>>> +		ret = spi_read(ads1018->spi, ads1018->rx_buf, sizeof(ads1018->rx_buf));
>>>> +		scan.conv = ads1018->rx_buf[0];
>>>> +	}
>>>> +
>>>> +	iio_device_release_buffer_mode(indio_dev);
>>>> +
>>>> +	if (ret)
>>>> +		goto out_notify_done;
>>>> +
>>>> +	iio_push_to_buffers_with_ts(indio_dev, &scan, sizeof(scan), pf->timestamp);
>>>> +
>>>> +out_notify_done:
>>>> +	iio_trigger_notify_done(ads1018->indio_trig);
>>>
>>> Jonathan et al., maybe we need an ACQUIRE() class for this? It will solve
>>> the conditional scoped guard case, no?
>
> No, ACQUIRE() is not scoped, just conditional. I don't think it
> will improve anything here.

Maybe I'm not understanding the problem fully?

I interpreted "ACQUIRE() class" as a general GUARD class, i.e.
	
	guard(iio_trigger_notify)(indio_dev->trig);

This way drivers may use other cleanup.h helpers cleaner, because of the
goto problem?

I do think it's a good idea, like a `defer` keyword. But it is a bit
unorthodox using guard for non locks.


-- 
 ~ Kurt
Re: [PATCH v3 2/2] iio: adc: Add ti-ads1018 driver
Posted by Andy Shevchenko 1 day, 4 hours ago
On Sun, Nov 30, 2025 at 5:31 AM Kurt Borja <kuurtb@gmail.com> wrote:
> On Sat Nov 29, 2025 at 9:21 AM -05, Andy Shevchenko wrote:

...

> >> + * @ad1018: Device data
> >> + *
> >> + * Calculates an appropriate delay for a single shot reading, assuming the
> >> + * device's maximum data-rate is used.
> >> + *
> >> + * Context: Expects iio_device_claim_direct() is held.
> >> + *
> >> + * Return: Delay in microseconds.
> >
> > Does 0 have any special meaning?
>
> This function is never 0.

Would be nice to mention this in the Return section.

...

> >> +    /* We subtract 10% data-rate error */
> >> +    hz -= DIV_ROUND_UP(hz, 10);
> >
> > Hmm... For delays I expect to see adding 10% to have a good margin.
>
> hz goes in the denomitor bellow, so less hz is more delay. Makes sense
> because worst case sample rate is less sample rate.

Please, rephrase or amend the comment to point this out. Because at
the first glance it's not obvious that subtract means delay increase.

...

> If no one prefers to do it, I can submit a patch implementing this. Same
> for the lockdep issue above.

If you are motivated to do so, please do!

> > * The macro is crafted to avoid potential overflows on 32-bit machines.
> > * This imposes restrictions to the possible values for @_fsr (less

s/to the/on the/

(in case you stick with my text)

> > * than 274878), and @_res (great or equal to 6 bits).

-- 
With Best Regards,
Andy Shevchenko
Re: [PATCH v3 2/2] iio: adc: Add ti-ads1018 driver
Posted by Andy Shevchenko 2 days, 7 hours ago
On Sat, Nov 29, 2025 at 04:21:46PM +0200, Andy Shevchenko wrote:
> On Fri, Nov 28, 2025 at 10:47:13PM -0500, Kurt Borja wrote:

...

> > +/**
> > + * ADS1018_FSR_TO_SCALE - Converts FSR into scale
> > + * @_fsr: Full-scale range in millivolts
> > + * @_res: ADC resolution
> 
> Add here something like this:
> 
> *
> * The macro is crafted to avoid potential overflows on 32-bit machines.
> * This imposes restrictions to the possible values for @_fsr (less
> * than 274878), and @_res (great or equal to 6 bits).

 * than 274878), and @_res (great than or equal to 6 bits).

(I missed "than")

> *
> 
> > + * Return: Scale in IIO_VAL_INT_PLUS_NANO format
> > + */
> > +#define ADS1018_FSR_TO_SCALE(_fsr, _res) \
> > +	{ 0, ((_fsr) * (MICRO >> 6)) / BIT((_res) - 6) }

-- 
With Best Regards,
Andy Shevchenko