* [PATCH v7 0/2] iio: imu: smi240: add bosch smi240 driver
@ 2024-09-13 10:00 Jianping.Shen
2024-09-13 10:00 ` [PATCH v7 1/2] dt-bindings: iio: imu: smi240: add Bosch smi240 Jianping.Shen
` (2 more replies)
0 siblings, 3 replies; 13+ messages in thread
From: Jianping.Shen @ 2024-09-13 10:00 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>
Add 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. 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
v4 -> v5
- No changes
v5 -> v6
- Fix checkpatch findings
v6 -> v7
- 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
v4 -> v5
- Merge the implementation in one simple file
- Add channel info for acc/gyro data channel
- Fix other findings
v5 -> v6
- Fix checkpatch findings
- Fix review findings
v6 -> v7
- Fix offset and scale
Shen Jianping (2):
dt-bindings: iio: imu: smi240: add Bosch smi240
iio: imu: smi240: add driver
.../bindings/iio/imu/bosch,smi240.yaml | 51 ++
drivers/iio/imu/Kconfig | 14 +
drivers/iio/imu/Makefile | 2 +
drivers/iio/imu/smi240.c | 611 ++++++++++++++++++
4 files changed, 678 insertions(+)
create mode 100644 Documentation/devicetree/bindings/iio/imu/bosch,smi240.yaml
create mode 100644 drivers/iio/imu/smi240.c
--
2.34.1
^ permalink raw reply [flat|nested] 13+ messages in thread
* [PATCH v7 1/2] dt-bindings: iio: imu: smi240: add Bosch smi240
2024-09-13 10:00 [PATCH v7 0/2] iio: imu: smi240: add bosch smi240 driver Jianping.Shen
@ 2024-09-13 10:00 ` Jianping.Shen
2024-09-13 17:54 ` Conor Dooley
2024-09-13 10:00 ` [PATCH v7 2/2] iio: imu: smi240: add driver Jianping.Shen
2024-09-17 16:59 ` [PATCH v7 0/2] iio: imu: smi240: add bosch smi240 driver Krzysztof Kozlowski
2 siblings, 1 reply; 13+ messages in thread
From: Jianping.Shen @ 2024-09-13 10:00 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>
add 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.
Reviewed-by: Rob Herring (Arm) <robh@kernel.org>
Reviewed-by: Krzysztof Kozlowski <krzysztof.kozlowski@linaro.org>
Reviewed-by: Conor Dooley <conor.dooley@microchip.com>
Signed-off-by: Shen Jianping <Jianping.Shen@de.bosch.com>
---
.../bindings/iio/imu/bosch,smi240.yaml | 51 +++++++++++++++++++
1 file changed, 51 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..58f1411728f
--- /dev/null
+++ b/Documentation/devicetree/bindings/iio/imu/bosch,smi240.yaml
@@ -0,0 +1,51 @@
+# 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:
+ Inertial Measurement Unit with Accelerometer and Gyroscope
+ 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] 13+ messages in thread
* [PATCH v7 2/2] iio: imu: smi240: add driver
2024-09-13 10:00 [PATCH v7 0/2] iio: imu: smi240: add bosch smi240 driver Jianping.Shen
2024-09-13 10:00 ` [PATCH v7 1/2] dt-bindings: iio: imu: smi240: add Bosch smi240 Jianping.Shen
@ 2024-09-13 10:00 ` Jianping.Shen
2024-09-14 16:32 ` Jonathan Cameron
2024-09-17 16:59 ` [PATCH v7 0/2] iio: imu: smi240: add bosch smi240 driver Krzysztof Kozlowski
2 siblings, 1 reply; 13+ messages in thread
From: Jianping.Shen @ 2024-09-13 10:00 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>
add 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. 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 | 14 +
drivers/iio/imu/Makefile | 2 +
drivers/iio/imu/smi240.c | 611 +++++++++++++++++++++++++++++++++++++++
3 files changed, 627 insertions(+)
create mode 100644 drivers/iio/imu/smi240.c
diff --git a/drivers/iio/imu/Kconfig b/drivers/iio/imu/Kconfig
index 52a155ff325..59d7f3cf8f0 100644
--- a/drivers/iio/imu/Kconfig
+++ b/drivers/iio/imu/Kconfig
@@ -96,6 +96,20 @@ config KMX61
source "drivers/iio/imu/inv_icm42600/Kconfig"
source "drivers/iio/imu/inv_mpu6050/Kconfig"
+
+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.
+
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..ca9c4db7725 100644
--- a/drivers/iio/imu/Makefile
+++ b/drivers/iio/imu/Makefile
@@ -27,5 +27,7 @@ obj-y += inv_mpu6050/
obj-$(CONFIG_KMX61) += kmx61.o
+obj-$(CONFIG_SMI240) += smi240.o
+
obj-y += st_lsm6dsx/
obj-y += st_lsm9ds0/
diff --git a/drivers/iio/imu/smi240.c b/drivers/iio/imu/smi240.c
new file mode 100644
index 00000000000..892e14f3f60
--- /dev/null
+++ b/drivers/iio/imu/smi240.c
@@ -0,0 +1,611 @@
+// SPDX-License-Identifier: BSD-3-Clause OR GPL-2.0
+/*
+ * Copyright (c) 2024 Robert Bosch GmbH.
+ */
+#include <linux/iio/buffer.h>
+#include <linux/iio/iio.h>
+#include <linux/iio/trigger.h>
+#include <linux/iio/trigger_consumer.h>
+#include <linux/iio/triggered_buffer.h>
+
+#include <linux/bitfield.h>
+#include <linux/bits.h>
+#include <linux/delay.h>
+#include <linux/device.h>
+#include <linux/module.h>
+#include <linux/regmap.h>
+#include <linux/spi/spi.h>
+#include <linux/units.h>
+
+#include <asm/unaligned.h>
+
+#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_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_BUS_ID_MASK GENMASK(31, 30)
+#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)
+
+/* T°C = (temp / 256) + 25 */
+#define SMI240_TEMP_OFFSET 6400 // 25 * 256
+#define SMI240_TEMP_SCALE 3906250 // (1 / 256) * 1e9
+
+#define SMI240_ACCEL_SCALE 500 // (1 / 2000) * 1e6
+#define SMI240_GYRO_SCALE 10000 // (1 / 100) * 1e6
+
+#define SMI240_LOW_BANDWIDTH_HZ 50
+#define SMI240_HIGH_BANDWIDTH_HZ 400
+
+#define SMI240_BUILT_IN_SELF_TEST_COUNT 3
+
+#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_SCALE) | \
+ 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_CPU, \
+ }, \
+}
+
+#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_CPU, \
+ }, \
+}
+
+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 built_in_self_test_count;
+ 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);
+};
+
+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,
+};
+
+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 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;
+ u16 *val = val_buf;
+ 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 = FIELD_PREP(SMI240_BUS_ID_MASK, SMI240_BUS_ID);
+ 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;
+
+ *val = FIELD_GET(SMI240_READ_DATA_MASK, response);
+
+ return 0;
+}
+
+static int smi240_regmap_spi_write(void *context, const void *data,
+ size_t count)
+{
+ u8 reg_addr;
+ u16 reg_data;
+ 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);
+
+ if (count < 2)
+ return -EINVAL;
+
+ reg_addr = ((u8 *)data)[0];
+ reg_data = get_unaligned_le16(&((u8 *)data)[1]);
+
+ request = FIELD_PREP(SMI240_BUS_ID_MASK, SMI240_BUS_ID);
+ 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_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->built_in_self_test_count - 1);
+
+ ret = regmap_write(data->regmap, SMI240_SOFT_CONFIG_REG, request);
+ if (ret)
+ return ret;
+
+ fsleep(SMI240_MECH_STARTUP_DELAY_US +
+ data->built_in_self_test_count * 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;
+
+ switch (chan_type) {
+ case IIO_TEMP:
+ reg = SMI240_TEMP_CUR_REG;
+ break;
+ case IIO_ACCEL:
+ reg = SMI240_ACCEL_X_CUR_REG + (axis - IIO_MOD_X);
+ break;
+ case IIO_ANGL_VEL:
+ reg = SMI240_GYRO_X_CUR_REG + (axis - IIO_MOD_X);
+ break;
+ default:
+ 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 base = SMI240_DATA_CAP_FIRST_REG, i = 0;
+ int ret, chan, sample;
+
+ data->capture = SMI240_CAPTURE_ON;
+
+ iio_for_each_active_channel(indio_dev, chan) {
+ ret = regmap_read(data->regmap, base + chan, &sample);
+ data->capture = SMI240_CAPTURE_OFF;
+ if (ret)
+ goto out;
+ data->buf[i++] = sample;
+ }
+
+ 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:
+ ret = iio_device_claim_direct_mode(indio_dev);
+ if (ret)
+ return ret;
+ ret = smi240_get_data(data, chan->type, chan->channel2, val);
+ iio_device_release_direct_mode(indio_dev);
+ 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;
+
+ case IIO_CHAN_INFO_SCALE:
+ switch (chan->type) {
+ case IIO_TEMP:
+ *val = SMI240_TEMP_SCALE / GIGA;
+ *val2 = SMI240_TEMP_SCALE % GIGA;
+ return IIO_VAL_INT_PLUS_NANO;
+ case IIO_ACCEL:
+ *val = 0;
+ *val2 = SMI240_ACCEL_SCALE;
+ return IIO_VAL_INT_PLUS_MICRO;
+ case IIO_ANGL_VEL:
+ *val = 0;
+ *val2 = SMI240_GYRO_SCALE;
+ return IIO_VAL_INT_PLUS_MICRO;
+ default:
+ return -EINVAL;
+ }
+
+ case IIO_CHAN_INFO_OFFSET:
+ if (chan->type == IIO_TEMP) {
+ *val = SMI240_TEMP_OFFSET;
+ return IIO_VAL_INT;
+ } else {
+ return -EINVAL;
+ }
+
+ 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_write_raw_get_fmt(struct iio_dev *indio_dev,
+ struct iio_chan_spec const *chan, long info)
+{
+ switch (info) {
+ case IIO_CHAN_INFO_SCALE:
+ switch (chan->type) {
+ case IIO_TEMP:
+ return IIO_VAL_INT_PLUS_NANO;
+ default:
+ return IIO_VAL_INT_PLUS_MICRO;
+ }
+ default:
+ return IIO_VAL_INT_PLUS_MICRO;
+ }
+}
+
+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->built_in_self_test_count = SMI240_BUILT_IN_SELF_TEST_COUNT;
+
+ 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,
+ .write_raw_get_fmt = smi240_write_raw_get_fmt,
+};
+
+static int smi240_probe(struct spi_device *spi)
+{
+ struct device *dev = &spi->dev;
+ struct iio_dev *indio_dev;
+ struct regmap *regmap;
+ struct smi240_data *data;
+ int ret, response;
+
+ indio_dev = devm_iio_device_alloc(dev, sizeof(*data));
+ if (!indio_dev)
+ return -ENOMEM;
+
+ regmap = devm_regmap_init(dev, &smi240_regmap_bus, dev,
+ &smi240_regmap_config);
+ if (IS_ERR(regmap))
+ return dev_err_probe(dev, PTR_ERR(regmap),
+ "Failed to initialize SPI Regmap\n");
+
+ 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;
+}
+
+static const struct spi_device_id smi240_spi_id[] = {
+ { "smi240" },
+ { }
+};
+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_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] 13+ messages in thread
* Re: [PATCH v7 1/2] dt-bindings: iio: imu: smi240: add Bosch smi240
2024-09-13 10:00 ` [PATCH v7 1/2] dt-bindings: iio: imu: smi240: add Bosch smi240 Jianping.Shen
@ 2024-09-13 17:54 ` Conor Dooley
2024-09-17 16:58 ` Krzysztof Kozlowski
0 siblings, 1 reply; 13+ messages in thread
From: Conor Dooley @ 2024-09-13 17:54 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
[-- Attachment #1: Type: text/plain, Size: 578 bytes --]
On Fri, Sep 13, 2024 at 12:00:10PM +0200, Jianping.Shen@de.bosch.com wrote:
> From: Shen Jianping <Jianping.Shen@de.bosch.com>
>
> add 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.
>
> Reviewed-by: Rob Herring (Arm) <robh@kernel.org>
> Reviewed-by: Krzysztof Kozlowski <krzysztof.kozlowski@linaro.org>
> Reviewed-by: Conor Dooley <conor.dooley@microchip.com>
3 reviews? Doing well for yourself!
[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 228 bytes --]
^ permalink raw reply [flat|nested] 13+ messages in thread
* Re: [PATCH v7 2/2] iio: imu: smi240: add driver
2024-09-13 10:00 ` [PATCH v7 2/2] iio: imu: smi240: add driver Jianping.Shen
@ 2024-09-14 16:32 ` Jonathan Cameron
2024-09-16 20:32 ` Shen Jianping (ME-SE/EAD2)
0 siblings, 1 reply; 13+ messages in thread
From: Jonathan Cameron @ 2024-09-14 16:32 UTC (permalink / raw)
To: Jianping.Shen
Cc: lars, robh, krzk+dt, conor+dt, dima.fedrau, marcelo.schmitt1,
linux-iio, devicetree, linux-kernel, Christian.Lorenz3,
Ulrike.Frauendorf, Kai.Dolde
On Fri, 13 Sep 2024 12:00:11 +0200
<Jianping.Shen@de.bosch.com> wrote:
> From: Shen Jianping <Jianping.Shen@de.bosch.com>
>
> add 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. 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>
Hi Shen,
I suspect I led you astray. regmap core seems unlikely to feed us
little endian buffers on writes (they should be CPU endian I think)
so there should be memcpy() for that not a get_unaligned_le16()
A few other minor comments inline that I missed before.
I'd probably have just tidied those up whilst applying if it wasn't
for the above question.
Jonathan
> diff --git a/drivers/iio/imu/smi240.c b/drivers/iio/imu/smi240.c
> new file mode 100644
> index 00000000000..892e14f3f60
> --- /dev/null
> +++ b/drivers/iio/imu/smi240.c
> @@ -0,0 +1,611 @@
> +// SPDX-License-Identifier: BSD-3-Clause OR GPL-2.0
> +/*
> + * Copyright (c) 2024 Robert Bosch GmbH.
> + */
> +#include <linux/iio/buffer.h>
> +#include <linux/iio/iio.h>
> +#include <linux/iio/trigger.h>
> +#include <linux/iio/trigger_consumer.h>
> +#include <linux/iio/triggered_buffer.h>
Conventionally this goes..
> +
> +#include <linux/bitfield.h>
> +#include <linux/bits.h>
> +#include <linux/delay.h>
> +#include <linux/device.h>
> +#include <linux/module.h>
> +#include <linux/regmap.h>
> +#include <linux/spi/spi.h>
> +#include <linux/units.h>
here.
> +
> +#include <asm/unaligned.h>
> +
> +#define SMI240_CHIP_ID 0x0024
> +
> +#define SMI240_SOFT_CONFIG_EOC_MASK BIT_MASK(0)
> +#define SMI240_SOFT_CONFIG_GYR_BW_MASK BIT_MASK(1)
BIT() only
You aren't applying these to a kernel bitmap which is an array
of unsigned longs (hence these macros have % BITS_PER_LONG
which makes no sense here).
> +#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_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
BIT() as mentioned below for these as well.
> +
> +#define SMI240_BUS_ID_MASK GENMASK(31, 30)
> +#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
BIT(20) ?
Same for other single bit masks.
> +#define SMI240_READ_DATA_MASK GENMASK(19, 4)
> +
> +/* T°C = (temp / 256) + 25 */
> +#define SMI240_TEMP_OFFSET 6400 // 25 * 256
> +#define SMI240_TEMP_SCALE 3906250 // (1 / 256) * 1e9
> +
> +#define SMI240_ACCEL_SCALE 500 // (1 / 2000) * 1e6
> +#define SMI240_GYRO_SCALE 10000 // (1 / 100) * 1e6
Even in this case, use traditional /* */ style comments.
> +
> +}
> +
> +static int smi240_regmap_spi_write(void *context, const void *data,
> + size_t count)
> +{
> + u8 reg_addr;
> + u16 reg_data;
> + 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);
> +
> + if (count < 2)
> + return -EINVAL;
> +
> + reg_addr = ((u8 *)data)[0];
> + reg_data = get_unaligned_le16(&((u8 *)data)[1]);
Why is the regmap core giving us an le16?
I probably sent you wrong way with this earlier :(
memcpy probably the correct choice here.
> +
> + request = FIELD_PREP(SMI240_BUS_ID_MASK, SMI240_BUS_ID);
> + 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] 13+ messages in thread
* RE: [PATCH v7 2/2] iio: imu: smi240: add driver
2024-09-14 16:32 ` Jonathan Cameron
@ 2024-09-16 20:32 ` Shen Jianping (ME-SE/EAD2)
2024-09-17 11:13 ` Jonathan Cameron
0 siblings, 1 reply; 13+ messages in thread
From: Shen Jianping (ME-SE/EAD2) @ 2024-09-16 20:32 UTC (permalink / raw)
To: Jonathan Cameron
Cc: lars@metafoo.de, robh@kernel.org, krzk+dt@kernel.org,
conor+dt@kernel.org, dima.fedrau@gmail.com,
marcelo.schmitt1@gmail.com, linux-iio@vger.kernel.org,
devicetree@vger.kernel.org, linux-kernel@vger.kernel.org,
Lorenz Christian (ME-SE/EAD2), Frauendorf Ulrike (ME/PJ-SW3),
Dolde Kai (ME-SE/PAE-A3)
>Hi Shen,
>
>I suspect I led you astray. regmap core seems unlikely to feed us little endian
>buffers on writes (they should be CPU endian I think) so there should be memcpy()
>for that not a get_unaligned_le16()
>
>> +
>> +static int smi240_regmap_spi_write(void *context, const void *data,
>> + size_t count)
>> +{
>> + u8 reg_addr;
>> + u16 reg_data;
>> + 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);
>> +
>> + if (count < 2)
>> + return -EINVAL;
>> +
>> + reg_addr = ((u8 *)data)[0];
>> + reg_data = get_unaligned_le16(&((u8 *)data)[1]);
>
>Why is the regmap core giving us an le16?
>I probably sent you wrong way with this earlier :( memcpy probably the correct
>choice here.
Yes, you are right. We shall use memcpy to keep the be CPU endian. Just using memcpy may be not enough.
Shall we also change regmap_config.val_format_endian from REGMAP_ENDIAN_LITTLE to REGMAP_ENDIAN_NATIVE ?
This is to make sure that regmap_write passes the reg-value to smi240_regmap_spi_write without changing the CPU endian.
^ permalink raw reply [flat|nested] 13+ messages in thread
* Re: [PATCH v7 2/2] iio: imu: smi240: add driver
2024-09-16 20:32 ` Shen Jianping (ME-SE/EAD2)
@ 2024-09-17 11:13 ` Jonathan Cameron
2024-09-17 13:13 ` Shen Jianping (ME-SE/EAD2)
0 siblings, 1 reply; 13+ messages in thread
From: Jonathan Cameron @ 2024-09-17 11:13 UTC (permalink / raw)
To: Shen Jianping (ME-SE/EAD2)
Cc: lars@metafoo.de, robh@kernel.org, krzk+dt@kernel.org,
conor+dt@kernel.org, dima.fedrau@gmail.com,
marcelo.schmitt1@gmail.com, linux-iio@vger.kernel.org,
devicetree@vger.kernel.org, linux-kernel@vger.kernel.org,
Lorenz Christian (ME-SE/EAD2), Frauendorf Ulrike (ME/PJ-SW3),
Dolde Kai (ME-SE/PAE-A3)
On Mon, 16 Sep 2024 20:32:56 +0000
"Shen Jianping (ME-SE/EAD2)" <Jianping.Shen@de.bosch.com> wrote:
> >Hi Shen,
> >
> >I suspect I led you astray. regmap core seems unlikely to feed us little endian
> >buffers on writes (they should be CPU endian I think) so there should be memcpy()
> >for that not a get_unaligned_le16()
> >
> >> +
> >> +static int smi240_regmap_spi_write(void *context, const void *data,
> >> + size_t count)
> >> +{
> >> + u8 reg_addr;
> >> + u16 reg_data;
> >> + 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);
> >> +
> >> + if (count < 2)
> >> + return -EINVAL;
> >> +
> >> + reg_addr = ((u8 *)data)[0];
> >> + reg_data = get_unaligned_le16(&((u8 *)data)[1]);
> >
> >Why is the regmap core giving us an le16?
> >I probably sent you wrong way with this earlier :( memcpy probably the correct
> >choice here.
>
> Yes, you are right. We shall use memcpy to keep the be CPU endian. Just using memcpy may be not enough.
>
> Shall we also change regmap_config.val_format_endian from REGMAP_ENDIAN_LITTLE to REGMAP_ENDIAN_NATIVE ?
>
> This is to make sure that regmap_write passes the reg-value to smi240_regmap_spi_write without changing the CPU endian.
>
Hmm. I'd missed that control. If the register data needs to be little endian
then it is correct to leave that set as REGMAP_ENDIAN_LITTLE as then
the regmap core will do the endian swap for you on Big endian systems.
If I follow that bit of regmap correctly it will then have the data
in the right order so the above still wants to just be a memcpy.
As it stands, on a Big endian host, regmap will use the val_format_endian
to decide to flip the bytes. This code then flips them back again and
the value written is big endian which is not what you intend!
Easy way to check this will be to set it, on your little endian
host, to REGMAP_BIG_ENDIAN and see what you get in the value.
Then consider if you'd had get_unaligned_be16
then it would end up as little endian again. This should mirror
the current situation if this driver runs on a big endian host.
Hope that confusing set of comments helps!
Jonathan
^ permalink raw reply [flat|nested] 13+ messages in thread
* RE: [PATCH v7 2/2] iio: imu: smi240: add driver
2024-09-17 11:13 ` Jonathan Cameron
@ 2024-09-17 13:13 ` Shen Jianping (ME-SE/EAD2)
2024-09-28 14:36 ` Jonathan Cameron
0 siblings, 1 reply; 13+ messages in thread
From: Shen Jianping (ME-SE/EAD2) @ 2024-09-17 13:13 UTC (permalink / raw)
To: Jonathan Cameron
Cc: lars@metafoo.de, robh@kernel.org, krzk+dt@kernel.org,
conor+dt@kernel.org, dima.fedrau@gmail.com,
marcelo.schmitt1@gmail.com, linux-iio@vger.kernel.org,
devicetree@vger.kernel.org, linux-kernel@vger.kernel.org,
Lorenz Christian (ME-SE/EAD2), Frauendorf Ulrike (ME/PJ-SW3),
Dolde Kai (ME-SE/PAE-A3)
>> >Hi Shen,
>> >
>> >I suspect I led you astray. regmap core seems unlikely to feed us
>> >little endian buffers on writes (they should be CPU endian I think)
>> >so there should be memcpy() for that not a get_unaligned_le16()
>> >
>> >> +
>> >> +static int smi240_regmap_spi_write(void *context, const void *data,
>> >> + size_t count)
>> >> +{
>> >> + u8 reg_addr;
>> >> + u16 reg_data;
>> >> + 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);
>> >> +
>> >> + if (count < 2)
>> >> + return -EINVAL;
>> >> +
>> >> + reg_addr = ((u8 *)data)[0];
>> >> + reg_data = get_unaligned_le16(&((u8 *)data)[1]);
>> >
>> >Why is the regmap core giving us an le16?
>> >I probably sent you wrong way with this earlier :( memcpy probably
>> >the correct choice here.
>>
>> Yes, you are right. We shall use memcpy to keep the be CPU endian. Just using
>memcpy may be not enough.
>>
>> Shall we also change regmap_config.val_format_endian from
>REGMAP_ENDIAN_LITTLE to REGMAP_ENDIAN_NATIVE ?
>>
>> This is to make sure that regmap_write passes the reg-value to
>smi240_regmap_spi_write without changing the CPU endian.
>>
>Hmm. I'd missed that control. If the register data needs to be little endian then it is
>correct to leave that set as REGMAP_ENDIAN_LITTLE as then the regmap core will
>do the endian swap for you on Big endian systems.
>
>If I follow that bit of regmap correctly it will then have the data in the right order so
>the above still wants to just be a memcpy.
>
>As it stands, on a Big endian host, regmap will use the val_format_endian to decide
>to flip the bytes. This code then flips them back again and the value written is big
>endian which is not what you intend!
>
>Easy way to check this will be to set it, on your little endian host, to
>REGMAP_BIG_ENDIAN and see what you get in the value.
>Then consider if you'd had get_unaligned_be16 then it would end up as little endian
>again. This should mirror the current situation if this driver runs on a big endian host.
>
>Hope that confusing set of comments helps!
>
>Jonathan
>
Hi Jonathan,
we check the regmap behavior with the following tests
1. host : little endian val_format_endian ==REGMAP_BIG_ENDIAN regmap_write(data->regmap, REG_ADDR, 0x12AB)
then in smi240_regmap_spi_write(void *context, const void *data, size_t count) we have data[0]== REG_ADDR, data[1]==0xAB , data[2]==0x12
2. host : little endian val_format_endian ==REGMAP_BIG_LITTLE regmap_write(data->regmap, REG_ADDR, 0x12AB)
then in smi240_regmap_spi_write(void *context, const void *data, size_t count) we have data[0]== REG_ADDR, data[1]==0x12 , data[2]==0xAB
3. host : little endian val_format_endian ==REGMAP_BIG_NATIVE regmap_write(data->regmap, REG_ADDR, 0x12AB)
then in smi240_regmap_spi_write(void *context, const void *data, size_t count) we have data[0]== REG_ADDR, data[1]==0x12 , data[2]==0xAB
when regmap_write passes the reg-value to the underlaying spi-write function, it flips the bytes if val_format_endian != cpu_endian
Since we prepare the request and the reg-value (as part of the request) with cpu_endian, we need to make sure that the cpu_endian keeps untouched until we pass the whole request to spi buffer using "iio_priv_data->spi_buf = cpu_to_be32(request)"
Therefore we need to remove the change of cpu_endian during the request preparation.
1. Instead get_unaligned_le16 now we use memcpy to take the reg-value without changing the cpu_endian.
2, we use REGMAP_BIG_NATIVE on val_format_endian to make sure when regmap_write passes the reg-value to the underlaying spi-write function the cpu_endian kept untouched.
This makes our driver be able to work properly on both little endian and big endian host. We tested the new changes on little endian host it works properly. Big endian host case is not tested yet, since today the big endian processors are almost dead.
The next version will looks like that.
static const struct regmap_config smi240_regmap_config = {
.reg_bits = 8,
.val_bits = 16,
.val_format_endian = REGMAP_ENDIAN_NATIVE,
};
static int smi240_regmap_spi_write(void *context, const void *data,size_t count)
{
u8 reg_addr;
u16 reg_data;
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);
if (count < 2)
return -EINVAL;
reg_addr = ((u8 *)data)[0];
memcpy(®_data, &((u8 *)data)[1], 2);
request = FIELD_PREP(SMI240_BUS_ID_MASK, SMI240_BUS_ID);
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));
}
Is the new version now correct ?
Best regards
Jianping Shen
^ permalink raw reply [flat|nested] 13+ messages in thread
* Re: [PATCH v7 1/2] dt-bindings: iio: imu: smi240: add Bosch smi240
2024-09-13 17:54 ` Conor Dooley
@ 2024-09-17 16:58 ` Krzysztof Kozlowski
2024-09-17 20:42 ` Conor Dooley
0 siblings, 1 reply; 13+ messages in thread
From: Krzysztof Kozlowski @ 2024-09-17 16:58 UTC (permalink / raw)
To: Conor Dooley, 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 13/09/2024 19:54, Conor Dooley wrote:
> On Fri, Sep 13, 2024 at 12:00:10PM +0200, Jianping.Shen@de.bosch.com wrote:
>> From: Shen Jianping <Jianping.Shen@de.bosch.com>
>>
>> add 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.
>>
>> Reviewed-by: Rob Herring (Arm) <robh@kernel.org>
>> Reviewed-by: Krzysztof Kozlowski <krzysztof.kozlowski@linaro.org>
>> Reviewed-by: Conor Dooley <conor.dooley@microchip.com>
>
> 3 reviews? Doing well for yourself!
There is certainly mess here, but that's correct. We both reviewed older
version and then new version was posted ignoring our tags. So Rob gave
review.
Changelog is so vague that I have no clue...
Best regards,
Krzysztof
^ permalink raw reply [flat|nested] 13+ messages in thread
* Re: [PATCH v7 0/2] iio: imu: smi240: add bosch smi240 driver
2024-09-13 10:00 [PATCH v7 0/2] iio: imu: smi240: add bosch smi240 driver Jianping.Shen
2024-09-13 10:00 ` [PATCH v7 1/2] dt-bindings: iio: imu: smi240: add Bosch smi240 Jianping.Shen
2024-09-13 10:00 ` [PATCH v7 2/2] iio: imu: smi240: add driver Jianping.Shen
@ 2024-09-17 16:59 ` Krzysztof Kozlowski
2024-09-18 8:14 ` Shen Jianping (ME-SE/EAD2)
2 siblings, 1 reply; 13+ messages in thread
From: Krzysztof Kozlowski @ 2024-09-17 16:59 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 13/09/2024 12:00, Jianping.Shen@de.bosch.com wrote:
> From: Shen Jianping <Jianping.Shen@de.bosch.com>
>
> Add 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. 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
>
> v4 -> v5
> - No changes
>
> v5 -> v6
> - Fix checkpatch findings
>
> v6 -> v7
> - 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
>
> v4 -> v5
> - Merge the implementation in one simple file
> - Add channel info for acc/gyro data channel
> - Fix other findings
?
>
> v5 -> v6
> - Fix checkpatch findings
> - Fix review findings
? What exactly happened? Your changelog is way too vague.
What happened with our reviews? Why did you get multiple of them?
Best regards,
Krzysztof
^ permalink raw reply [flat|nested] 13+ messages in thread
* Re: [PATCH v7 1/2] dt-bindings: iio: imu: smi240: add Bosch smi240
2024-09-17 16:58 ` Krzysztof Kozlowski
@ 2024-09-17 20:42 ` Conor Dooley
0 siblings, 0 replies; 13+ messages in thread
From: Conor Dooley @ 2024-09-17 20:42 UTC (permalink / raw)
To: Krzysztof Kozlowski
Cc: Jianping.Shen, jic23, lars, robh, krzk+dt, conor+dt, dima.fedrau,
marcelo.schmitt1, linux-iio, devicetree, linux-kernel,
Christian.Lorenz3, Ulrike.Frauendorf, Kai.Dolde
[-- Attachment #1: Type: text/plain, Size: 1042 bytes --]
On Tue, Sep 17, 2024 at 06:58:24PM +0200, Krzysztof Kozlowski wrote:
> On 13/09/2024 19:54, Conor Dooley wrote:
> > On Fri, Sep 13, 2024 at 12:00:10PM +0200, Jianping.Shen@de.bosch.com wrote:
> >> From: Shen Jianping <Jianping.Shen@de.bosch.com>
> >>
> >> add 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.
> >>
> >> Reviewed-by: Rob Herring (Arm) <robh@kernel.org>
> >> Reviewed-by: Krzysztof Kozlowski <krzysztof.kozlowski@linaro.org>
> >> Reviewed-by: Conor Dooley <conor.dooley@microchip.com>
> >
> > 3 reviews? Doing well for yourself!
>
> There is certainly mess here, but that's correct. We both reviewed older
> version and then new version was posted ignoring our tags. So Rob gave
> review.
>
> Changelog is so vague that I have no clue...
Yeah, I figured something like that had happened. Just a tongue-in-cheek
comment ;)
[-- Attachment #2: signature.asc --]
[-- Type: application/pgp-signature, Size: 228 bytes --]
^ permalink raw reply [flat|nested] 13+ messages in thread
* RE: [PATCH v7 0/2] iio: imu: smi240: add bosch smi240 driver
2024-09-17 16:59 ` [PATCH v7 0/2] iio: imu: smi240: add bosch smi240 driver Krzysztof Kozlowski
@ 2024-09-18 8:14 ` Shen Jianping (ME-SE/EAD2)
0 siblings, 0 replies; 13+ messages in thread
From: Shen Jianping (ME-SE/EAD2) @ 2024-09-18 8:14 UTC (permalink / raw)
To: Krzysztof Kozlowski, jic23@kernel.org, lars@metafoo.de,
robh@kernel.org, krzk+dt@kernel.org, conor+dt@kernel.org,
dima.fedrau@gmail.com, marcelo.schmitt1@gmail.com,
linux-iio@vger.kernel.org, devicetree@vger.kernel.org,
linux-kernel@vger.kernel.org, Lorenz Christian (ME-SE/EAD2),
Frauendorf Ulrike (ME/PJ-SW3), Dolde Kai (ME-SE/PAE-A3)
>> Add 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. 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
>>
>> v4 -> v5
>> - No changes
>>
>> v5 -> v6
>> - Fix checkpatch findings
>>
>> v6 -> v7
>> - 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
>>
>> v4 -> v5
>> - Merge the implementation in one simple file
>> - Add channel info for acc/gyro data channel
>> - Fix other findings
>
>?
>
>>
>> v5 -> v6
>> - Fix checkpatch findings
>> - Fix review findings
>
>? What exactly happened? Your changelog is way too vague.
>
>What happened with our reviews? Why did you get multiple of them?
>
Sorry for the confusing. let me make it clear
1. On 15.08 Conor reviewed the V3 dt-binding
2. On 26.08 we submit V4 (same as v3) without adding review tag. Krzysztof reviewed again and told us, that we need add review tag in patch.
3. On 05.09 we submit V5 which contains 2 tailing space in the description. This leads to checkpatch error. Krzysztof told us to get rid of those checkpatch errors.
4. On 10.09 we removed the tailing space and submit V6 (same as v3 and v4) without adding review tag. Rog gave the last review.
5. On 13.09 we submit V7 (same as v3, v4, and v6) with review tag of Conor, Krzysztof, and Rob.
That is where the 3 reviews come from.
In the dt-binding changelog we have "v5 -> v6 Fix checkpatch findings"
Best regards
Jianping
^ permalink raw reply [flat|nested] 13+ messages in thread
* Re: [PATCH v7 2/2] iio: imu: smi240: add driver
2024-09-17 13:13 ` Shen Jianping (ME-SE/EAD2)
@ 2024-09-28 14:36 ` Jonathan Cameron
0 siblings, 0 replies; 13+ messages in thread
From: Jonathan Cameron @ 2024-09-28 14:36 UTC (permalink / raw)
To: Shen Jianping (ME-SE/EAD2)
Cc: lars@metafoo.de, robh@kernel.org, krzk+dt@kernel.org,
conor+dt@kernel.org, dima.fedrau@gmail.com,
marcelo.schmitt1@gmail.com, linux-iio@vger.kernel.org,
devicetree@vger.kernel.org, linux-kernel@vger.kernel.org,
Lorenz Christian (ME-SE/EAD2), Frauendorf Ulrike (ME/PJ-SW3),
Dolde Kai (ME-SE/PAE-A3)
On Tue, 17 Sep 2024 13:13:57 +0000
"Shen Jianping (ME-SE/EAD2)" <Jianping.Shen@de.bosch.com> wrote:
> >> >Hi Shen,
> >> >
> >> >I suspect I led you astray. regmap core seems unlikely to feed us
> >> >little endian buffers on writes (they should be CPU endian I think)
> >> >so there should be memcpy() for that not a get_unaligned_le16()
> >> >
> >> >> +
> >> >> +static int smi240_regmap_spi_write(void *context, const void *data,
> >> >> + size_t count)
> >> >> +{
> >> >> + u8 reg_addr;
> >> >> + u16 reg_data;
> >> >> + 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);
> >> >> +
> >> >> + if (count < 2)
> >> >> + return -EINVAL;
> >> >> +
> >> >> + reg_addr = ((u8 *)data)[0];
> >> >> + reg_data = get_unaligned_le16(&((u8 *)data)[1]);
> >> >
> >> >Why is the regmap core giving us an le16?
> >> >I probably sent you wrong way with this earlier :( memcpy probably
> >> >the correct choice here.
> >>
> >> Yes, you are right. We shall use memcpy to keep the be CPU endian. Just using
> >memcpy may be not enough.
> >>
> >> Shall we also change regmap_config.val_format_endian from
> >REGMAP_ENDIAN_LITTLE to REGMAP_ENDIAN_NATIVE ?
> >>
> >> This is to make sure that regmap_write passes the reg-value to
> >smi240_regmap_spi_write without changing the CPU endian.
> >>
> >Hmm. I'd missed that control. If the register data needs to be little endian then it is
> >correct to leave that set as REGMAP_ENDIAN_LITTLE as then the regmap core will
> >do the endian swap for you on Big endian systems.
> >
> >If I follow that bit of regmap correctly it will then have the data in the right order so
> >the above still wants to just be a memcpy.
> >
> >As it stands, on a Big endian host, regmap will use the val_format_endian to decide
> >to flip the bytes. This code then flips them back again and the value written is big
> >endian which is not what you intend!
> >
> >Easy way to check this will be to set it, on your little endian host, to
> >REGMAP_BIG_ENDIAN and see what you get in the value.
> >Then consider if you'd had get_unaligned_be16 then it would end up as little endian
> >again. This should mirror the current situation if this driver runs on a big endian host.
> >
> >Hope that confusing set of comments helps!
> >
> >Jonathan
> >
> Hi Jonathan,
>
> we check the regmap behavior with the following tests
>
> 1. host : little endian val_format_endian ==REGMAP_BIG_ENDIAN regmap_write(data->regmap, REG_ADDR, 0x12AB)
> then in smi240_regmap_spi_write(void *context, const void *data, size_t count) we have data[0]== REG_ADDR, data[1]==0xAB , data[2]==0x12
>
> 2. host : little endian val_format_endian ==REGMAP_BIG_LITTLE regmap_write(data->regmap, REG_ADDR, 0x12AB)
> then in smi240_regmap_spi_write(void *context, const void *data, size_t count) we have data[0]== REG_ADDR, data[1]==0x12 , data[2]==0xAB
>
> 3. host : little endian val_format_endian ==REGMAP_BIG_NATIVE regmap_write(data->regmap, REG_ADDR, 0x12AB)
> then in smi240_regmap_spi_write(void *context, const void *data, size_t count) we have data[0]== REG_ADDR, data[1]==0x12 , data[2]==0xAB
>
> when regmap_write passes the reg-value to the underlaying spi-write function, it flips the bytes if val_format_endian != cpu_endian
>
> Since we prepare the request and the reg-value (as part of the request) with cpu_endian, we need to make sure that the cpu_endian keeps untouched until we pass the whole request to spi buffer using "iio_priv_data->spi_buf = cpu_to_be32(request)"
> Therefore we need to remove the change of cpu_endian during the request preparation.
>
> 1. Instead get_unaligned_le16 now we use memcpy to take the reg-value without changing the cpu_endian.
> 2, we use REGMAP_BIG_NATIVE on val_format_endian to make sure when regmap_write passes the reg-value to the underlaying spi-write function the cpu_endian kept untouched.
>
> This makes our driver be able to work properly on both little endian and big endian host. We tested the new changes on little endian host it works properly. Big endian host case is not tested yet, since today the big endian processors are almost dead.
>
> The next version will looks like that.
>
> static const struct regmap_config smi240_regmap_config = {
> .reg_bits = 8,
> .val_bits = 16,
> .val_format_endian = REGMAP_ENDIAN_NATIVE,
You say REGMAP_BIG_NATIVE above by which I think you mean REGMAP_ENDIAN_BIG
(which seems correct to me) but then set REGMAP_ENDIAN_NATIVE here.
Other than that this looks correct and thanks for working through
the test cases above.
>
> };
>
> static int smi240_regmap_spi_write(void *context, const void *data,size_t count)
> {
> u8 reg_addr;
> u16 reg_data;
> 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);
> if (count < 2)
> return -EINVAL;
>
> reg_addr = ((u8 *)data)[0];
> memcpy(®_data, &((u8 *)data)[1], 2);
>
> request = FIELD_PREP(SMI240_BUS_ID_MASK, SMI240_BUS_ID);
> 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));
> }
>
> Is the new version now correct ?
>
> Best regards
>
> Jianping Shen
>
>
>
>
>
>
>
>
>
>
^ permalink raw reply [flat|nested] 13+ messages in thread
end of thread, other threads:[~2024-09-28 14:36 UTC | newest]
Thread overview: 13+ messages (download: mbox.gz follow: Atom feed
-- links below jump to the message on this page --
2024-09-13 10:00 [PATCH v7 0/2] iio: imu: smi240: add bosch smi240 driver Jianping.Shen
2024-09-13 10:00 ` [PATCH v7 1/2] dt-bindings: iio: imu: smi240: add Bosch smi240 Jianping.Shen
2024-09-13 17:54 ` Conor Dooley
2024-09-17 16:58 ` Krzysztof Kozlowski
2024-09-17 20:42 ` Conor Dooley
2024-09-13 10:00 ` [PATCH v7 2/2] iio: imu: smi240: add driver Jianping.Shen
2024-09-14 16:32 ` Jonathan Cameron
2024-09-16 20:32 ` Shen Jianping (ME-SE/EAD2)
2024-09-17 11:13 ` Jonathan Cameron
2024-09-17 13:13 ` Shen Jianping (ME-SE/EAD2)
2024-09-28 14:36 ` Jonathan Cameron
2024-09-17 16:59 ` [PATCH v7 0/2] iio: imu: smi240: add bosch smi240 driver Krzysztof Kozlowski
2024-09-18 8:14 ` Shen Jianping (ME-SE/EAD2)
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).