devicetree.vger.kernel.org archive mirror
 help / color / mirror / Atom feed
* [PATCH v1 0/3] iio: adc: ti-ads7924: add ADS7924 driver
@ 2022-12-22 20:36 Hugo Villeneuve
  2022-12-22 20:36 ` [PATCH v1 1/3] iio: adc: Kconfig: add SPI interface mention to AD7924 description Hugo Villeneuve
                   ` (2 more replies)
  0 siblings, 3 replies; 14+ messages in thread
From: Hugo Villeneuve @ 2022-12-22 20:36 UTC (permalink / raw)
  To: hvilleneuve, jic23, lars, robh+dt, krzysztof.kozlowski+dt
  Cc: linux-iio, devicetree, linux-kernel, hugo

From: Hugo Villeneuve <hvilleneuve@dimonoff.com>

Hello,
this patch series adds the driver for the Texas Instruments ADS7924.

The Texas Instruments ADS7924 is a 4 channels, 12-bit analog to
digital converter (ADC) with an I2C interface.

Patch 1 adds a Kconfig comment to help differentiate between the Analog
      Devices AD7924 (SPI) and the TI ADS7924 (I2C).

Patch 2 contains the driver for the ADS7924.

Patch 3 add the dt-bindings for the ADS7924.

I have tested the driver using the Texas Instruments ADS7924EVM board connected
to a Variscite Symphony EVK with a IMX8MN NANO SOM:
  - Tested reset pin Ok
  - Tested regulator setup Ok
  - Tested reading sysfs in_voltage_scale Ok
  - Tested reading sysfs in_voltageX_raw (x=0 to 3) Ok


Thank you.

Hugo Villeneuve (3):
  iio: adc: Kconfig: add SPI interface mention to AD7924 description
  iio: adc: ti-ads7924: add ADS7924 driver
  dt-bindings: iio: adc: add ADS7924

 .../bindings/iio/adc/ti,ads7924.yaml          | 103 ++++
 MAINTAINERS                                   |   7 +
 drivers/iio/adc/Kconfig                       |  15 +-
 drivers/iio/adc/Makefile                      |   1 +
 drivers/iio/adc/ti-ads7924.c                  | 514 ++++++++++++++++++
 5 files changed, 639 insertions(+), 1 deletion(-)
 create mode 100644 Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml
 create mode 100644 drivers/iio/adc/ti-ads7924.c


base-commit: 4652bc537a2e0b44959489f45e4684fa4f143a45
-- 
2.30.2


^ permalink raw reply	[flat|nested] 14+ messages in thread

* [PATCH v1 1/3] iio: adc: Kconfig: add SPI interface mention to AD7924 description
  2022-12-22 20:36 [PATCH v1 0/3] iio: adc: ti-ads7924: add ADS7924 driver Hugo Villeneuve
@ 2022-12-22 20:36 ` Hugo Villeneuve
  2022-12-23 14:12   ` Jonathan Cameron
  2022-12-22 20:36 ` [PATCH v1 2/3] iio: adc: ti-ads7924: add ADS7924 driver Hugo Villeneuve
  2022-12-22 20:36 ` [PATCH v1 3/3] dt-bindings: iio: adc: add ADS7924 Hugo Villeneuve
  2 siblings, 1 reply; 14+ messages in thread
From: Hugo Villeneuve @ 2022-12-22 20:36 UTC (permalink / raw)
  To: hvilleneuve, jic23, lars, robh+dt, krzysztof.kozlowski+dt
  Cc: linux-iio, devicetree, linux-kernel, hugo

From: Hugo Villeneuve <hvilleneuve@dimonoff.com>

The Analog Devices AD7924 uses an SPI interface. There is also a Texas
Instruments ADS7924 which uses an I2C interface.

Adding the SPI mention to the AD7924 will help to avoid confusion
between the two chips.

Signed-off-by: Hugo Villeneuve <hvilleneuve@dimonoff.com>
---
 drivers/iio/adc/Kconfig | 2 +-
 1 file changed, 1 insertion(+), 1 deletion(-)

diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig
index 46c4fc2fc534..235319546974 100644
--- a/drivers/iio/adc/Kconfig
+++ b/drivers/iio/adc/Kconfig
@@ -243,7 +243,7 @@ config AD7923
 	select IIO_TRIGGERED_BUFFER
 	help
 	  Say yes here to build support for Analog Devices
-	  AD7904, AD7914, AD7923, AD7924 4 Channel ADCs.
+	  AD7904, AD7914, AD7923, AD7924 4 Channel SPI ADCs.
 
 	  To compile this driver as a module, choose M here: the
 	  module will be called ad7923.
-- 
2.30.2


^ permalink raw reply related	[flat|nested] 14+ messages in thread

* [PATCH v1 2/3] iio: adc: ti-ads7924: add ADS7924 driver
  2022-12-22 20:36 [PATCH v1 0/3] iio: adc: ti-ads7924: add ADS7924 driver Hugo Villeneuve
  2022-12-22 20:36 ` [PATCH v1 1/3] iio: adc: Kconfig: add SPI interface mention to AD7924 description Hugo Villeneuve
@ 2022-12-22 20:36 ` Hugo Villeneuve
  2022-12-23 14:47   ` Jonathan Cameron
  2022-12-22 20:36 ` [PATCH v1 3/3] dt-bindings: iio: adc: add ADS7924 Hugo Villeneuve
  2 siblings, 1 reply; 14+ messages in thread
From: Hugo Villeneuve @ 2022-12-22 20:36 UTC (permalink / raw)
  To: hvilleneuve, jic23, lars, robh+dt, krzysztof.kozlowski+dt
  Cc: linux-iio, devicetree, linux-kernel, hugo

From: Hugo Villeneuve <hvilleneuve@dimonoff.com>

The Texas Instruments ADS7924 is a 4 channels, 12-bit analog to
digital converter (ADC) with an I2C interface.

Signed-off-by: Hugo Villeneuve <hvilleneuve@dimonoff.com>
---
 MAINTAINERS                  |   7 +
 drivers/iio/adc/Kconfig      |  13 +
 drivers/iio/adc/Makefile     |   1 +
 drivers/iio/adc/ti-ads7924.c | 514 +++++++++++++++++++++++++++++++++++
 4 files changed, 535 insertions(+)
 create mode 100644 drivers/iio/adc/ti-ads7924.c

diff --git a/MAINTAINERS b/MAINTAINERS
index 4ced1f994442..7abe6f0cd2cd 100644
--- a/MAINTAINERS
+++ b/MAINTAINERS
@@ -20545,6 +20545,13 @@ M:	Robert Richter <rric@kernel.org>
 S:	Odd Fixes
 F:	drivers/gpio/gpio-thunderx.c
 
+TI ADS7924 ADC DRIVER
+M:	Hugo Villeneuve <hvilleneuve@dimonoff.com>
+L:	linux-iio@vger.kernel.org
+S:	Supported
+F:	Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml
+F:	drivers/iio/adc/ti-ads7924.c
+
 TI AM437X VPFE DRIVER
 M:	"Lad, Prabhakar" <prabhakar.csengg@gmail.com>
 L:	linux-media@vger.kernel.org
diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig
index 235319546974..18adcd6200b0 100644
--- a/drivers/iio/adc/Kconfig
+++ b/drivers/iio/adc/Kconfig
@@ -1207,6 +1207,19 @@ config TI_ADS1015
 	  This driver can also be built as a module. If so, the module will be
 	  called ti-ads1015.
 
+config TI_ADS7924
+	tristate "Texas Instruments ADS7924 ADC"
+	depends on I2C
+	select REGMAP_I2C
+	select IIO_BUFFER
+	select IIO_TRIGGERED_BUFFER
+	help
+	  If you say yes here you get support for Texas Instruments ADS7924
+	  4 channels, 12-bit I2C ADC chip.
+
+	  This driver can also be built as a module. If so, the module will be
+	  called ti-ads7924.
+
 config TI_ADS7950
 	tristate "Texas Instruments ADS7950 ADC driver"
 	depends on SPI && GPIOLIB
diff --git a/drivers/iio/adc/Makefile b/drivers/iio/adc/Makefile
index 6e08415c3f3a..1e5bdf47a091 100644
--- a/drivers/iio/adc/Makefile
+++ b/drivers/iio/adc/Makefile
@@ -107,6 +107,7 @@ obj-$(CONFIG_TI_ADC108S102) += ti-adc108s102.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_ADS7924) += ti-ads7924.o
 obj-$(CONFIG_TI_ADS7950) += ti-ads7950.o
 obj-$(CONFIG_TI_ADS8344) += ti-ads8344.o
 obj-$(CONFIG_TI_ADS8688) += ti-ads8688.o
