devicetree.vger.kernel.org archive mirror
 help / color / mirror / Atom feed
* [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor
@ 2025-08-02  6:44 Dixit Parmar
  2025-08-02  6:44 ` [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor Dixit Parmar
                   ` (2 more replies)
  0 siblings, 3 replies; 22+ messages in thread
From: Dixit Parmar @ 2025-08-02  6:44 UTC (permalink / raw)
  To: Jonathan Cameron, David Lechner, Nuno Sá, Andy Shevchenko,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley
  Cc: linux-kernel, linux-iio, devicetree, Dixit Parmar

The Infineon TLV493D is a Low-Power 3D Magnetic Sensor. The Sensor
applications includes joysticks, control elements (white goods,
multifunction knops), or electric meters (anti tampering) and any
other application that requires accurate angular measurements at
low power consumptions.

The Sensor is configured over I2C, and as part of Sensor measurement
data it provides 3-Axis magnetic fields and temperature core measurement.

The driver supports raw value read and buffered input via external trigger
to allow streaming values with the same sensing timestamp.

While sensor has interrupt pin multiplexed with I2C SCL pin. But for bus
configurations interrupt(INT) is not recommended, unless timing constraints
between I2C data transfers and interrupt pulses are monitored and aligned.

The Sensor's I2C register map and mode information is described in product
User Manual[Link].

Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
Link: https://www.mouser.com/pdfDocs/Infineon-TLV493D-A1B6_3DMagnetic-UserManual-v01_03-EN.pdf
Signed-off-by: Dixit Parmar <dixitparmar19@gmail.com>
---
Changes in v2:
- Drop regmap implementation in favor of using direct i2c APIs to
  have uniform communication APIs across the driver.
- Remove custom device-tree properties as suggested and hardcode
  setting operating mode in probe().
- Derive and hardcode temperature offset from raw offset and compensation.
- Add missing device name(tlv493_) prefix in global variables.
- Change float operation with multiplier to fixed value(1100).
- Change Magnetic field reporting to Guass SI unit.
- User FIELD_PREP instead of direct bitwise ops.
- Convert sensor channel parsing logic from Macro to function for
  better readability.
- Discard unused #define's.
- Discard IIO_CHAN_INFO_PROCESSED.
- Maintain alphabetical order of config options in Makefile and Kconfig.
- Readability fixes.
- Link to v1: https://lore.kernel.org/r/20250726-tlv493d-sensor-v6_16-rc5-v1-0-deac027e6f32@gmail.com

---
Dixit Parmar (2):
      iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor
      dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor

 .../iio/magnetometer/infineon,tlv493d.yaml         |  45 ++
 .../devicetree/bindings/trivial-devices.yaml       |   2 -
 drivers/iio/magnetometer/Kconfig                   |  13 +
 drivers/iio/magnetometer/Makefile                  |   2 +
 drivers/iio/magnetometer/tlv493d.c                 | 556 +++++++++++++++++++++
 5 files changed, 616 insertions(+), 2 deletions(-)
---
base-commit: d7b8f8e20813f0179d8ef519541a3527e7661d3a
change-id: 20250726-tlv493d-sensor-v6_16-rc5-18c712093b27

Best regards,
-- 
Dixit Parmar <dixitparmar19@gmail.com>


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

* [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor
  2025-08-02  6:44 [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor Dixit Parmar
@ 2025-08-02  6:44 ` Dixit Parmar
  2025-08-02 11:43   ` Jonathan Cameron
  2025-08-06 16:27   ` kernel test robot
  2025-08-02  6:44 ` [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor Dixit Parmar
  2025-08-02  8:53 ` [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor Andy Shevchenko
  2 siblings, 2 replies; 22+ messages in thread
From: Dixit Parmar @ 2025-08-02  6:44 UTC (permalink / raw)
  To: Jonathan Cameron, David Lechner, Nuno Sá, Andy Shevchenko,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley
  Cc: linux-kernel, linux-iio, devicetree, Dixit Parmar

The Infineon TLV493D is a Low-Power 3D Magnetic Sensor. The Sensor
applications includes joysticks, control elements (white goods,
multifunction knops), or electric meters (anti tampering) and any
other application that requires accurate angular measurements at
low power consumptions.

The Sensor is configured over I2C, and as part of Sensor measurement
data it provides 3-Axis magnetic fields and temperature core measurement.

The driver supports raw value read and buffered input via external trigger
to allow streaming values with the same sensing timestamp.

While sensor has interrupt pin multiplexed with I2C SCL pin. But for bus
configurations interrupt(INT) is not recommended, unless timing constraints
between I2C data transfers and interrupt pulses are monitored and aligned.

The Sensor's I2C register map and mode information is described in product
User Manual[Link].

Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
Link: https://www.mouser.com/pdfDocs/Infineon-TLV493D-A1B6_3DMagnetic-UserManual-v01_03-EN.pdf
Signed-off-by: Dixit Parmar <dixitparmar19@gmail.com>
---
 drivers/iio/magnetometer/Kconfig   |  13 +
 drivers/iio/magnetometer/Makefile  |   2 +
 drivers/iio/magnetometer/tlv493d.c | 556 +++++++++++++++++++++++++++++++++++++
 3 files changed, 571 insertions(+)

diff --git a/drivers/iio/magnetometer/Kconfig b/drivers/iio/magnetometer/Kconfig
index 3debf1320ad1..e073ebe11810 100644
--- a/drivers/iio/magnetometer/Kconfig
+++ b/drivers/iio/magnetometer/Kconfig
@@ -173,6 +173,19 @@ config IIO_ST_MAGN_SPI_3AXIS
 	  To compile this driver as a module, choose M here. The module
 	  will be called st_magn_spi.
 
+config INFINEON_TLV493D
+	tristate "Infineon TLV493D Low-Power 3D Magnetic Sensor"
+	depends on I2C
+	select IIO_BUFFER
+	select IIO_TRIGGERED_BUFFER
+	help
+	  Say Y here to add support for the Infineon TLV493D-A1B6 Low-
+	  Power 3D Megnetic Sensor.
+
+	  This driver can also be compiled as a module.
+	  To compile this driver as a module, choose M here: the module
+	  will be called tlv493d.
+
 config SENSORS_HMC5843
 	tristate
 	select IIO_BUFFER
diff --git a/drivers/iio/magnetometer/Makefile b/drivers/iio/magnetometer/Makefile
index 9297723a97d8..dfe970fcacb8 100644
--- a/drivers/iio/magnetometer/Makefile
+++ b/drivers/iio/magnetometer/Makefile
@@ -23,6 +23,8 @@ st_magn-$(CONFIG_IIO_BUFFER) += st_magn_buffer.o
 obj-$(CONFIG_IIO_ST_MAGN_I2C_3AXIS) += st_magn_i2c.o
 obj-$(CONFIG_IIO_ST_MAGN_SPI_3AXIS) += st_magn_spi.o
 
+obj-$(CONFIG_INFINEON_TLV493D)		+= tlv493d.o
+
 obj-$(CONFIG_SENSORS_HMC5843)		+= hmc5843_core.o
 obj-$(CONFIG_SENSORS_HMC5843_I2C)	+= hmc5843_i2c.o
 obj-$(CONFIG_SENSORS_HMC5843_SPI)	+= hmc5843_spi.o
diff --git a/drivers/iio/magnetometer/tlv493d.c b/drivers/iio/magnetometer/tlv493d.c
new file mode 100644
index 000000000000..da1569ae97bf
--- /dev/null
+++ b/drivers/iio/magnetometer/tlv493d.c
@@ -0,0 +1,556 @@
+// SPDX-License-Identifier: GPL-2.0-only
+/**
+ * Driver for the Infineon TLV493D Low-Power 3D Magnetic Sensor
+ *
+ * Copyright (C) 2025 Dixit Parmar <dixitparmar19@gmail.com>
+ */
+
+#include <linux/bits.h>
+#include <linux/bitfield.h>
+#include <linux/delay.h>
+#include <linux/i2c.h>
+#include <linux/iopoll.h>
+#include <linux/module.h>
+#include <linux/pm_runtime.h>
+#include <linux/regulator/consumer.h>
+#include <linux/types.h>
+#include <linux/units.h>
+
+#include <linux/iio/buffer.h>
+#include <linux/iio/iio.h>
+#include <linux/iio/trigger_consumer.h>
+#include <linux/iio/triggered_buffer.h>
+
+#define TLV493D_RD_REG_BX	0x00
+#define TLV493D_RD_REG_BY	0x01
+#define TLV493D_RD_REG_BZ	0x02
+#define TLV493D_RD_REG_TEMP	0x03
+#define TLV493D_RD_REG_BX2	0x04
+#define TLV493D_RD_REG_BZ2	0x05
+#define TLV493D_RD_REG_TEMP2	0x06
+#define TLV493D_RD_REG_RES1	0x07
+#define TLV493D_RD_REG_RES2	0x08
+#define TLV493D_RD_REG_RES3	0x09
+#define TLV493D_RD_REG_MAX	0x0a
+#define TLV493D_WR_REG_RES	0x00
+#define TLV493D_WR_REG_MODE1	0x01
+#define TLV493D_WR_REG_RES2	0x02
+#define TLV493D_WR_REG_MODE2	0x03
+#define TLV493D_WR_REG_MAX	0x04
+
+#define TLV493D_BX_MAG_X_AXIS_MSB	GENMASK(7, 0)
+#define TLV493D_BX2_MAG_X_AXIS_LSB	GENMASK(7, 4)
+#define TLV493D_BY_MAG_Y_AXIS_MSB	GENMASK(7, 0)
+#define TLV493D_BX2_MAG_Y_AXIS_LSB	GENMASK(3, 0)
+#define TLV493D_BZ_MAG_Z_AXIS_MSB	GENMASK(7, 0)
+#define TLV493D_BZ2_MAG_Z_AXIS_LSB	GENMASK(3, 0)
+#define TLV493D_TEMP_TEMP_MSB		GENMASK(7, 4)
+#define TLV493D_TEMP2_TEMP_LSB		GENMASK(7, 0)
+#define TLV493D_TEMP_CHANNEL		GENMASK(1, 0)
+#define TLV493D_MODE1_MOD_LOWFAST	GENMASK(1, 0)
+#define TLV493D_MODE2_LP_PERIOD	BIT(6)
+#define TLV493D_RD_REG_RES1_WR_MASK	GENMASK(4, 3)
+#define TLV493D_RD_REG_RES2_WR_MASK	GENMASK(7, 0)
+#define TLV493D_RD_REG_RES3_WR_MASK	GENMASK(4, 0)
+
+enum tlv493d_channels {
+	TLV493D_AXIS_X = 0,
+	TLV493D_AXIS_Y,
+	TLV493D_AXIS_Z,
+	TLV493D_TEMPERATURE
+};
+
+enum tlv493d_op_mode {
+	TLV493D_OP_MODE_POWERDOWN = 0,
+	TLV493D_OP_MODE_FAST,
+	TLV493D_OP_MODE_LOWPOWER,
+	TLV493D_OP_MODE_ULTRA_LOWPOWER,
+	TLV493D_OP_MODE_MASTERCONTROLLED,
+	TLV493D_OP_MODE_MAX
+};
+
+struct tlv493d_mode {
+	u8 m;
+	u32 sleep_us;
+};
+
+struct tlv493d_data {
+	struct device *dev;
+	struct i2c_client *client;
+	/* protects from simultaneous sensor access and register readings */
+	struct mutex lock;
+	u8 mode;
+	u8 wr_regs[TLV493D_WR_REG_MAX];
+};
+
+/*
+ * Different mode has different measurement cycle time, this time is
+ * used in deriving the sleep and timemout while reading the data from
+ * sensor in polling.
+ * Power-down mode: No measurement.
+ * Fast mode: Freq:3.3 KHz. Measurement time:305 usec.
+ * Low-power mode: Freq:100 Hz. Measurement time:10 msec.
+ * Ultra low-power mode: Freq:10 Hz. Measurement time:100 msec.
+ * Master controlled mode: Freq:3.3 Khz. Measurement time:305 usec.
+ */
+static struct tlv493d_mode tlv493d_mode_info[TLV493D_OP_MODE_MAX] = {
+	{ .m = TLV493D_OP_MODE_POWERDOWN, .sleep_us = 0 },
+	{ .m = TLV493D_OP_MODE_FAST, .sleep_us = 305 },
+	{ .m = TLV493D_OP_MODE_LOWPOWER, .sleep_us = 10 * USEC_PER_MSEC	},
+	{ .m = TLV493D_OP_MODE_ULTRA_LOWPOWER, .sleep_us = 100 * USEC_PER_MSEC },
+	{ .m = TLV493D_OP_MODE_MASTERCONTROLLED, .sleep_us = 305 }
+};
+
+/*
+ * The datasheet mentions the sensor supports only direct byte-stream write
+ * starting from register address 0x0. So for any modification to be made to
+ * any write registers, it must be written starting from the register address
+ * 0x0. I2C write operation should not contain register address in the I2C
+ * frame, it should contains only raw byte stream for the write registers.
+ * I2C Frame: |S|SlaveAddr Wr|Ack|Byte[0]|Ack|Byte[1]|Ack|.....|Sp|
+ */
+static int tlv493d_write_all_regs(struct tlv493d_data *data)
+{
+	int ret;
+
+	if (!data || !data->client)
+		return -EINVAL;
+
+	ret = i2c_master_send(data->client, data->wr_regs, ARRAY_SIZE(data->wr_regs));
+	if (ret < 0) {
+		dev_err(data->dev, "i2c write registers failed, error: %d\n", ret);
+		return ret;
+	}
+
+	return 0;
+}
+
+static int tlv493d_set_operating_mode(struct tlv493d_data *data, u8 mode)
+{
+	if (!data)
+		return -EINVAL;
+
+	u8 mode1_cfg, mode2_cfg;
+
+	switch (mode) {
+	case TLV493D_OP_MODE_POWERDOWN:
+		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 0);
+		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
+		break;
+
+	case TLV493D_OP_MODE_FAST:
+		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 1);
+		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
+		break;
+
+	case TLV493D_OP_MODE_LOWPOWER:
+		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 2);
+		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 1);
+		break;
+
+	case TLV493D_OP_MODE_ULTRA_LOWPOWER:
+		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 2);
+		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
+		break;
+
+	case TLV493D_OP_MODE_MASTERCONTROLLED:
+		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 3);
+		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
+		break;
+
+	default:
+		dev_err(data->dev, "invalid mode configuration\n");
+		return -EINVAL;
+	}
+
+	data->wr_regs[TLV493D_WR_REG_MODE1] |= mode1_cfg;
+	data->wr_regs[TLV493D_WR_REG_MODE2] |= mode2_cfg;
+
+	return tlv493d_write_all_regs(data);
+}
+
+static s16 tlv493d_get_channel_data(u8 *b, u8 ch)
+{
+	if (!b)
+		return -EINVAL;
+
+	u16 val = 0;
+
+	switch (ch) {
+	case TLV493D_AXIS_X:
+		val = FIELD_GET(TLV493D_BX_MAG_X_AXIS_MSB, b[TLV493D_RD_REG_BX]) << 4 |
+			FIELD_GET(TLV493D_BX2_MAG_X_AXIS_LSB, b[TLV493D_RD_REG_BX2]) >> 4;
+		break;
+	case TLV493D_AXIS_Y:
+		val = FIELD_GET(TLV493D_BY_MAG_Y_AXIS_MSB, b[TLV493D_RD_REG_BY]) << 4 |
+			FIELD_GET(TLV493D_BX2_MAG_Y_AXIS_LSB, b[TLV493D_RD_REG_BX2]);
+		break;
+	case TLV493D_AXIS_Z:
+		val = FIELD_GET(TLV493D_BZ_MAG_Z_AXIS_MSB, b[TLV493D_RD_REG_BZ]) << 4 |
+			FIELD_GET(TLV493D_BZ2_MAG_Z_AXIS_LSB, b[TLV493D_RD_REG_BZ2]);
+		break;
+	case TLV493D_TEMPERATURE:
+		val = FIELD_GET(TLV493D_TEMP_TEMP_MSB, b[TLV493D_RD_REG_TEMP]) << 8 |
+			FIELD_GET(TLV493D_TEMP2_TEMP_LSB, b[TLV493D_RD_REG_TEMP2]);
+		break;
+	default:
+		return -EINVAL;
+	}
+
+	return sign_extend32(val, 11);
+}
+
+static int tlv493d_get_measurements(struct tlv493d_data *data, s16 *x, s16 *y,
+				s16 *z, s16 *t)
+{
+	u8 buff[7] = {};
+	int err, ret;
+	struct tlv493d_mode *mode;
+
+	if (!data)
+		return -EINVAL;
+
+	guard(mutex)(&data->lock);
+
+	ret = pm_runtime_resume_and_get(data->dev);
+	if (ret < 0)
+		return ret;
+
+	mode = &tlv493d_mode_info[data->mode];
+
+	/*
+	 * Poll until data is valid,
+	 * For a valid data TLV493D_TEMP_CHANNEL bit of TLV493D_RD_REG_TEMP should be set to 0.
+	 * The sampling time depends on the sensor mode. poll 3x the time of the sampling time.
+	 */
+	ret = read_poll_timeout(i2c_master_recv, err, err ||
+			FIELD_GET(TLV493D_TEMP_CHANNEL, buff[TLV493D_RD_REG_TEMP]) == 0,
+			mode->sleep_us, (3 * mode->sleep_us), false, data->client, buff,
+			ARRAY_SIZE(buff));
+	if (ret) {
+		dev_err(data->dev, "i2c read poll timeout, error:%d\n", ret);
+		goto out;
+	}
+	if (err < 0) {
+		dev_err(data->dev, "i2c read data failed, error:%d\n", err);
+		ret = err;
+		goto out;
+	}
+
+	*x = tlv493d_get_channel_data(buff, TLV493D_AXIS_X);
+	*y = tlv493d_get_channel_data(buff, TLV493D_AXIS_Y);
+	*z = tlv493d_get_channel_data(buff, TLV493D_AXIS_Z);
+	*t = tlv493d_get_channel_data(buff, TLV493D_TEMPERATURE);
+
+out:
+	pm_runtime_mark_last_busy(data->dev);
+	pm_runtime_put_autosuspend(data->dev);
+	return ret;
+}
+
+static int tlv493d_init(struct tlv493d_data *data)
+{
+	int ret;
+	u8 buff[TLV493D_RD_REG_MAX];
+
+	if (!data)
+		return -EINVAL;
+
+	/*
+	 * The sensor initialization requires below steps to be followed,
+	 * 1. Power-up sensor.
+	 * 2. Read and store read-registers map (0x0-0x9).
+	 * 3. Copy values from read reserved registers to write reserved fields (0x0-0x3).
+	 * 4. Set operating mode.
+	 * 5. Write to all registers.
+	 */
+	ret = i2c_master_recv(data->client, buff, ARRAY_SIZE(buff));
+	if (ret < 0) {
+		dev_err(data->dev, "i2c read failed, error %d\n", ret);
+		return ret;
+	}
+
+	/* Write register 0x0 is reserved. Does not require to be updated.*/
+	data->wr_regs[0] = 0;
+	data->wr_regs[1] = buff[TLV493D_RD_REG_RES1] & TLV493D_RD_REG_RES1_WR_MASK;
+	data->wr_regs[2] = buff[TLV493D_RD_REG_RES2] & TLV493D_RD_REG_RES2_WR_MASK;
+	data->wr_regs[3] = buff[TLV493D_RD_REG_RES3] & TLV493D_RD_REG_RES3_WR_MASK;
+
+	ret = tlv493d_set_operating_mode(data, data->mode);
+	if (ret < 0) {
+		dev_err(data->dev, "failed to set operating mode\n");
+		return ret;
+	}
+
+	return 0;
+}
+
+static int tlv493d_read_raw(struct iio_dev *indio_dev,
+			const struct iio_chan_spec *chan, int *val,
+			int *val2, long mask)
+{
+	struct tlv493d_data *data = iio_priv(indio_dev);
+	s16 x, y, z, t;
+	int ret;
+
+	switch (mask) {
+	case IIO_CHAN_INFO_RAW:
+		ret = tlv493d_get_measurements(data, &x, &y, &z, &t);
+		if (ret)
+			return ret;
+
+		/* Return raw values for requested channel */
+		switch (chan->address) {
+		case TLV493D_AXIS_X:
+			*val = x;
+			return IIO_VAL_INT;
+		case TLV493D_AXIS_Y:
+			*val = y;
+			return IIO_VAL_INT;
+		case TLV493D_AXIS_Z:
+			*val = z;
+			return IIO_VAL_INT;
+		case TLV493D_TEMPERATURE:
+			*val = t;
+			return IIO_VAL_INT;
+		default:
+			return -EINVAL;
+		}
+	case IIO_CHAN_INFO_SCALE:
+		switch (chan->type) {
+		case IIO_MAGN:
+			/*
+			 * Magnetic field scale: 0.0098 mTesla (i.e. 9.8 µT)
+			 * Magnetic filed in Guass: mT * 10 = 0.098.
+			 */
+			*val = 98;
+			*val2 = 1000;
+			return IIO_VAL_FRACTIONAL;
+		case IIO_TEMP:
+			/*
+			 * Temperature scale: 1.1 °C per LSB, expressed as 1100 m°C
+			 * Returned as integer for IIO core to apply:
+			 * temp = (raw + offset) * scale
+			 */
+			*val = 1100;
+			return IIO_VAL_INT;
+		default:
+			return -EINVAL;
+		}
+	case IIO_CHAN_INFO_OFFSET:
+		switch (chan->type) {
+		case IIO_TEMP:
+			/*
+			 * Temperature offset includes sensor-specific raw offset
+			 * plus compensation for +25°C bias in formula.
+			 * offset = -raw_offset + (25000 / 1100)
+			 * -340 + 22.72 = -317.28
+			 */
+			*val = -31728;
+			*val2 = 100;
+			return IIO_VAL_FRACTIONAL;
+		default:
+			return -EINVAL;
+		}
+
+	default:
+		return -EINVAL;
+	}
+
+	return 0;
+}
+
+static irqreturn_t tlv493d_trigger_handler(int irq, void *ptr)
+{
+	struct iio_poll_func *pf = ptr;
+	struct iio_dev *indio_dev = pf->indio_dev;
+	struct tlv493d_data *data = iio_priv(indio_dev);
+
+	struct {
+		s16 channels[3];
+		s16 temperature;
+		aligned_s64 timestamp;
+	} scan;
+
+	s16 x, y, z, t;
+	int ret;
+
+	ret = tlv493d_get_measurements(data, &x, &y, &z, &t);
+	if (ret) {
+		dev_err(data->dev, "failed to read sensor data\n");
+		goto trig_out;
+	}
+
+	scan.channels[0] = x;
+	scan.channels[1] = y;
+	scan.channels[2] = z;
+	scan.temperature = t;
+	iio_push_to_buffers_with_ts(indio_dev, &scan, sizeof(scan),
+				pf->timestamp);
+trig_out:
+	iio_trigger_notify_done(indio_dev->trig);
+
+	return IRQ_HANDLED;
+}
+
+#define TLV493D_AXIS_CHANNEL(axis, index)			\
+	{							\
+		.type = IIO_MAGN,				\
+		.modified = 1,					\
+		.channel2 = IIO_MOD_##axis,			\
+		.info_mask_separate = BIT(IIO_CHAN_INFO_RAW) |	\
+				BIT(IIO_CHAN_INFO_SCALE),	\
+		.address = index,				\
+		.scan_index = index,				\
+		.scan_type = {					\
+			.sign = 's',				\
+			.realbits = 12,				\
+			.storagebits = 16,			\
+			.endianness = IIO_CPU,			\
+		},						\
+	}
+
+static const struct iio_chan_spec tlv493d_channels[] = {
+	TLV493D_AXIS_CHANNEL(X, TLV493D_AXIS_X),
+	TLV493D_AXIS_CHANNEL(Y, TLV493D_AXIS_Y),
+	TLV493D_AXIS_CHANNEL(Z, TLV493D_AXIS_Z),
+	{
+		.type = IIO_TEMP,
+		.info_mask_separate = BIT(IIO_CHAN_INFO_RAW) |
+				BIT(IIO_CHAN_INFO_SCALE) |
+				BIT(IIO_CHAN_INFO_OFFSET),
+		.address = TLV493D_TEMPERATURE,
+		.scan_index = TLV493D_TEMPERATURE,
+		.scan_type = {
+			.sign = 's',
+			.realbits = 12,
+			.storagebits = 16,
+			.endianness = IIO_CPU,
+		},
+	},
+	IIO_CHAN_SOFT_TIMESTAMP(4),
+};
+
+static const struct iio_info tlv493d_info = {
+	.read_raw = tlv493d_read_raw,
+};
+
+static const struct iio_buffer_setup_ops tlv493d_setup_ops = { NULL };
+
+static const unsigned long tlv493d_scan_masks[] = { GENMASK(3, 0), 0 };
+
+static int tlv493d_probe(struct i2c_client *client)
+{
+	struct device *dev = &client->dev;
+	struct iio_dev *indio_dev;
+	struct tlv493d_data *data;
+	int ret;
+
+	indio_dev = devm_iio_device_alloc(dev, sizeof(*data));
+	if (!indio_dev)
+		return -ENOMEM;
+
+	data = iio_priv(indio_dev);
+	data->dev = dev;
+	data->client = client;
+	i2c_set_clientdata(client, indio_dev);
+
+	ret = devm_mutex_init(dev, &data->lock);
+	if (ret)
+		return ret;
+
+	ret = devm_regulator_get_enable(dev, "vdd");
+	if (ret)
+		return dev_err_probe(dev, ret, "failed to enable regulator\n");
+
+	/*
+	 * Setting Sensor default operating mode as Master Controlled mode as
+	 * it performs measurement cycle on-request only and stays in Power-Down
+	 * mode until next cycle is initiated.
+	 */
+	data->mode = TLV493D_OP_MODE_MASTERCONTROLLED;
+	ret = tlv493d_init(data);
+	if (ret)
+		return dev_err_probe(dev, ret, "failed to initialize\n");
+
+	indio_dev->info = &tlv493d_info;
+	indio_dev->modes = INDIO_DIRECT_MODE;
+	indio_dev->name = client->name;
+	indio_dev->channels = tlv493d_channels;
+	indio_dev->num_channels = ARRAY_SIZE(tlv493d_channels);
+	indio_dev->available_scan_masks = tlv493d_scan_masks;
+
+	ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
+			iio_pollfunc_store_time, tlv493d_trigger_handler,
+			&tlv493d_setup_ops);
+	if (ret < 0)
+		return dev_err_probe(dev, ret, "iio triggered buffer setup failed\n");
+
+	ret = pm_runtime_set_active(dev);
+	if (ret < 0)
+		return ret;
+
+	ret = devm_pm_runtime_enable(dev);
+	if (ret < 0)
+		return ret;
+
+	pm_runtime_get_noresume(dev);
+	pm_runtime_set_autosuspend_delay(dev, 500);
+	pm_runtime_use_autosuspend(dev);
+
+	pm_runtime_mark_last_busy(dev);
+	pm_runtime_put_autosuspend(dev);
+
+	ret = devm_iio_device_register(dev, indio_dev);
+	if (ret)
+		return dev_err_probe(dev, ret, "iio device register failed\n");
+
+	return 0;
+}
+
+static int tlv493d_runtime_suspend(struct device *dev)
+{
+	struct iio_dev *indio_dev = dev_get_drvdata(dev);
+	struct tlv493d_data *data = iio_priv(indio_dev);
+
+	return tlv493d_set_operating_mode(data, TLV493D_OP_MODE_POWERDOWN);
+}
+
+static int tlv493d_runtime_resume(struct device *dev)
+{
+	struct iio_dev *indio_dev = dev_get_drvdata(dev);
+	struct tlv493d_data *data = iio_priv(indio_dev);
+
+	return tlv493d_set_operating_mode(data, data->mode);
+}
+
+static DEFINE_RUNTIME_DEV_PM_OPS(tlv493d_pm_ops,
+			tlv493d_runtime_suspend, tlv493d_runtime_resume, NULL);
+
+static const struct i2c_device_id tlv493d_id[] = {
+	{ "tlv493d" },
+	{ }
+};
+MODULE_DEVICE_TABLE(i2c, tlv493d_id);
+
+static const struct of_device_id tlv493d_of_match[] = {
+	{ .compatible = "infineon,tlv493d-a1b6", },
+	{ }
+};
+MODULE_DEVICE_TABLE(of, tlv493d_of_match);
+
+static struct i2c_driver tlv493d_driver = {
+	.driver = {
+		.name = "tlv493d",
+		.of_match_table = tlv493d_of_match,
+		.pm = pm_ptr(&tlv493d_pm_ops),
+	},
+	.probe = tlv493d_probe,
+	.id_table = tlv493d_id,
+};
+
+module_i2c_driver(tlv493d_driver);
+
+MODULE_LICENSE("GPL");
+MODULE_DESCRIPTION("Infineon TLV493D Low-Power 3D Magnetic Sensor");
+MODULE_AUTHOR("Dixit Parmar <dixitparmar19@gmail.com>");

-- 
2.43.0


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

* [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor
  2025-08-02  6:44 [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor Dixit Parmar
  2025-08-02  6:44 ` [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor Dixit Parmar
@ 2025-08-02  6:44 ` Dixit Parmar
  2025-08-02  7:45   ` Krzysztof Kozlowski
  2025-08-03 16:20   ` Rob Herring (Arm)
  2025-08-02  8:53 ` [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor Andy Shevchenko
  2 siblings, 2 replies; 22+ messages in thread
From: Dixit Parmar @ 2025-08-02  6:44 UTC (permalink / raw)
  To: Jonathan Cameron, David Lechner, Nuno Sá, Andy Shevchenko,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley
  Cc: linux-kernel, linux-iio, devicetree, Dixit Parmar

Document the bindings for Infineon TLV493D Low-Power 3D Magnetic Sensor
controlled by I2C interface. Main applications includes joysticks, control
elements (white goods, multifunction knops), or electric meters (anti-
tampering).
Drop duplicated entry for infineon,tlv493d from trivial-devices.yaml as
its documented in infineon,tlv493d.yaml now.

Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
Signed-off-by: Dixit Parmar <dixitparmar19@gmail.com>
---
 .../iio/magnetometer/infineon,tlv493d.yaml         | 45 ++++++++++++++++++++++
 .../devicetree/bindings/trivial-devices.yaml       |  2 -
 2 files changed, 45 insertions(+), 2 deletions(-)

diff --git a/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml b/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml
new file mode 100644
index 000000000000..ebcf29067a16
--- /dev/null
+++ b/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml
@@ -0,0 +1,45 @@
+# SPDX-License-Identifier: GPL-2.0-only OR BSD-2-Clause
+%YAML 1.2
+---
+$id: http://devicetree.org/schemas/iio/magnetometer/infineon,tlv493d.yaml#
+$schema: http://devicetree.org/meta-schemas/core.yaml#
+
+title: Infineon Technologies TLV493D Low-Power 3D Magnetic Sensor
+
+maintainers:
+  - Dixit Parmar <dixitparmar19@gmail.com>
+
+properties:
+  $nodename:
+    pattern: '^magnetometer@[0-9a-f]+$'
+
+  compatible:
+    const: infineon,tlv493d-a1b6
+
+  reg:
+    maxItems: 1
+
+  vdd:
+    description: 2.8V to 3.5V VDD supply
+
+  interrupts:
+    maxItems: 1
+
+required:
+  - compatible
+  - reg
+  - vdd
+
+additionalProperties: false
+
+example:
+  - |
+    i2c {
+      #address-cells = <1>;
+      #size-cells = <0>;
+      magnetometer@5e {
+        compatible = "infineon,tlv493d-a1b6";
+        reg = <0x5e>;
+        vdd = <&hall_vcc>;
+      };
+    };
diff --git a/Documentation/devicetree/bindings/trivial-devices.yaml b/Documentation/devicetree/bindings/trivial-devices.yaml
index 27930708ccd5..9e0eb5c873d2 100644
--- a/Documentation/devicetree/bindings/trivial-devices.yaml
+++ b/Documentation/devicetree/bindings/trivial-devices.yaml
@@ -125,8 +125,6 @@ properties:
           - infineon,ir36021
             # Infineon IRPS5401 Voltage Regulator (PMIC)
           - infineon,irps5401
-            # Infineon TLV493D-A1B6 I2C 3D Magnetic Sensor
-          - infineon,tlv493d-a1b6
             # Infineon Hot-swap controller xdp710
           - infineon,xdp710
             # Infineon Multi-phase Digital VR Controller xdpe11280

-- 
2.43.0


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

* Re: [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor
  2025-08-02  6:44 ` [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor Dixit Parmar
@ 2025-08-02  7:45   ` Krzysztof Kozlowski
  2025-08-04  2:44     ` Dixit Parmar
  2025-08-03 16:20   ` Rob Herring (Arm)
  1 sibling, 1 reply; 22+ messages in thread
From: Krzysztof Kozlowski @ 2025-08-02  7:45 UTC (permalink / raw)
  To: Dixit Parmar, Jonathan Cameron, David Lechner, Nuno Sá,
	Andy Shevchenko, Rob Herring, Krzysztof Kozlowski, Conor Dooley
  Cc: linux-kernel, linux-iio, devicetree

On 02/08/2025 08:44, Dixit Parmar wrote:
> Document the bindings for Infineon TLV493D Low-Power 3D Magnetic Sensor
> controlled by I2C interface. Main applications includes joysticks, control
> elements (white goods, multifunction knops), or electric meters (anti-
> tampering).
> Drop duplicated entry for infineon,tlv493d from trivial-devices.yaml as
> its documented in infineon,tlv493d.yaml now.
> 
> Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
> Signed-off-by: Dixit Parmar <dixitparmar19@gmail.com>
> ---
>  .../iio/magnetometer/infineon,tlv493d.yaml         | 45 ++++++++++++++++++++++
>  .../devicetree/bindings/trivial-devices.yaml       |  2 -
>  2 files changed, 45 insertions(+), 2 deletions(-)
> 
> diff --git a/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml b/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml
> new file mode 100644
> index 000000000000..ebcf29067a16
> --- /dev/null
> +++ b/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml


Filename should match compatible. Otherwise a1b6 is just confusing.

Best regards,
Krzysztof

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

* Re: [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor
  2025-08-02  6:44 [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor Dixit Parmar
  2025-08-02  6:44 ` [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor Dixit Parmar
  2025-08-02  6:44 ` [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor Dixit Parmar
@ 2025-08-02  8:53 ` Andy Shevchenko
  2025-08-02 11:15   ` Jonathan Cameron
  2025-08-04  2:52   ` Dixit Parmar
  2 siblings, 2 replies; 22+ messages in thread
From: Andy Shevchenko @ 2025-08-02  8:53 UTC (permalink / raw)
  To: Dixit Parmar
  Cc: Jonathan Cameron, David Lechner, Nuno Sá, Andy Shevchenko,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, linux-kernel,
	linux-iio, devicetree

On Sat, Aug 2, 2025 at 8:44 AM Dixit Parmar <dixitparmar19@gmail.com> wrote:
>
> The Infineon TLV493D is a Low-Power 3D Magnetic Sensor. The Sensor
> applications includes joysticks, control elements (white goods,
> multifunction knops), or electric meters (anti tampering) and any
> other application that requires accurate angular measurements at
> low power consumptions.
>
> The Sensor is configured over I2C, and as part of Sensor measurement
> data it provides 3-Axis magnetic fields and temperature core measurement.
>
> The driver supports raw value read and buffered input via external trigger
> to allow streaming values with the same sensing timestamp.
>
> While sensor has interrupt pin multiplexed with I2C SCL pin. But for bus

the sensor
an interrupt
an I2C

> configurations interrupt(INT) is not recommended, unless timing constraints
> between I2C data transfers and interrupt pulses are monitored and aligned.
>
> The Sensor's I2C register map and mode information is described in product
> User Manual[Link].

Replace Link here with 1...

> Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
> Link: https://www.mouser.com/pdfDocs/Infineon-TLV493D-A1B6_3DMagnetic-UserManual-v01_03-EN.pdf

...and add space followed by [1] here.

...

> Changes in v2:
> - Drop regmap implementation in favor of using direct i2c APIs to
>   have uniform communication APIs across the driver.

This I don't understand. I mean the motivation behind this. Usually
direct I2C communication is used to do some initial checks and
configuration and rarely for the actuall run-time driver
functionality. Otherwise it means that the regmap may be used with a
customised read and write methods.


-- 
With Best Regards,
Andy Shevchenko

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

* Re: [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor
  2025-08-02  8:53 ` [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor Andy Shevchenko
@ 2025-08-02 11:15   ` Jonathan Cameron
  2025-08-02 13:17     ` Andy Shevchenko
  2025-08-04  2:52   ` Dixit Parmar
  1 sibling, 1 reply; 22+ messages in thread
From: Jonathan Cameron @ 2025-08-02 11:15 UTC (permalink / raw)
  To: Andy Shevchenko
  Cc: Dixit Parmar, David Lechner, Nuno Sá, Andy Shevchenko,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, linux-kernel,
	linux-iio, devicetree

On Sat, 2 Aug 2025 10:53:30 +0200
Andy Shevchenko <andy.shevchenko@gmail.com> wrote:

> On Sat, Aug 2, 2025 at 8:44 AM Dixit Parmar <dixitparmar19@gmail.com> wrote:
> >
> > The Infineon TLV493D is a Low-Power 3D Magnetic Sensor. The Sensor
> > applications includes joysticks, control elements (white goods,
> > multifunction knops), or electric meters (anti tampering) and any
> > other application that requires accurate angular measurements at
> > low power consumptions.
> >
> > The Sensor is configured over I2C, and as part of Sensor measurement
> > data it provides 3-Axis magnetic fields and temperature core measurement.
> >
> > The driver supports raw value read and buffered input via external trigger
> > to allow streaming values with the same sensing timestamp.
> >
> > While sensor has interrupt pin multiplexed with I2C SCL pin. But for bus  
> 
> the sensor
> an interrupt
> an I2C
> 
> > configurations interrupt(INT) is not recommended, unless timing constraints
> > between I2C data transfers and interrupt pulses are monitored and aligned.
> >
> > The Sensor's I2C register map and mode information is described in product
> > User Manual[Link].  
> 
> Replace Link here with 1...
> 
> > Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
> > Link: https://www.mouser.com/pdfDocs/Infineon-TLV493D-A1B6_3DMagnetic-UserManual-v01_03-EN.pdf  
> 
> ...and add space followed by [1] here.
> 
> ...
> 
> > Changes in v2:
> > - Drop regmap implementation in favor of using direct i2c APIs to
> >   have uniform communication APIs across the driver.  
> 
> This I don't understand. I mean the motivation behind this. Usually
> direct I2C communication is used to do some initial checks and
> configuration and rarely for the actuall run-time driver
> functionality. Otherwise it means that the regmap may be used with a
> customised read and write methods.
> 

This was my suggestion.  The device has very odd characteristics that
means writes really are not register based.  You have to write them all
every time with now addressing.

So to me regmap just wasn't a good choice here. You could do something
some nasty stuff to hammer it into a custom regmap, but to me it's just
not a good fit.

Jonathan

> 


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

* Re: [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor
  2025-08-02  6:44 ` [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor Dixit Parmar
@ 2025-08-02 11:43   ` Jonathan Cameron
  2025-08-02 13:25     ` Andy Shevchenko
  2025-08-04  3:18     ` Dixit Parmar
  2025-08-06 16:27   ` kernel test robot
  1 sibling, 2 replies; 22+ messages in thread
From: Jonathan Cameron @ 2025-08-02 11:43 UTC (permalink / raw)
  To: Dixit Parmar
  Cc: David Lechner, Nuno Sá, Andy Shevchenko, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, linux-kernel, linux-iio,
	devicetree

On Sat, 02 Aug 2025 12:14:27 +0530
Dixit Parmar <dixitparmar19@gmail.com> wrote:

> The Infineon TLV493D is a Low-Power 3D Magnetic Sensor. The Sensor
> applications includes joysticks, control elements (white goods,
> multifunction knops), or electric meters (anti tampering) and any
> other application that requires accurate angular measurements at
> low power consumptions.
> 
> The Sensor is configured over I2C, and as part of Sensor measurement
> data it provides 3-Axis magnetic fields and temperature core measurement.
> 
> The driver supports raw value read and buffered input via external trigger
> to allow streaming values with the same sensing timestamp.
> 
> While sensor has interrupt pin multiplexed with I2C SCL pin. But for bus
> configurations interrupt(INT) is not recommended, unless timing constraints
> between I2C data transfers and interrupt pulses are monitored and aligned.
> 
> The Sensor's I2C register map and mode information is described in product
> User Manual[Link].
> 
> Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
> Link: https://www.mouser.com/pdfDocs/Infineon-TLV493D-A1B6_3DMagnetic-UserManual-v01_03-EN.pdf
> Signed-off-by: Dixit Parmar <dixitparmar19@gmail.com>

Hi Dixit,

Some additional comments inline.

> diff --git a/drivers/iio/magnetometer/tlv493d.c b/drivers/iio/magnetometer/tlv493d.c
> new file mode 100644
> index 000000000000..da1569ae97bf
> --- /dev/null
> +++ b/drivers/iio/magnetometer/tlv493d.c

> +enum tlv493d_op_mode {
> +	TLV493D_OP_MODE_POWERDOWN = 0,
> +	TLV493D_OP_MODE_FAST,
> +	TLV493D_OP_MODE_LOWPOWER,
> +	TLV493D_OP_MODE_ULTRA_LOWPOWER,
> +	TLV493D_OP_MODE_MASTERCONTROLLED,
> +	TLV493D_OP_MODE_MAX
In order to be able to use this as the type for a parameter as suggested
below, you'll need to drop MODE_MAX.  Comments on why you shouldn't
need that anyway below.

> +};
> +
> +struct tlv493d_mode {
> +	u8 m;
You have an enum type.  Much better to use it.

> +	u32 sleep_us;
> +};
> +
> +struct tlv493d_data {
> +	struct device *dev;
> +	struct i2c_client *client;
> +	/* protects from simultaneous sensor access and register readings */
> +	struct mutex lock;
> +	u8 mode;
> +	u8 wr_regs[TLV493D_WR_REG_MAX];
> +};
> +
> +/*
> + * Different mode has different measurement cycle time, this time is
> + * used in deriving the sleep and timemout while reading the data from
> + * sensor in polling.
> + * Power-down mode: No measurement.
> + * Fast mode: Freq:3.3 KHz. Measurement time:305 usec.
> + * Low-power mode: Freq:100 Hz. Measurement time:10 msec.
> + * Ultra low-power mode: Freq:10 Hz. Measurement time:100 msec.
> + * Master controlled mode: Freq:3.3 Khz. Measurement time:305 usec.
> + */
> +static struct tlv493d_mode tlv493d_mode_info[TLV493D_OP_MODE_MAX] = {
If you want to size it, do it using the enum values. [] is fine here
	[TLV493D_OP_MODE_POWERDOWN] = { }

I'm not sure why this should embed the index.  Can you just drop .m?

> +	{ .m = TLV493D_OP_MODE_POWERDOWN, .sleep_us = 0 },
> +	{ .m = TLV493D_OP_MODE_FAST, .sleep_us = 305 },
> +	{ .m = TLV493D_OP_MODE_LOWPOWER, .sleep_us = 10 * USEC_PER_MSEC	},
> +	{ .m = TLV493D_OP_MODE_ULTRA_LOWPOWER, .sleep_us = 100 * USEC_PER_MSEC },
> +	{ .m = TLV493D_OP_MODE_MASTERCONTROLLED, .sleep_us = 305 }
> +};
> +
> +/*
> + * The datasheet mentions the sensor supports only direct byte-stream write
> + * starting from register address 0x0. So for any modification to be made to
> + * any write registers, it must be written starting from the register address
> + * 0x0. I2C write operation should not contain register address in the I2C
> + * frame, it should contains only raw byte stream for the write registers.
> + * I2C Frame: |S|SlaveAddr Wr|Ack|Byte[0]|Ack|Byte[1]|Ack|.....|Sp|
> + */
> +static int tlv493d_write_all_regs(struct tlv493d_data *data)
> +{
> +	int ret;
> +
> +	if (!data || !data->client)
If either of these happen, something went very very wrong.
No need for the checks.  Remove all similar ones.

> +		return -EINVAL;
> +
> +	ret = i2c_master_send(data->client, data->wr_regs, ARRAY_SIZE(data->wr_regs));
> +	if (ret < 0) {
> +		dev_err(data->dev, "i2c write registers failed, error: %d\n", ret);
> +		return ret;
> +	}
> +
> +	return 0;
> +}
> +
> +static int tlv493d_set_operating_mode(struct tlv493d_data *data, u8 mode)
As below. Use the enum type.
> +{
> +	if (!data)
> +		return -EINVAL;

As above. Data is never going to be NULL, so don't check it.

> +
> +	u8 mode1_cfg, mode2_cfg;
> +
> +	switch (mode) {
> +	case TLV493D_OP_MODE_POWERDOWN:
> +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 0);
> +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
> +		break;
> +
> +	case TLV493D_OP_MODE_FAST:
> +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 1);
> +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
> +		break;
> +
> +	case TLV493D_OP_MODE_LOWPOWER:
> +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 2);
> +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 1);
> +		break;
> +
> +	case TLV493D_OP_MODE_ULTRA_LOWPOWER:
> +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 2);
> +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
> +		break;
> +
> +	case TLV493D_OP_MODE_MASTERCONTROLLED:
> +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 3);
> +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
> +		break;
> +
> +	default:
> +		dev_err(data->dev, "invalid mode configuration\n");
> +		return -EINVAL;
And with the enum type you shouldn't need a default.

> +	}
> +
> +	data->wr_regs[TLV493D_WR_REG_MODE1] |= mode1_cfg;
> +	data->wr_regs[TLV493D_WR_REG_MODE2] |= mode2_cfg;
> +
> +	return tlv493d_write_all_regs(data);
> +}
> +
> +static s16 tlv493d_get_channel_data(u8 *b, u8 ch)
Use the enum. 
> +{
> +	if (!b)
> +		return -EINVAL;
Unnecessary check
> +
> +	u16 val = 0;
Variable declarations at the top of scope unless strong reason to do otherwise
(only normally done for auto cleanup)
> +
> +	switch (ch) {
> +	case TLV493D_AXIS_X:
> +		val = FIELD_GET(TLV493D_BX_MAG_X_AXIS_MSB, b[TLV493D_RD_REG_BX]) << 4 |
> +			FIELD_GET(TLV493D_BX2_MAG_X_AXIS_LSB, b[TLV493D_RD_REG_BX2]) >> 4;
> +		break;
> +	case TLV493D_AXIS_Y:
> +		val = FIELD_GET(TLV493D_BY_MAG_Y_AXIS_MSB, b[TLV493D_RD_REG_BY]) << 4 |
> +			FIELD_GET(TLV493D_BX2_MAG_Y_AXIS_LSB, b[TLV493D_RD_REG_BX2]);
> +		break;
> +	case TLV493D_AXIS_Z:
> +		val = FIELD_GET(TLV493D_BZ_MAG_Z_AXIS_MSB, b[TLV493D_RD_REG_BZ]) << 4 |
> +			FIELD_GET(TLV493D_BZ2_MAG_Z_AXIS_LSB, b[TLV493D_RD_REG_BZ2]);
> +		break;
> +	case TLV493D_TEMPERATURE:
> +		val = FIELD_GET(TLV493D_TEMP_TEMP_MSB, b[TLV493D_RD_REG_TEMP]) << 8 |
> +			FIELD_GET(TLV493D_TEMP2_TEMP_LSB, b[TLV493D_RD_REG_TEMP2]);
> +		break;
> +	default:
> +		return -EINVAL;
And with the enum, there will be no need to have a default.
Not to mention passing -EINVAL through an s16 is unusual and I doubt wise.

> +	}
> +
> +	return sign_extend32(val, 11);
> +}
> +
> +static int tlv493d_get_measurements(struct tlv493d_data *data, s16 *x, s16 *y,
> +				s16 *z, s16 *t)
> +{
> +	u8 buff[7] = {};
> +	int err, ret;
> +	struct tlv493d_mode *mode;
> +
> +	if (!data)
> +		return -EINVAL;
> +
> +	guard(mutex)(&data->lock);
> +
> +	ret = pm_runtime_resume_and_get(data->dev);
> +	if (ret < 0)
> +		return ret;
> +
> +	mode = &tlv493d_mode_info[data->mode];
> +
> +	/*
> +	 * Poll until data is valid,
> +	 * For a valid data TLV493D_TEMP_CHANNEL bit of TLV493D_RD_REG_TEMP should be set to 0.
> +	 * The sampling time depends on the sensor mode. poll 3x the time of the sampling time.
> +	 */
> +	ret = read_poll_timeout(i2c_master_recv, err, err ||
> +			FIELD_GET(TLV493D_TEMP_CHANNEL, buff[TLV493D_RD_REG_TEMP]) == 0,
> +			mode->sleep_us, (3 * mode->sleep_us), false, data->client, buff,
> +			ARRAY_SIZE(buff));
> +	if (ret) {
> +		dev_err(data->dev, "i2c read poll timeout, error:%d\n", ret);
> +		goto out;
> +	}
> +	if (err < 0) {
> +		dev_err(data->dev, "i2c read data failed, error:%d\n", err);
> +		ret = err;
> +		goto out;
> +	}
> +
> +	*x = tlv493d_get_channel_data(buff, TLV493D_AXIS_X);
> +	*y = tlv493d_get_channel_data(buff, TLV493D_AXIS_Y);
> +	*z = tlv493d_get_channel_data(buff, TLV493D_AXIS_Z);
> +	*t = tlv493d_get_channel_data(buff, TLV493D_TEMPERATURE);
> +
> +out:
> +	pm_runtime_mark_last_busy(data->dev);
I've just rebased (mid merge window so i'll do it again on rc1) and now
have the version of pm_runtime_put_autosuspend() that internally calls
pm_runtime_mark_last_busy().

So please drop the line above if you need to do a v3.
 
> +	pm_runtime_put_autosuspend(data->dev);
> +	return ret;
> +}

> +static int tlv493d_read_raw(struct iio_dev *indio_dev,
> +			const struct iio_chan_spec *chan, int *val,
> +			int *val2, long mask)
> +{
> +	struct tlv493d_data *data = iio_priv(indio_dev);
> +	s16 x, y, z, t;
> +	int ret;
> +
> +	switch (mask) {
> +	case IIO_CHAN_INFO_RAW:
> +		ret = tlv493d_get_measurements(data, &x, &y, &z, &t);
> +		if (ret)
> +			return ret;
> +
> +		/* Return raw values for requested channel */
> +		switch (chan->address) {
> +		case TLV493D_AXIS_X:
> +			*val = x;
> +			return IIO_VAL_INT;
> +		case TLV493D_AXIS_Y:
> +			*val = y;
> +			return IIO_VAL_INT;
> +		case TLV493D_AXIS_Z:
> +			*val = z;
> +			return IIO_VAL_INT;
> +		case TLV493D_TEMPERATURE:
> +			*val = t;
> +			return IIO_VAL_INT;
> +		default:
> +			return -EINVAL;
> +		}
> +	case IIO_CHAN_INFO_SCALE:
> +		switch (chan->type) {
> +		case IIO_MAGN:
> +			/*
> +			 * Magnetic field scale: 0.0098 mTesla (i.e. 9.8 µT)
> +			 * Magnetic filed in Guass: mT * 10 = 0.098.
> +			 */
> +			*val = 98;
> +			*val2 = 1000;
> +			return IIO_VAL_FRACTIONAL;
> +		case IIO_TEMP:
> +			/*
> +			 * Temperature scale: 1.1 °C per LSB, expressed as 1100 m°C
> +			 * Returned as integer for IIO core to apply:
> +			 * temp = (raw + offset) * scale
> +			 */
> +			*val = 1100;
> +			return IIO_VAL_INT;
> +		default:
> +			return -EINVAL;
> +		}
> +	case IIO_CHAN_INFO_OFFSET:
> +		switch (chan->type) {
> +		case IIO_TEMP:
> +			/*
> +			 * Temperature offset includes sensor-specific raw offset
> +			 * plus compensation for +25°C bias in formula.
> +			 * offset = -raw_offset + (25000 / 1100)
> +			 * -340 + 22.72 = -317.28
> +			 */
> +			*val = -31728;
> +			*val2 = 100;
> +			return IIO_VAL_FRACTIONAL;
> +		default:
> +			return -EINVAL;
> +		}
> +
> +	default:
> +		return -EINVAL;
> +	}
> +
> +	return 0;

Can you get here? If not drop this.  Compilers are very good at complaining if
code changes later such that we should add this back.

> +}

> +static const struct iio_info tlv493d_info = {
> +	.read_raw = tlv493d_read_raw,
> +};
> +
> +static const struct iio_buffer_setup_ops tlv493d_setup_ops = { NULL };

No need specify that NULL. Due to some odd quirks of compiler specific
handling and C spec evolution (none of which apply to the kernel because
we carefully choose build options) that is actually less likely to do what
you want than = { };



> +
> +static const unsigned long tlv493d_scan_masks[] = { GENMASK(3, 0), 0 };
> +
> +static int tlv493d_probe(struct i2c_client *client)
> +{
> +	struct device *dev = &client->dev;
> +	struct iio_dev *indio_dev;
> +	struct tlv493d_data *data;
> +	int ret;
> +
> +	indio_dev = devm_iio_device_alloc(dev, sizeof(*data));
> +	if (!indio_dev)
> +		return -ENOMEM;
> +
> +	data = iio_priv(indio_dev);
> +	data->dev = dev;
> +	data->client = client;
> +	i2c_set_clientdata(client, indio_dev);
> +
> +	ret = devm_mutex_init(dev, &data->lock);
> +	if (ret)
> +		return ret;
> +
> +	ret = devm_regulator_get_enable(dev, "vdd");
> +	if (ret)
> +		return dev_err_probe(dev, ret, "failed to enable regulator\n");
> +
> +	/*
> +	 * Setting Sensor default operating mode as Master Controlled mode as
> +	 * it performs measurement cycle on-request only and stays in Power-Down
> +	 * mode until next cycle is initiated.
> +	 */
> +	data->mode = TLV493D_OP_MODE_MASTERCONTROLLED;
> +	ret = tlv493d_init(data);
> +	if (ret)
> +		return dev_err_probe(dev, ret, "failed to initialize\n");
> +
> +	indio_dev->info = &tlv493d_info;
> +	indio_dev->modes = INDIO_DIRECT_MODE;
> +	indio_dev->name = client->name;
> +	indio_dev->channels = tlv493d_channels;
> +	indio_dev->num_channels = ARRAY_SIZE(tlv493d_channels);
> +	indio_dev->available_scan_masks = tlv493d_scan_masks;
> +
> +	ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
> +			iio_pollfunc_store_time, tlv493d_trigger_handler,
> +			&tlv493d_setup_ops);
Similar to below no alignment. Something like;
	ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
					      iio_pollfunc_store_time,
					      tlv493d_trigger_handler,
					      &tlv493d_setup_ops);

If you do have a case where the line ends up very long with this style, then
indent only one tab more than line above. If that applied here it would be.

	ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
		iio_pollfunc_store_time, tlv493d_trigger_handler,
		&tlv493d_setup_ops);



> +	if (ret < 0)
> +		return dev_err_probe(dev, ret, "iio triggered buffer setup failed\n");
> +
> +	ret = pm_runtime_set_active(dev);
> +	if (ret < 0)
> +		return ret;
> +
> +	ret = devm_pm_runtime_enable(dev);
> +	if (ret < 0)
> +		return ret;
> +
> +	pm_runtime_get_noresume(dev);
> +	pm_runtime_set_autosuspend_delay(dev, 500);
> +	pm_runtime_use_autosuspend(dev);
> +
> +	pm_runtime_mark_last_busy(dev);
> +	pm_runtime_put_autosuspend(dev);
> +
> +	ret = devm_iio_device_register(dev, indio_dev);
> +	if (ret)
> +		return dev_err_probe(dev, ret, "iio device register failed\n");
> +
> +	return 0;
> +}
> +
> +static int tlv493d_runtime_suspend(struct device *dev)
> +{
> +	struct iio_dev *indio_dev = dev_get_drvdata(dev);
> +	struct tlv493d_data *data = iio_priv(indio_dev);
> +
> +	return tlv493d_set_operating_mode(data, TLV493D_OP_MODE_POWERDOWN);
> +}
> +
> +static int tlv493d_runtime_resume(struct device *dev)
> +{
> +	struct iio_dev *indio_dev = dev_get_drvdata(dev);
> +	struct tlv493d_data *data = iio_priv(indio_dev);

Trivial but you could do
	struct tlv493d_data *data = iio_priv(dev_get_drvdata(dev));
with no real loss of readability.

> +
> +	return tlv493d_set_operating_mode(data, data->mode);
> +}
> +
> +static DEFINE_RUNTIME_DEV_PM_OPS(tlv493d_pm_ops,
> +			tlv493d_runtime_suspend, tlv493d_runtime_resume, NULL);
Preferred wrapping here is
static DEFINE_RUNTIME_DEV_PM_OPS(tlv493d_pm_ops, tlv493d_runtime_suspend,
				 tlv493d_runtime_resume, NULL);

So go nearer 80 chars on first line and align second line below the parameters
on the first line.

Jonathan


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

* Re: [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor
  2025-08-02 11:15   ` Jonathan Cameron
@ 2025-08-02 13:17     ` Andy Shevchenko
  0 siblings, 0 replies; 22+ messages in thread
From: Andy Shevchenko @ 2025-08-02 13:17 UTC (permalink / raw)
  To: Jonathan Cameron
  Cc: Dixit Parmar, David Lechner, Nuno Sá, Andy Shevchenko,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, linux-kernel,
	linux-iio, devicetree

On Sat, Aug 2, 2025 at 1:16 PM Jonathan Cameron <jic23@kernel.org> wrote:
>
> On Sat, 2 Aug 2025 10:53:30 +0200
> Andy Shevchenko <andy.shevchenko@gmail.com> wrote:
> > On Sat, Aug 2, 2025 at 8:44 AM Dixit Parmar <dixitparmar19@gmail.com> wrote:
> > >
> > > The Infineon TLV493D is a Low-Power 3D Magnetic Sensor. The Sensor
> > > applications includes joysticks, control elements (white goods,
> > > multifunction knops), or electric meters (anti tampering) and any
> > > other application that requires accurate angular measurements at
> > > low power consumptions.
> > >
> > > The Sensor is configured over I2C, and as part of Sensor measurement
> > > data it provides 3-Axis magnetic fields and temperature core measurement.
> > >
> > > The driver supports raw value read and buffered input via external trigger
> > > to allow streaming values with the same sensing timestamp.
> > >
> > > While sensor has interrupt pin multiplexed with I2C SCL pin. But for bus
> >
> > the sensor
> > an interrupt
> > an I2C
> >
> > > configurations interrupt(INT) is not recommended, unless timing constraints
> > > between I2C data transfers and interrupt pulses are monitored and aligned.
> > >
> > > The Sensor's I2C register map and mode information is described in product
> > > User Manual[Link].
> >
> > Replace Link here with 1...
> >
> > > Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
> > > Link: https://www.mouser.com/pdfDocs/Infineon-TLV493D-A1B6_3DMagnetic-UserManual-v01_03-EN.pdf
> >
> > ...and add space followed by [1] here.

Note, my above comment also applies to the actual patch.

...

> > > Changes in v2:
> > > - Drop regmap implementation in favor of using direct i2c APIs to
> > >   have uniform communication APIs across the driver.
> >
> > This I don't understand. I mean the motivation behind this. Usually
> > direct I2C communication is used to do some initial checks and
> > configuration and rarely for the actuall run-time driver
> > functionality. Otherwise it means that the regmap may be used with a
> > customised read and write methods.
>
> This was my suggestion.  The device has very odd characteristics that
> means writes really are not register based.  You have to write them all
> every time with now addressing.
>
> So to me regmap just wasn't a good choice here. You could do something
> some nasty stuff to hammer it into a custom regmap, but to me it's just
> not a good fit.

I see, thanks for explaining this to me. Okay, let's leave for now
with the direct use of I2C APIs.


-- 
With Best Regards,
Andy Shevchenko

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

* Re: [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor
  2025-08-02 11:43   ` Jonathan Cameron
@ 2025-08-02 13:25     ` Andy Shevchenko
  2025-08-04  3:18     ` Dixit Parmar
  1 sibling, 0 replies; 22+ messages in thread
From: Andy Shevchenko @ 2025-08-02 13:25 UTC (permalink / raw)
  To: Jonathan Cameron
  Cc: Dixit Parmar, David Lechner, Nuno Sá, Andy Shevchenko,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, linux-kernel,
	linux-iio, devicetree

On Sat, Aug 2, 2025 at 1:43 PM Jonathan Cameron <jic23@kernel.org> wrote:
> On Sat, 02 Aug 2025 12:14:27 +0530
> Dixit Parmar <dixitparmar19@gmail.com> wrote:

...

> > +/*
> > + * Different mode has different measurement cycle time, this time is
> > + * used in deriving the sleep and timemout while reading the data from

timeout

> > + * sensor in polling.
> > + * Power-down mode: No measurement.
> > + * Fast mode: Freq:3.3 KHz. Measurement time:305 usec.
> > + * Low-power mode: Freq:100 Hz. Measurement time:10 msec.
> > + * Ultra low-power mode: Freq:10 Hz. Measurement time:100 msec.
> > + * Master controlled mode: Freq:3.3 Khz. Measurement time:305 usec.
> > + */

...

> > +/*
> > + * The datasheet mentions the sensor supports only direct byte-stream write
> > + * starting from register address 0x0. So for any modification to be made to
> > + * any write registers, it must be written starting from the register address
> > + * 0x0. I2C write operation should not contain register address in the I2C
> > + * frame, it should contains only raw byte stream for the write registers.

contain

> > + * I2C Frame: |S|SlaveAddr Wr|Ack|Byte[0]|Ack|Byte[1]|Ack|.....|Sp|
> > + */

...

> > +                     /*
> > +                      * Magnetic field scale: 0.0098 mTesla (i.e. 9.8 µT)
> > +                      * Magnetic filed in Guass: mT * 10 = 0.098.

field
Gauss

> > +                      */

...

> > +static DEFINE_RUNTIME_DEV_PM_OPS(tlv493d_pm_ops,
> > +                     tlv493d_runtime_suspend, tlv493d_runtime_resume, NULL);
> Preferred wrapping here is
> static DEFINE_RUNTIME_DEV_PM_OPS(tlv493d_pm_ops, tlv493d_runtime_suspend,
>                                  tlv493d_runtime_resume, NULL);
>
> So go nearer 80 chars on first line and align second line below the parameters
> on the first line.

I prefer the original split as it's more logical.
One can make use of 2x TAB indentation, however it might be a bit
inconsistent with the rest of the code.

-- 
With Best Regards,
Andy Shevchenko

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

* Re: [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor
  2025-08-02  6:44 ` [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor Dixit Parmar
  2025-08-02  7:45   ` Krzysztof Kozlowski
@ 2025-08-03 16:20   ` Rob Herring (Arm)
  2025-08-04  2:41     ` Dixit Parmar
  1 sibling, 1 reply; 22+ messages in thread
From: Rob Herring (Arm) @ 2025-08-03 16:20 UTC (permalink / raw)
  To: Dixit Parmar
  Cc: Nuno Sá, Jonathan Cameron, Krzysztof Kozlowski,
	David Lechner, linux-iio, Conor Dooley, Andy Shevchenko,
	linux-kernel, devicetree


On Sat, 02 Aug 2025 12:14:28 +0530, Dixit Parmar wrote:
> Document the bindings for Infineon TLV493D Low-Power 3D Magnetic Sensor
> controlled by I2C interface. Main applications includes joysticks, control
> elements (white goods, multifunction knops), or electric meters (anti-
> tampering).
> Drop duplicated entry for infineon,tlv493d from trivial-devices.yaml as
> its documented in infineon,tlv493d.yaml now.
> 
> Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
> Signed-off-by: Dixit Parmar <dixitparmar19@gmail.com>
> ---
>  .../iio/magnetometer/infineon,tlv493d.yaml         | 45 ++++++++++++++++++++++
>  .../devicetree/bindings/trivial-devices.yaml       |  2 -
>  2 files changed, 45 insertions(+), 2 deletions(-)
> 

My bot found errors running 'make dt_binding_check' on your patch:

yamllint warnings/errors:

dtschema/dtc warnings/errors:
/builds/robherring/dt-review-ci/linux/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml: vdd: missing type definition
/builds/robherring/dt-review-ci/linux/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml: 'example' is not one of ['$id', '$schema', 'title', 'description', 'examples', 'required', 'allOf', 'anyOf', 'oneOf', 'definitions', '$defs', 'additionalProperties', 'dependencies', 'dependentRequired', 'dependentSchemas', 'patternProperties', 'properties', 'not', 'if', 'then', 'else', 'unevaluatedProperties', 'deprecated', 'maintainers', 'select', '$ref']
	from schema $id: http://devicetree.org/meta-schemas/base.yaml#

doc reference errors (make refcheckdocs):

See https://patchwork.ozlabs.org/project/devicetree-bindings/patch/20250802-tlv493d-sensor-v6_16-rc5-v2-2-e867df86ad93@gmail.com

The base for the series is generally the latest rc1. A different dependency
should be noted in *this* patch.

If you already ran 'make dt_binding_check' and didn't see the above
error(s), then make sure 'yamllint' is installed and dt-schema is up to
date:

pip3 install dtschema --upgrade

Please check and re-submit after running the above command yourself. Note
that DT_SCHEMA_FILES can be set to your schema file to speed up checking
your schema. However, it must be unset to test all examples with your schema.


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

* Re: [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor
  2025-08-03 16:20   ` Rob Herring (Arm)
@ 2025-08-04  2:41     ` Dixit Parmar
  2025-08-05 16:35       ` David Lechner
  0 siblings, 1 reply; 22+ messages in thread
From: Dixit Parmar @ 2025-08-04  2:41 UTC (permalink / raw)
  To: Rob Herring (Arm)
  Cc: Nuno Sá, Jonathan Cameron, Krzysztof Kozlowski,
	David Lechner, linux-iio, Conor Dooley, Andy Shevchenko,
	linux-kernel, devicetree

On Sun, Aug 03, 2025 at 11:20:40AM -0500, Rob Herring (Arm) wrote:
> 
> On Sat, 02 Aug 2025 12:14:28 +0530, Dixit Parmar wrote:
> > Document the bindings for Infineon TLV493D Low-Power 3D Magnetic Sensor
> > controlled by I2C interface. Main applications includes joysticks, control
> > elements (white goods, multifunction knops), or electric meters (anti-
> > tampering).
> > Drop duplicated entry for infineon,tlv493d from trivial-devices.yaml as
> > its documented in infineon,tlv493d.yaml now.
> > 
> > Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
> > Signed-off-by: Dixit Parmar <dixitparmar19@gmail.com>
> > ---
> >  .../iio/magnetometer/infineon,tlv493d.yaml         | 45 ++++++++++++++++++++++
> >  .../devicetree/bindings/trivial-devices.yaml       |  2 -
> >  2 files changed, 45 insertions(+), 2 deletions(-)
> > 
> 
> My bot found errors running 'make dt_binding_check' on your patch:
> 
> yamllint warnings/errors:
> 
> dtschema/dtc warnings/errors:
> /builds/robherring/dt-review-ci/linux/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml: vdd: missing type definition
> /builds/robherring/dt-review-ci/linux/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml: 'example' is not one of ['$id', '$schema', 'title', 'description', 'examples', 'required', 'allOf', 'anyOf', 'oneOf', 'definitions', '$defs', 'additionalProperties', 'dependencies', 'dependentRequired', 'dependentSchemas', 'patternProperties', 'properties', 'not', 'if', 'then', 'else', 'unevaluatedProperties', 'deprecated', 'maintainers', 'select', '$ref']
> 	from schema $id: http://devicetree.org/meta-schemas/base.yaml#
> 
Ack.
> doc reference errors (make refcheckdocs):
> 
> See https://patchwork.ozlabs.org/project/devicetree-bindings/patch/20250802-tlv493d-sensor-v6_16-rc5-v2-2-e867df86ad93@gmail.com
> 
> The base for the series is generally the latest rc1. A different dependency
> should be noted in *this* patch.
>
I did not get this fully, is this concerning?
> If you already ran 'make dt_binding_check' and didn't see the above
> error(s), then make sure 'yamllint' is installed and dt-schema is up to
> date:
> 
> pip3 install dtschema --upgrade
> 
> Please check and re-submit after running the above command yourself. Note
> that DT_SCHEMA_FILES can be set to your schema file to speed up checking
> your schema. However, it must be unset to test all examples with your schema.
> 
Thanks,
Dixit

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

* Re: [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor
  2025-08-02  7:45   ` Krzysztof Kozlowski
@ 2025-08-04  2:44     ` Dixit Parmar
  2025-08-04  6:03       ` Krzysztof Kozlowski
  0 siblings, 1 reply; 22+ messages in thread
From: Dixit Parmar @ 2025-08-04  2:44 UTC (permalink / raw)
  To: Krzysztof Kozlowski
  Cc: Jonathan Cameron, David Lechner, Nuno Sá, Andy Shevchenko,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, linux-kernel,
	linux-iio, devicetree

On Sat, Aug 02, 2025 at 09:45:29AM +0200, Krzysztof Kozlowski wrote:
> On 02/08/2025 08:44, Dixit Parmar wrote:
> > Document the bindings for Infineon TLV493D Low-Power 3D Magnetic Sensor
> > controlled by I2C interface. Main applications includes joysticks, control
> > elements (white goods, multifunction knops), or electric meters (anti-
> > tampering).
> > Drop duplicated entry for infineon,tlv493d from trivial-devices.yaml as
> > its documented in infineon,tlv493d.yaml now.
> > 
> > Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
> > Signed-off-by: Dixit Parmar <dixitparmar19@gmail.com>
> > ---
> >  .../iio/magnetometer/infineon,tlv493d.yaml         | 45 ++++++++++++++++++++++
> >  .../devicetree/bindings/trivial-devices.yaml       |  2 -
> >  2 files changed, 45 insertions(+), 2 deletions(-)
> > 
> > diff --git a/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml b/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml
> > new file mode 100644
> > index 000000000000..ebcf29067a16
> > --- /dev/null
> > +++ b/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml
> 
> 
> Filename should match compatible. Otherwise a1b6 is just confusing.
>
Idea behind having a1b6 is that the TLV493D is sensor series and this
a1b6 is one of the models. As this driver is intended, developed and
validated on a1b6 I kept it in compatible, though the file name contains
only the sensor series. In my undertanding, this same file & driver can
be reused for other drivers from same family with new compatible fields.
Does that make sense?
> Best regards,
> Krzysztof

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

* Re: [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor
  2025-08-02  8:53 ` [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor Andy Shevchenko
  2025-08-02 11:15   ` Jonathan Cameron
@ 2025-08-04  2:52   ` Dixit Parmar
  2025-08-04  9:03     ` Andy Shevchenko
  1 sibling, 1 reply; 22+ messages in thread
From: Dixit Parmar @ 2025-08-04  2:52 UTC (permalink / raw)
  To: Andy Shevchenko
  Cc: Jonathan Cameron, David Lechner, Nuno Sá, Andy Shevchenko,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, linux-kernel,
	linux-iio, devicetree

On Sat, Aug 02, 2025 at 10:53:30AM +0200, Andy Shevchenko wrote:
> On Sat, Aug 2, 2025 at 8:44 AM Dixit Parmar <dixitparmar19@gmail.com> wrote:
> >
> > The Infineon TLV493D is a Low-Power 3D Magnetic Sensor. The Sensor
> > applications includes joysticks, control elements (white goods,
> > multifunction knops), or electric meters (anti tampering) and any
> > other application that requires accurate angular measurements at
> > low power consumptions.
> >
> > The Sensor is configured over I2C, and as part of Sensor measurement
> > data it provides 3-Axis magnetic fields and temperature core measurement.
> >
> > The driver supports raw value read and buffered input via external trigger
> > to allow streaming values with the same sensing timestamp.
> >
> > While sensor has interrupt pin multiplexed with I2C SCL pin. But for bus
> 
> the sensor
> an interrupt
> an I2C
> 
> > configurations interrupt(INT) is not recommended, unless timing constraints
> > between I2C data transfers and interrupt pulses are monitored and aligned.
> >
> > The Sensor's I2C register map and mode information is described in product
> > User Manual[Link].
> 
> Replace Link here with 1...
>
> > Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
> > Link: https://www.mouser.com/pdfDocs/Infineon-TLV493D-A1B6_3DMagnetic-UserManual-v01_03-EN.pdf
> 
> ...and add space followed by [1] here.
> 
Orginally it was with [1] only. But I thought I should use known standard tag here
so came up with link. For my understanding, what is the standard practice for this?
> ...
> 
> > Changes in v2:
> > - Drop regmap implementation in favor of using direct i2c APIs to
> >   have uniform communication APIs across the driver.
> 
> This I don't understand. I mean the motivation behind this. Usually
> direct I2C communication is used to do some initial checks and
> configuration and rarely for the actuall run-time driver
> functionality. Otherwise it means that the regmap may be used with a
> customised read and write methods.
>
On addition to what Jonathan explained, reading from sensor also is not addressable.
i.e. To read any sensor register the read op must be performed to read starting from 0
always, without specifying reg address.
> 
> -- 
> With Best Regards,
> Andy Shevchenko

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

* Re: [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor
  2025-08-02 11:43   ` Jonathan Cameron
  2025-08-02 13:25     ` Andy Shevchenko
@ 2025-08-04  3:18     ` Dixit Parmar
  2025-08-05 16:32       ` David Lechner
  2025-08-10 18:34       ` Jonathan Cameron
  1 sibling, 2 replies; 22+ messages in thread
From: Dixit Parmar @ 2025-08-04  3:18 UTC (permalink / raw)
  To: Jonathan Cameron
  Cc: David Lechner, Nuno Sá, Andy Shevchenko, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, linux-kernel, linux-iio,
	devicetree

On Sat, Aug 02, 2025 at 12:43:33PM +0100, Jonathan Cameron wrote:
> On Sat, 02 Aug 2025 12:14:27 +0530
> Dixit Parmar <dixitparmar19@gmail.com> wrote:
> 
> > The Infineon TLV493D is a Low-Power 3D Magnetic Sensor. The Sensor
> > applications includes joysticks, control elements (white goods,
> > multifunction knops), or electric meters (anti tampering) and any
> > other application that requires accurate angular measurements at
> > low power consumptions.
> > 
> > The Sensor is configured over I2C, and as part of Sensor measurement
> > data it provides 3-Axis magnetic fields and temperature core measurement.
> > 
> > The driver supports raw value read and buffered input via external trigger
> > to allow streaming values with the same sensing timestamp.
> > 
> > While sensor has interrupt pin multiplexed with I2C SCL pin. But for bus
> > configurations interrupt(INT) is not recommended, unless timing constraints
> > between I2C data transfers and interrupt pulses are monitored and aligned.
> > 
> > The Sensor's I2C register map and mode information is described in product
> > User Manual[Link].
> > 
> > Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
> > Link: https://www.mouser.com/pdfDocs/Infineon-TLV493D-A1B6_3DMagnetic-UserManual-v01_03-EN.pdf
> > Signed-off-by: Dixit Parmar <dixitparmar19@gmail.com>
> 
> Hi Dixit,
> 
> Some additional comments inline.
> 
> > diff --git a/drivers/iio/magnetometer/tlv493d.c b/drivers/iio/magnetometer/tlv493d.c
> > new file mode 100644
> > index 000000000000..da1569ae97bf
> > --- /dev/null
> > +++ b/drivers/iio/magnetometer/tlv493d.c
> 
> > +enum tlv493d_op_mode {
> > +	TLV493D_OP_MODE_POWERDOWN = 0,
> > +	TLV493D_OP_MODE_FAST,
> > +	TLV493D_OP_MODE_LOWPOWER,
> > +	TLV493D_OP_MODE_ULTRA_LOWPOWER,
> > +	TLV493D_OP_MODE_MASTERCONTROLLED,
> > +	TLV493D_OP_MODE_MAX
> In order to be able to use this as the type for a parameter as suggested
> below, you'll need to drop MODE_MAX.  Comments on why you shouldn't
> need that anyway below.
> 
> > +};
> > +
> > +struct tlv493d_mode {
> > +	u8 m;
> You have an enum type.  Much better to use it.
> 
> > +	u32 sleep_us;
> > +};
> > +
> > +struct tlv493d_data {
> > +	struct device *dev;
> > +	struct i2c_client *client;
> > +	/* protects from simultaneous sensor access and register readings */
> > +	struct mutex lock;
> > +	u8 mode;
> > +	u8 wr_regs[TLV493D_WR_REG_MAX];
> > +};
> > +
> > +/*
> > + * Different mode has different measurement cycle time, this time is
> > + * used in deriving the sleep and timemout while reading the data from
> > + * sensor in polling.
> > + * Power-down mode: No measurement.
> > + * Fast mode: Freq:3.3 KHz. Measurement time:305 usec.
> > + * Low-power mode: Freq:100 Hz. Measurement time:10 msec.
> > + * Ultra low-power mode: Freq:10 Hz. Measurement time:100 msec.
> > + * Master controlled mode: Freq:3.3 Khz. Measurement time:305 usec.
> > + */
> > +static struct tlv493d_mode tlv493d_mode_info[TLV493D_OP_MODE_MAX] = {
> If you want to size it, do it using the enum values. [] is fine here
> 	[TLV493D_OP_MODE_POWERDOWN] = { }
> 
> I'm not sure why this should embed the index.  Can you just drop .m?
>
Indeed, In V2 I wanted to change this to a u32 array containing the
timing values for all mode and drop struct, but was skeptical.
IMO that would also be a clean way rather than having it in struct. Makes sense?
> > +	{ .m = TLV493D_OP_MODE_POWERDOWN, .sleep_us = 0 },
> > +	{ .m = TLV493D_OP_MODE_FAST, .sleep_us = 305 },
> > +	{ .m = TLV493D_OP_MODE_LOWPOWER, .sleep_us = 10 * USEC_PER_MSEC	},
> > +	{ .m = TLV493D_OP_MODE_ULTRA_LOWPOWER, .sleep_us = 100 * USEC_PER_MSEC },
> > +	{ .m = TLV493D_OP_MODE_MASTERCONTROLLED, .sleep_us = 305 }
> > +};
> > +
> > +/*
> > + * The datasheet mentions the sensor supports only direct byte-stream write
> > + * starting from register address 0x0. So for any modification to be made to
> > + * any write registers, it must be written starting from the register address
> > + * 0x0. I2C write operation should not contain register address in the I2C
> > + * frame, it should contains only raw byte stream for the write registers.
> > + * I2C Frame: |S|SlaveAddr Wr|Ack|Byte[0]|Ack|Byte[1]|Ack|.....|Sp|
> > + */
> > +static int tlv493d_write_all_regs(struct tlv493d_data *data)
> > +{
> > +	int ret;
> > +
> > +	if (!data || !data->client)
> If either of these happen, something went very very wrong.
> No need for the checks.  Remove all similar ones.
> 
Interesting, Is the idea behind is that this API is used within the
driver and the inputs are known? Ofcourse it saves some CPU cycles.
> > +		return -EINVAL;
> > +
> > +	ret = i2c_master_send(data->client, data->wr_regs, ARRAY_SIZE(data->wr_regs));
> > +	if (ret < 0) {
> > +		dev_err(data->dev, "i2c write registers failed, error: %d\n", ret);
> > +		return ret;
> > +	}
> > +
> > +	return 0;
> > +}
> > +
> > +static int tlv493d_set_operating_mode(struct tlv493d_data *data, u8 mode)
> As below. Use the enum type.
> > +{
> > +	if (!data)
> > +		return -EINVAL;
> 
> As above. Data is never going to be NULL, so don't check it.
> 
> > +
> > +	u8 mode1_cfg, mode2_cfg;
> > +
> > +	switch (mode) {
> > +	case TLV493D_OP_MODE_POWERDOWN:
> > +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 0);
> > +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
> > +		break;
> > +
> > +	case TLV493D_OP_MODE_FAST:
> > +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 1);
> > +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
> > +		break;
> > +
> > +	case TLV493D_OP_MODE_LOWPOWER:
> > +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 2);
> > +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 1);
> > +		break;
> > +
> > +	case TLV493D_OP_MODE_ULTRA_LOWPOWER:
> > +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 2);
> > +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
> > +		break;
> > +
> > +	case TLV493D_OP_MODE_MASTERCONTROLLED:
> > +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 3);
> > +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
> > +		break;
> > +
> > +	default:
> > +		dev_err(data->dev, "invalid mode configuration\n");
> > +		return -EINVAL;
> And with the enum type you shouldn't need a default.
> 
Can you please help me understand this better? So far my learning was,
wherever there is switch case, it must have default case handled
appropriatly.
> > +	}
> > +
> > +	data->wr_regs[TLV493D_WR_REG_MODE1] |= mode1_cfg;
> > +	data->wr_regs[TLV493D_WR_REG_MODE2] |= mode2_cfg;
> > +
> > +	return tlv493d_write_all_regs(data);
> > +}
> > +
> > +static s16 tlv493d_get_channel_data(u8 *b, u8 ch)
> Use the enum. 
> > +{
> > +	if (!b)
> > +		return -EINVAL;
> Unnecessary check
> > +
> > +	u16 val = 0;
> Variable declarations at the top of scope unless strong reason to do otherwise
> (only normally done for auto cleanup)
> > +
> > +	switch (ch) {
> > +	case TLV493D_AXIS_X:
> > +		val = FIELD_GET(TLV493D_BX_MAG_X_AXIS_MSB, b[TLV493D_RD_REG_BX]) << 4 |
> > +			FIELD_GET(TLV493D_BX2_MAG_X_AXIS_LSB, b[TLV493D_RD_REG_BX2]) >> 4;
> > +		break;
> > +	case TLV493D_AXIS_Y:
> > +		val = FIELD_GET(TLV493D_BY_MAG_Y_AXIS_MSB, b[TLV493D_RD_REG_BY]) << 4 |
> > +			FIELD_GET(TLV493D_BX2_MAG_Y_AXIS_LSB, b[TLV493D_RD_REG_BX2]);
> > +		break;
> > +	case TLV493D_AXIS_Z:
> > +		val = FIELD_GET(TLV493D_BZ_MAG_Z_AXIS_MSB, b[TLV493D_RD_REG_BZ]) << 4 |
> > +			FIELD_GET(TLV493D_BZ2_MAG_Z_AXIS_LSB, b[TLV493D_RD_REG_BZ2]);
> > +		break;
> > +	case TLV493D_TEMPERATURE:
> > +		val = FIELD_GET(TLV493D_TEMP_TEMP_MSB, b[TLV493D_RD_REG_TEMP]) << 8 |
> > +			FIELD_GET(TLV493D_TEMP2_TEMP_LSB, b[TLV493D_RD_REG_TEMP2]);
> > +		break;
> > +	default:
> > +		return -EINVAL;
> And with the enum, there will be no need to have a default.
> Not to mention passing -EINVAL through an s16 is unusual and I doubt wise.
> 
> > +	}
> > +
> > +	return sign_extend32(val, 11);
> > +}
> > +
> > +static int tlv493d_get_measurements(struct tlv493d_data *data, s16 *x, s16 *y,
> > +				s16 *z, s16 *t)
> > +{
> > +	u8 buff[7] = {};
> > +	int err, ret;
> > +	struct tlv493d_mode *mode;
> > +
> > +	if (!data)
> > +		return -EINVAL;
> > +
> > +	guard(mutex)(&data->lock);
> > +
> > +	ret = pm_runtime_resume_and_get(data->dev);
> > +	if (ret < 0)
> > +		return ret;
> > +
> > +	mode = &tlv493d_mode_info[data->mode];
> > +
> > +	/*
> > +	 * Poll until data is valid,
> > +	 * For a valid data TLV493D_TEMP_CHANNEL bit of TLV493D_RD_REG_TEMP should be set to 0.
> > +	 * The sampling time depends on the sensor mode. poll 3x the time of the sampling time.
> > +	 */
> > +	ret = read_poll_timeout(i2c_master_recv, err, err ||
> > +			FIELD_GET(TLV493D_TEMP_CHANNEL, buff[TLV493D_RD_REG_TEMP]) == 0,
> > +			mode->sleep_us, (3 * mode->sleep_us), false, data->client, buff,
> > +			ARRAY_SIZE(buff));
> > +	if (ret) {
> > +		dev_err(data->dev, "i2c read poll timeout, error:%d\n", ret);
> > +		goto out;
> > +	}
> > +	if (err < 0) {
> > +		dev_err(data->dev, "i2c read data failed, error:%d\n", err);
> > +		ret = err;
> > +		goto out;
> > +	}
> > +
> > +	*x = tlv493d_get_channel_data(buff, TLV493D_AXIS_X);
> > +	*y = tlv493d_get_channel_data(buff, TLV493D_AXIS_Y);
> > +	*z = tlv493d_get_channel_data(buff, TLV493D_AXIS_Z);
> > +	*t = tlv493d_get_channel_data(buff, TLV493D_TEMPERATURE);
> > +
> > +out:
> > +	pm_runtime_mark_last_busy(data->dev);
> I've just rebased (mid merge window so i'll do it again on rc1) and now
> have the version of pm_runtime_put_autosuspend() that internally calls
> pm_runtime_mark_last_busy().
> 
> So please drop the line above if you need to do a v3.
>  
Okay.
> > +	pm_runtime_put_autosuspend(data->dev);
> > +	return ret;
> > +}
> 
> > +static int tlv493d_read_raw(struct iio_dev *indio_dev,
> > +			const struct iio_chan_spec *chan, int *val,
> > +			int *val2, long mask)
> > +{
> > +	struct tlv493d_data *data = iio_priv(indio_dev);
> > +	s16 x, y, z, t;
> > +	int ret;
> > +
> > +	switch (mask) {
> > +	case IIO_CHAN_INFO_RAW:
> > +		ret = tlv493d_get_measurements(data, &x, &y, &z, &t);
> > +		if (ret)
> > +			return ret;
> > +
> > +		/* Return raw values for requested channel */
> > +		switch (chan->address) {
> > +		case TLV493D_AXIS_X:
> > +			*val = x;
> > +			return IIO_VAL_INT;
> > +		case TLV493D_AXIS_Y:
> > +			*val = y;
> > +			return IIO_VAL_INT;
> > +		case TLV493D_AXIS_Z:
> > +			*val = z;
> > +			return IIO_VAL_INT;
> > +		case TLV493D_TEMPERATURE:
> > +			*val = t;
> > +			return IIO_VAL_INT;
> > +		default:
> > +			return -EINVAL;
> > +		}
> > +	case IIO_CHAN_INFO_SCALE:
> > +		switch (chan->type) {
> > +		case IIO_MAGN:
> > +			/*
> > +			 * Magnetic field scale: 0.0098 mTesla (i.e. 9.8 µT)
> > +			 * Magnetic filed in Guass: mT * 10 = 0.098.
> > +			 */
> > +			*val = 98;
> > +			*val2 = 1000;
> > +			return IIO_VAL_FRACTIONAL;
> > +		case IIO_TEMP:
> > +			/*
> > +			 * Temperature scale: 1.1 °C per LSB, expressed as 1100 m°C
> > +			 * Returned as integer for IIO core to apply:
> > +			 * temp = (raw + offset) * scale
> > +			 */
> > +			*val = 1100;
> > +			return IIO_VAL_INT;
> > +		default:
> > +			return -EINVAL;
> > +		}
> > +	case IIO_CHAN_INFO_OFFSET:
> > +		switch (chan->type) {
> > +		case IIO_TEMP:
> > +			/*
> > +			 * Temperature offset includes sensor-specific raw offset
> > +			 * plus compensation for +25°C bias in formula.
> > +			 * offset = -raw_offset + (25000 / 1100)
> > +			 * -340 + 22.72 = -317.28
> > +			 */
> > +			*val = -31728;
> > +			*val2 = 100;
> > +			return IIO_VAL_FRACTIONAL;
> > +		default:
> > +			return -EINVAL;
> > +		}
> > +
> > +	default:
> > +		return -EINVAL;
> > +	}
> > +
> > +	return 0;
> 
> Can you get here? If not drop this.  Compilers are very good at complaining if
> code changes later such that we should add this back.
> 
> > +}
> 
> > +static const struct iio_info tlv493d_info = {
> > +	.read_raw = tlv493d_read_raw,
> > +};
> > +
> > +static const struct iio_buffer_setup_ops tlv493d_setup_ops = { NULL };
> 
> No need specify that NULL. Due to some odd quirks of compiler specific
> handling and C spec evolution (none of which apply to the kernel because
> we carefully choose build options) that is actually less likely to do what
> you want than = { };
> 
Originally it was { } in V1. Got review comment that it must have NULL
if no ops is being passed, so I added (May be I would have asked and
understand their point). Nevertheless will remove NULL.
> 
> 
> > +
> > +static const unsigned long tlv493d_scan_masks[] = { GENMASK(3, 0), 0 };
> > +
> > +static int tlv493d_probe(struct i2c_client *client)
> > +{
> > +	struct device *dev = &client->dev;
> > +	struct iio_dev *indio_dev;
> > +	struct tlv493d_data *data;
> > +	int ret;
> > +
> > +	indio_dev = devm_iio_device_alloc(dev, sizeof(*data));
> > +	if (!indio_dev)
> > +		return -ENOMEM;
> > +
> > +	data = iio_priv(indio_dev);
> > +	data->dev = dev;
> > +	data->client = client;
> > +	i2c_set_clientdata(client, indio_dev);
> > +
> > +	ret = devm_mutex_init(dev, &data->lock);
> > +	if (ret)
> > +		return ret;
> > +
> > +	ret = devm_regulator_get_enable(dev, "vdd");
> > +	if (ret)
> > +		return dev_err_probe(dev, ret, "failed to enable regulator\n");
> > +
> > +	/*
> > +	 * Setting Sensor default operating mode as Master Controlled mode as
> > +	 * it performs measurement cycle on-request only and stays in Power-Down
> > +	 * mode until next cycle is initiated.
> > +	 */
> > +	data->mode = TLV493D_OP_MODE_MASTERCONTROLLED;
> > +	ret = tlv493d_init(data);
> > +	if (ret)
> > +		return dev_err_probe(dev, ret, "failed to initialize\n");
> > +
> > +	indio_dev->info = &tlv493d_info;
> > +	indio_dev->modes = INDIO_DIRECT_MODE;
> > +	indio_dev->name = client->name;
> > +	indio_dev->channels = tlv493d_channels;
> > +	indio_dev->num_channels = ARRAY_SIZE(tlv493d_channels);
> > +	indio_dev->available_scan_masks = tlv493d_scan_masks;
> > +
> > +	ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
> > +			iio_pollfunc_store_time, tlv493d_trigger_handler,
> > +			&tlv493d_setup_ops);
> Similar to below no alignment. Something like;
> 	ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
> 					      iio_pollfunc_store_time,
> 					      tlv493d_trigger_handler,
> 					      &tlv493d_setup_ops);
> 
> If you do have a case where the line ends up very long with this style, then
> indent only one tab more than line above. If that applied here it would be.
> 
> 	ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
> 		iio_pollfunc_store_time, tlv493d_trigger_handler,
> 		&tlv493d_setup_ops);
> 
> 
> 
> > +	if (ret < 0)
> > +		return dev_err_probe(dev, ret, "iio triggered buffer setup failed\n");
> > +
> > +	ret = pm_runtime_set_active(dev);
> > +	if (ret < 0)
> > +		return ret;
> > +
> > +	ret = devm_pm_runtime_enable(dev);
> > +	if (ret < 0)
> > +		return ret;
> > +
> > +	pm_runtime_get_noresume(dev);
> > +	pm_runtime_set_autosuspend_delay(dev, 500);
> > +	pm_runtime_use_autosuspend(dev);
> > +
> > +	pm_runtime_mark_last_busy(dev);
> > +	pm_runtime_put_autosuspend(dev);
> > +
> > +	ret = devm_iio_device_register(dev, indio_dev);
> > +	if (ret)
> > +		return dev_err_probe(dev, ret, "iio device register failed\n");
> > +
> > +	return 0;
> > +}
> > +
> > +static int tlv493d_runtime_suspend(struct device *dev)
> > +{
> > +	struct iio_dev *indio_dev = dev_get_drvdata(dev);
> > +	struct tlv493d_data *data = iio_priv(indio_dev);
> > +
> > +	return tlv493d_set_operating_mode(data, TLV493D_OP_MODE_POWERDOWN);
> > +}
> > +
> > +static int tlv493d_runtime_resume(struct device *dev)
> > +{
> > +	struct iio_dev *indio_dev = dev_get_drvdata(dev);
> > +	struct tlv493d_data *data = iio_priv(indio_dev);
> 
> Trivial but you could do
> 	struct tlv493d_data *data = iio_priv(dev_get_drvdata(dev));
> with no real loss of readability.
> 
> > +
> > +	return tlv493d_set_operating_mode(data, data->mode);
> > +}
> > +
> > +static DEFINE_RUNTIME_DEV_PM_OPS(tlv493d_pm_ops,
> > +			tlv493d_runtime_suspend, tlv493d_runtime_resume, NULL);
> Preferred wrapping here is
> static DEFINE_RUNTIME_DEV_PM_OPS(tlv493d_pm_ops, tlv493d_runtime_suspend,
> 				 tlv493d_runtime_resume, NULL);
> 
> So go nearer 80 chars on first line and align second line below the parameters
> on the first line.
> 
> Jonathan
> 

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

