devicetree.vger.kernel.org archive mirror
 help / color / mirror / Atom feed
* [PATCH v4 0/2] iio: imu: smi240: add bosch smi240 driver
@ 2024-08-26 14:05 Jianping.Shen
  2024-08-26 14:05 ` [PATCH v4 1/2] dt-bindings: iio: imu: smi240: devicetree binding Jianping.Shen
  2024-08-26 14:05 ` [PATCH v4 2/2] iio: imu: smi240: imu driver Jianping.Shen
  0 siblings, 2 replies; 6+ messages in thread
From: Jianping.Shen @ 2024-08-26 14:05 UTC (permalink / raw)
  To: jic23, lars, robh, krzk+dt, conor+dt, dima.fedrau,
	marcelo.schmitt1, linux-iio, devicetree, linux-kernel,
	Jianping.Shen, Christian.Lorenz3, Ulrike.Frauendorf, Kai.Dolde

From: Shen Jianping <Jianping.Shen@de.bosch.com>

This patchset adds the iio driver for bosch imu smi240. The smi240
is a combined three axis angular rate and three axis acceleration
sensor module with a measurement range of +/-300°/s and up to 16g.
Smi240 does not support interrupt. This driver provides raw data
access for each axis through sysfs, and tiggered buffer for
continuous sampling. A synchronous acc and gyro sampling can be
triggered by setting the capture bit in spi read command.

dt-bindings: 
v1 -> v2
    - Add more detail in description
    - Add maintainer
    - Add vdd and vddio power supply
    - Use generic node name
    - Order the properties according to DTS coding style
 v2 -> v3   
    - improve description
    - improve supply definition
    - make supply definition as required
    - add supply definition in example
v3 -> v4
    - no changes

imu driver:
v1 -> v2
    - Use regmap for register access
    - Redefine channel for each singel axis
    - Provide triggered buffer
    - Fix findings in Kconfig
    - Remove unimportant functions
v2 -> v3
    - Use enum für capture mode
    - Using spi default init value instead manual init 
    - remove duplicated module declaration
    - Fix code to avoid warning
v3 -> v4
    - Use DMA safe buffer
    - Use channel info instead of custom ABI
    - Fix other findings

Shen Jianping (2):
  dt-bindings: iio: imu: smi240: devicetree binding
  iio: imu: smi240: imu driver

 .../bindings/iio/imu/bosch,smi240.yaml        |  52 +++
 drivers/iio/imu/Kconfig                       |   1 +
 drivers/iio/imu/Makefile                      |   1 +
 drivers/iio/imu/smi240/Kconfig                |  12 +
 drivers/iio/imu/smi240/Makefile               |   7 +
 drivers/iio/imu/smi240/smi240.h               |  35 ++
 drivers/iio/imu/smi240/smi240_core.c          | 385 ++++++++++++++++++
 drivers/iio/imu/smi240/smi240_spi.c           | 172 ++++++++
 8 files changed, 665 insertions(+)
 create mode 100644 Documentation/devicetree/bindings/iio/imu/bosch,smi240.yaml
 create mode 100644 drivers/iio/imu/smi240/Kconfig
 create mode 100644 drivers/iio/imu/smi240/Makefile
 create mode 100644 drivers/iio/imu/smi240/smi240.h
 create mode 100644 drivers/iio/imu/smi240/smi240_core.c
 create mode 100644 drivers/iio/imu/smi240/smi240_spi.c

-- 
2.34.1


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

* [PATCH v4 1/2] dt-bindings: iio: imu: smi240: devicetree binding
  2024-08-26 14:05 [PATCH v4 0/2] iio: imu: smi240: add bosch smi240 driver Jianping.Shen
@ 2024-08-26 14:05 ` Jianping.Shen
  2024-08-26 14:53   ` Krzysztof Kozlowski
  2024-08-26 14:05 ` [PATCH v4 2/2] iio: imu: smi240: imu driver Jianping.Shen
  1 sibling, 1 reply; 6+ messages in thread
From: Jianping.Shen @ 2024-08-26 14:05 UTC (permalink / raw)
  To: jic23, lars, robh, krzk+dt, conor+dt, dima.fedrau,
	marcelo.schmitt1, linux-iio, devicetree, linux-kernel,
	Jianping.Shen, Christian.Lorenz3, Ulrike.Frauendorf, Kai.Dolde

From: Shen Jianping <Jianping.Shen@de.bosch.com>

This patch adds devicetree binding for Bosch imu smi240.
The smi240 is a combined three axis angular rate and
three axis acceleration sensor module.

* The smi240 requires VDD and VDDIO 
* Provides only spi interface.
* Does not support interrupt.

Signed-off-by: Shen Jianping <Jianping.Shen@de.bosch.com>
---
 .../bindings/iio/imu/bosch,smi240.yaml        | 52 +++++++++++++++++++
 1 file changed, 52 insertions(+)
 create mode 100644 Documentation/devicetree/bindings/iio/imu/bosch,smi240.yaml

diff --git a/Documentation/devicetree/bindings/iio/imu/bosch,smi240.yaml b/Documentation/devicetree/bindings/iio/imu/bosch,smi240.yaml
new file mode 100644
index 00000000000..6f1fb4b892c
--- /dev/null
+++ b/Documentation/devicetree/bindings/iio/imu/bosch,smi240.yaml
@@ -0,0 +1,52 @@
+# SPDX-License-Identifier: (GPL-2.0 OR BSD-2-Clause)
+%YAML 1.2
+---
+$id: http://devicetree.org/schemas/iio/imu/bosch,smi240.yaml#
+$schema: http://devicetree.org/meta-schemas/core.yaml#
+
+title: Bosch smi240 imu
+
+maintainers:
+  - Jianping Shen <Jianping.Shen@de.bosch.com>
+
+description:
+  The smi240 is a combined three axis angular rate and three 
+  axis acceleration sensor module with a measurement range of 
+  +/-300°/s and up to 16g.
+  https://www.bosch-semiconductors.com/mems-sensors/highly-automated-driving/smi240/
+
+properties:
+  compatible:
+    const: bosch,smi240
+
+  reg:
+    maxItems: 1
+
+  vdd-supply: true
+  vddio-supply: true
+
+required:
+  - compatible
+  - reg
+  - vdd-supply
+  - vddio-supply
+
+allOf:
+  - $ref: /schemas/spi/spi-peripheral-props.yaml#
+
+unevaluatedProperties: false
+
+examples:
+  - |
+    spi {
+        #address-cells = <1>;
+        #size-cells = <0>;
+
+        imu@0 {
+            compatible = "bosch,smi240";
+            reg = <0>;
+            vdd-supply = <&vdd>;
+            vddio-supply = <&vddio>;
+            spi-max-frequency = <10000000>;
+        };
+    };
-- 
2.34.1


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

* [PATCH v4 2/2] iio: imu: smi240: imu driver
  2024-08-26 14:05 [PATCH v4 0/2] iio: imu: smi240: add bosch smi240 driver Jianping.Shen
  2024-08-26 14:05 ` [PATCH v4 1/2] dt-bindings: iio: imu: smi240: devicetree binding Jianping.Shen