diff --git a/drivers/iio/adc/ti-ads7924.c b/drivers/iio/adc/ti-ads7924.c
new file mode 100644
index 000000000000..e9ca7a045d18
--- /dev/null
+++ b/drivers/iio/adc/ti-ads7924.c
@@ -0,0 +1,514 @@
+// SPDX-License-Identifier: GPL-2.0
+/*
+ * IIO driver for Texas Instruments ADS7924 ADC, 12-bit, 4-Channels, I2C
+ *
+ * iio/adc/ti-ads7924.c
+ * Author: Hugo Villeneuve <hvilleneuve@dimonoff.com>
+ * Copyright 2022 DimOnOff
+ *
+ * based on iio/adc/ti-ads1015.c
+ * Copyright (c) 2016, Intel Corporation.
+ *
+ * Datasheets: https://www.ti.com/lit/gpn/ads7924
+ */
+
+#include <linux/module.h>
+#include <linux/init.h>
+#include <linux/irq.h>
+#include <linux/i2c.h>
+#include <linux/property.h>
+#include <linux/regmap.h>
+#include <linux/mutex.h>
+#include <linux/delay.h>
+
+#include <linux/iio/iio.h>
+#include <linux/iio/types.h>
+#include <linux/iio/sysfs.h>
+#include <linux/iio/buffer.h>
+#include <linux/gpio/consumer.h>
+#include <linux/regulator/consumer.h>
+
+#define ADS7924_DRV_NAME "ads7924"
+
+#define ADS7924_CHANNELS 4
+
+/* Registers. */
+#define ADS7924_MODECNTRL_REG	0x00
+#define ADS7924_INTCNTRL_REG	0x01
+#define ADS7924_DATA0_U_REG	0x02
+#define ADS7924_DATA0_L_REG	0x03
+#define ADS7924_DATA1_U_REG	0x04
+#define ADS7924_DATA1_L_REG	0x05
+#define ADS7924_DATA2_U_REG	0x06
+#define ADS7924_DATA2_L_REG	0x07
+#define ADS7924_DATA3_U_REG	0x08
+#define ADS7924_DATA3_L_REG	0x09
+#define ADS7924_ULR0_REG	0x0A
+#define ADS7924_LLR0_REG	0x0B
+#define ADS7924_ULR1_REG	0x0C
+#define ADS7924_LLR1_REG	0x0D
+#define ADS7924_ULR2_REG	0x0E
+#define ADS7924_LLR2_REG	0x0F
+#define ADS7924_ULR3_REG	0x10
+#define ADS7924_LLR3_REG	0x11
+#define ADS7924_INTCONFIG_REG	0x12
+#define ADS7924_SLPCONFIG_REG	0x13
+#define ADS7924_ACQCONFIG_REG	0x14
+#define ADS7924_PWRCONFIG_REG	0x15
+#define ADS7924_RESET_REG	0x16
+
+/* Register address INC bit: when set to '1', the register address is
+ * automatically incremented after every register read which allows convenient
+ * reading of multiple registers. Set INC to '0' when reading a single register.
+ */
+#define ADS7924_AUTO_INCREMENT_BIT	BIT(7)
+
+#define ADS7924_MODECNTRL_MODE_SHIFT	2
+#define ADS7924_MODECNTRL_MODE_MASK	GENMASK(7, ADS7924_MODECNTRL_MODE_SHIFT)
+
+#define ADS7924_MODECNTRL_SEL_SHIFT	0
+#define ADS7924_MODECNTRL_SEL_MASK	GENMASK(1, ADS7924_MODECNTRL_SEL_SHIFT)
+
+#define ADS7924_CFG_INTPOL_BIT		1
+#define ADS7924_CFG_INTTRIG_BIT		0
+
+#define ADS7924_CFG_INTPOL_MASK		BIT(ADS7924_CFG_INTPOL_BIT)
+#define ADS7924_CFG_INTTRIG_MASK	BIT(ADS7924_CFG_INTTRIG_BIT)
+
+/* Interrupt pin polarity */
+#define ADS7924_CFG_INTPOL_LOW		0
+#define ADS7924_CFG_INTPOL_HIGH		1
+
+/* Interrupt pin signaling */
+#define ADS7924_CFG_INTTRIG_LEVEL	0
+#define ADS7924_CFG_INTTRIG_EDGE	1
+
+/* Mode control values */
+#define ADS7924_MODECNTRL_IDLE			0x00
+#define ADS7924_MODECNTRL_AWAKE			0x20
+#define ADS7924_MODECNTRL_MANUAL_SINGLE		0x30
+#define ADS7924_MODECNTRL_MANUAL_SCAN		0x32
+#define ADS7924_MODECNTRL_AUTO_SINGLE		0x31
+#define ADS7924_MODECNTRL_AUTO_SCAN		0x33
+#define ADS7924_MODECNTRL_AUTO_SINGLE_SLEEP	0x39
+#define ADS7924_MODECNTRL_AUTO_SCAN_SLEEP	0x3B
+#define ADS7924_MODECNTRL_AUTO_BURST_SLEEP	0x3F
+
+#define ADS7924_ACQTIME_SHIFT	0
+#define ADS7924_ACQTIME_MASK	GENMASK(4, ADS7924_ACQTIME_SHIFT)
+
+#define ADS7924_PWRUPTIME_SHIFT	0
+#define ADS7924_PWRUPTIME_MASK	GENMASK(4, ADS7924_PWRUPTIME_SHIFT)
+
+/* The power-up time is allowed to elapse whenever the device has been shutdown
+ * in idle mode. Power-up time can allow external circuits, such as an
+ * operational amplifier, between the MUXOUT and ADCIN pins to turn on.
+ * The nominal time programmed by the PUTIME[4:0] register bits is given by:
+ *     t PU = PWRUPTIME[4:0] × 2 μs
+ * If a power-up time is not required, set the bits to '0' to effectively bypass.
+ */
+#define ADS7924_PWRUPTIME_US 0 /* Bypass (0us). */
+
+/* Acquisition Time. Minimum is 6us. */
+#define ADS7924_ACQTIME_US 6 /* Disable (6us). */
+
+/* The conversion time is always 4μs and cannot be programmed by the user. */
+#define ADS7924_CONVTIME_US 4
+
+#define ADS7924_TOTAL_CONVTIME (ADS7924_PWRUPTIME_US + ADS7924_ACQTIME_US + \
+				ADS7924_CONVTIME_US)
+
+#define ADS7924_SLEEP_DELAY_MS		2000
+
+enum ads7924_channels {
+	ADS7924_CH0,
+	ADS7924_CH1,
+	ADS7924_CH2,
+	ADS7924_CH3,
+	ADS7924_TIMESTAMP,
+};
+
+#define ADS7924_V_CHAN(_chan, _addr) {				\
+	.type = IIO_VOLTAGE,					\
+	.indexed = 1,						\
+	.address = _addr,					\
+	.channel = _chan,					\
+	.info_mask_separate = BIT(IIO_CHAN_INFO_RAW), 		\
+	.info_mask_shared_by_type = BIT(IIO_CHAN_INFO_SCALE),	\
+	.scan_index = _addr,					\
+	.scan_type = {						\
+		.sign = 's',					\
+		.realbits = 12,					\
+		.storagebits = 16,				\
+		.shift = 4,					\
+		.endianness = IIO_CPU,				\
+	},							\
+	.datasheet_name = "AIN"#_chan,				\
+}
+
+/* To map a channel with its corresponding data register (MSB). */
+static const unsigned int ads7924_channel_data_msb_regs[] = {
+	ADS7924_DATA0_U_REG,
+	ADS7924_DATA1_U_REG,
+	ADS7924_DATA2_U_REG,
+	ADS7924_DATA3_U_REG
+};
+
+struct ads7924_data {
+	struct device *dev;
+	struct regmap *regmap;
+	struct regulator *vref_reg;
+
+	/* GPIO descriptor for device hard-reset pin. */
+	struct gpio_desc *reset_gpio;
+
+	/*
+	 * Protects ADC ops, e.g: concurrent sysfs/buffered
+	 * data reads, configuration updates
+	 */
+	struct mutex lock;
+
+	/*
+	 * Set to true when the ADC is switched to the continuous-conversion
+	 * mode and exits from a power-down state. This flag is used to avoid
+	 * getting the stale result from the conversion register.
+	 */
+	bool conv_invalid;
+};
+
+static bool ads7924_is_writeable_reg(struct device *dev, unsigned int reg)
+{
+	switch (reg) {
+	case ADS7924_MODECNTRL_REG:
+	case ADS7924_INTCNTRL_REG:
+	case ADS7924_ULR0_REG:
+	case ADS7924_LLR0_REG:
+	case ADS7924_ULR1_REG:
+	case ADS7924_LLR1_REG:
+	case ADS7924_ULR2_REG:
+	case ADS7924_LLR2_REG:
+	case ADS7924_ULR3_REG:
+	case ADS7924_LLR3_REG:
+	case ADS7924_INTCONFIG_REG:
+	case ADS7924_SLPCONFIG_REG:
+	case ADS7924_ACQCONFIG_REG:
+	case ADS7924_PWRCONFIG_REG:
+	case ADS7924_RESET_REG:
+		return true;
+	default:
+		return false;
+	}
+}
+
+static const struct regmap_config ads7924_regmap_config = {
+	.reg_bits = 8,
+	.val_bits = 8,
+	.max_register = ADS7924_RESET_REG,
+	.writeable_reg = ads7924_is_writeable_reg,
+};
+
+static const struct iio_chan_spec ads7924_channels[] = {
+	ADS7924_V_CHAN(0, ADS7924_CH0),
+	ADS7924_V_CHAN(1, ADS7924_CH1),
+	ADS7924_V_CHAN(2, ADS7924_CH2),
+	ADS7924_V_CHAN(3, ADS7924_CH3),
+	IIO_CHAN_SOFT_TIMESTAMP(ADS7924_TIMESTAMP),
+};
+
+static
+int ads7924_get_adc_result(struct ads7924_data *data, int chan, int *val)
+{
+	int ret;
+	__be16 be_val;
+
+	if (chan < 0 || chan >= ADS7924_CHANNELS)
+		return -EINVAL;
+
+	if (data->conv_invalid) {
+		int conv_time;
+
+		conv_time = ADS7924_TOTAL_CONVTIME;
+		/* Allow 10% for internal clock inaccuracy. */
+		conv_time += conv_time / 10;
+		usleep_range(conv_time, conv_time + 1);
+		data->conv_invalid = false;
+	}
+
+	ret = regmap_raw_read(data->regmap, ADS7924_AUTO_INCREMENT_BIT |
+			      ads7924_channel_data_msb_regs[chan],
+			      &be_val, sizeof(be_val));
+	if (ret)
+		return ret;
+
+	*val = be16_to_cpu(be_val);
+	*val = *val >> ads7924_channels[chan].scan_type.shift;
+
+	return ret;
+}
+
+static int ads7924_read_raw(struct iio_dev *indio_dev,
+			    struct iio_chan_spec const *chan, int *val,
+			    int *val2, long mask)
+{
+	int ret, vref_uv;
+	struct ads7924_data *data = iio_priv(indio_dev);
+
+	mutex_lock(&data->lock);
+
+	switch (mask) {
+	case IIO_CHAN_INFO_RAW: {
+		ret = iio_device_claim_direct_mode(indio_dev);
+		if (ret)
+			break;
+
+		ret = ads7924_get_adc_result(data, chan->address, val);
+		if (ret < 0)
+			dev_dbg(data->dev, "%s error1\n", __func__);
+		else
+			ret = IIO_VAL_INT;
+
+		iio_device_release_direct_mode(indio_dev);
+		break;
+	}
+	case IIO_CHAN_INFO_SCALE:
+		vref_uv = regulator_get_voltage(data->vref_reg);
+		if (vref_uv < 0) {
+			/* dummy regulator "get_voltage" returns -EINVAL */
+			ret = -EINVAL;
+		} else {
+			*val =  vref_uv / 1000; /* Convert reg voltage to mV */
+			*val2 = chan->scan_type.realbits; /* Data bits */
+			ret = IIO_VAL_FRACTIONAL_LOG2;
+		}
+		break;
+	default:
+		ret = -EINVAL;
+		break;
+	}
+
+	mutex_unlock(&data->lock);
+
+	return ret;
+}
+
+static const struct iio_info ads7924_info = {
+	.read_raw	= ads7924_read_raw,
+};
+
+static int ads7924_of_parse_channel_config(struct iio_dev *indio_dev,
+					   struct device_node *np)
+{
+	struct ads7924_data *priv = iio_priv(indio_dev);
+	struct device *dev = priv->dev;
+	struct device_node *child;
+	int num_channels;
+	unsigned int channel = 0;
+	int ret;
+
+	num_channels = of_get_available_child_count(np);
+	if (!num_channels) {
+		dev_err(dev, "no channel children\n");
+		return -ENODEV;
+	}
+	dev_dbg(dev, "found %d ADC channels\n", num_channels);
+
+	for_each_available_child_of_node(np, child) {
+		ret = of_property_read_u32(child, "reg", &channel);
+		if (ret)
+			goto err;
+
+		if (channel >= ADS7924_CHANNELS) {
+			dev_err(dev, "invalid channel index %d\n", channel);
+			ret = -EINVAL;
+			goto err;
+		}
+	}
+
+	return 0;
+err:
+	of_node_put(child);
+
+	return ret;
+}
+
+static int ads7924_set_conv_mode(struct ads7924_data *data, int mode)
+{
+	/* When switching between modes, be sure to first select the Awake mode
+	 * and then switch to the desired mode. This procedure ensures the
+	 * internal control logic is properly synchronized.
+	 */
+	if (mode != ADS7924_MODECNTRL_IDLE) {
+		int ret;
+
+		ret = regmap_update_bits(data->regmap, ADS7924_MODECNTRL_REG,
+					 ADS7924_MODECNTRL_MODE_MASK,
+					 ADS7924_MODECNTRL_AWAKE <<
+					 ADS7924_MODECNTRL_MODE_SHIFT);
+		if (ret)
+			return ret;
+	}
+
+	return regmap_update_bits(data->regmap, ADS7924_MODECNTRL_REG,
+				  ADS7924_MODECNTRL_MODE_MASK,
+				  mode << ADS7924_MODECNTRL_MODE_SHIFT);
+}
+
+static int ads7924_reset(struct iio_dev *indio_dev)
+{
+	struct ads7924_data *data = iio_priv(indio_dev);
+
+	if (data->reset_gpio) {
+		gpiod_set_value(data->reset_gpio, 1); /* Assert. */
+		/* Educated guess: assert time not specified in datasheet... */
+		mdelay(100);
+		gpiod_set_value(data->reset_gpio, 0); /* Deassert. */
+	} else {
+		int ret;
+
+		/* A write of 10101010 to this register will generate a
+		 * software reset of the ADS7924.
+		 */
+		ret = regmap_write(data->regmap, ADS7924_RESET_REG, 0b10101010);
+		if (ret)
+			return ret;
+	}
+
+	return 0;
+};
+
+static void ads7924_reg_disable(void *data)
+{
+	regulator_disable(data);
+}
+
+static int ads7924_probe(struct i2c_client *client)
+{
+	struct iio_dev *indio_dev;
+	struct ads7924_data *data;
+	struct device *dev = &client->dev;
+	int ret;
+
+	indio_dev = devm_iio_device_alloc(&client->dev, sizeof(*data));
+	if (!indio_dev)
+		return -ENOMEM;
+
+	i2c_set_clientdata(client, indio_dev);
+
+	data = iio_priv(indio_dev);
+
+	data->dev = dev;
+
+	/* Initialize the reset GPIO as output with an initial value of 0. */
+	data->reset_gpio = devm_gpiod_get_optional(dev, "reset", GPIOD_OUT_LOW);
+	if (IS_ERR(data->reset_gpio))
+		return PTR_ERR(data->reset_gpio);
+
+	mutex_init(&data->lock);
+
+	indio_dev->name = ADS7924_DRV_NAME;
+	indio_dev->modes = INDIO_DIRECT_MODE;
+
+	indio_dev->channels = ads7924_channels;
+	indio_dev->num_channels = ARRAY_SIZE(ads7924_channels);
+	indio_dev->info = &ads7924_info;
+
+	ret = ads7924_of_parse_channel_config(indio_dev, dev->of_node);
+	if (ret < 0)
+		return ret;
+
+	data->regmap = devm_regmap_init_i2c(client, &ads7924_regmap_config);
+	if (IS_ERR(data->regmap)) {
+		dev_err(dev, "Failed to allocate register map\n");
+		return PTR_ERR(data->regmap);
+	}
+
+	data->vref_reg = devm_regulator_get(dev, "vref");
+	if (IS_ERR(data->vref_reg)) {
+		dev_err(dev, "devm_regulator_get() failed\n");
+		return PTR_ERR(data->vref_reg);
+	}
+
+	ret = regulator_enable(data->vref_reg);
+	if (ret) {
+		dev_err(dev, "regulator_enable() failed\n");
+		return ret;
+	}
+
+	ret = devm_add_action_or_reset(dev, ads7924_reg_disable, data->vref_reg);
+	if (ret) {
+		dev_err(dev, "devm_add_action_or_reset() failed\n");
+		return ret;
+	}
+
+	ret = ads7924_reset(indio_dev);
+	if (ret < 0) {
+		dev_err(dev, "Failed to reset device\n");
+		return ret;
+	}
+
+	ret = ads7924_set_conv_mode(data,
+				    ADS7924_MODECNTRL_AUTO_SCAN);
+	if (ret)
+		return ret;
+
+	/* Disable signal acquire time. */
+	ret = regmap_update_bits(data->regmap, ADS7924_ACQCONFIG_REG,
+				 ADS7924_ACQTIME_MASK, 0);
+	if (ret < 0) {
+		dev_err(dev, "Disable signal acquire time failed\n");
+		return ret;
+	}
+
+	/* Disable power-up time. */
+	ret = regmap_update_bits(data->regmap, ADS7924_PWRCONFIG_REG,
+				 ADS7924_PWRUPTIME_MASK, 0);
+	if (ret < 0) {
+		dev_err(dev, "Disable power-up time failed\n");
+		return ret;
+	}
+
+	data->conv_invalid = true;
+
+	ret = iio_device_register(indio_dev);
+	if (ret < 0) {
+		dev_err(dev, "Failed to register IIO device\n");
+		return ret;
+	}
+
+	return 0;
+}
+
+static void ads7924_remove(struct i2c_client *client)
+{
+	struct iio_dev *indio_dev = i2c_get_clientdata(client);
+	struct ads7924_data *data = iio_priv(indio_dev);
+	int ret;
+
+	iio_device_unregister(indio_dev);
+
+	ret = ads7924_set_conv_mode(data, ADS7924_MODECNTRL_IDLE);
+	if (ret)
+		dev_warn(&client->dev, "Failed to power down (%pe)\n",
+			 ERR_PTR(ret));
+}
+
+static const struct of_device_id ads7924_of_match[] = {
+	{ .compatible = "ti,ads7924", },
+	{}
+};
+MODULE_DEVICE_TABLE(of, ads7924_of_match);
+
+static struct i2c_driver ads7924_driver = {
+	.driver = {
+		.name = ADS7924_DRV_NAME,
+		.of_match_table = ads7924_of_match,
+	},
+	.probe_new	= ads7924_probe,
+	.remove		= ads7924_remove,
+};
+
+module_i2c_driver(ads7924_driver);
+
+MODULE_AUTHOR("Hugo Villeneuve <hvilleneuve@dimonoff.com>");
+MODULE_DESCRIPTION("Texas Instruments ADS7924 ADC I2C driver");
+MODULE_LICENSE("GPL");
-- 
2.30.2