* Re: [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor
  2025-08-04  2:44     ` Dixit Parmar
@ 2025-08-04  6:03       ` Krzysztof Kozlowski
  2025-08-04  6:16         ` Krzysztof Kozlowski
  0 siblings, 1 reply; 22+ messages in thread
From: Krzysztof Kozlowski @ 2025-08-04  6:03 UTC (permalink / raw)
  To: Dixit Parmar
  Cc: Jonathan Cameron, David Lechner, Nuno Sá, Andy Shevchenko,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, linux-kernel,
	linux-iio, devicetree

On 04/08/2025 04:44, Dixit Parmar wrote:
> On Sat, Aug 02, 2025 at 09:45:29AM +0200, Krzysztof Kozlowski wrote:
>> On 02/08/2025 08:44, Dixit Parmar wrote:
>>> Document the bindings for Infineon TLV493D Low-Power 3D Magnetic Sensor
>>> controlled by I2C interface. Main applications includes joysticks, control
>>> elements (white goods, multifunction knops), or electric meters (anti-
>>> tampering).
>>> Drop duplicated entry for infineon,tlv493d from trivial-devices.yaml as
>>> its documented in infineon,tlv493d.yaml now.
>>>
>>> Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
>>> Signed-off-by: Dixit Parmar <dixitparmar19@gmail.com>
>>> ---
>>>  .../iio/magnetometer/infineon,tlv493d.yaml         | 45 ++++++++++++++++++++++
>>>  .../devicetree/bindings/trivial-devices.yaml       |  2 -
>>>  2 files changed, 45 insertions(+), 2 deletions(-)
>>>
>>> diff --git a/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml b/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml
>>> new file mode 100644
>>> index 000000000000..ebcf29067a16
>>> --- /dev/null
>>> +++ b/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml
>>
>>
>> Filename should match compatible. Otherwise a1b6 is just confusing.
>>
> Idea behind having a1b6 is that the TLV493D is sensor series and this
> a1b6 is one of the models. As this driver is intended, developed and
> validated on a1b6 I kept it in compatible, though the file name contains
> only the sensor series. In my undertanding, this same file & driver can
> be reused for other drivers from same family with new compatible fields.
> Does that make sense?

No, because I did not speak about drivers at all. Please follow
kernel/DT conventions.

Best regards,
Krzysztof

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

* Re: [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor
  2025-08-04  6:03       ` Krzysztof Kozlowski
@ 2025-08-04  6:16         ` Krzysztof Kozlowski
  2025-08-04 13:36           ` Dixit Parmar
  0 siblings, 1 reply; 22+ messages in thread
From: Krzysztof Kozlowski @ 2025-08-04  6:16 UTC (permalink / raw)
  To: Dixit Parmar
  Cc: Jonathan Cameron, David Lechner, Nuno Sá, Andy Shevchenko,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, linux-kernel,
	linux-iio, devicetree

On 04/08/2025 08:03, Krzysztof Kozlowski wrote:
>>>>
>>>> diff --git a/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml b/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml
>>>> new file mode 100644
>>>> index 000000000000..ebcf29067a16
>>>> --- /dev/null
>>>> +++ b/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml
>>>
>>>
>>> Filename should match compatible. Otherwise a1b6 is just confusing.
>>>
>> Idea behind having a1b6 is that the TLV493D is sensor series and this
>> a1b6 is one of the models. As this driver is intended, developed and
>> validated on a1b6 I kept it in compatible, though the file name contains
>> only the sensor series. In my undertanding, this same file & driver can
>> be reused for other drivers from same family with new compatible fields.
>> Does that make sense?
> 
> No, because I did not speak about drivers at all. Please follow
> kernel/DT conventions.
> 

And now I see this wasn't ever tested. :/

Best regards,
Krzysztof

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

* Re: [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor
  2025-08-04  2:52   ` Dixit Parmar
@ 2025-08-04  9:03     ` Andy Shevchenko
  0 siblings, 0 replies; 22+ messages in thread
From: Andy Shevchenko @ 2025-08-04  9:03 UTC (permalink / raw)
  To: Dixit Parmar
  Cc: Jonathan Cameron, David Lechner, Nuno Sá, Andy Shevchenko,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, linux-kernel,
	linux-iio, devicetree

On Mon, Aug 4, 2025 at 4:53 AM Dixit Parmar <dixitparmar19@gmail.com> wrote:
> On Sat, Aug 02, 2025 at 10:53:30AM +0200, Andy Shevchenko wrote:
> > On Sat, Aug 2, 2025 at 8:44 AM Dixit Parmar <dixitparmar19@gmail.com> wrote:

...

> > > The Sensor's I2C register map and mode information is described in product
> > > User Manual[Link].
> >
> > Replace Link here with 1...
> >
> > > Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
> > > Link: https://www.mouser.com/pdfDocs/Infineon-TLV493D-A1B6_3DMagnetic-UserManual-v01_03-EN.pdf
> >
> > ...and add space followed by [1] here.
> >
> Orginally it was with [1] only. But I thought I should use known standard tag here
> so came up with link. For my understanding, what is the standard practice for this?

The expected format is

Link: $URL [1]

where $URL is the above URL.

...

> > > Changes in v2:
> > > - Drop regmap implementation in favor of using direct i2c APIs to
> > >   have uniform communication APIs across the driver.
> >
> > This I don't understand. I mean the motivation behind this. Usually
> > direct I2C communication is used to do some initial checks and
> > configuration and rarely for the actuall run-time driver
> > functionality. Otherwise it means that the regmap may be used with a
> > customised read and write methods.
> >
> On addition to what Jonathan explained, reading from sensor also is not addressable.
> i.e. To read any sensor register the read op must be performed to read starting from 0
> always, without specifying reg address.

Okay, if not yet commented in the code, please add that somewhere in
the top comment of the file.

-- 
With Best Regards,
Andy Shevchenko

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

* Re: [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor
  2025-08-04  6:16         ` Krzysztof Kozlowski
@ 2025-08-04 13:36           ` Dixit Parmar
  0 siblings, 0 replies; 22+ messages in thread
From: Dixit Parmar @ 2025-08-04 13:36 UTC (permalink / raw)
  To: Krzysztof Kozlowski
  Cc: Jonathan Cameron, David Lechner, Nuno Sá, Andy Shevchenko,
	Rob Herring, Krzysztof Kozlowski, Conor Dooley, linux-kernel,
	linux-iio, devicetree

On Mon, Aug 04, 2025 at 08:16:36AM +0200, Krzysztof Kozlowski wrote:
> On 04/08/2025 08:03, Krzysztof Kozlowski wrote:
> >>>>
> >>>> diff --git a/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml b/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml
> >>>> new file mode 100644
> >>>> index 000000000000..ebcf29067a16
> >>>> --- /dev/null
> >>>> +++ b/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml
> >>>
> >>>
> >>> Filename should match compatible. Otherwise a1b6 is just confusing.
> >>>
> >> Idea behind having a1b6 is that the TLV493D is sensor series and this
> >> a1b6 is one of the models. As this driver is intended, developed and
> >> validated on a1b6 I kept it in compatible, though the file name contains
> >> only the sensor series. In my undertanding, this same file & driver can
> >> be reused for other drivers from same family with new compatible fields.
> >> Does that make sense?
> > 
> > No, because I did not speak about drivers at all. Please follow
> > kernel/DT conventions.
> > 
> 
> And now I see this wasn't ever tested. :/
>
You're right. I just learned about the devicetree binding validation process post
your comment, make dt_binding_check. This is my first time contributing to DT bindings,
so I wasn't aware of the requirement to validate the schema before submission.
There was mention of this in the bot error reported, now I see.
Apologies for the oversight. I'll make sure this does not get repeated.
> Best regards,
> Krzysztof

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

* Re: [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor
  2025-08-04  3:18     ` Dixit Parmar
@ 2025-08-05 16:32       ` David Lechner
  2025-08-10 18:34       ` Jonathan Cameron
  1 sibling, 0 replies; 22+ messages in thread
From: David Lechner @ 2025-08-05 16:32 UTC (permalink / raw)
  To: Dixit Parmar, Jonathan Cameron
  Cc: Nuno Sá, Andy Shevchenko, Rob Herring, Krzysztof Kozlowski,
	Conor Dooley, linux-kernel, linux-iio, devicetree

On 8/3/25 10:18 PM, Dixit Parmar wrote:
>>> +static const struct iio_buffer_setup_ops tlv493d_setup_ops = { NULL };
>>
>> No need specify that NULL. Due to some odd quirks of compiler specific
>> handling and C spec evolution (none of which apply to the kernel because
>> we carefully choose build options) that is actually less likely to do what
>> you want than = { };
>>
> Originally it was { } in V1. Got review comment that it must have NULL
> if no ops is being passed, so I added (May be I would have asked and
> understand their point). Nevertheless will remove NULL.

We don't need tlv493d_setup_ops at all. The NULL comes later where
tlv493d_setup_ops was used:

ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
			iio_pollfunc_store_time,
			tlv493d_trigger_handler,
			NULL);

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

* Re: [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor
  2025-08-04  2:41     ` Dixit Parmar
@ 2025-08-05 16:35       ` David Lechner
  0 siblings, 0 replies; 22+ messages in thread
From: David Lechner @ 2025-08-05 16:35 UTC (permalink / raw)
  To: Dixit Parmar, Rob Herring (Arm)
  Cc: Nuno Sá, Jonathan Cameron, Krzysztof Kozlowski, linux-iio,
	Conor Dooley, Andy Shevchenko, linux-kernel, devicetree

On 8/3/25 9:41 PM, Dixit Parmar wrote:
> On Sun, Aug 03, 2025 at 11:20:40AM -0500, Rob Herring (Arm) wrote:
>>
>> On Sat, 02 Aug 2025 12:14:28 +0530, Dixit Parmar wrote:
>>> Document the bindings for Infineon TLV493D Low-Power 3D Magnetic Sensor
>>> controlled by I2C interface. Main applications includes joysticks, control
>>> elements (white goods, multifunction knops), or electric meters (anti-
>>> tampering).
>>> Drop duplicated entry for infineon,tlv493d from trivial-devices.yaml as
>>> its documented in infineon,tlv493d.yaml now.
>>>
>>> Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
>>> Signed-off-by: Dixit Parmar <dixitparmar19@gmail.com>
>>> ---
>>>  .../iio/magnetometer/infineon,tlv493d.yaml         | 45 ++++++++++++++++++++++
>>>  .../devicetree/bindings/trivial-devices.yaml       |  2 -
>>>  2 files changed, 45 insertions(+), 2 deletions(-)
>>>
>>
>> My bot found errors running 'make dt_binding_check' on your patch:
>>
>> yamllint warnings/errors:
>>
>> dtschema/dtc warnings/errors:
>> /builds/robherring/dt-review-ci/linux/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml: vdd: missing type definition
>> /builds/robherring/dt-review-ci/linux/Documentation/devicetree/bindings/iio/magnetometer/infineon,tlv493d.yaml: 'example' is not one of ['$id', '$schema', 'title', 'description', 'examples', 'required', 'allOf', 'anyOf', 'oneOf', 'definitions', '$defs', 'additionalProperties', 'dependencies', 'dependentRequired', 'dependentSchemas', 'patternProperties', 'properties', 'not', 'if', 'then', 'else', 'unevaluatedProperties', 'deprecated', 'maintainers', 'select', '$ref']
>> 	from schema $id: http://devicetree.org/meta-schemas/base.yaml#
>>
> Ack.
>> doc reference errors (make refcheckdocs):
>>
>> See https://patchwork.ozlabs.org/project/devicetree-bindings/patch/20250802-tlv493d-sensor-v6_16-rc5-v2-2-e867df86ad93@gmail.com
>>
>> The base for the series is generally the latest rc1. A different dependency
>> should be noted in *this* patch.
>>
> I did not get this fully, is this concerning?

Nothing to worry about in this case. This is a new binding with nothing
unusual, so there are no dependencies.

>> If you already ran 'make dt_binding_check' and didn't see the above
>> error(s), then make sure 'yamllint' is installed and dt-schema is up to
>> date:
>>
>> pip3 install dtschema --upgrade
>>
>> Please check and re-submit after running the above command yourself. Note
>> that DT_SCHEMA_FILES can be set to your schema file to speed up checking
>> your schema. However, it must be unset to test all examples with your schema.
>>
> Thanks,
> Dixit


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

* Re: [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor
  2025-08-02  6:44 ` [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor Dixit Parmar
  2025-08-02 11:43   ` Jonathan Cameron
@ 2025-08-06 16:27   ` kernel test robot
  1 sibling, 0 replies; 22+ messages in thread
From: kernel test robot @ 2025-08-06 16:27 UTC (permalink / raw)
  To: Dixit Parmar, Jonathan Cameron, David Lechner, Nuno Sá,
	Andy Shevchenko, Rob Herring, Krzysztof Kozlowski, Conor Dooley
  Cc: oe-kbuild-all, linux-kernel, linux-iio, devicetree, Dixit Parmar

Hi Dixit,

kernel test robot noticed the following build errors:

[auto build test ERROR on d7b8f8e20813f0179d8ef519541a3527e7661d3a]

url:    https://github.com/intel-lab-lkp/linux/commits/Dixit-Parmar/iio-magnetometer-add-support-for-Infineon-TLV493D-3D-Magentic-sensor/20250802-144615
base:   d7b8f8e20813f0179d8ef519541a3527e7661d3a
patch link:    https://lore.kernel.org/r/20250802-tlv493d-sensor-v6_16-rc5-v2-1-e867df86ad93%40gmail.com
patch subject: [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor
config: um-allyesconfig (https://download.01.org/0day-ci/archive/20250807/202508070051.wZvtQr6x-lkp@intel.com/config)
compiler: gcc-12 (Debian 12.2.0-14+deb12u1) 12.2.0
reproduce (this is a W=1 build): (https://download.01.org/0day-ci/archive/20250807/202508070051.wZvtQr6x-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/202508070051.wZvtQr6x-lkp@intel.com/

All errors (new ones prefixed by >>):

   In file included from include/uapi/linux/posix_types.h:5,
                    from include/uapi/linux/types.h:14,
                    from include/linux/types.h:6,
                    from include/linux/kasan-checks.h:5,
                    from include/asm-generic/rwonce.h:26,
                    from ./arch/x86/include/generated/asm/rwonce.h:1,
                    from include/linux/compiler.h:390,
                    from include/linux/build_bug.h:5,
                    from include/linux/bits.h:32,
                    from drivers/iio/magnetometer/tlv493d.c:8:
>> include/linux/stddef.h:8:14: error: positional initialization of field in 'struct' declared with 'designated_init' attribute [-Werror=designated-init]
       8 | #define NULL ((void *)0)
         |              ^
   drivers/iio/magnetometer/tlv493d.c:438:64: note: in expansion of macro 'NULL'
     438 | static const struct iio_buffer_setup_ops tlv493d_setup_ops = { NULL };
         |                                                                ^~~~
   include/linux/stddef.h:8:14: note: (near initialization for 'tlv493d_setup_ops')
       8 | #define NULL ((void *)0)
         |              ^
   drivers/iio/magnetometer/tlv493d.c:438:64: note: in expansion of macro 'NULL'
     438 | static const struct iio_buffer_setup_ops tlv493d_setup_ops = { NULL };
         |                                                                ^~~~
   cc1: some warnings being treated as errors


vim +8 include/linux/stddef.h

^1da177e4c3f41 Linus Torvalds   2005-04-16  6  
^1da177e4c3f41 Linus Torvalds   2005-04-16  7  #undef NULL
^1da177e4c3f41 Linus Torvalds   2005-04-16 @8  #define NULL ((void *)0)
6e218287432472 Richard Knutsson 2006-09-30  9  

-- 
0-DAY CI Kernel Test Service
https://github.com/intel/lkp-tests/wiki

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

* Re: [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor
  2025-08-04  3:18     ` Dixit Parmar
  2025-08-05 16:32       ` David Lechner
@ 2025-08-10 18:34       ` Jonathan Cameron
  1 sibling, 0 replies; 22+ messages in thread
From: Jonathan Cameron @ 2025-08-10 18:34 UTC (permalink / raw)
  To: Dixit Parmar
  Cc: David Lechner, Nuno Sá, Andy Shevchenko, Rob Herring,
	Krzysztof Kozlowski, Conor Dooley, linux-kernel, linux-iio,
	devicetree

On Mon, 4 Aug 2025 08:48:25 +0530
Dixit Parmar <dixitparmar19@gmail.com> wrote:

> On Sat, Aug 02, 2025 at 12:43:33PM +0100, Jonathan Cameron wrote:
> > On Sat, 02 Aug 2025 12:14:27 +0530
> > Dixit Parmar <dixitparmar19@gmail.com> wrote:
> >   
> > > The Infineon TLV493D is a Low-Power 3D Magnetic Sensor. The Sensor
> > > applications includes joysticks, control elements (white goods,
> > > multifunction knops), or electric meters (anti tampering) and any
> > > other application that requires accurate angular measurements at
> > > low power consumptions.
> > > 
> > > The Sensor is configured over I2C, and as part of Sensor measurement
> > > data it provides 3-Axis magnetic fields and temperature core measurement.
> > > 
> > > The driver supports raw value read and buffered input via external trigger
> > > to allow streaming values with the same sensing timestamp.
> > > 
> > > While sensor has interrupt pin multiplexed with I2C SCL pin. But for bus
> > > configurations interrupt(INT) is not recommended, unless timing constraints
> > > between I2C data transfers and interrupt pulses are monitored and aligned.
> > > 
> > > The Sensor's I2C register map and mode information is described in product
> > > User Manual[Link].
> > > 
> > > Datasheet: https://www.infineon.com/assets/row/public/documents/24/49/infineon-tlv493d-a1b6-datasheet-en.pdf
> > > Link: https://www.mouser.com/pdfDocs/Infineon-TLV493D-A1B6_3DMagnetic-UserManual-v01_03-EN.pdf
> > > Signed-off-by: Dixit Parmar <dixitparmar19@gmail.com>  
> > 
> > Hi Dixit,
> > 
> > Some additional comments inline.
> >   
> > > diff --git a/drivers/iio/magnetometer/tlv493d.c b/drivers/iio/magnetometer/tlv493d.c
> > > new file mode 100644
> > > index 000000000000..da1569ae97bf
> > > --- /dev/null
> > > +++ b/drivers/iio/magnetometer/tlv493d.c  
> >   
> > > +enum tlv493d_op_mode {
> > > +	TLV493D_OP_MODE_POWERDOWN = 0,
> > > +	TLV493D_OP_MODE_FAST,
> > > +	TLV493D_OP_MODE_LOWPOWER,
> > > +	TLV493D_OP_MODE_ULTRA_LOWPOWER,
> > > +	TLV493D_OP_MODE_MASTERCONTROLLED,
> > > +	TLV493D_OP_MODE_MAX  
> > In order to be able to use this as the type for a parameter as suggested
> > below, you'll need to drop MODE_MAX.  Comments on why you shouldn't
> > need that anyway below.
> >   
> > > +};
> > > +
> > > +struct tlv493d_mode {
> > > +	u8 m;  
> > You have an enum type.  Much better to use it.
> >   
> > > +	u32 sleep_us;
> > > +};
> > > +
> > > +struct tlv493d_data {
> > > +	struct device *dev;
> > > +	struct i2c_client *client;
> > > +	/* protects from simultaneous sensor access and register readings */
> > > +	struct mutex lock;
> > > +	u8 mode;
> > > +	u8 wr_regs[TLV493D_WR_REG_MAX];
> > > +};
> > > +
> > > +/*
> > > + * Different mode has different measurement cycle time, this time is
> > > + * used in deriving the sleep and timemout while reading the data from
> > > + * sensor in polling.
> > > + * Power-down mode: No measurement.
> > > + * Fast mode: Freq:3.3 KHz. Measurement time:305 usec.
> > > + * Low-power mode: Freq:100 Hz. Measurement time:10 msec.
> > > + * Ultra low-power mode: Freq:10 Hz. Measurement time:100 msec.
> > > + * Master controlled mode: Freq:3.3 Khz. Measurement time:305 usec.
> > > + */
> > > +static struct tlv493d_mode tlv493d_mode_info[TLV493D_OP_MODE_MAX] = {  
> > If you want to size it, do it using the enum values. [] is fine here
> > 	[TLV493D_OP_MODE_POWERDOWN] = { }
> > 
> > I'm not sure why this should embed the index.  Can you just drop .m?
> >  
> Indeed, In V2 I wanted to change this to a u32 array containing the
> timing values for all mode and drop struct, but was skeptical.
> IMO that would also be a clean way rather than having it in struct. Makes sense?


Yes, an array is what we want here.  But use the enum to index it both
when setting and querying.


> > > +	{ .m = TLV493D_OP_MODE_POWERDOWN, .sleep_us = 0 },
> > > +	{ .m = TLV493D_OP_MODE_FAST, .sleep_us = 305 },
> > > +	{ .m = TLV493D_OP_MODE_LOWPOWER, .sleep_us = 10 * USEC_PER_MSEC	},
> > > +	{ .m = TLV493D_OP_MODE_ULTRA_LOWPOWER, .sleep_us = 100 * USEC_PER_MSEC },
> > > +	{ .m = TLV493D_OP_MODE_MASTERCONTROLLED, .sleep_us = 305 }
> > > +};
> > > +
> > > +/*
> > > + * The datasheet mentions the sensor supports only direct byte-stream write
> > > + * starting from register address 0x0. So for any modification to be made to
> > > + * any write registers, it must be written starting from the register address
> > > + * 0x0. I2C write operation should not contain register address in the I2C
> > > + * frame, it should contains only raw byte stream for the write registers.
> > > + * I2C Frame: |S|SlaveAddr Wr|Ack|Byte[0]|Ack|Byte[1]|Ack|.....|Sp|
> > > + */
> > > +static int tlv493d_write_all_regs(struct tlv493d_data *data)
> > > +{
> > > +	int ret;
> > > +
> > > +	if (!data || !data->client)  
> > If either of these happen, something went very very wrong.
> > No need for the checks.  Remove all similar ones.
> >   
> Interesting, Is the idea behind is that this API is used within the
> driver and the inputs are known? Ofcourse it saves some CPU cycles.

Exactly - if it's local and we can see the tests are never needed then
maybe the compiler will notice, but we can avoid even having the code.

> > > +		return -EINVAL;
> > > +
> > > +	ret = i2c_master_send(data->client, data->wr_regs, ARRAY_SIZE(data->wr_regs));
> > > +	if (ret < 0) {
> > > +		dev_err(data->dev, "i2c write registers failed, error: %d\n", ret);
> > > +		return ret;
> > > +	}
> > > +
> > > +	return 0;
> > > +}
> > > +
> > > +static int tlv493d_set_operating_mode(struct tlv493d_data *data, u8 mode)  
> > As below. Use the enum type.  
> > > +{
> > > +	if (!data)
> > > +		return -EINVAL;  
> > 
> > As above. Data is never going to be NULL, so don't check it.
> >   
> > > +
> > > +	u8 mode1_cfg, mode2_cfg;
> > > +
> > > +	switch (mode) {
> > > +	case TLV493D_OP_MODE_POWERDOWN:
> > > +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 0);
> > > +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
> > > +		break;
> > > +
> > > +	case TLV493D_OP_MODE_FAST:
> > > +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 1);
> > > +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
> > > +		break;
> > > +
> > > +	case TLV493D_OP_MODE_LOWPOWER:
> > > +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 2);
> > > +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 1);
> > > +		break;
> > > +
> > > +	case TLV493D_OP_MODE_ULTRA_LOWPOWER:
> > > +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 2);
> > > +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
> > > +		break;
> > > +
> > > +	case TLV493D_OP_MODE_MASTERCONTROLLED:
> > > +		mode1_cfg = FIELD_PREP(TLV493D_MODE1_MOD_LOWFAST, 3);
> > > +		mode2_cfg = FIELD_PREP(TLV493D_MODE2_LP_PERIOD, 0);
> > > +		break;
> > > +
> > > +	default:
> > > +		dev_err(data->dev, "invalid mode configuration\n");
> > > +		return -EINVAL;  
> > And with the enum type you shouldn't need a default.
> >   
> Can you please help me understand this better? So far my learning was,
> wherever there is switch case, it must have default case handled
> appropriatly.

If you passing in an enum, the compiler should be able to tell if you
are out of range.  Every enum value has an entry in the switch statement
therefore default is covering nothing and can be dropped.

That then defends against later adding a new enum value and failing
to cover it as the compiler then complains a case is not handled.

Jonathan


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

end of thread, other threads:[~2025-08-10 18:34 UTC | newest]

Thread overview: 22+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2025-08-02  6:44 [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor Dixit Parmar
2025-08-02  6:44 ` [PATCH v2 1/2] iio: magnetometer: add support for Infineon TLV493D 3D Magentic sensor Dixit Parmar
2025-08-02 11:43   ` Jonathan Cameron
2025-08-02 13:25     ` Andy Shevchenko
2025-08-04  3:18     ` Dixit Parmar
2025-08-05 16:32       ` David Lechner
2025-08-10 18:34       ` Jonathan Cameron
2025-08-06 16:27   ` kernel test robot
2025-08-02  6:44 ` [PATCH v2 2/2] dt-bindings: iio: magnetometer: document Infineon TLV493D 3D Magnetic sensor Dixit Parmar
2025-08-02  7:45   ` Krzysztof Kozlowski
2025-08-04  2:44     ` Dixit Parmar
2025-08-04  6:03       ` Krzysztof Kozlowski
2025-08-04  6:16         ` Krzysztof Kozlowski
2025-08-04 13:36           ` Dixit Parmar
2025-08-03 16:20   ` Rob Herring (Arm)
2025-08-04  2:41     ` Dixit Parmar
2025-08-05 16:35       ` David Lechner
2025-08-02  8:53 ` [PATCH v2 0/2] iio: magnetometer: add support for Infineon TLV493D 3D Magnetic Sensor Andy Shevchenko
2025-08-02 11:15   ` Jonathan Cameron
2025-08-02 13:17     ` Andy Shevchenko
2025-08-04  2:52   ` Dixit Parmar
2025-08-04  9:03     ` Andy Shevchenko

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).