@ 2024-08-26 14:05 ` Jianping.Shen
  2024-08-26 14:57   ` Krzysztof Kozlowski
  2024-08-28 13:43   ` Jonathan Cameron
  1 sibling, 2 replies; 6+ messages in thread
From: Jianping.Shen @ 2024-08-26 14:05 UTC (permalink / raw)
  To: jic23, lars, robh, krzk+dt, conor+dt, dima.fedrau,
	marcelo.schmitt1, linux-iio, devicetree, linux-kernel,
	Jianping.Shen, Christian.Lorenz3, Ulrike.Frauendorf, Kai.Dolde

From: Shen Jianping <Jianping.Shen@de.bosch.com>

This patch adds the iio driver for bosch imu smi240. The smi240
is a combined three axis angular rate and three axis acceleration
sensor module with a measurement range of +/-300°/s and up to 16g.
Smi240 does not support interrupt. A synchronous acc and gyro
sampling can be triggered by setting the capture bit in spi read
command.

Implemented features:
* raw data access for each axis through sysfs
* tiggered buffer for continuous sampling
* synchronous acc and gyro data from tiggered buffer

Signed-off-by: Shen Jianping <Jianping.Shen@de.bosch.com>
---
 drivers/iio/imu/Kconfig              |   1 +
 drivers/iio/imu/Makefile             |   1 +
 drivers/iio/imu/smi240/Kconfig       |  12 +
 drivers/iio/imu/smi240/Makefile      |   7 +
 drivers/iio/imu/smi240/smi240.h      |  35 +++
 drivers/iio/imu/smi240/smi240_core.c | 385 +++++++++++++++++++++++++++
 drivers/iio/imu/smi240/smi240_spi.c  | 172 ++++++++++++
 7 files changed, 613 insertions(+)
 create mode 100644 drivers/iio/imu/smi240/Kconfig
 create mode 100644 drivers/iio/imu/smi240/Makefile
 create mode 100644 drivers/iio/imu/smi240/smi240.h
 create mode 100644 drivers/iio/imu/smi240/smi240_core.c
 create mode 100644 drivers/iio/imu/smi240/smi240_spi.c

diff --git a/drivers/iio/imu/Kconfig b/drivers/iio/imu/Kconfig
index 52a155ff325..8808074513d 100644
--- a/drivers/iio/imu/Kconfig
+++ b/drivers/iio/imu/Kconfig
@@ -96,6 +96,7 @@ config KMX61
 
 source "drivers/iio/imu/inv_icm42600/Kconfig"
 source "drivers/iio/imu/inv_mpu6050/Kconfig"
+source "drivers/iio/imu/smi240/Kconfig"
 source "drivers/iio/imu/st_lsm6dsx/Kconfig"
 source "drivers/iio/imu/st_lsm9ds0/Kconfig"
 
diff --git a/drivers/iio/imu/Makefile b/drivers/iio/imu/Makefile
index 7e2d7d5c3b7..b6f162ae4ed 100644
--- a/drivers/iio/imu/Makefile
+++ b/drivers/iio/imu/Makefile
@@ -27,5 +27,6 @@ obj-y += inv_mpu6050/
 
 obj-$(CONFIG_KMX61) += kmx61.o
 
+obj-y += smi240/
 obj-y += st_lsm6dsx/
 obj-y += st_lsm9ds0/
diff --git a/drivers/iio/imu/smi240/Kconfig b/drivers/iio/imu/smi240/Kconfig
new file mode 100644
index 00000000000..b7f3598f6c4
--- /dev/null
+++ b/drivers/iio/imu/smi240/Kconfig
@@ -0,0 +1,12 @@
+config SMI240
+	tristate "Bosch Sensor SMI240 Inertial Measurement Unit"
+	depends on SPI
+	select REGMAP_SPI
+	select IIO_BUFFER
+	select IIO_TRIGGERED_BUFFER
+	help
+	  If you say yes here you get support for SMI240 IMU on SPI with
+	  accelerometer and gyroscope.
+
+	  This driver can also be built as a module. If so, the module will be
+	  called smi240.
diff --git a/drivers/iio/imu/smi240/Makefile b/drivers/iio/imu/smi240/Makefile
new file mode 100644
index 00000000000..0e5f7db7d78
--- /dev/null
+++ b/drivers/iio/imu/smi240/Makefile
@@ -0,0 +1,7 @@
+# SPDX-License-Identifier: BSD-3-Clause OR GPL-2.0
+#
+# Makefile for Bosch SMI240
+#
+obj-$(CONFIG_SMI240) += smi240.o
+smi240-objs := smi240_core.o
+smi240-objs += smi240_spi.o
diff --git a/drivers/iio/imu/smi240/smi240.h b/drivers/iio/imu/smi240/smi240.h
new file mode 100644
index 00000000000..b1690793f9b
--- /dev/null
+++ b/drivers/iio/imu/smi240/smi240.h
@@ -0,0 +1,35 @@
+/* SPDX-License-Identifier: BSD-3-Clause OR GPL-2.0 */
+/*
+ * Copyright (c) 2024 Robert Bosch GmbH.
+ */
+#ifndef _SMI240_H
+#define _SMI240_H
+
+#include <linux/iio/iio.h>
+
+struct regmap;
+struct device;
+
+enum capture_mode { SMI240_CAPTURE_OFF = 0, SMI240_CAPTURE_ON = 1 };
+
+struct smi240_data {
+	struct regmap *regmap;
+	u16 accel_filter_freq;
+	u16 anglvel_filter_freq;
+	u8 bite_reps;
+	enum capture_mode capture;
+	/*
+	 * Ensure natural alignment for timestamp if present.
+	 * Channel size: 2 bytes.
+	 * Max length needed: 2 * 3 channels + temp channel + 2 bytes padding + 8 byte ts.
+	 * If fewer channels are enabled, less space may be needed, as
+	 * long as the timestamp is still aligned to 8 bytes.
+	 */
+	s16 buf[12] __aligned(8);
+
+	__be32 spi_buf __aligned(IIO_DMA_MINALIGN);
+};
+
+int smi240_core_probe(struct device *dev, struct regmap *regmap);
+
+#endif /* _SMI240_H */
diff --git a/drivers/iio/imu/smi240/smi240_core.c b/drivers/iio/imu/smi240/smi240_core.c
new file mode 100644
index 00000000000..fc0226af843
--- /dev/null
+++ b/drivers/iio/imu/smi240/smi240_core.c
@@ -0,0 +1,385 @@
+// SPDX-License-Identifier: BSD-3-Clause OR GPL-2.0
+/*
+ * Copyright (c) 2024 Robert Bosch GmbH.
+ */
+#include <linux/device.h>
+#include <linux/regmap.h>
+#include <linux/delay.h>
+#include <linux/bits.h>
+#include <linux/bitfield.h>
+#include <linux/iio/iio.h>
+#include <linux/iio/triggered_buffer.h>
+#include <linux/iio/trigger_consumer.h>
+#include <linux/iio/buffer.h>
+#include <linux/iio/trigger.h>
+
+#include "smi240.h"
+
+enum {
+	SMI240_TEMP_OBJECT,
+	SMI240_SCAN_ACCEL_X,
+	SMI240_SCAN_ACCEL_Y,
+	SMI240_SCAN_ACCEL_Z,
+	SMI240_SCAN_GYRO_X,
+	SMI240_SCAN_GYRO_Y,
+	SMI240_SCAN_GYRO_Z,
+	SMI240_SCAN_TIMESTAMP,
+};
+
+#define SMI240_CHIP_ID 0x0024
+
+#define SMI240_SOFT_CONFIG_EOC_MASK BIT_MASK(0)
+#define SMI240_SOFT_CONFIG_GYR_BW_MASK BIT_MASK(1)
+#define SMI240_SOFT_CONFIG_ACC_BW_MASK BIT_MASK(2)
+#define SMI240_SOFT_CONFIG_BITE_AUTO_MASK BIT_MASK(3)
+#define SMI240_SOFT_CONFIG_BITE_REP_MASK GENMASK(6, 4)
+
+#define SMI240_CHIP_ID_REG 0x00
+#define SMI240_SOFT_CONFIG_REG 0x0A
+#define SMI240_TEMP_CUR_REG 0x10
+#define SMI240_ACCEL_X_CUR_REG 0x11
+#define SMI240_GYRO_X_CUR_REG 0x14
+#define SMI240_DATA_CAP_FIRST_REG 0x17
+#define SMI240_CMD_REG 0x2F
+
+#define SMI240_SOFT_RESET_CMD 0xB6
+
+#define SMI240_BITE_SEQUENCE_DELAY_US 140000
+#define SMI240_FILTER_FLUSH_DELAY_US 60000
+#define SMI240_DIGITAL_STARTUP_DELAY_US 120000
+#define SMI240_MECH_STARTUP_DELAY_US 100000
+
+#define SMI240_LOW_BANDWIDTH_HZ 50
+#define SMI240_HIGH_BANDWIDTH_HZ 400
+
+#define SMI240_DATA_CHANNEL(_type, _axis, _index)              \
+	{                                                          \
+		.type = _type,                                         \
+		.modified = 1,                                         \
+		.channel2 = IIO_MOD_##_axis,                           \
+		.info_mask_separate = BIT(IIO_CHAN_INFO_RAW),          \
+		.info_mask_shared_by_type =                            \
+			BIT(IIO_CHAN_INFO_LOW_PASS_FILTER_3DB_FREQUENCY),  \
+		.info_mask_shared_by_type_available =                  \
+			BIT(IIO_CHAN_INFO_LOW_PASS_FILTER_3DB_FREQUENCY),  \
+		.scan_index = _index,                                  \
+		.scan_type = {                                         \
+			.sign = 's',                                       \
+			.realbits = 16,                                    \
+			.storagebits = 16,                                 \
+			.endianness = IIO_LE,                              \
+		},                                                     \
+	}
+
+#define SMI240_TEMP_CHANNEL(_index)                            \
+	{                                                          \
+		.type = IIO_TEMP,                                      \
+		.modified = 1,                                         \
+		.channel2 = IIO_MOD_TEMP_OBJECT,                       \
+		.info_mask_separate = BIT(IIO_CHAN_INFO_RAW) |         \
+				      BIT(IIO_CHAN_INFO_OFFSET) |              \
+				      BIT(IIO_CHAN_INFO_SCALE),                \
+		.scan_index = _index,                                  \
+		.scan_type = {                                         \
+			.sign = 's',                                       \
+			.realbits = 16,                                    \
+			.storagebits = 16,                                 \
+			.endianness = IIO_LE,                              \
+		},                                                     \
+	}
+
+static const struct iio_chan_spec smi240_channels[] = {
+	SMI240_TEMP_CHANNEL(SMI240_TEMP_OBJECT),
+	SMI240_DATA_CHANNEL(IIO_ACCEL, X, SMI240_SCAN_ACCEL_X),
+	SMI240_DATA_CHANNEL(IIO_ACCEL, Y, SMI240_SCAN_ACCEL_Y),
+	SMI240_DATA_CHANNEL(IIO_ACCEL, Z, SMI240_SCAN_ACCEL_Z),
+	SMI240_DATA_CHANNEL(IIO_ANGL_VEL, X, SMI240_SCAN_GYRO_X),
+	SMI240_DATA_CHANNEL(IIO_ANGL_VEL, Y, SMI240_SCAN_GYRO_Y),
+	SMI240_DATA_CHANNEL(IIO_ANGL_VEL, Z, SMI240_SCAN_GYRO_Z),
+	IIO_CHAN_SOFT_TIMESTAMP(SMI240_SCAN_TIMESTAMP),
+};
+
+static const int smi240_low_pass_freqs[] = { SMI240_LOW_BANDWIDTH_HZ,
+					     SMI240_HIGH_BANDWIDTH_HZ };
+
+static int smi240_soft_reset(struct smi240_data *data)
+{
+	int ret;
+
+	ret = regmap_write(data->regmap, SMI240_CMD_REG, SMI240_SOFT_RESET_CMD);
+	if (ret)
+		return ret;
+	fsleep(SMI240_DIGITAL_STARTUP_DELAY_US);
+
+	return 0;
+}
+
+static int smi240_soft_config(struct smi240_data *data)
+{
+	int ret;
+	u8 acc_bw, gyr_bw;
+	u16 request;
+
+	switch (data->accel_filter_freq) {
+	case SMI240_LOW_BANDWIDTH_HZ:
+		acc_bw = 0x1;
+		break;
+	case SMI240_HIGH_BANDWIDTH_HZ:
+		acc_bw = 0x0;
+		break;
+	default:
+		return -EINVAL;
+	}
+
+	switch (data->anglvel_filter_freq) {
+	case SMI240_LOW_BANDWIDTH_HZ:
+		gyr_bw = 0x1;
+		break;
+	case SMI240_HIGH_BANDWIDTH_HZ:
+		gyr_bw = 0x0;
+		break;
+	default:
+		return -EINVAL;
+	}
+
+	request = FIELD_PREP(SMI240_SOFT_CONFIG_EOC_MASK, 1);
+	request |= FIELD_PREP(SMI240_SOFT_CONFIG_GYR_BW_MASK, gyr_bw);
+	request |= FIELD_PREP(SMI240_SOFT_CONFIG_ACC_BW_MASK, acc_bw);
+	request |= FIELD_PREP(SMI240_SOFT_CONFIG_BITE_AUTO_MASK, 1);
+	request |= FIELD_PREP(SMI240_SOFT_CONFIG_BITE_REP_MASK,
+			      data->bite_reps - 1);
+
+	ret = regmap_write(data->regmap, SMI240_SOFT_CONFIG_REG, request);
+	if (ret)
+		return ret;
+
+	fsleep(SMI240_MECH_STARTUP_DELAY_US +
+	       data->bite_reps * SMI240_BITE_SEQUENCE_DELAY_US +
+	       SMI240_FILTER_FLUSH_DELAY_US);
+
+	return 0;
+}
+
+static int smi240_get_low_pass_filter_freq(struct smi240_data *data,
+					   int chan_type, int *val)
+{
+	switch (chan_type) {
+	case IIO_ACCEL:
+		*val = data->accel_filter_freq;
+		return 0;
+	case IIO_ANGL_VEL:
+		*val = data->anglvel_filter_freq;
+		return 0;
+	default:
+		return -EINVAL;
+	}
+}
+
+static int smi240_get_data(struct smi240_data *data, int chan_type, int axis,
+			   int *val)
+{
+	u8 reg;
+	int ret, sample;
+
+	if (chan_type == IIO_TEMP)
+		reg = SMI240_TEMP_CUR_REG;
+	else if (chan_type == IIO_ACCEL)
+		reg = SMI240_ACCEL_X_CUR_REG + (axis - IIO_MOD_X);
+	else if (chan_type == IIO_ANGL_VEL)
+		reg = SMI240_GYRO_X_CUR_REG + (axis - IIO_MOD_X);
+	else
+		return -EINVAL;
+
+	ret = regmap_read(data->regmap, reg, &sample);
+	if (ret)
+		return ret;
+
+	*val = sign_extend32(sample, 15);
+
+	return 0;
+}
+
+static irqreturn_t smi240_trigger_handler(int irq, void *p)
+{
+	struct iio_poll_func *pf = p;
+	struct iio_dev *indio_dev = pf->indio_dev;
+	struct smi240_data *data = iio_priv(indio_dev);
+	int ret, chan, i = 0;
+
+	data->capture = SMI240_CAPTURE_ON;
+
+	for_each_set_bit(chan, indio_dev->active_scan_mask,
+			 indio_dev->masklength) {
+		ret = regmap_read(data->regmap,
+				  SMI240_DATA_CAP_FIRST_REG + chan,
+				  (int *)&data->buf[i]);
+		data->capture = SMI240_CAPTURE_OFF;
+		if (ret)
+			goto out;
+		i++;
+	}
+
+	iio_push_to_buffers_with_timestamp(indio_dev, data->buf, pf->timestamp);
+
+out:
+	iio_trigger_notify_done(indio_dev->trig);
+	return IRQ_HANDLED;
+}
+
+static int smi240_read_avail(struct iio_dev *indio_dev,
+			     struct iio_chan_spec const *chan, const int **vals,
+			     int *type, int *length, long mask)
+{
+	switch (mask) {
+	case IIO_CHAN_INFO_LOW_PASS_FILTER_3DB_FREQUENCY:
+		*vals = smi240_low_pass_freqs;
+		*length = ARRAY_SIZE(smi240_low_pass_freqs);
+		*type = IIO_VAL_INT;
+		return IIO_AVAIL_LIST;
+	default:
+		return -EINVAL;
+	}
+}
+
+static int smi240_read_raw(struct iio_dev *indio_dev,
+			   struct iio_chan_spec const *chan, int *val,
+			   int *val2, long mask)
+{
+	int ret;
+	struct smi240_data *data = iio_priv(indio_dev);
+
+	switch (mask) {
+	case IIO_CHAN_INFO_RAW:
+		if (iio_buffer_enabled(indio_dev))
+			return -EBUSY;
+		ret = smi240_get_data(data, chan->type, chan->channel2, val);
+		if (ret)
+			return ret;
+		return IIO_VAL_INT;
+
+	case IIO_CHAN_INFO_LOW_PASS_FILTER_3DB_FREQUENCY:
+		ret = smi240_get_low_pass_filter_freq(data, chan->type, val);
+		if (ret)
+			return ret;
+		return IIO_VAL_INT;
+
+	/*
+	 * T°C = (temp / 256) + 25
+	 * Tm°C = 1000 * ((temp * 100 / 25600) + 25)
+	 * scale: 100000 / 25600 = 3.906250
+	 * offset: 25000
+	 */
+	case IIO_CHAN_INFO_SCALE:
+		*val = 3;
+		*val2 = 906250;
+		return IIO_VAL_INT_PLUS_MICRO;
+	case IIO_CHAN_INFO_OFFSET:
+		*val = 25000;
+		return IIO_VAL_INT;
+
+	default:
+		return -EINVAL;
+	}
+}
+
+static int smi240_write_raw(struct iio_dev *indio_dev,
+			    struct iio_chan_spec const *chan, int val, int val2,
+			    long mask)
+{
+	int ret, i;
+	struct smi240_data *data = iio_priv(indio_dev);
+
+	switch (mask) {
+	case IIO_CHAN_INFO_LOW_PASS_FILTER_3DB_FREQUENCY:
+		for (i = 0; i < ARRAY_SIZE(smi240_low_pass_freqs); i++) {
+			if (val == smi240_low_pass_freqs[i])
+				break;
+		}
+
+		if (i == ARRAY_SIZE(smi240_low_pass_freqs))
+			return -EINVAL;
+
+		switch (chan->type) {
+		case IIO_ACCEL:
+			data->accel_filter_freq = val;
+			break;
+		case IIO_ANGL_VEL:
+			data->anglvel_filter_freq = val;
+			break;
+		default:
+			return -EINVAL;
+		}
+		break;
+	default:
+		return -EINVAL;
+	}
+
+	/* Write access to soft config is locked until hard/soft reset */
+	ret = smi240_soft_reset(data);
+	if (ret)
+		return ret;
+
+	return smi240_soft_config(data);
+}
+
+static int smi240_init(struct smi240_data *data)
+{
+	data->accel_filter_freq = SMI240_HIGH_BANDWIDTH_HZ;
+	data->anglvel_filter_freq = SMI240_HIGH_BANDWIDTH_HZ;
+	data->bite_reps = 3;
+
+	return smi240_soft_config(data);
+}
+
+static const struct iio_info smi240_info = {
+	.read_avail = smi240_read_avail,
+	.read_raw = smi240_read_raw,
+	.write_raw = smi240_write_raw,
+};
+
+int smi240_core_probe(struct device *dev, struct regmap *regmap)
+{
+	struct iio_dev *indio_dev;
+	struct smi240_data *data;
+	int ret, response;
+
+	indio_dev = devm_iio_device_alloc(dev, sizeof(*data));
+	if (!indio_dev)
+		return -ENOMEM;
+
+	data = iio_priv(indio_dev);
+	dev_set_drvdata(dev, indio_dev);
+	data->regmap = regmap;
+	data->capture = SMI240_CAPTURE_OFF;
+
+	ret = regmap_read(data->regmap, SMI240_CHIP_ID_REG, &response);
+	if (ret)
+		return dev_err_probe(dev, ret, "Read chip id failed\n");
+
+	if (response != SMI240_CHIP_ID)
+		dev_info(dev, "Unknown chip id: 0x%04x\n", response);
+
+	ret = smi240_init(data);
+	if (ret)
+		return dev_err_probe(dev, ret,
+				     "Device initialization failed\n");
+
+	indio_dev->channels = smi240_channels;
+	indio_dev->num_channels = ARRAY_SIZE(smi240_channels);
+	indio_dev->name = "smi240";
+	indio_dev->modes = INDIO_DIRECT_MODE;
+	indio_dev->info = &smi240_info;
+
+	ret = devm_iio_triggered_buffer_setup(dev, indio_dev,
+					      iio_pollfunc_store_time,
+					      smi240_trigger_handler, NULL);
+	if (ret)
+		return dev_err_probe(dev, ret,
+				     "Setup triggered buffer failed\n");
+
+	ret = devm_iio_device_register(dev, indio_dev);
+	if (ret)
+		return dev_err_probe(dev, ret, "Register IIO device failed\n");
+
+	return 0;
+}
diff --git a/drivers/iio/imu/smi240/smi240_spi.c b/drivers/iio/imu/smi240/smi240_spi.c
new file mode 100644
index 00000000000..d308f6407da
--- /dev/null
+++ b/drivers/iio/imu/smi240/smi240_spi.c
@@ -0,0 +1,172 @@
+// SPDX-License-Identifier: BSD-3-Clause OR GPL-2.0
+/*
+ * Copyright (c) 2024 Robert Bosch GmbH.
+ */
+#include <linux/module.h>
+#include <linux/of.h>
+#include <linux/device.h>
+#include <linux/regmap.h>
+#include <linux/spi/spi.h>
+#include <linux/bitfield.h>
+#include <linux/iio/iio.h>
+#include <asm/unaligned.h>
+
+#include "smi240.h"
+
+#define SMI240_CRC_INIT 0x05
+#define SMI240_CRC_POLY 0x0B
+#define SMI240_BUS_ID 0x00
+
+#define SMI240_SD_BIT_MASK 0x80000000
+#define SMI240_CS_BIT_MASK 0x00000008
+
+#define SMI240_WRITE_ADDR_MASK GENMASK(29, 22)
+#define SMI240_WRITE_BIT_MASK 0x00200000
+#define SMI240_WRITE_DATA_MASK GENMASK(18, 3)
+#define SMI240_CAP_BIT_MASK 0x00100000
+#define SMI240_READ_DATA_MASK GENMASK(19, 4)
+
+static u8 smi240_crc3(u32 data, u8 init, u8 poly)
+{
+	u8 crc = init;
+	u8 do_xor;
+	s8 i = 31;
+
+	do {
+		do_xor = crc & 0x04;
+		crc <<= 1;
+		crc |= 0x01 & (data >> i);
+		if (do_xor)
+			crc ^= poly;
+
+		crc &= 0x07;
+	} while (--i >= 0);
+
+	return crc;
+}
+
+static bool smi240_sensor_data_is_valid(u32 data)
+{
+	if (smi240_crc3(data, SMI240_CRC_INIT, SMI240_CRC_POLY) != 0)
+		return false;
+
+	if (FIELD_GET(SMI240_SD_BIT_MASK, data) &
+	    FIELD_GET(SMI240_CS_BIT_MASK, data))
+		return false;
+
+	return true;
+}
+
+static int smi240_regmap_spi_read(void *context, const void *reg_buf,
+				  size_t reg_size, void *val_buf,
+				  size_t val_size)
+{
+	int ret;
+	u32 request, response;
+	struct spi_device *spi = context;
+	struct iio_dev *indio_dev = dev_get_drvdata(&spi->dev);
+	struct smi240_data *iio_priv_data = iio_priv(indio_dev);
+
+	request = SMI240_BUS_ID << 30;
+	request |= FIELD_PREP(SMI240_CAP_BIT_MASK, iio_priv_data->capture);
+	request |= FIELD_PREP(SMI240_WRITE_ADDR_MASK, *(u8 *)reg_buf);
+	request |= smi240_crc3(request, SMI240_CRC_INIT, SMI240_CRC_POLY);
+
+	iio_priv_data->spi_buf = cpu_to_be32(request);
+
+	/*
+	 * SMI240 module consists of a 32Bit Out Of Frame (OOF)
+	 * SPI protocol, where the slave interface responds to
+	 * the Master request in the next frame.
+	 * CS signal must toggle (> 700 ns) between the frames.
+	 */
+	ret = spi_write(spi, &iio_priv_data->spi_buf, sizeof(request));
+	if (ret)
+		return ret;
+
+	ret = spi_read(spi, &iio_priv_data->spi_buf, sizeof(response));
+	if (ret)
+		return ret;
+
+	response = be32_to_cpu(iio_priv_data->spi_buf);
+
+	if (!smi240_sensor_data_is_valid(response))
+		return -EIO;
+
+	response = FIELD_GET(SMI240_READ_DATA_MASK, response);
+	memcpy(val_buf, &response, val_size);
+
+	return 0;
+}
+
+static int smi240_regmap_spi_write(void *context, const void *data,
+				   size_t count)
+{
+	u32 request;
+	struct spi_device *spi = context;
+	struct iio_dev *indio_dev = dev_get_drvdata(&spi->dev);
+	struct smi240_data *iio_priv_data = iio_priv(indio_dev);
+	u8 reg_addr = ((u8 *)data)[0];
+	u16 reg_data = get_unaligned_le16(&((u8 *)data)[1]);
+
+	request = SMI240_BUS_ID << 30;
+	request |= FIELD_PREP(SMI240_WRITE_BIT_MASK, 1);
+	request |= FIELD_PREP(SMI240_WRITE_ADDR_MASK, reg_addr);
+	request |= FIELD_PREP(SMI240_WRITE_DATA_MASK, reg_data);
+	request |= smi240_crc3(request, SMI240_CRC_INIT, SMI240_CRC_POLY);
+
+	iio_priv_data->spi_buf = cpu_to_be32(request);
+
+	return spi_write(spi, &iio_priv_data->spi_buf, sizeof(request));
+}
+
+static const struct regmap_bus smi240_regmap_bus = {
+	.read = smi240_regmap_spi_read,
+	.write = smi240_regmap_spi_write,
+};
+
+static const struct regmap_config smi240_regmap_config = {
+	.reg_bits = 8,
+	.val_bits = 16,
+	.val_format_endian = REGMAP_ENDIAN_LITTLE,
+};
+
+static int smi240_spi_probe(struct spi_device *spi)
+{
+	struct regmap *regmap;
+
+	regmap = devm_regmap_init(&spi->dev, &smi240_regmap_bus, &spi->dev,
+				  &smi240_regmap_config);
+	if (IS_ERR(regmap))
+		return dev_err_probe(&spi->dev, PTR_ERR(regmap),
+				     "Failed to initialize SPI Regmap\n");
+
+	return smi240_core_probe(&spi->dev, regmap);
+}
+
+static const struct spi_device_id smi240_spi_id[] = {
+	{ "smi240", 0 },
+	{ }
+};
+MODULE_DEVICE_TABLE(spi, smi240_spi_id);
+
+static const struct of_device_id smi240_of_match[] = {
+	{ .compatible = "bosch,smi240" },
+	{ }
+};
+MODULE_DEVICE_TABLE(of, smi240_of_match);
+
+static struct spi_driver smi240_spi_driver = {
+	.probe = smi240_spi_probe,
+	.id_table = smi240_spi_id,
+	.driver = {
+		.of_match_table = smi240_of_match,
+		.name = "smi240",
+	},
+};
+module_spi_driver(smi240_spi_driver);
+
+MODULE_AUTHOR("Markus Lochmann <markus.lochmann@de.bosch.com>");
+MODULE_AUTHOR("Stefan Gutmann <stefan.gutmann@de.bosch.com>");
+MODULE_DESCRIPTION("Bosch SMI240 SPI driver");
+MODULE_LICENSE("Dual BSD/GPL");
-- 
2.34.1


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

* Re: [PATCH v4 1/2] dt-bindings: iio: imu: smi240: devicetree binding
  2024-08-26 14:05 ` [PATCH v4 1/2] dt-bindings: iio: imu: smi240: devicetree binding Jianping.Shen