^ permalink raw reply related	[flat|nested] 14+ messages in thread

* [PATCH v1 3/3] dt-bindings: iio: adc: add ADS7924
  2022-12-22 20:36 [PATCH v1 0/3] iio: adc: ti-ads7924: add ADS7924 driver Hugo Villeneuve
  2022-12-22 20:36 ` [PATCH v1 1/3] iio: adc: Kconfig: add SPI interface mention to AD7924 description Hugo Villeneuve
  2022-12-22 20:36 ` [PATCH v1 2/3] iio: adc: ti-ads7924: add ADS7924 driver Hugo Villeneuve
@ 2022-12-22 20:36 ` Hugo Villeneuve
  2022-12-23  8:19   ` Krzysztof Kozlowski
  2022-12-23 14:50   ` Jonathan Cameron
  2 siblings, 2 replies; 14+ messages in thread
From: Hugo Villeneuve @ 2022-12-22 20:36 UTC (permalink / raw)
  To: hvilleneuve, jic23, lars, robh+dt, krzysztof.kozlowski+dt
  Cc: linux-iio, devicetree, linux-kernel, hugo

From: Hugo Villeneuve <hvilleneuve@dimonoff.com>

Add device tree bindings document for the Texas Instruments ADS7924
ADC.

Signed-off-by: Hugo Villeneuve <hvilleneuve@dimonoff.com>
---
 .../bindings/iio/adc/ti,ads7924.yaml          | 103 ++++++++++++++++++
 1 file changed, 103 insertions(+)
 create mode 100644 Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml

diff --git a/Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml b/Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml
new file mode 100644
index 000000000000..5408ec95e417
--- /dev/null
+++ b/Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml
@@ -0,0 +1,103 @@
+# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
+%YAML 1.2
+---
+$id: http://devicetree.org/schemas/iio/adc/ti,ads7924.yaml#
+$schema: http://devicetree.org/meta-schemas/core.yaml#
+
+title: TI ADS7924 4 channels 12 bits I2C analog to digital converter
+
+maintainers:
+  - Hugo Villeneuve <hvilleneuve@dimonoff.com>
+
+description: |
+  Texas Instruments ADS7924 4 channels 12 bits I2C analog to digital converter
+
+  Specifications:
+    https://www.ti.com/lit/gpn/ads7924
+
+properties:
+  compatible:
+    const: ti,ads7924
+
+  vref-supply:
+    description:
+      The regulator supply for the ADC reference voltage (AVDD)
+
+  reg:
+    maxItems: 1
+
+  reset-gpios:
+    description:
+      GPIO used for controlling the reset pin
+    maxItems: 1
+
+  "#address-cells":
+    const: 1
+
+  "#size-cells":
+    const: 0
+
+  "#io-channel-cells":
+    const: 1
+
+required:
+  - compatible
+  - reg
+  - vref-supply
+  - "#address-cells"
+  - "#size-cells"
+
+additionalProperties: false
+
+patternProperties:
+  "^channel@[0-3]+$":
+    type: object
+    description:
+      Child nodes needed for each channel that the platform uses.
+
+    properties:
+      reg:
+        description: |
+          0: Voltage over AIN0 and GND.
+          1: Voltage over AIN1 and GND.
+          2: Voltage over AIN2 and GND.
+          3: Voltage over AIN3 and GND.
+        items:
+          - minimum: 0
+            maximum: 3
+
+    required:
+      - reg
+
+examples:
+  - |
+    i2c {
+        #address-cells = <1>;
+        #size-cells = <0>;
+
+        adc@48 {
+            compatible = "ti,ads7924";
+            reg = <0x48>;
+            vref-supply = <&ads7924_reg>;
+            reset-gpios = <&gpio 5 GPIO_ACTIVE_LOW>;
+            #address-cells = <1>;
+            #size-cells = <0>;
+            channel@0 {
+              reg = <0>;
+              label = "CH0";
+            };
+            channel@1 {
+              reg = <1>;
+              label = "CH1";
+            };
+            channel@2 {
+              reg = <2>;
+              label = "CH2";
+            };
+            channel@3 {
+              reg = <3>;
+              label = "CH3";
+            };
+        };
+    };
+...
-- 
2.30.2


^ permalink raw reply related	[flat|nested] 14+ messages in thread

* Re: [PATCH v1 3/3] dt-bindings: iio: adc: add ADS7924
  2022-12-22 20:36 ` [PATCH v1 3/3] dt-bindings: iio: adc: add ADS7924 Hugo Villeneuve
@ 2022-12-23  8:19   ` Krzysztof Kozlowski
  2022-12-23 14:09     ` Jonathan Cameron
  2022-12-23 14:50   ` Jonathan Cameron
  1 sibling, 1 reply; 14+ messages in thread
From: Krzysztof Kozlowski @ 2022-12-23  8:19 UTC (permalink / raw)
  To: Hugo Villeneuve, hvilleneuve, jic23, lars, robh+dt,
	krzysztof.kozlowski+dt
  Cc: linux-iio, devicetree, linux-kernel

On 22/12/2022 21:36, Hugo Villeneuve wrote:
> From: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> 
> Add device tree bindings document for the Texas Instruments ADS7924
> ADC.
> 
> Signed-off-by: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> ---
>  .../bindings/iio/adc/ti,ads7924.yaml          | 103 ++++++++++++++++++
>  1 file changed, 103 insertions(+)
>  create mode 100644 Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml
> 
> diff --git a/Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml b/Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml
> new file mode 100644
> index 000000000000..5408ec95e417
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml
> @@ -0,0 +1,103 @@
> +# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
> +%YAML 1.2
> +---
> +$id: http://devicetree.org/schemas/iio/adc/ti,ads7924.yaml#
> +$schema: http://devicetree.org/meta-schemas/core.yaml#
> +
> +title: TI ADS7924 4 channels 12 bits I2C analog to digital converter
> +
> +maintainers:
> +  - Hugo Villeneuve <hvilleneuve@dimonoff.com>
> +
> +description: |
> +  Texas Instruments ADS7924 4 channels 12 bits I2C analog to digital converter
> +
> +  Specifications:
> +    https://www.ti.com/lit/gpn/ads7924
> +
> +properties:
> +  compatible:
> +    const: ti,ads7924
> +
> +  vref-supply:
> +    description:
> +      The regulator supply for the ADC reference voltage (AVDD)
> +
> +  reg:
> +    maxItems: 1
> +
> +  reset-gpios:
> +    description:
> +      GPIO used for controlling the reset pin

Drop description, it's obvious (unless you want to actually describe
some pieces of the hardware).

> +    maxItems: 1
> +
> +  "#address-cells":
> +    const: 1
> +
> +  "#size-cells":
> +    const: 0
> +
> +  "#io-channel-cells":
> +    const: 1
> +
> +required:
> +  - compatible
> +  - reg
> +  - vref-supply
> +  - "#address-cells"
> +  - "#size-cells"

Keep the same order as in properties. This one is more common (reg after
compatible).

> +
> +additionalProperties: false
> +
> +patternProperties:

patternProperties go immediately after properties.

> +  "^channel@[0-3]+$":
> +    type: object

additionalProperties: false on this level

> +    description:
> +      Child nodes needed for each channel that the platform uses.

I cannot understand this sentence at all. Instead describe the hardware
you are here representing. What's this?

> +
> +    properties:
> +      reg:
> +        description: |
> +          0: Voltage over AIN0 and GND.
> +          1: Voltage over AIN1 and GND.
> +          2: Voltage over AIN2 and GND.
> +          3: Voltage over AIN3 and GND.
> +        items:
> +          - minimum: 0
> +            maximum: 3
> +
> +    required:
> +      - reg
> +
> +examples:
> +  - |
> +    i2c {
> +        #address-cells = <1>;
> +        #size-cells = <0>;
> +
> +        adc@48 {
> +            compatible = "ti,ads7924";
> +            reg = <0x48>;
> +            vref-supply = <&ads7924_reg>;
> +            reset-gpios = <&gpio 5 GPIO_ACTIVE_LOW>;
> +            #address-cells = <1>;
> +            #size-cells = <0>;
> +            channel@0 {
> +              reg = <0>;

Messed indentation. Keep 4 spaces.

> +              label = "CH0";
> +            };
> +            channel@1 {
> +              reg = <1>;
> +              label = "CH1";
> +            };
> +            channel@2 {
> +              reg = <2>;
> +              label = "CH2";
> +            };
> +            channel@3 {
> +              reg = <3>;
> +              label = "CH3";
> +            };
> +        };
> +    };
> +...

Best regards,
Krzysztof


^ permalink raw reply	[flat|nested] 14+ messages in thread

* Re: [PATCH v1 3/3] dt-bindings: iio: adc: add ADS7924
  2022-12-23  8:19   ` Krzysztof Kozlowski
@ 2022-12-23 14:09     ` Jonathan Cameron
  2022-12-23 17:56       ` Hugo Villeneuve
  0 siblings, 1 reply; 14+ messages in thread
From: Jonathan Cameron @ 2022-12-23 14:09 UTC (permalink / raw)
  To: Krzysztof Kozlowski
  Cc: Hugo Villeneuve, hvilleneuve, lars, robh+dt,
	krzysztof.kozlowski+dt, linux-iio, devicetree, linux-kernel

> 
> > +    description:
> > +      Child nodes needed for each channel that the platform uses.  
> 
> I cannot understand this sentence at all. Instead describe the hardware
> you are here representing. What's this?

Needs rewording, but basically - "Which pins are connected to anything?"



^ permalink raw reply	[flat|nested] 14+ messages in thread

* Re: [PATCH v1 1/3] iio: adc: Kconfig: add SPI interface mention to AD7924 description
  2022-12-22 20:36 ` [PATCH v1 1/3] iio: adc: Kconfig: add SPI interface mention to AD7924 description Hugo Villeneuve
@ 2022-12-23 14:12   ` Jonathan Cameron
  2022-12-23 18:52     ` Hugo Villeneuve
  0 siblings, 1 reply; 14+ messages in thread
From: Jonathan Cameron @ 2022-12-23 14:12 UTC (permalink / raw)
  To: Hugo Villeneuve
  Cc: hvilleneuve, lars, robh+dt, krzysztof.kozlowski+dt, linux-iio,
	devicetree, linux-kernel

On Thu, 22 Dec 2022 15:36:08 -0500
Hugo Villeneuve <hugo@hugovil.com> wrote:

> From: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> 
> The Analog Devices AD7924 uses an SPI interface. There is also a Texas
> Instruments ADS7924 which uses an I2C interface.
> 
> Adding the SPI mention to the AD7924 will help to avoid confusion
> between the two chips.
Hi Hugo,

Welcome to IIO.

I don't really mind this, but given they have different part numbers
and the similarly named TI part could just have easily been SPI
I'm not sure the clarification is really useful.

Also, under all the circumstances I can think of, if you can see the
help text you can also see the SPI dependence clearly listed.

Hence I think is just noise, though I'm guessing it reflects a
confusion you ran into!

Jonathan


> 
> Signed-off-by: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> ---
>  drivers/iio/adc/Kconfig | 2 +-
>  1 file changed, 1 insertion(+), 1 deletion(-)
> 
> diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig
> index 46c4fc2fc534..235319546974 100644
> --- a/drivers/iio/adc/Kconfig
> +++ b/drivers/iio/adc/Kconfig
> @@ -243,7 +243,7 @@ config AD7923
>  	select IIO_TRIGGERED_BUFFER
>  	help
>  	  Say yes here to build support for Analog Devices
> -	  AD7904, AD7914, AD7923, AD7924 4 Channel ADCs.
> +	  AD7904, AD7914, AD7923, AD7924 4 Channel SPI ADCs.
>  
>  	  To compile this driver as a module, choose M here: the
>  	  module will be called ad7923.


^ permalink raw reply	[flat|nested] 14+ messages in thread

* Re: [PATCH v1 2/3] iio: adc: ti-ads7924: add ADS7924 driver
  2022-12-22 20:36 ` [PATCH v1 2/3] iio: adc: ti-ads7924: add ADS7924 driver Hugo Villeneuve
@ 2022-12-23 14:47   ` Jonathan Cameron
  2023-01-10 15:38     ` Hugo Villeneuve
  0 siblings, 1 reply; 14+ messages in thread
From: Jonathan Cameron @ 2022-12-23 14:47 UTC (permalink / raw)
  To: Hugo Villeneuve
  Cc: hvilleneuve, lars, robh+dt, krzysztof.kozlowski+dt, linux-iio,
	devicetree, linux-kernel

On Thu, 22 Dec 2022 15:36:09 -0500
Hugo Villeneuve <hugo@hugovil.com> wrote:

> From: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> 
> The Texas Instruments ADS7924 is a 4 channels, 12-bit analog to
> digital converter (ADC) with an I2C interface.
> 
> Signed-off-by: Hugo Villeneuve <hvilleneuve@dimonoff.com>

Hi Hugo,

Thanks for the driver. Some comments inline.
Given the various bits of support present, are you planning to follow up
with buffered support (chardev etc).

Jonathan

> ---
>  MAINTAINERS                  |   7 +
>  drivers/iio/adc/Kconfig      |  13 +
>  drivers/iio/adc/Makefile     |   1 +
>  drivers/iio/adc/ti-ads7924.c | 514 +++++++++++++++++++++++++++++++++++
>  4 files changed, 535 insertions(+)
>  create mode 100644 drivers/iio/adc/ti-ads7924.c
> 

...

> diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig
> index 235319546974..18adcd6200b0 100644
> --- a/drivers/iio/adc/Kconfig
> +++ b/drivers/iio/adc/Kconfig
> @@ -1207,6 +1207,19 @@ config TI_ADS1015
>  	  This driver can also be built as a module. If so, the module will be
>  	  called ti-ads1015.
>  
> +config TI_ADS7924
> +	tristate "Texas Instruments ADS7924 ADC"
> +	depends on I2C
> +	select REGMAP_I2C
> +	select IIO_BUFFER
> +	select IIO_TRIGGERED_BUFFER

No buffer support yet. So drop these for now.

> +	help
> +	  If you say yes here you get support for Texas Instruments ADS7924
> +	  4 channels, 12-bit I2C ADC chip.
> +
> +	  This driver can also be built as a module. If so, the module will be
> +	  called ti-ads7924.
> +
>  config TI_ADS7950
>  	tristate "Texas Instruments ADS7950 ADC driver"
>  	depends on SPI && GPIOLIB
> diff --git a/drivers/iio/adc/Makefile b/drivers/iio/adc/Makefile
> index 6e08415c3f3a..1e5bdf47a091 100644
> --- a/drivers/iio/adc/Makefile
> +++ b/drivers/iio/adc/Makefile
> @@ -107,6 +107,7 @@ obj-$(CONFIG_TI_ADC108S102) += ti-adc108s102.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_ADS7924) += ti-ads7924.o
>  obj-$(CONFIG_TI_ADS7950) += ti-ads7950.o
>  obj-$(CONFIG_TI_ADS8344) += ti-ads8344.o
>  obj-$(CONFIG_TI_ADS8688) += ti-ads8688.o
> diff --git a/drivers/iio/adc/ti-ads7924.c b/drivers/iio/adc/ti-ads7924.c
> new file mode 100644
> index 000000000000..e9ca7a045d18
> --- /dev/null
> +++ b/drivers/iio/adc/ti-ads7924.c
> @@ -0,0 +1,514 @@
> +// SPDX-License-Identifier: GPL-2.0
> +/*
> + * IIO driver for Texas Instruments ADS7924 ADC, 12-bit, 4-Channels, I2C
> + *
> + * iio/adc/ti-ads7924.c
> + * Author: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> + * Copyright 2022 DimOnOff
> + *
> + * based on iio/adc/ti-ads1015.c
> + * Copyright (c) 2016, Intel Corporation.
> + *
> + * Datasheets: https://www.ti.com/lit/gpn/ads7924
Add as a tag to the tag block of the patch description.

Datasheet: https://www.ti.com/lit/gpn/ads7924
on the line above your signoff.
There are some automated tools that will pick this up I think.

> + */
> +
> +#include <linux/module.h>
> +#include <linux/init.h>
> +#include <linux/irq.h>
> +#include <linux/i2c.h>
> +#include <linux/property.h>

hmm. you include property.h then use the of ones...

> +#include <linux/regmap.h>
> +#include <linux/mutex.h>
> +#include <linux/delay.h>

Put this block in alphabetical order.

> +
> +#include <linux/iio/iio.h>
> +#include <linux/iio/types.h>
> +#include <linux/iio/sysfs.h>

Don't think that's used.  Normally only needed for custom attributes.

> +#include <linux/iio/buffer.h>

Not currently used.

> +#include <linux/gpio/consumer.h>
> +#include <linux/regulator/consumer.h>
> +
> +#define ADS7924_DRV_NAME "ads7924"
> +
> +#define ADS7924_CHANNELS 4
> +
> +/* Registers. */
> +#define ADS7924_MODECNTRL_REG	0x00
> +#define ADS7924_INTCNTRL_REG	0x01
> +#define ADS7924_DATA0_U_REG	0x02
> +#define ADS7924_DATA0_L_REG	0x03
> +#define ADS7924_DATA1_U_REG	0x04
> +#define ADS7924_DATA1_L_REG	0x05
> +#define ADS7924_DATA2_U_REG	0x06
> +#define ADS7924_DATA2_L_REG	0x07
> +#define ADS7924_DATA3_U_REG	0x08
> +#define ADS7924_DATA3_L_REG	0x09
> +#define ADS7924_ULR0_REG	0x0A
> +#define ADS7924_LLR0_REG	0x0B
> +#define ADS7924_ULR1_REG	0x0C
> +#define ADS7924_LLR1_REG	0x0D
> +#define ADS7924_ULR2_REG	0x0E
> +#define ADS7924_LLR2_REG	0x0F
> +#define ADS7924_ULR3_REG	0x10
> +#define ADS7924_LLR3_REG	0x11
> +#define ADS7924_INTCONFIG_REG	0x12
> +#define ADS7924_SLPCONFIG_REG	0x13
> +#define ADS7924_ACQCONFIG_REG	0x14
> +#define ADS7924_PWRCONFIG_REG	0x15
> +#define ADS7924_RESET_REG	0x16
> +

Comment syntax as below.

> +/* Register address INC bit: when set to '1', the register address is
> + * automatically incremented after every register read which allows convenient
> + * reading of multiple registers. Set INC to '0' when reading a single register.
> + */
> +#define ADS7924_AUTO_INCREMENT_BIT	BIT(7)
> +
> +#define ADS7924_MODECNTRL_MODE_SHIFT	2
> +#define ADS7924_MODECNTRL_MODE_MASK	GENMASK(7, ADS7924_MODECNTRL_MODE_SHIFT)
> +
> +#define ADS7924_MODECNTRL_SEL_SHIFT	0

As below, don't provide a _SHIFT macro for any of these.
The MASK should be the only one needed as it implicitly contains the shift anyway.

> +#define ADS7924_MODECNTRL_SEL_MASK	GENMASK(1, ADS7924_MODECNTRL_SEL_SHIFT)
> +
> +#define ADS7924_CFG_INTPOL_BIT		1
> +#define ADS7924_CFG_INTTRIG_BIT		0
> +
> +#define ADS7924_CFG_INTPOL_MASK		BIT(ADS7924_CFG_INTPOL_BIT)
> +#define ADS7924_CFG_INTTRIG_MASK	BIT(ADS7924_CFG_INTTRIG_BIT)
> +
> +/* Interrupt pin polarity */
> +#define ADS7924_CFG_INTPOL_LOW		0
> +#define ADS7924_CFG_INTPOL_HIGH		1
> +
> +/* Interrupt pin signaling */
> +#define ADS7924_CFG_INTTRIG_LEVEL	0
> +#define ADS7924_CFG_INTTRIG_EDGE	1
> +
> +/* Mode control values */
> +#define ADS7924_MODECNTRL_IDLE			0x00
> +#define ADS7924_MODECNTRL_AWAKE			0x20
> +#define ADS7924_MODECNTRL_MANUAL_SINGLE		0x30
> +#define ADS7924_MODECNTRL_MANUAL_SCAN		0x32
> +#define ADS7924_MODECNTRL_AUTO_SINGLE		0x31
> +#define ADS7924_MODECNTRL_AUTO_SCAN		0x33
> +#define ADS7924_MODECNTRL_AUTO_SINGLE_SLEEP	0x39
> +#define ADS7924_MODECNTRL_AUTO_SCAN_SLEEP	0x3B
> +#define ADS7924_MODECNTRL_AUTO_BURST_SLEEP	0x3F
> +
> +#define ADS7924_ACQTIME_SHIFT	0
> +#define ADS7924_ACQTIME_MASK	GENMASK(4, ADS7924_ACQTIME_SHIFT)
> +
> +#define ADS7924_PWRUPTIME_SHIFT	0

No point in providing shift. The mask definition should always be sufficient
if using FIELD_GET / FIELD_PREP()

> +#define ADS7924_PWRUPTIME_MASK	GENMASK(4, ADS7924_PWRUPTIME_SHIFT)
> +
> +/* The power-up time is allowed to elapse whenever the device has been shutdown
Comment syntax
/*
 * The power-up....

> + * in idle mode. Power-up time can allow external circuits, such as an
> + * operational amplifier, between the MUXOUT and ADCIN pins to turn on.
> + * The nominal time programmed by the PUTIME[4:0] register bits is given by:
> + *     t PU = PWRUPTIME[4:0] × 2 μs
> + * If a power-up time is not required, set the bits to '0' to effectively bypass.
> + */
> +#define ADS7924_PWRUPTIME_US 0 /* Bypass (0us). */
> +
> +/* Acquisition Time. Minimum is 6us. */
> +#define ADS7924_ACQTIME_US 6 /* Disable (6us). */

Disable?  Strange comment for something called acquisition time.

> +
> +/* The conversion time is always 4μs and cannot be programmed by the user. */
> +#define ADS7924_CONVTIME_US 4
> +
> +#define ADS7924_TOTAL_CONVTIME (ADS7924_PWRUPTIME_US + ADS7924_ACQTIME_US + \
> +				ADS7924_CONVTIME_US)

Postfix this with _US as well.  It's good habit to put units in defines, so
do it everywhere it makes sense.

> +
> +#define ADS7924_SLEEP_DELAY_MS		2000
> +
> +enum ads7924_channels {
> +	ADS7924_CH0,
> +	ADS7924_CH1,
> +	ADS7924_CH2,
> +	ADS7924_CH3,
> +	ADS7924_TIMESTAMP,
> +};
> +
> +#define ADS7924_V_CHAN(_chan, _addr) {				\
> +	.type = IIO_VOLTAGE,					\
> +	.indexed = 1,						\
> +	.address = _addr,					\
> +	.channel = _chan,					\
> +	.info_mask_separate = BIT(IIO_CHAN_INFO_RAW), 		\
> +	.info_mask_shared_by_type = BIT(IIO_CHAN_INFO_SCALE),	\
> +	.scan_index = _addr,					\
> +	.scan_type = {						\
> +		.sign = 's',					\
> +		.realbits = 12,					\

You are using the shift element which is fine, but I think the majority of this
isn't yet used as no buffer support. As such, I'd drop anything you aren't
using for now. Add it back if you add buffered support in future.

> +		.storagebits = 16,				\
> +		.shift = 4,					\
> +		.endianness = IIO_CPU,				\

It's big endian off the devices, so that's how you should present it
to userspace via a buffered interface (this scan_type entry has no
standard meaning except for buffered interfaces).

> +	},							\
> +	.datasheet_name = "AIN"#_chan,				\
> +}
> +
> +/* To map a channel with its corresponding data register (MSB). */
> +static const unsigned int ads7924_channel_data_msb_regs[] = {
> +	ADS7924_DATA0_U_REG,
> +	ADS7924_DATA1_U_REG,
> +	ADS7924_DATA2_U_REG,
> +	ADS7924_DATA3_U_REG

It's possible this driver might one day support more elements in here (maybe
there is an 8 channel otherwise compatible part), so add a trailing comma.

Generally the only time we don't ask for trailing commas is after NULL terminators
or other entries that will by definition always be the last element.

> +};
> +