@ 2024-08-26 14:53   ` Krzysztof Kozlowski
  0 siblings, 0 replies; 6+ messages in thread
From: Krzysztof Kozlowski @ 2024-08-26 14:53 UTC (permalink / raw)
  To: Jianping.Shen, jic23, lars, robh, krzk+dt, conor+dt, dima.fedrau,
	marcelo.schmitt1, linux-iio, devicetree, linux-kernel,
	Christian.Lorenz3, Ulrike.Frauendorf, Kai.Dolde

On 26/08/2024 16:05, Jianping.Shen@de.bosch.com wrote:
> From: Shen Jianping <Jianping.Shen@de.bosch.com>
> 
> This patch adds devicetree binding for Bosch imu smi240.

Please do not use "This commit/patch/change", but imperative mood. See
longer explanation here:
https://elixir.bootlin.com/linux/v5.17.1/source/Documentation/process/submitting-patches.rst#L95

A nit, subject: drop second/last, redundant "devicetree bindings". The
"dt-bindings" prefix is already stating that these are bindings.
See also:
https://elixir.bootlin.com/linux/v6.7-rc8/source/Documentation/devicetree/bindings/submitting-patches.rst#L18
Instead: "add Bosch FULL NAME OF THE DEVICE"


> The smi240 is a combined three axis angular rate and
> three axis acceleration sensor module.
> 
> * The smi240 requires VDD and VDDIO 
> * Provides only spi interface.
> * Does not support interrupt.

I don't understand why you mention above. It does not support interrupt,
just like it does not support AXI bus, 500 GPIOs etc. It suggests you
speak about driver, not hardware.

Just describe what this device is - like first sentence.

With some improvements here:

Reviewed-by: Krzysztof Kozlowski <krzysztof.kozlowski@linaro.org>


---

<form letter>
This is an automated instruction, just in case, because many review tags
are being ignored. If you know the process, you can skip it (please do
not feel offended by me posting it here - no bad intentions intended).
If you do not know the process, here is a short explanation:

Please add Acked-by/Reviewed-by/Tested-by tags when posting new
versions, under or above your Signed-off-by tag. Tag is "received", when
provided in a message replied to you on the mailing list. Tools like b4
can help here. However, there's no need to repost patches *only* to add
the tags. The upstream maintainer will do that for tags received on the
version they apply.

https://elixir.bootlin.com/linux/v6.5-rc3/source/Documentation/process/submitting-patches.rst#L577
</form letter>

Best regards,
Krzysztof


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

* Re: [PATCH v4 2/2] iio: imu: smi240: imu driver
  2024-08-26 14:05 ` [PATCH v4 2/2] iio: imu: smi240: imu driver Jianping.Shen