> +static const struct iio_chan_spec ads7924_channels[] = {
> +	ADS7924_V_CHAN(0, ADS7924_CH0),
> +	ADS7924_V_CHAN(1, ADS7924_CH1),
> +	ADS7924_V_CHAN(2, ADS7924_CH2),
> +	ADS7924_V_CHAN(3, ADS7924_CH3),
> +	IIO_CHAN_SOFT_TIMESTAMP(ADS7924_TIMESTAMP),

Timestamp doesn't do anything useful until you support buffered modes.
So drop it for now.

> +};
> +
> +static
> +int ads7924_get_adc_result(struct ads7924_data *data, int chan, int *val)
> +{
> +	int ret;
> +	__be16 be_val;
> +
> +	if (chan < 0 || chan >= ADS7924_CHANNELS)
> +		return -EINVAL;
> +
> +	if (data->conv_invalid) {
> +		int conv_time;
> +
> +		conv_time = ADS7924_TOTAL_CONVTIME;
> +		/* Allow 10% for internal clock inaccuracy. */
> +		conv_time += conv_time / 10;
> +		usleep_range(conv_time, conv_time + 1);
> +		data->conv_invalid = false;
> +	}
> +
> +	ret = regmap_raw_read(data->regmap, ADS7924_AUTO_INCREMENT_BIT |
> +			      ads7924_channel_data_msb_regs[chan],
> +			      &be_val, sizeof(be_val));
> +	if (ret)
> +		return ret;
> +
> +	*val = be16_to_cpu(be_val);
> +	*val = *val >> ads7924_channels[chan].scan_type.shift;
> +
> +	return ret;
> +}
> +
> +static int ads7924_read_raw(struct iio_dev *indio_dev,
> +			    struct iio_chan_spec const *chan, int *val,
> +			    int *val2, long mask)
> +{
> +	int ret, vref_uv;
> +	struct ads7924_data *data = iio_priv(indio_dev);
> +
> +	mutex_lock(&data->lock);
> +
> +	switch (mask) {
> +	case IIO_CHAN_INFO_RAW: {
> +		ret = iio_device_claim_direct_mode(indio_dev);
> +		if (ret)
> +			break;
> +
> +		ret = ads7924_get_adc_result(data, chan->address, val);
> +		if (ret < 0)

Check the error code after iio_device_release_direct / mutex_unlock()
That way you can return directly.

Note, if you add support later for buffered mode, taking a local lock
outside of claiming direct mode can deadlock.  You are better off
moving the mutex_lock/unlock inside iio_device_claim_direct_mode()

As a side note, iio_device_claim_direct_mode() only does something useful
if you are supporting buffered mode... So for now it shouldn't really
be in this driver at all.  The point of that call is protect against
transitions into buffered modes whilst a call is flight that might
make a mess of that transition or be affected by it.

> +			dev_dbg(data->dev, "%s error1\n", __func__);
> +		else
> +			ret = IIO_VAL_INT;
> +
> +		iio_device_release_direct_mode(indio_dev);
> +		break;
> +	}
> +	case IIO_CHAN_INFO_SCALE:
> +		vref_uv = regulator_get_voltage(data->vref_reg);
> +		if (vref_uv < 0) {
> +			/* dummy regulator "get_voltage" returns -EINVAL */
> +			ret = -EINVAL;
> +		} else {
> +			*val =  vref_uv / 1000; /* Convert reg voltage to mV */
> +			*val2 = chan->scan_type.realbits; /* Data bits */
> +			ret = IIO_VAL_FRACTIONAL_LOG2;
> +		}
> +		break;
> +	default:
> +		ret = -EINVAL;
> +		break;
> +	}
> +
> +	mutex_unlock(&data->lock);

You only need the lock for the INFO_RAW switch branch as far as I can see.
Hence good to reduce it's scope to just that.  It may make sense to factor
out the code there to a separate function to simplify the error paths
(a goto out of a switch is a bit nasty to read)

> +
> +	return ret;
> +}
> +
> +static const struct iio_info ads7924_info = {
> +	.read_raw	= ads7924_read_raw,
> +};
> +
> +static int ads7924_of_parse_channel_config(struct iio_dev *indio_dev,
> +					   struct device_node *np)
> +{
> +	struct ads7924_data *priv = iio_priv(indio_dev);
> +	struct device *dev = priv->dev;
> +	struct device_node *child;
> +	int num_channels;
> +	unsigned int channel = 0;
> +	int ret;
> +
> +	num_channels = of_get_available_child_count(np);

As mentioned below, this should be changed to use the generic firmware
property accessors in include/linux/property.h
Amongst other things that lets us use the driver with various software
added properties (e.g. if it's on a daughter board etc) or via ACPI
and the PRP0001 magic ID.

> +	if (!num_channels) {
> +		dev_err(dev, "no channel children\n");
> +		return -ENODEV;
> +	}
> +	dev_dbg(dev, "found %d ADC channels\n", num_channels);
> +
> +	for_each_available_child_of_node(np, child) {
> +		ret = of_property_read_u32(child, "reg", &channel);
> +		if (ret)
> +			goto err;
> +
> +		if (channel >= ADS7924_CHANNELS) {
> +			dev_err(dev, "invalid channel index %d\n", channel);
> +			ret = -EINVAL;
> +			goto err;
> +		}
> +	}
> +
> +	return 0;
> +err:
> +	of_node_put(child);
> +
> +	return ret;
> +}
> +
> +static int ads7924_set_conv_mode(struct ads7924_data *data, int mode)
> +{
> +	/* When switching between modes, be sure to first select the Awake mode

IIO comment syntax is the most common one in kernel code (a few exceptions exist
for historical reasons).  Anyhow.

	/*
	 * When switching...
	 * ...
	 */

> +	 * and then switch to the desired mode. This procedure ensures the
> +	 * internal control logic is properly synchronized.
> +	 */
> +	if (mode != ADS7924_MODECNTRL_IDLE) {
> +		int ret;
> +
> +		ret = regmap_update_bits(data->regmap, ADS7924_MODECNTRL_REG,
> +					 ADS7924_MODECNTRL_MODE_MASK,
> +					 ADS7924_MODECNTRL_AWAKE <<
> +					 ADS7924_MODECNTRL_MODE_SHIFT);
Use FIELD_PREP()

> +		if (ret)
> +			return ret;
> +	}
> +
> +	return regmap_update_bits(data->regmap, ADS7924_MODECNTRL_REG,
> +				  ADS7924_MODECNTRL_MODE_MASK,
> +				  mode << ADS7924_MODECNTRL_MODE_SHIFT);
> +}

...

> +
> +static int ads7924_probe(struct i2c_client *client)
> +{
> +	struct iio_dev *indio_dev;
> +	struct ads7924_data *data;
> +	struct device *dev = &client->dev;
> +	int ret;
> +
> +	indio_dev = devm_iio_device_alloc(&client->dev, sizeof(*data));
> +	if (!indio_dev)
> +		return -ENOMEM;
> +
> +	i2c_set_clientdata(client, indio_dev);

Once you've dropped remove after taking all the calls dev managed
you can drop this as I don't think it's used elswhere.

> +
> +	data = iio_priv(indio_dev);
> +
> +	data->dev = dev;
> +
> +	/* Initialize the reset GPIO as output with an initial value of 0. */
> +	data->reset_gpio = devm_gpiod_get_optional(dev, "reset", GPIOD_OUT_LOW);
> +	if (IS_ERR(data->reset_gpio))
> +		return PTR_ERR(data->reset_gpio);
> +
> +	mutex_init(&data->lock);
> +
> +	indio_dev->name = ADS7924_DRV_NAME;

I'd rather see the string here. There is no particular reason why it should
be the driver name.

> +	indio_dev->modes = INDIO_DIRECT_MODE;
> +
> +	indio_dev->channels = ads7924_channels;
> +	indio_dev->num_channels = ARRAY_SIZE(ads7924_channels);
> +	indio_dev->info = &ads7924_info;
> +
> +	ret = ads7924_of_parse_channel_config(indio_dev, dev->of_node);

We shouldn't see device tree specific handling in a modern driver.
Use the generic accessors in include/linux/property.h

> +	if (ret < 0)
> +		return ret;
> +
> +	data->regmap = devm_regmap_init_i2c(client, &ads7924_regmap_config);
> +	if (IS_ERR(data->regmap)) {
> +		dev_err(dev, "Failed to allocate register map\n");
> +		return PTR_ERR(data->regmap);
> +	}
> +
> +	data->vref_reg = devm_regulator_get(dev, "vref");
> +	if (IS_ERR(data->vref_reg)) {
> +		dev_err(dev, "devm_regulator_get() failed\n");
> +		return PTR_ERR(data->vref_reg);

This is an example of a call that can defer so you should definitely
be using dev_err_probe() as we want the resulting debug info.
It's good practice to just use that everwhere in probe() functions.

> +	}
> +
> +	ret = regulator_enable(data->vref_reg);
> +	if (ret) {
> +		dev_err(dev, "regulator_enable() failed\n");
> +		return ret;
> +	}
> +
> +	ret = devm_add_action_or_reset(dev, ads7924_reg_disable, data->vref_reg);
> +	if (ret) {
> +		dev_err(dev, "devm_add_action_or_reset() failed\n");
> +		return ret;
> +	}
> +
> +	ret = ads7924_reset(indio_dev);
> +	if (ret < 0) {
> +		dev_err(dev, "Failed to reset device\n");
> +		return ret;
> +	}
> +
> +	ret = ads7924_set_conv_mode(data,
> +				    ADS7924_MODECNTRL_AUTO_SCAN);
> +	if (ret)
> +		return ret;

You set this, but whilst you have it set back to idle in remove()
you don't do that in the error paths for this function.
If you change to registering the switch to IDLE to a devm_add_action_or_reset()
callback then it will get automatically called in both paths.

> +
> +	/* Disable signal acquire time. */
> +	ret = regmap_update_bits(data->regmap, ADS7924_ACQCONFIG_REG,
> +				 ADS7924_ACQTIME_MASK, 0);
> +	if (ret < 0) {
> +		dev_err(dev, "Disable signal acquire time failed\n");
> +		return ret;
> +	}
> +
> +	/* Disable power-up time. */
> +	ret = regmap_update_bits(data->regmap, ADS7924_PWRCONFIG_REG,
> +				 ADS7924_PWRUPTIME_MASK, 0);
> +	if (ret < 0) {
> +		dev_err(dev, "Disable power-up time failed\n");
> +		return ret;
> +	}
> +
> +	data->conv_invalid = true;
> +
> +	ret = iio_device_register(indio_dev);
> +	if (ret < 0) {
> +		dev_err(dev, "Failed to register IIO device\n");

For errors in probe function use the cleaner (and deferred probe aware)
		return dev_err_probe(dev, ret, "Failed to register IIO device\n");

Same for all other error messages in probe().

> +		return ret;
> +	}
> +
> +	return 0;
> +}
> +
> +static void ads7924_remove(struct i2c_client *client)
> +{
> +	struct iio_dev *indio_dev = i2c_get_clientdata(client);
> +	struct ads7924_data *data = iio_priv(indio_dev);
> +	int ret;
> +
> +	iio_device_unregister(indio_dev);
Having made the changes suggested below, you can call devm_iio_device_register()
and avoid need for this call.

> +
> +	ret = ads7924_set_conv_mode(data, ADS7924_MODECNTRL_IDLE);

I would suggest wrapping this call up in a callback registered
with devm_add_action_or_reset()  That will allow you to
drop the remove function entirely. It also simplifies error handling.

> +	if (ret)
> +		dev_warn(&client->dev, "Failed to power down (%pe)\n",
> +			 ERR_PTR(ret));
> +}
> +
> +static const struct of_device_id ads7924_of_match[] = {

strange though it may seem, you also need the legacy
i2c_device_id table. There are a couple of reasons why:

1) It's the table used to generate the  module aliases to make
   autoprobing of the module used (there was an attempt to do that
   via the of_device_id table, but for a reason I can't remember it
   didn't work out.
2) There are fun routes via which that old school table is still used.

Hence for now we are in the slightly silly position of having to provide
both.

> +	{ .compatible = "ti,ads7924", },
> +	{}
> +};
> +MODULE_DEVICE_TABLE(of, ads7924_of_match);
> +
> +static struct i2c_driver ads7924_driver = {
> +	.driver = {
> +		.name = ADS7924_DRV_NAME,
With the other use inline, just put the string here as well.
Saves a reviewer having to check the define is reasonable.

> +		.of_match_table = ads7924_of_match,
> +	},
> +	.probe_new	= ads7924_probe,
> +	.remove		= ads7924_remove,
> +};
> +
> +module_i2c_driver(ads7924_driver);
> +
> +MODULE_AUTHOR("Hugo Villeneuve <hvilleneuve@dimonoff.com>");
> +MODULE_DESCRIPTION("Texas Instruments ADS7924 ADC I2C driver");
> +MODULE_LICENSE("GPL");


^ permalink raw reply	[flat|nested] 14+ messages in thread

* Re: [PATCH v1 3/3] dt-bindings: iio: adc: add ADS7924
  2022-12-22 20:36 ` [PATCH v1 3/3] dt-bindings: iio: adc: add ADS7924 Hugo Villeneuve
  2022-12-23  8:19   ` Krzysztof Kozlowski
@ 2022-12-23 14:50   ` Jonathan Cameron
  2022-12-23 19:24     ` Hugo Villeneuve
  1 sibling, 1 reply; 14+ messages in thread
From: Jonathan Cameron @ 2022-12-23 14:50 UTC (permalink / raw)
  To: Hugo Villeneuve
  Cc: hvilleneuve, lars, robh+dt, krzysztof.kozlowski+dt, linux-iio,
	devicetree, linux-kernel

On Thu, 22 Dec 2022 15:36:10 -0500
Hugo Villeneuve <hugo@hugovil.com> wrote:

> From: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> 
> Add device tree bindings document for the Texas Instruments ADS7924
> ADC.
> 
> Signed-off-by: Hugo Villeneuve <hvilleneuve@dimonoff.com>

Hi Hugo,

Whilst you aren't using it yet, the binding should still attempt to be
a full description of the hardware, so I'd expect the interrupt line to
be part of it.

Otherwise, Krzysztof already covered this in detail.

Jonathan


> ---
>  .../bindings/iio/adc/ti,ads7924.yaml          | 103 ++++++++++++++++++
>  1 file changed, 103 insertions(+)
>  create mode 100644 Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml
> 
> diff --git a/Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml b/Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml
> new file mode 100644
> index 000000000000..5408ec95e417
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml
> @@ -0,0 +1,103 @@
> +# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
> +%YAML 1.2
> +---
> +$id: http://devicetree.org/schemas/iio/adc/ti,ads7924.yaml#
> +$schema: http://devicetree.org/meta-schemas/core.yaml#
> +
> +title: TI ADS7924 4 channels 12 bits I2C analog to digital converter
> +
> +maintainers:
> +  - Hugo Villeneuve <hvilleneuve@dimonoff.com>
> +
> +description: |
> +  Texas Instruments ADS7924 4 channels 12 bits I2C analog to digital converter
> +
> +  Specifications:
> +    https://www.ti.com/lit/gpn/ads7924
> +
> +properties:
> +  compatible:
> +    const: ti,ads7924
> +
> +  vref-supply:
> +    description:
> +      The regulator supply for the ADC reference voltage (AVDD)
> +
> +  reg:
> +    maxItems: 1
> +
> +  reset-gpios:
> +    description:
> +      GPIO used for controlling the reset pin
> +    maxItems: 1
> +
> +  "#address-cells":
> +    const: 1
> +
> +  "#size-cells":
> +    const: 0
> +
> +  "#io-channel-cells":
> +    const: 1
> +
> +required:
> +  - compatible
> +  - reg
> +  - vref-supply
> +  - "#address-cells"
> +  - "#size-cells"
> +
> +additionalProperties: false
> +
> +patternProperties:
> +  "^channel@[0-3]+$":
> +    type: object
> +    description:
> +      Child nodes needed for each channel that the platform uses.
> +
> +    properties:
> +      reg:
> +        description: |
> +          0: Voltage over AIN0 and GND.
> +          1: Voltage over AIN1 and GND.
> +          2: Voltage over AIN2 and GND.
> +          3: Voltage over AIN3 and GND.
> +        items:
> +          - minimum: 0
> +            maximum: 3
> +
> +    required:
> +      - reg
> +
> +examples:
> +  - |
> +    i2c {
> +        #address-cells = <1>;
> +        #size-cells = <0>;
> +
> +        adc@48 {
> +            compatible = "ti,ads7924";
> +            reg = <0x48>;
> +            vref-supply = <&ads7924_reg>;
> +            reset-gpios = <&gpio 5 GPIO_ACTIVE_LOW>;
> +            #address-cells = <1>;
> +            #size-cells = <0>;
> +            channel@0 {
> +              reg = <0>;
> +              label = "CH0";
> +            };
> +            channel@1 {
> +              reg = <1>;
> +              label = "CH1";
> +            };
> +            channel@2 {
> +              reg = <2>;
> +              label = "CH2";
> +            };
> +            channel@3 {
> +              reg = <3>;
> +              label = "CH3";
> +            };
> +        };
> +    };
> +...


^ permalink raw reply	[flat|nested] 14+ messages in thread

* Re: [PATCH v1 3/3] dt-bindings: iio: adc: add ADS7924
  2022-12-23 14:09     ` Jonathan Cameron
@ 2022-12-23 17:56       ` Hugo Villeneuve
  0 siblings, 0 replies; 14+ messages in thread
From: Hugo Villeneuve @ 2022-12-23 17:56 UTC (permalink / raw)
  To: Jonathan Cameron
  Cc: Krzysztof Kozlowski, hvilleneuve, lars, robh+dt,
	krzysztof.kozlowski+dt, linux-iio, devicetree, linux-kernel