@ 2024-08-26 14:57   ` Krzysztof Kozlowski
  2024-08-28 13:43   ` Jonathan Cameron
  1 sibling, 0 replies; 6+ messages in thread
From: Krzysztof Kozlowski @ 2024-08-26 14:57 UTC (permalink / raw)
  To: Jianping.Shen, jic23, lars, robh, krzk+dt, conor+dt, dima.fedrau,
	marcelo.schmitt1, linux-iio, devicetree, linux-kernel,
	Christian.Lorenz3, Ulrike.Frauendorf, Kai.Dolde

On 26/08/2024 16:05, Jianping.Shen@de.bosch.com wrote:
> From: Shen Jianping <Jianping.Shen@de.bosch.com>
> 
> This patch adds the iio driver for bosch imu smi240. The smi240
> is a combined three axis angular rate and three axis acceleration
> sensor module with a measurement range of +/-300°/s and up to 16g.
> Smi240 does not support interrupt. A synchronous acc and gyro
> sampling can be triggered by setting the capture bit in spi read
> command.
> 
> Implemented features:
> * raw data access for each axis through sysfs
> * tiggered buffer for continuous sampling
> * synchronous acc and gyro data from tiggered buffer
> 

...

> +
> +static int smi240_spi_probe(struct spi_device *spi)
> +{
> +	struct regmap *regmap;
> +
> +	regmap = devm_regmap_init(&spi->dev, &smi240_regmap_bus, &spi->dev,
> +				  &smi240_regmap_config);
> +	if (IS_ERR(regmap))
> +		return dev_err_probe(&spi->dev, PTR_ERR(regmap),
> +				     "Failed to initialize SPI Regmap\n");
> +
> +	return smi240_core_probe(&spi->dev, regmap);

If the device supports only SPI (according to first patch description),
this entire split between core-spi does not make any sense. Just merge
these files.

Best regards,
Krzysztof


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

* Re: [PATCH v4 2/2] iio: imu: smi240: imu driver
  2024-08-26 14:05 ` [PATCH v4 2/2] iio: imu: smi240: imu driver Jianping.Shen
  2024-08-26 14:57   ` Krzysztof Kozlowski
@ 2024-08-28 13:43   ` Jonathan Cameron
  1 sibling, 0 replies; 6+ messages in thread
From: Jonathan Cameron @ 2024-08-28 13:43 UTC (permalink / raw)
  To: Jianping.Shen
  Cc: jic23, lars, robh, krzk+dt, conor+dt, dima.fedrau,
	marcelo.schmitt1, linux-iio, devicetree, linux-kernel,
	Christian.Lorenz3, Ulrike.Frauendorf, Kai.Dolde

On Mon, 26 Aug 2024 16:05:45 +0200
<Jianping.Shen@de.bosch.com> wrote:

> From: Shen Jianping <Jianping.Shen@de.bosch.com>
> 
> This patch adds the iio driver for bosch imu smi240. The smi240
> is a combined three axis angular rate and three axis acceleration
> sensor module with a measurement range of +/-300°/s and up to 16g.
> Smi240 does not support interrupt. A synchronous acc and gyro
> sampling can be triggered by setting the capture bit in spi read
> command.
> 
> Implemented features:
> * raw data access for each axis through sysfs
> * tiggered buffer for continuous sampling
> * synchronous acc and gyro data from tiggered buffer
> 
> Signed-off-by: Shen Jianping <Jianping.Shen@de.bosch.com>
As per the other review, I'd really prefer this as one simple file.
I know you want to keep it looking like other IMUs, but it is a much
simpler devices, so the complexity they need is not appropriate here.

A few things inline,

Jonathan

> diff --git a/drivers/iio/imu/smi240/smi240_core.c b/drivers/iio/imu/smi240/smi240_core.c
> new file mode 100644
> index 00000000000..fc0226af843
> --- /dev/null
> +++ b/drivers/iio/imu/smi240/smi240_core.c
> @@ -0,0 +1,385 @@
...

> +#define SMI240_DATA_CHANNEL(_type, _axis, _index)              \
> +	{                                                          \
> +		.type = _type,                                         \
> +		.modified = 1,                                         \
> +		.channel2 = IIO_MOD_##_axis,                           \
> +		.info_mask_separate = BIT(IIO_CHAN_INFO_RAW),          \

No scaling?  I'd expect the offset + scale for an accelerometer or gyro
channel to be well defined in the datasheet.


> +		.info_mask_shared_by_type =                            \
> +			BIT(IIO_CHAN_INFO_LOW_PASS_FILTER_3DB_FREQUENCY),  \
> +		.info_mask_shared_by_type_available =                  \
> +			BIT(IIO_CHAN_INFO_LOW_PASS_FILTER_3DB_FREQUENCY),  \


> diff --git a/drivers/iio/imu/smi240/smi240_spi.c b/drivers/iio/imu/smi240/smi240_spi.c
> new file mode 100644
> index 00000000000..d308f6407da
> --- /dev/null
> +++ b/drivers/iio/imu/smi240/smi240_spi.c
> @@ -0,0 +1,172 @@
> +// SPDX-License-Identifier: BSD-3-Clause OR GPL-2.0
> +/*
> + * Copyright (c) 2024 Robert Bosch GmbH.
> + */
> +#include <linux/module.h>
> +#include <linux/of.h>
> +#include <linux/device.h>
> +#include <linux/regmap.h>
> +#include <linux/spi/spi.h>
> +#include <linux/bitfield.h>
> +#include <linux/iio/iio.h>
> +#include <asm/unaligned.h>

Alphabetical order preferred.


> +static int smi240_regmap_spi_read(void *context, const void *reg_buf,
> +				  size_t reg_size, void *val_buf,
> +				  size_t val_size)
> +{
> +	int ret;
> +	u32 request, response;
> +	struct spi_device *spi = context;
> +	struct iio_dev *indio_dev = dev_get_drvdata(&spi->dev);
> +	struct smi240_data *iio_priv_data = iio_priv(indio_dev);
> +
> +	request = SMI240_BUS_ID << 30;
FIELD_PREP for this field as well (and define the mask etc).

> +	request |= FIELD_PREP(SMI240_CAP_BIT_MASK, iio_priv_data->capture);
> +	request |= FIELD_PREP(SMI240_WRITE_ADDR_MASK, *(u8 *)reg_buf);
> +	request |= smi240_crc3(request, SMI240_CRC_INIT, SMI240_CRC_POLY);
> +
> +	iio_priv_data->spi_buf = cpu_to_be32(request);
> +
> +	/*
> +	 * SMI240 module consists of a 32Bit Out Of Frame (OOF)
> +	 * SPI protocol, where the slave interface responds to
> +	 * the Master request in the next frame.
> +	 * CS signal must toggle (> 700 ns) between the frames.
> +	 */
> +	ret = spi_write(spi, &iio_priv_data->spi_buf, sizeof(request));
> +	if (ret)
> +		return ret;
> +
> +	ret = spi_read(spi, &iio_priv_data->spi_buf, sizeof(response));
> +	if (ret)
> +		return ret;
> +
> +	response = be32_to_cpu(iio_priv_data->spi_buf);
> +
> +	if (!smi240_sensor_data_is_valid(response))
> +		return -EIO;
> +
> +	response = FIELD_GET(SMI240_READ_DATA_MASK, response);
> +	memcpy(val_buf, &response, val_size);
> +
> +	return 0;
> +}
> +
> +static int smi240_regmap_spi_write(void *context, const void *data,
> +				   size_t count)
> +{
> +	u32 request;
> +	struct spi_device *spi = context;
> +	struct iio_dev *indio_dev = dev_get_drvdata(&spi->dev);
> +	struct smi240_data *iio_priv_data = iio_priv(indio_dev);
> +	u8 reg_addr = ((u8 *)data)[0];
> +	u16 reg_data = get_unaligned_le16(&((u8 *)data)[1]);
> +
> +	request = SMI240_BUS_ID << 30;

FIELD_PREP() for this one as well with appropriate mask.

> +	request |= FIELD_PREP(SMI240_WRITE_BIT_MASK, 1);
> +	request |= FIELD_PREP(SMI240_WRITE_ADDR_MASK, reg_addr);
> +	request |= FIELD_PREP(SMI240_WRITE_DATA_MASK, reg_data);
> +	request |= smi240_crc3(request, SMI240_CRC_INIT, SMI240_CRC_POLY);
> +
> +	iio_priv_data->spi_buf = cpu_to_be32(request);
> +
> +	return spi_write(spi, &iio_priv_data->spi_buf, sizeof(request));
> +}


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

end of thread, other threads:[~2024-08-28 13:43 UTC | newest]

Thread overview: 6+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2024-08-26 14:05 [PATCH v4 0/2] iio: imu: smi240: add bosch smi240 driver Jianping.Shen
2024-08-26 14:05 ` [PATCH v4 1/2] dt-bindings: iio: imu: smi240: devicetree binding Jianping.Shen
2024-08-26 14:53   ` Krzysztof Kozlowski
2024-08-26 14:05 ` [PATCH v4 2/2] iio: imu: smi240: imu driver Jianping.Shen
2024-08-26 14:57   ` Krzysztof Kozlowski
2024-08-28 13:43   ` Jonathan Cameron

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