On Fri, 23 Dec 2022 14:09:08 +0000
Jonathan Cameron <jic23@kernel.org> wrote:

> > 
> > > +    description:
> > > +      Child nodes needed for each channel that the platform uses.  
> > 
> > I cannot understand this sentence at all. Instead describe the hardware
> > you are here representing. What's this?
> 
> Needs rewording, but basically - "Which pins are connected to anything?"

Hi Jonathan and Krzysztof,
when writing this driver a few months ago, I used as a starting point the C source file and the YAML file of the TI ADS1015 driver.

I cannot say that I fully understand the sentence myself :) So I will reword it.

I will also take care of the other dt-bindings comments for version 2.

Thank you for your feedback.

Hugo V.

-- 
Hugo Villeneuve <hugo@hugovil.com>

^ permalink raw reply	[flat|nested] 14+ messages in thread

* Re: [PATCH v1 1/3] iio: adc: Kconfig: add SPI interface mention to AD7924 description
  2022-12-23 14:12   ` Jonathan Cameron
@ 2022-12-23 18:52     ` Hugo Villeneuve
  2022-12-30 18:03       ` Jonathan Cameron
  0 siblings, 1 reply; 14+ messages in thread
From: Hugo Villeneuve @ 2022-12-23 18:52 UTC (permalink / raw)
  To: Jonathan Cameron
  Cc: hvilleneuve, lars, robh+dt, krzysztof.kozlowski+dt, linux-iio,
	devicetree, linux-kernel

On Fri, 23 Dec 2022 14:12:32 +0000
Jonathan Cameron <jic23@kernel.org> wrote:

> On Thu, 22 Dec 2022 15:36:08 -0500
> Hugo Villeneuve <hugo@hugovil.com> wrote:
> 
> > From: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> > 
> > The Analog Devices AD7924 uses an SPI interface. There is also a Texas
> > Instruments ADS7924 which uses an I2C interface.
> > 
> > Adding the SPI mention to the AD7924 will help to avoid confusion
> > between the two chips.
> Hi Hugo,
> 
> Welcome to IIO.
> 
> I don't really mind this, but given they have different part numbers
> and the similarly named TI part could just have easily been SPI
> I'm not sure the clarification is really useful.
> 
> Also, under all the circumstances I can think of, if you can see the
> help text you can also see the SPI dependence clearly listed.
> 
> Hence I think is just noise, though I'm guessing it reflects a
> confusion you ran into!
> 
> Jonathan

Hi Jonathan,
yes, I initially tought that the TI ADS7924 was already supported because of the AD7924 entry. I wrongly assumed that the parts were similar and TI just renamed it because they bought Analog Devices. I am pretty sure that I am not the only one having made a similar error :)

Of course, both chips differ not only because of their interface (SPI vs I2C), but also in their modes of operation and registers, interrupt pin presence (ADS7924), etc.

But I can drop this patch if you want.

Hugo V.



> > Signed-off-by: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> > ---
> >  drivers/iio/adc/Kconfig | 2 +-
> >  1 file changed, 1 insertion(+), 1 deletion(-)
> > 
> > diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig
> > index 46c4fc2fc534..235319546974 100644
> > --- a/drivers/iio/adc/Kconfig
> > +++ b/drivers/iio/adc/Kconfig
> > @@ -243,7 +243,7 @@ config AD7923
> >  	select IIO_TRIGGERED_BUFFER
> >  	help
> >  	  Say yes here to build support for Analog Devices
> > -	  AD7904, AD7914, AD7923, AD7924 4 Channel ADCs.
> > +	  AD7904, AD7914, AD7923, AD7924 4 Channel SPI ADCs.
> >  
> >  	  To compile this driver as a module, choose M here: the
> >  	  module will be called ad7923.
> 
> 


-- 
Hugo Villeneuve <hugo@hugovil.com>

^ permalink raw reply	[flat|nested] 14+ messages in thread

* Re: [PATCH v1 3/3] dt-bindings: iio: adc: add ADS7924
  2022-12-23 14:50   ` Jonathan Cameron
@ 2022-12-23 19:24     ` Hugo Villeneuve
  0 siblings, 0 replies; 14+ messages in thread
From: Hugo Villeneuve @ 2022-12-23 19:24 UTC (permalink / raw)
  To: Jonathan Cameron
  Cc: hvilleneuve, lars, robh+dt, krzysztof.kozlowski+dt, linux-iio,
	devicetree, linux-kernel

On Fri, 23 Dec 2022 14:50:13 +0000
Jonathan Cameron <jic23@kernel.org> wrote:

> On Thu, 22 Dec 2022 15:36:10 -0500
> Hugo Villeneuve <hugo@hugovil.com> wrote:
> 
> > From: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> > 
> > Add device tree bindings document for the Texas Instruments ADS7924
> > ADC.
> > 
> > Signed-off-by: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> 
> Hi Hugo,
> 
> Whilst you aren't using it yet, the binding should still attempt to be
> a full description of the hardware, so I'd expect the interrupt line to
> be part of it.
> 
> Otherwise, Krzysztof already covered this in detail.

Ok, makes sense. Added.

Hugo.

 > Jonathan
> 
> 
> > ---
> >  .../bindings/iio/adc/ti,ads7924.yaml          | 103 ++++++++++++++++++
> >  1 file changed, 103 insertions(+)
> >  create mode 100644 Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml
> > 
> > diff --git a/Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml b/Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml
> > new file mode 100644
> > index 000000000000..5408ec95e417
> > --- /dev/null
> > +++ b/Documentation/devicetree/bindings/iio/adc/ti,ads7924.yaml
> > @@ -0,0 +1,103 @@
> > +# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
> > +%YAML 1.2
> > +---
> > +$id: http://devicetree.org/schemas/iio/adc/ti,ads7924.yaml#
> > +$schema: http://devicetree.org/meta-schemas/core.yaml#
> > +
> > +title: TI ADS7924 4 channels 12 bits I2C analog to digital converter
> > +
> > +maintainers:
> > +  - Hugo Villeneuve <hvilleneuve@dimonoff.com>
> > +
> > +description: |
> > +  Texas Instruments ADS7924 4 channels 12 bits I2C analog to digital converter
> > +
> > +  Specifications:
> > +    https://www.ti.com/lit/gpn/ads7924
> > +
> > +properties:
> > +  compatible:
> > +    const: ti,ads7924
> > +
> > +  vref-supply:
> > +    description:
> > +      The regulator supply for the ADC reference voltage (AVDD)
> > +
> > +  reg:
> > +    maxItems: 1
> > +
> > +  reset-gpios:
> > +    description:
> > +      GPIO used for controlling the reset pin
> > +    maxItems: 1
> > +
> > +  "#address-cells":
> > +    const: 1
> > +
> > +  "#size-cells":
> > +    const: 0
> > +
> > +  "#io-channel-cells":
> > +    const: 1
> > +
> > +required:
> > +  - compatible
> > +  - reg
> > +  - vref-supply
> > +  - "#address-cells"
> > +  - "#size-cells"
> > +
> > +additionalProperties: false
> > +
> > +patternProperties:
> > +  "^channel@[0-3]+$":
> > +    type: object
> > +    description:
> > +      Child nodes needed for each channel that the platform uses.
> > +
> > +    properties:
> > +      reg:
> > +        description: |
> > +          0: Voltage over AIN0 and GND.
> > +          1: Voltage over AIN1 and GND.
> > +          2: Voltage over AIN2 and GND.
> > +          3: Voltage over AIN3 and GND.
> > +        items:
> > +          - minimum: 0
> > +            maximum: 3
> > +
> > +    required:
> > +      - reg
> > +
> > +examples:
> > +  - |
> > +    i2c {
> > +        #address-cells = <1>;
> > +        #size-cells = <0>;
> > +
> > +        adc@48 {
> > +            compatible = "ti,ads7924";
> > +            reg = <0x48>;
> > +            vref-supply = <&ads7924_reg>;
> > +            reset-gpios = <&gpio 5 GPIO_ACTIVE_LOW>;
> > +            #address-cells = <1>;
> > +            #size-cells = <0>;
> > +            channel@0 {
> > +              reg = <0>;
> > +              label = "CH0";
> > +            };
> > +            channel@1 {
> > +              reg = <1>;
> > +              label = "CH1";
> > +            };
> > +            channel@2 {
> > +              reg = <2>;
> > +              label = "CH2";
> > +            };
> > +            channel@3 {
> > +              reg = <3>;
> > +              label = "CH3";
> > +            };
> > +        };
> > +    };
> > +...
> 
> 


-- 
Hugo Villeneuve <hugo@hugovil.com>

^ permalink raw reply	[flat|nested] 14+ messages in thread

* Re: [PATCH v1 1/3] iio: adc: Kconfig: add SPI interface mention to AD7924 description
  2022-12-23 18:52     ` Hugo Villeneuve
@ 2022-12-30 18:03       ` Jonathan Cameron
  0 siblings, 0 replies; 14+ messages in thread
From: Jonathan Cameron @ 2022-12-30 18:03 UTC (permalink / raw)
  To: Hugo Villeneuve
  Cc: hvilleneuve, lars, robh+dt, krzysztof.kozlowski+dt, linux-iio,
	devicetree, linux-kernel

On Fri, 23 Dec 2022 13:52:09 -0500
Hugo Villeneuve <hugo@hugovil.com> wrote:

> On Fri, 23 Dec 2022 14:12:32 +0000
> Jonathan Cameron <jic23@kernel.org> wrote:
> 
> > On Thu, 22 Dec 2022 15:36:08 -0500
> > Hugo Villeneuve <hugo@hugovil.com> wrote:
> >   
> > > From: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> > > 
> > > The Analog Devices AD7924 uses an SPI interface. There is also a Texas
> > > Instruments ADS7924 which uses an I2C interface.
> > > 
> > > Adding the SPI mention to the AD7924 will help to avoid confusion
> > > between the two chips.  
> > Hi Hugo,
> > 
> > Welcome to IIO.
> > 
> > I don't really mind this, but given they have different part numbers
> > and the similarly named TI part could just have easily been SPI
> > I'm not sure the clarification is really useful.
> > 
> > Also, under all the circumstances I can think of, if you can see the
> > help text you can also see the SPI dependence clearly listed.
> > 
> > Hence I think is just noise, though I'm guessing it reflects a
> > confusion you ran into!
> > 
> > Jonathan  
> 
> Hi Jonathan,
> yes, I initially tought that the TI ADS7924 was already supported because of the AD7924 entry. I wrongly assumed that the parts were similar and TI just renamed it because they bought Analog Devices. I am pretty sure that I am not the only one having made a similar error :)
> 

Yikes.  If TI bought ADI that would definitely be big news (my uninformed
guess it it would never get past competition authorities :)

I do vaguely wonder if long term we'll have to start naming drivers
with vendor prefixes as we will eventually get significant naming clashes.
Still I'm not keen to do it until we have a real problem.


> Of course, both chips differ not only because of their interface (SPI vs I2C), but also in their modes of operation and registers, interrupt pin presence (ADS7924), etc.
> 
> But I can drop this patch if you want.

Will do,

Thanks,

Jonathan

> 
> Hugo V.
> 
> 
> 
> > > Signed-off-by: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> > > ---
> > >  drivers/iio/adc/Kconfig | 2 +-
> > >  1 file changed, 1 insertion(+), 1 deletion(-)
> > > 
> > > diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig
> > > index 46c4fc2fc534..235319546974 100644
> > > --- a/drivers/iio/adc/Kconfig
> > > +++ b/drivers/iio/adc/Kconfig
> > > @@ -243,7 +243,7 @@ config AD7923
> > >  	select IIO_TRIGGERED_BUFFER
> > >  	help
> > >  	  Say yes here to build support for Analog Devices
> > > -	  AD7904, AD7914, AD7923, AD7924 4 Channel ADCs.
> > > +	  AD7904, AD7914, AD7923, AD7924 4 Channel SPI ADCs.
> > >  
> > >  	  To compile this driver as a module, choose M here: the
> > >  	  module will be called ad7923.  
> > 
> >   
> 
> 


^ permalink raw reply	[flat|nested] 14+ messages in thread

* Re: [PATCH v1 2/3] iio: adc: ti-ads7924: add ADS7924 driver
  2022-12-23 14:47   ` Jonathan Cameron
@ 2023-01-10 15:38     ` Hugo Villeneuve
  0 siblings, 0 replies; 14+ messages in thread
From: Hugo Villeneuve @ 2023-01-10 15:38 UTC (permalink / raw)
  To: Jonathan Cameron
  Cc: hvilleneuve, lars, robh+dt, krzysztof.kozlowski+dt, linux-iio,
	devicetree, linux-kernel

On Fri, 23 Dec 2022 14:47:19 +0000
Jonathan Cameron <jic23@kernel.org> wrote:

> On Thu, 22 Dec 2022 15:36:09 -0500
> Hugo Villeneuve <hugo@hugovil.com> wrote:
> 
> > From: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> > 
> > The Texas Instruments ADS7924 is a 4 channels, 12-bit analog to
> > digital converter (ADC) with an I2C interface.
> > 
> > Signed-off-by: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> 
> Hi Hugo,
> 
> Thanks for the driver. Some comments inline.
> Given the various bits of support present, are you planning to follow up
> with buffered support (chardev etc).
> 
> Jonathan

Hi Jonathan,
thank you for your extensive feedback!

As a general note, I wrote that driver using the ADS1015 as a starting point (circa january 2022). So in fact I removed buffered support, and also other unused features to have the simplest driver possible. That explain why you see a lot of defines/variables that could be removed for now.

I was thinking of maybe adding those features at a later time, once a first version of this simple driver is accepted into the kernel. In the meantime, I will remove these unused defines/variables.

> > ---
> >  MAINTAINERS                  |   7 +
> >  drivers/iio/adc/Kconfig      |  13 +
> >  drivers/iio/adc/Makefile     |   1 +
> >  drivers/iio/adc/ti-ads7924.c | 514 +++++++++++++++++++++++++++++++++++
> >  4 files changed, 535 insertions(+)
> >  create mode 100644 drivers/iio/adc/ti-ads7924.c
> > 
> 
> ...
> 
> > diff --git a/drivers/iio/adc/Kconfig b/drivers/iio/adc/Kconfig
> > index 235319546974..18adcd6200b0 100644
> > --- a/drivers/iio/adc/Kconfig
> > +++ b/drivers/iio/adc/Kconfig
> > @@ -1207,6 +1207,19 @@ config TI_ADS1015
> >  	  This driver can also be built as a module. If so, the module will be
> >  	  called ti-ads1015.
> >  
> > +config TI_ADS7924
> > +	tristate "Texas Instruments ADS7924 ADC"
> > +	depends on I2C
> > +	select REGMAP_I2C
> > +	select IIO_BUFFER
> > +	select IIO_TRIGGERED_BUFFER
> 
> No buffer support yet. So drop these for now.

Done.

> > +	help
> > +	  If you say yes here you get support for Texas Instruments ADS7924
> > +	  4 channels, 12-bit I2C ADC chip.
> > +
> > +	  This driver can also be built as a module. If so, the module will be
> > +	  called ti-ads7924.
> > +
> >  config TI_ADS7950
> >  	tristate "Texas Instruments ADS7950 ADC driver"
> >  	depends on SPI && GPIOLIB
> > diff --git a/drivers/iio/adc/Makefile b/drivers/iio/adc/Makefile
> > index 6e08415c3f3a..1e5bdf47a091 100644
> > --- a/drivers/iio/adc/Makefile
> > +++ b/drivers/iio/adc/Makefile
> > @@ -107,6 +107,7 @@ obj-$(CONFIG_TI_ADC108S102) += ti-adc108s102.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_ADS7924) += ti-ads7924.o
> >  obj-$(CONFIG_TI_ADS7950) += ti-ads7950.o
> >  obj-$(CONFIG_TI_ADS8344) += ti-ads8344.o
> >  obj-$(CONFIG_TI_ADS8688) += ti-ads8688.o
> > diff --git a/drivers/iio/adc/ti-ads7924.c b/drivers/iio/adc/ti-ads7924.c
> > new file mode 100644
> > index 000000000000..e9ca7a045d18
> > --- /dev/null
> > +++ b/drivers/iio/adc/ti-ads7924.c
> > @@ -0,0 +1,514 @@
> > +// SPDX-License-Identifier: GPL-2.0
> > +/*
> > + * IIO driver for Texas Instruments ADS7924 ADC, 12-bit, 4-Channels, I2C
> > + *
> > + * iio/adc/ti-ads7924.c
> > + * Author: Hugo Villeneuve <hvilleneuve@dimonoff.com>
> > + * Copyright 2022 DimOnOff
> > + *
> > + * based on iio/adc/ti-ads1015.c
> > + * Copyright (c) 2016, Intel Corporation.
> > + *
> > + * Datasheets: https://www.ti.com/lit/gpn/ads7924
> Add as a tag to the tag block of the patch description.
> 
> Datasheet: https://www.ti.com/lit/gpn/ads7924
> on the line above your signoff.
> There are some automated tools that will pick this up I think.

Done.

> > + */
> > +
> > +#include <linux/module.h>
> > +#include <linux/init.h>
> > +#include <linux/irq.h>
> > +#include <linux/i2c.h>
> > +#include <linux/property.h>
> 
> hmm. you include property.h then use the of ones...

Now fixed after implementing your suggestions below, so keeping this include.

 
> > +#include <linux/regmap.h>
> > +#include <linux/mutex.h>
> > +#include <linux/delay.h>
> 
> Put this block in alphabetical order.

Ok done.

> > +
> > +#include <linux/iio/iio.h>
> > +#include <linux/iio/types.h>
> > +#include <linux/iio/sysfs.h>
> 
> Don't think that's used.  Normally only needed for custom attributes.

Ok removed.

> > +#include <linux/iio/buffer.h>
> 
> Not currently used.

Ok removed.

> > +#include <linux/gpio/consumer.h>
> > +#include <linux/regulator/consumer.h>
> > +
> > +#define ADS7924_DRV_NAME "ads7924"
> > +
> > +#define ADS7924_CHANNELS 4
> > +
> > +/* Registers. */
> > +#define ADS7924_MODECNTRL_REG	0x00
> > +#define ADS7924_INTCNTRL_REG	0x01
> > +#define ADS7924_DATA0_U_REG	0x02
> > +#define ADS7924_DATA0_L_REG	0x03
> > +#define ADS7924_DATA1_U_REG	0x04
> > +#define ADS7924_DATA1_L_REG	0x05
> > +#define ADS7924_DATA2_U_REG	0x06
> > +#define ADS7924_DATA2_L_REG	0x07
> > +#define ADS7924_DATA3_U_REG	0x08
> > +#define ADS7924_DATA3_L_REG	0x09
> > +#define ADS7924_ULR0_REG	0x0A
> > +#define ADS7924_LLR0_REG	0x0B
> > +#define ADS7924_ULR1_REG	0x0C
> > +#define ADS7924_LLR1_REG	0x0D
> > +#define ADS7924_ULR2_REG	0x0E
> > +#define ADS7924_LLR2_REG	0x0F
> > +#define ADS7924_ULR3_REG	0x10
> > +#define ADS7924_LLR3_REG	0x11
> > +#define ADS7924_INTCONFIG_REG	0x12
> > +#define ADS7924_SLPCONFIG_REG	0x13
> > +#define ADS7924_ACQCONFIG_REG	0x14
> > +#define ADS7924_PWRCONFIG_REG	0x15
> > +#define ADS7924_RESET_REG	0x16
> > +
> 
> Comment syntax as below.

Ok done.

> 
> > +/* Register address INC bit: when set to '1', the register address is
> > + * automatically incremented after every register read which allows convenient
> > + * reading of multiple registers. Set INC to '0' when reading a single register.
> > + */
> > +#define ADS7924_AUTO_INCREMENT_BIT	BIT(7)
> > +
> > +#define ADS7924_MODECNTRL_MODE_SHIFT	2
> > +#define ADS7924_MODECNTRL_MODE_MASK	GENMASK(7, ADS7924_MODECNTRL_MODE_SHIFT)
> > +
> > +#define ADS7924_MODECNTRL_SEL_SHIFT	0
> 
> As below, don't provide a _SHIFT macro for any of these.
> The MASK should be the only one needed as it implicitly contains the shift anyway.

Ok, done, now using FIELD_PREP as you suggested. Much simpler this way!


> > +#define ADS7924_MODECNTRL_SEL_MASK	GENMASK(1, ADS7924_MODECNTRL_SEL_SHIFT)
> > +
> > +#define ADS7924_CFG_INTPOL_BIT		1
> > +#define ADS7924_CFG_INTTRIG_BIT		0
> > +
> > +#define ADS7924_CFG_INTPOL_MASK		BIT(ADS7924_CFG_INTPOL_BIT)
> > +#define ADS7924_CFG_INTTRIG_MASK	BIT(ADS7924_CFG_INTTRIG_BIT)
> > +
> > +/* Interrupt pin polarity */
> > +#define ADS7924_CFG_INTPOL_LOW		0
> > +#define ADS7924_CFG_INTPOL_HIGH		1
> > +
> > +/* Interrupt pin signaling */
> > +#define ADS7924_CFG_INTTRIG_LEVEL	0
> > +#define ADS7924_CFG_INTTRIG_EDGE	1
> > +
> > +/* Mode control values */
> > +#define ADS7924_MODECNTRL_IDLE			0x00
> > +#define ADS7924_MODECNTRL_AWAKE			0x20
> > +#define ADS7924_MODECNTRL_MANUAL_SINGLE		0x30
> > +#define ADS7924_MODECNTRL_MANUAL_SCAN		0x32
> > +#define ADS7924_MODECNTRL_AUTO_SINGLE		0x31
> > +#define ADS7924_MODECNTRL_AUTO_SCAN		0x33
> > +#define ADS7924_MODECNTRL_AUTO_SINGLE_SLEEP	0x39
> > +#define ADS7924_MODECNTRL_AUTO_SCAN_SLEEP	0x3B
> > +#define ADS7924_MODECNTRL_AUTO_BURST_SLEEP	0x3F
> > +
> > +#define ADS7924_ACQTIME_SHIFT	0
> > +#define ADS7924_ACQTIME_MASK	GENMASK(4, ADS7924_ACQTIME_SHIFT)
> > +
> > +#define ADS7924_PWRUPTIME_SHIFT	0
> 
> No point in providing shift. The mask definition should always be sufficient
> if using FIELD_GET / FIELD_PREP()

Ok, done (now using FIELD_PREP as you suggested).

> > +#define ADS7924_PWRUPTIME_MASK	GENMASK(4, ADS7924_PWRUPTIME_SHIFT)
> > +
> > +/* The power-up time is allowed to elapse whenever the device has been shutdown
> Comment syntax
> /*
>  * The power-up....

Done.

> > + * in idle mode. Power-up time can allow external circuits, such as an
> > + * operational amplifier, between the MUXOUT and ADCIN pins to turn on.
> > + * The nominal time programmed by the PUTIME[4:0] register bits is given by:
> > + *     t PU = PWRUPTIME[4:0] × 2 μs
> > + * If a power-up time is not required, set the bits to '0' to effectively bypass.
> > + */
> > +#define ADS7924_PWRUPTIME_US 0 /* Bypass (0us). */
> > +
> > +/* Acquisition Time. Minimum is 6us. */
> > +#define ADS7924_ACQTIME_US 6 /* Disable (6us). */
> 
> Disable?  Strange comment for something called acquisition time.

Agreed, I have reworded the comment to make it clearer.

> > +
> > +/* The conversion time is always 4μs and cannot be programmed by the user. */
> > +#define ADS7924_CONVTIME_US 4
> > +
> > +#define ADS7924_TOTAL_CONVTIME (ADS7924_PWRUPTIME_US + ADS7924_ACQTIME_US + \
> > +				ADS7924_CONVTIME_US)
> 
> Postfix this with _US as well.  It's good habit to put units in defines, so
> do it everywhere it makes sense.

Ok done.

> > +
> > +#define ADS7924_SLEEP_DELAY_MS		2000
> > +
> > +enum ads7924_channels {
> > +	ADS7924_CH0,
> > +	ADS7924_CH1,
> > +	ADS7924_CH2,
> > +	ADS7924_CH3,
> > +	ADS7924_TIMESTAMP,
> > +};
> > +
> > +#define ADS7924_V_CHAN(_chan, _addr) {				\
> > +	.type = IIO_VOLTAGE,					\
> > +	.indexed = 1,						\
> > +	.address = _addr,					\
> > +	.channel = _chan,					\
> > +	.info_mask_separate = BIT(IIO_CHAN_INFO_RAW), 		\
> > +	.info_mask_shared_by_type = BIT(IIO_CHAN_INFO_SCALE),	\
> > +	.scan_index = _addr,					\
> > +	.scan_type = {						\
> > +		.sign = 's',					\
> > +		.realbits = 12,					\
> 
> You are using the shift element which is fine, but I think the majority of this
> isn't yet used as no buffer support. As such, I'd drop anything you aren't
> using for now. Add it back if you add buffered support in future.
> 
> > +		.storagebits = 16,				\
> > +		.shift = 4,					\
> > +		.endianness = IIO_CPU,				\
> 
> It's big endian off the devices, so that's how you should present it
> to userspace via a buffered interface (this scan_type entry has no
> standard meaning except for buffered interfaces).

Ok, dropped scan_index and scan_type fields.

> 
> > +	},							\
> > +	.datasheet_name = "AIN"#_chan,				\
> > +}
> > +
> > +/* To map a channel with its corresponding data register (MSB). */
> > +static const unsigned int ads7924_channel_data_msb_regs[] = {
> > +	ADS7924_DATA0_U_REG,
> > +	ADS7924_DATA1_U_REG,
> > +	ADS7924_DATA2_U_REG,
> > +	ADS7924_DATA3_U_REG
> 
> It's possible this driver might one day support more elements in here (maybe
> there is an 8 channel otherwise compatible part), so add a trailing comma.
> 
> Generally the only time we don't ask for trailing commas is after NULL terminators
> or other entries that will by definition always be the last element.

Noted, but I finally removed this array, as I am now using the "address" field inside structure iio_chan_spec to store the register address.

> > +};
> > +
> 
> 
> > +static const struct iio_chan_spec ads7924_channels[] = {
> > +	ADS7924_V_CHAN(0, ADS7924_CH0),
> > +	ADS7924_V_CHAN(1, ADS7924_CH1),
> > +	ADS7924_V_CHAN(2, ADS7924_CH2),
> > +	ADS7924_V_CHAN(3, ADS7924_CH3),
> > +	IIO_CHAN_SOFT_TIMESTAMP(ADS7924_TIMESTAMP),
> 
> Timestamp doesn't do anything useful until you support buffered modes.
> So drop it for now.

Ok dropped.

> > +};
> > +
> > +static
> > +int ads7924_get_adc_result(struct ads7924_data *data, int chan, int *val)
> > +{
> > +	int ret;
> > +	__be16 be_val;
> > +
> > +	if (chan < 0 || chan >= ADS7924_CHANNELS)
> > +		return -EINVAL;
> > +
> > +	if (data->conv_invalid) {
> > +		int conv_time;
> > +
> > +		conv_time = ADS7924_TOTAL_CONVTIME;
> > +		/* Allow 10% for internal clock inaccuracy. */
> > +		conv_time += conv_time / 10;
> > +		usleep_range(conv_time, conv_time + 1);
> > +		data->conv_invalid = false;
> > +	}
> > +
> > +	ret = regmap_raw_read(data->regmap, ADS7924_AUTO_INCREMENT_BIT |
> > +			      ads7924_channel_data_msb_regs[chan],
> > +			      &be_val, sizeof(be_val));
> > +	if (ret)
> > +		return ret;
> > +
> > +	*val = be16_to_cpu(be_val);
> > +	*val = *val >> ads7924_channels[chan].scan_type.shift;
> > +
> > +	return ret;
> > +}
> > +
> > +static int ads7924_read_raw(struct iio_dev *indio_dev,
> > +			    struct iio_chan_spec const *chan, int *val,
> > +			    int *val2, long mask)
> > +{
> > +	int ret, vref_uv;
> > +	struct ads7924_data *data = iio_priv(indio_dev);
> > +
> > +	mutex_lock(&data->lock);
> > +
> > +	switch (mask) {
> > +	case IIO_CHAN_INFO_RAW: {
> > +		ret = iio_device_claim_direct_mode(indio_dev);
> > +		if (ret)
> > +			break;
> > +
> > +		ret = ads7924_get_adc_result(data, chan->address, val);
> > +		if (ret < 0)
> 
> Check the error code after iio_device_release_direct / mutex_unlock()
> That way you can return directly.
> 
> Note, if you add support later for buffered mode, taking a local lock
> outside of claiming direct mode can deadlock.  You are better off
> moving the mutex_lock/unlock inside iio_device_claim_direct_mode()

Ok, noted for the future if I add buffered modes.

> As a side note, iio_device_claim_direct_mode() only does something useful
> if you are supporting buffered mode... So for now it shouldn't really
> be in this driver at all.  The point of that call is protect against
> transitions into buffered modes whilst a call is flight that might
> make a mess of that transition or be affected by it.

Ok, removed iio_device_claim_direct_mode() for now.

> 
> > +			dev_dbg(data->dev, "%s error1\n", __func__);
> > +		else
> > +			ret = IIO_VAL_INT;
> > +
> > +		iio_device_release_direct_mode(indio_dev);
> > +		break;
> > +	}
> > +	case IIO_CHAN_INFO_SCALE:
> > +		vref_uv = regulator_get_voltage(data->vref_reg);
> > +		if (vref_uv < 0) {
> > +			/* dummy regulator "get_voltage" returns -EINVAL */
> > +			ret = -EINVAL;
> > +		} else {
> > +			*val =  vref_uv / 1000; /* Convert reg voltage to mV */
> > +			*val2 = chan->scan_type.realbits; /* Data bits */
> > +			ret = IIO_VAL_FRACTIONAL_LOG2;
> > +		}
> > +		break;
> > +	default:
> > +		ret = -EINVAL;
> > +		break;
> > +	}
> > +
> > +	mutex_unlock(&data->lock);
> 
> You only need the lock for the INFO_RAW switch branch as far as I can see.
> Hence good to reduce it's scope to just that.  It may make sense to factor
> out the code there to a separate function to simplify the error paths
> (a goto out of a switch is a bit nasty to read)

Done for the lock/unlock.

> > +
> > +	return ret;
> > +}
> > +
> > +static const struct iio_info ads7924_info = {
> > +	.read_raw	= ads7924_read_raw,
> > +};
> > +
> > +static int ads7924_of_parse_channel_config(struct iio_dev *indio_dev,
> > +					   struct device_node *np)
> > +{
> > +	struct ads7924_data *priv = iio_priv(indio_dev);
> > +	struct device *dev = priv->dev;
> > +	struct device_node *child;
> > +	int num_channels;
> > +	unsigned int channel = 0;
> > +	int ret;
> > +
> > +	num_channels = of_get_available_child_count(np);
> 
> As mentioned below, this should be changed to use the generic firmware
> property accessors in include/linux/property.h
> Amongst other things that lets us use the driver with various software
> added properties (e.g. if it's on a daughter board etc) or via ACPI
> and the PRP0001 magic ID.

Ok, converted.

> > +	if (!num_channels) {
> > +		dev_err(dev, "no channel children\n");
> > +		return -ENODEV;
> > +	}
> > +	dev_dbg(dev, "found %d ADC channels\n", num_channels);
> > +
> > +	for_each_available_child_of_node(np, child) {
> > +		ret = of_property_read_u32(child, "reg", &channel);
> > +		if (ret)
> > +			goto err;
> > +
> > +		if (channel >= ADS7924_CHANNELS) {
> > +			dev_err(dev, "invalid channel index %d\n", channel);
> > +			ret = -EINVAL;
> > +			goto err;
> > +		}
> > +	}
> > +
> > +	return 0;
> > +err:
> > +	of_node_put(child);
> > +
> > +	return ret;
> > +}
> > +
> > +static int ads7924_set_conv_mode(struct ads7924_data *data, int mode)
> > +{
> > +	/* When switching between modes, be sure to first select the Awake mode
> 
> IIO comment syntax is the most common one in kernel code (a few exceptions exist
> for historical reasons).  Anyhow.
> 
> 	/*
> 	 * When switching...
> 	 * ...
> 	 */

Done.

> > +	 * and then switch to the desired mode. This procedure ensures the
> > +	 * internal control logic is properly synchronized.
> > +	 */
> > +	if (mode != ADS7924_MODECNTRL_IDLE) {
> > +		int ret;
> > +
> > +		ret = regmap_update_bits(data->regmap, ADS7924_MODECNTRL_REG,
> > +					 ADS7924_MODECNTRL_MODE_MASK,
> > +					 ADS7924_MODECNTRL_AWAKE <<
> > +					 ADS7924_MODECNTRL_MODE_SHIFT);
> Use FIELD_PREP()

Done.

> > +		if (ret)
> > +			return ret;
> > +	}
> > +
> > +	return regmap_update_bits(data->regmap, ADS7924_MODECNTRL_REG,
> > +				  ADS7924_MODECNTRL_MODE_MASK,
> > +				  mode << ADS7924_MODECNTRL_MODE_SHIFT);
> > +}
> 
> ...
> 
> > +
> > +static int ads7924_probe(struct i2c_client *client)
> > +{
> > +	struct iio_dev *indio_dev;
> > +	struct ads7924_data *data;
> > +	struct device *dev = &client->dev;
> > +	int ret;
> > +
> > +	indio_dev = devm_iio_device_alloc(&client->dev, sizeof(*data));
> > +	if (!indio_dev)
> > +		return -ENOMEM;
> > +
> > +	i2c_set_clientdata(client, indio_dev);
> 
> Once you've dropped remove after taking all the calls dev managed
> you can drop this as I don't think it's used elswhere.

Done.

> 
> > +
> > +	data = iio_priv(indio_dev);
> > +
> > +	data->dev = dev;
> > +
> > +	/* Initialize the reset GPIO as output with an initial value of 0. */
> > +	data->reset_gpio = devm_gpiod_get_optional(dev, "reset", GPIOD_OUT_LOW);
> > +	if (IS_ERR(data->reset_gpio))
> > +		return PTR_ERR(data->reset_gpio);
> > +
> > +	mutex_init(&data->lock);
> > +
> > +	indio_dev->name = ADS7924_DRV_NAME;
> 
> I'd rather see the string here. There is no particular reason why it should
> be the driver name.

Done.

> > +	indio_dev->modes = INDIO_DIRECT_MODE;
> > +
> > +	indio_dev->channels = ads7924_channels;
> > +	indio_dev->num_channels = ARRAY_SIZE(ads7924_channels);
> > +	indio_dev->info = &ads7924_info;
> > +
> > +	ret = ads7924_of_parse_channel_config(indio_dev, dev->of_node);
> 
> We shouldn't see device tree specific handling in a modern driver.
> Use the generic accessors in include/linux/property.h

Done.

> > +	if (ret < 0)
> > +		return ret;
> > +
> > +	data->regmap = devm_regmap_init_i2c(client, &ads7924_regmap_config);
> > +	if (IS_ERR(data->regmap)) {
> > +		dev_err(dev, "Failed to allocate register map\n");
> > +		return PTR_ERR(data->regmap);
> > +	}
> > +
> > +	data->vref_reg = devm_regulator_get(dev, "vref");
> > +	if (IS_ERR(data->vref_reg)) {
> > +		dev_err(dev, "devm_regulator_get() failed\n");
> > +		return PTR_ERR(data->vref_reg);
> 
> This is an example of a call that can defer so you should definitely
> be using dev_err_probe() as we want the resulting debug info.
> It's good practice to just use that everwhere in probe() functions.

Done.

> > +	}
> > +
> > +	ret = regulator_enable(data->vref_reg);
> > +	if (ret) {
> > +		dev_err(dev, "regulator_enable() failed\n");
> > +		return ret;
> > +	}
> > +
> > +	ret = devm_add_action_or_reset(dev, ads7924_reg_disable, data->vref_reg);
> > +	if (ret) {
> > +		dev_err(dev, "devm_add_action_or_reset() failed\n");
> > +		return ret;
> > +	}
> > +
> > +	ret = ads7924_reset(indio_dev);
> > +	if (ret < 0) {
> > +		dev_err(dev, "Failed to reset device\n");
> > +		return ret;
> > +	}
> > +
> > +	ret = ads7924_set_conv_mode(data,
> > +				    ADS7924_MODECNTRL_AUTO_SCAN);
> > +	if (ret)
> > +		return ret;
> 
> You set this, but whilst you have it set back to idle in remove()
> you don't do that in the error paths for this function.
> If you change to registering the switch to IDLE to a devm_add_action_or_reset()
> callback then it will get automatically called in both paths.

Done. 

> > +
> > +	/* Disable signal acquire time. */
> > +	ret = regmap_update_bits(data->regmap, ADS7924_ACQCONFIG_REG,
> > +				 ADS7924_ACQTIME_MASK, 0);
> > +	if (ret < 0) {
> > +		dev_err(dev, "Disable signal acquire time failed\n");
> > +		return ret;
> > +	}
> > +
> > +	/* Disable power-up time. */
> > +	ret = regmap_update_bits(data->regmap, ADS7924_PWRCONFIG_REG,
> > +				 ADS7924_PWRUPTIME_MASK, 0);
> > +	if (ret < 0) {
> > +		dev_err(dev, "Disable power-up time failed\n");
> > +		return ret;
> > +	}
> > +
> > +	data->conv_invalid = true;
> > +
> > +	ret = iio_device_register(indio_dev);
> > +	if (ret < 0) {
> > +		dev_err(dev, "Failed to register IIO device\n");
> 
> For errors in probe function use the cleaner (and deferred probe aware)
> 		return dev_err_probe(dev, ret, "Failed to register IIO device\n");

Done.

 
> Same for all other error messages in probe().
> 

Done.

> > +		return ret;
> > +	}
> > +
> > +	return 0;
> > +}
> > +
> > +static void ads7924_remove(struct i2c_client *client)
> > +{
> > +	struct iio_dev *indio_dev = i2c_get_clientdata(client);
> > +	struct ads7924_data *data = iio_priv(indio_dev);
> > +	int ret;
> > +
> > +	iio_device_unregister(indio_dev);
> Having made the changes suggested below, you can call devm_iio_device_register()
> and avoid need for this call.

Done.

> > +
> > +	ret = ads7924_set_conv_mode(data, ADS7924_MODECNTRL_IDLE);
> 
> I would suggest wrapping this call up in a callback registered
> with devm_add_action_or_reset()  That will allow you to
> drop the remove function entirely. It also simplifies error handling.

Done.

> 
> > +	if (ret)
> > +		dev_warn(&client->dev, "Failed to power down (%pe)\n",
> > +			 ERR_PTR(ret));
> > +}
> > +
> > +static const struct of_device_id ads7924_of_match[] = {
> 
> strange though it may seem, you also need the legacy
> i2c_device_id table. There are a couple of reasons why:
> 
> 1) It's the table used to generate the  module aliases to make
>    autoprobing of the module used (there was an attempt to do that
>    via the of_device_id table, but for a reason I can't remember it
>    didn't work out.
> 2) There are fun routes via which that old school table is still used.
> 
> Hence for now we are in the slightly silly position of having to provide
> both.

Done.

> > +	{ .compatible = "ti,ads7924", },
> > +	{}
> > +};
> > +MODULE_DEVICE_TABLE(of, ads7924_of_match);
> > +
> > +static struct i2c_driver ads7924_driver = {
> > +	.driver = {
> > +		.name = ADS7924_DRV_NAME,
> With the other use inline, just put the string here as well.
> Saves a reviewer having to check the define is reasonable.

Done.

> 
> > +		.of_match_table = ads7924_of_match,
> > +	},
> > +	.probe_new	= ads7924_probe,
> > +	.remove		= ads7924_remove,
> > +};
> > +
> > +module_i2c_driver(ads7924_driver);
> > +
> > +MODULE_AUTHOR("Hugo Villeneuve <hvilleneuve@dimonoff.com>");
> > +MODULE_DESCRIPTION("Texas Instruments ADS7924 ADC I2C driver");
> > +MODULE_LICENSE("GPL");

I will submit a V2 version with all those changes soon.

Thank you, Hugo V.

^ permalink raw reply	[flat|nested] 14+ messages in thread

end of thread, other threads:[~2023-01-10 15:39 UTC | newest]

Thread overview: 14+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2022-12-22 20:36 [PATCH v1 0/3] iio: adc: ti-ads7924: add ADS7924 driver Hugo Villeneuve
2022-12-22 20:36 ` [PATCH v1 1/3] iio: adc: Kconfig: add SPI interface mention to AD7924 description Hugo Villeneuve
2022-12-23 14:12   ` Jonathan Cameron
2022-12-23 18:52     ` Hugo Villeneuve
2022-12-30 18:03       ` Jonathan Cameron
2022-12-22 20:36 ` [PATCH v1 2/3] iio: adc: ti-ads7924: add ADS7924 driver Hugo Villeneuve
2022-12-23 14:47   ` Jonathan Cameron
2023-01-10 15:38     ` Hugo Villeneuve
2022-12-22 20:36 ` [PATCH v1 3/3] dt-bindings: iio: adc: add ADS7924 Hugo Villeneuve
2022-12-23  8:19   ` Krzysztof Kozlowski
2022-12-23 14:09     ` Jonathan Cameron
2022-12-23 17:56       ` Hugo Villeneuve
2022-12-23 14:50   ` Jonathan Cameron
2022-12-23 19:24     ` Hugo Villeneuve

This is a public inbox, see mirroring instructions
for how to clone and mirror all data and code used for this inbox;
as well as URLs for NNTP newsgroup(s).