2016-04-01 12:29:12

by Daniel Baluta

[permalink] [raw]
Subject: [PATCH] iio: imu: Add initial support for Bosch BMI160

BMI160 is an Inertial Measurement Unit (IMU) which provides acceleration
and angular rate measurement. It also offers a secondary I2C interface
for connecting a magnetometer sensor (usually BMM160).

Current driver offers support for accelerometer and gyroscope readings
via sysfs or via buffer interface using an external trigger (e.g.
hrtimer). Data is retrieved from IMU via I2C or SPI interface.

Datasheet is at:
http://www.mouser.com/ds/2/783/BST-BMI160-DS000-07-786474.pdf

Signed-off-by: Daniel Baluta <[email protected]>
---
drivers/iio/imu/Kconfig | 2 +
drivers/iio/imu/Makefile | 1 +
drivers/iio/imu/bmi160/Kconfig | 32 ++
drivers/iio/imu/bmi160/Makefile | 6 +
drivers/iio/imu/bmi160/bmi160.h | 8 +
drivers/iio/imu/bmi160/bmi160_core.c | 588 +++++++++++++++++++++++++++++++++++
drivers/iio/imu/bmi160/bmi160_i2c.c | 79 +++++
drivers/iio/imu/bmi160/bmi160_spi.c | 71 +++++
8 files changed, 787 insertions(+)
create mode 100644 drivers/iio/imu/bmi160/Kconfig
create mode 100644 drivers/iio/imu/bmi160/Makefile
create mode 100644 drivers/iio/imu/bmi160/bmi160.h
create mode 100644 drivers/iio/imu/bmi160/bmi160_core.c
create mode 100644 drivers/iio/imu/bmi160/bmi160_i2c.c
create mode 100644 drivers/iio/imu/bmi160/bmi160_spi.c

diff --git a/drivers/iio/imu/Kconfig b/drivers/iio/imu/Kconfig
index 5e610f7..1f1ad41 100644
--- a/drivers/iio/imu/Kconfig
+++ b/drivers/iio/imu/Kconfig
@@ -25,6 +25,8 @@ config ADIS16480
Say yes here to build support for Analog Devices ADIS16375, ADIS16480,
ADIS16485, ADIS16488 inertial sensors.

+source "drivers/iio/imu/bmi160/Kconfig"
+
config KMX61
tristate "Kionix KMX61 6-axis accelerometer and magnetometer"
depends on I2C
diff --git a/drivers/iio/imu/Makefile b/drivers/iio/imu/Makefile
index e1e6e3d..c71bcd3 100644
--- a/drivers/iio/imu/Makefile
+++ b/drivers/iio/imu/Makefile
@@ -13,6 +13,7 @@ adis_lib-$(CONFIG_IIO_ADIS_LIB_BUFFER) += adis_trigger.o
adis_lib-$(CONFIG_IIO_ADIS_LIB_BUFFER) += adis_buffer.o
obj-$(CONFIG_IIO_ADIS_LIB) += adis_lib.o

+obj-y += bmi160/
obj-y += inv_mpu6050/

obj-$(CONFIG_KMX61) += kmx61.o
diff --git a/drivers/iio/imu/bmi160/Kconfig b/drivers/iio/imu/bmi160/Kconfig
new file mode 100644
index 0000000..adb512f
--- /dev/null
+++ b/drivers/iio/imu/bmi160/Kconfig
@@ -0,0 +1,32 @@
+#
+# BMI160 IMU driver
+#
+
+config BMI160
+ tristate
+ select IIO_BUFFER
+ select IIO_TRIGGERED_BUFFER
+
+config BMI160_I2C
+ tristate "Bosch BMI160 I2C driver"
+ depends on I2C
+ select BMI160
+ select REGMAP_I2C
+ help
+ If you say yes you get support BMI160 IMU on I2C with accelerometer,
+ gyroscope and external BMG160 magnetometer.
+
+ This driver can also be built as a module. If so, the module will be
+ called bmi160_i2c.
+
+config BMI160_SPI
+ tristate "Bosch BMI160 SPI driver"
+ depends on SPI
+ select BMI160
+ select REGMAP_SPI
+ help
+ If you say yes you get support BMI160 IMU on SPI with accelerometer,
+ gyroscope and external BMG160 magnetometer.
+
+ This driver can also be built as a module. If so, the module will be
+ called bmi160_i2c.
diff --git a/drivers/iio/imu/bmi160/Makefile b/drivers/iio/imu/bmi160/Makefile
new file mode 100644
index 0000000..10365e4
--- /dev/null
+++ b/drivers/iio/imu/bmi160/Makefile
@@ -0,0 +1,6 @@
+#
+# Makefile for Bosch BMI160 IMU
+#
+obj-$(CONFIG_BMI160) += bmi160_core.o
+obj-$(CONFIG_BMI160_I2C) += bmi160_i2c.o
+obj-$(CONFIG_BMI160_SPI) += bmi160_spi.o
diff --git a/drivers/iio/imu/bmi160/bmi160.h b/drivers/iio/imu/bmi160/bmi160.h
new file mode 100644
index 0000000..c5f7b2d
--- /dev/null
+++ b/drivers/iio/imu/bmi160/bmi160.h
@@ -0,0 +1,8 @@
+#ifndef BMI160_H_
+#define BMI160_H_
+
+int bmi160_core_probe(struct device *dev, struct regmap *regmap,
+ const char *name, bool use_spi);
+void bmi160_core_remove(struct device *dev);
+
+#endif /* BMI160_H_ */
diff --git a/drivers/iio/imu/bmi160/bmi160_core.c b/drivers/iio/imu/bmi160/bmi160_core.c
new file mode 100644
index 0000000..d6ce643
--- /dev/null
+++ b/drivers/iio/imu/bmi160/bmi160_core.c
@@ -0,0 +1,588 @@
+/*
+ * BMI160 - Bosch IMU (accel, gyro plus external magnetometer)
+ *
+ * Copyright (c) 2016, Intel Corporation.
+ *
+ * This file is subject to the terms and conditions of version 2 of
+ * the GNU General Public License. See the file COPYING in the main
+ * directory of this archive for more details.
+ *
+ * IIO core driver for BMI160, with support for I2C/SPI busses
+ *
+ * TODO: magnetometer, interrupts, hardware FIFO
+ */
+#include <linux/module.h>
+#include <linux/regmap.h>
+#include <linux/acpi.h>
+#include <linux/delay.h>
+
+#include <linux/iio/iio.h>
+#include <linux/iio/triggered_buffer.h>
+#include <linux/iio/trigger_consumer.h>
+#include <linux/iio/buffer.h>
+
+#include "bmi160.h"
+
+#define BMI160_REG_CHIP_ID 0x00
+#define BMI160_CHIP_ID_VAL 0xD1
+
+#define BMI160_REG_PMU_STATUS 0x03
+
+/* X axis data low byte address, the rest can be obtained using axis offset */
+#define BMI160_REG_DATA_MAGN_XOUT_L 0x04
+#define BMI160_REG_DATA_GYRO_XOUT_L 0x0C
+#define BMI160_REG_DATA_ACCEL_XOUT_L 0x12
+
+#define BMI160_REG_ACCEL_CONFIG 0x40
+#define BMI160_ACCEL_CONFIG_ODR_MASK GENMASK(3, 0)
+#define BMI160_ACCEL_CONFIG_BWP_MASK GENMASK(6, 4)
+
+#define BMI160_REG_ACCEL_RANGE 0x41
+#define BMI160_ACCEL_RANGE_2G 0x03
+#define BMI160_ACCEL_RANGE_4G 0x05
+#define BMI160_ACCEL_RANGE_8G 0x08
+#define BMI160_ACCEL_RANGE_16G 0x0C
+
+#define BMI160_REG_GYRO_CONFIG 0x42
+#define BMI160_GYRO_CONFIG_ODR_MASK GENMASK(3, 0)
+#define BMI160_GYRO_CONFIG_BWP_MASK GENMASK(5, 4)
+
+#define BMI160_REG_GYRO_RANGE 0x43
+#define BMI160_GYRO_RANGE_2000DPS 0x00
+#define BMI160_GYRO_RANGE_1000DPS 0x01
+#define BMI160_GYRO_RANGE_500DPS 0x02
+#define BMI160_GYRO_RANGE_250DPS 0x03
+#define BMI160_GYRO_RANGE_125DPS 0x04
+
+#define BMI160_REG_CMD 0x7E
+#define BMI160_CMD_ACCEL_PM_SUSPEND 0x10
+#define BMI160_CMD_ACCEL_PM_NORMAL 0x11
+#define BMI160_CMD_ACCEL_PM_LOW_POWER 0x12
+#define BMI160_CMD_GYRO_PM_SUSPEND 0x14
+#define BMI160_CMD_GYRO_PM_NORMAL 0x15
+#define BMI160_CMD_GYRO_PM_FAST_STARTUP 0x17
+#define BMI160_CMD_SOFTRESET 0xB6
+
+#define BMI160_REG_DUMMY 0x7F
+
+#define BMI160_ACCEL_PMU_MIN_SLEEP 3200 /* usec */
+#define BMI160_ACCEL_PMU_MAX_SLEEP 3800
+#define BMI160_GYRO_PMU_MIN_SLEEP 55000
+#define BMI160_GYRO_PMU_MAX_SLEEP 80000
+#define BMI160_SOFTRESET_SLEEP 1000
+
+#define BMI160_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_SAMP_FREQ), \
+ .scan_index = _index, \
+ .scan_type = { \
+ .sign = 's', \
+ .realbits = 16, \
+ .storagebits = 16, \
+ .shift = 0, \
+ .endianness = IIO_LE, \
+ }, \
+}
+
+/* scan indexes follow DATA register order */
+enum bmi160_scan_axis {
+ BMI160_SCAN_EXT_MAGN_X = 0,
+ BMI160_SCAN_EXT_MAGN_Y,
+ BMI160_SCAN_EXT_MAGN_Z,
+ BMI160_SCAN_RHALL,
+ BMI160_SCAN_GYRO_X,
+ BMI160_SCAN_GYRO_Y,
+ BMI160_SCAN_GYRO_Z,
+ BMI160_SCAN_ACCEL_X,
+ BMI160_SCAN_ACCEL_Y,
+ BMI160_SCAN_ACCEL_Z,
+ BMI160_SCAN_TIMESTAMP,
+};
+
+enum bmi160_sensor_type {
+ BMI160_ACCEL = 0,
+ BMI160_GYRO,
+ BMI160_EXT_MAGN,
+ BMI160_NUM_SENSORS /* must be last */
+};
+
+struct bmi160_data {
+ struct regmap *regmap;
+};
+
+struct bmi160_regs {
+ u8 data; /* LSB byte register for X-axis */
+ u8 config;
+ u8 config_odr_mask;
+ u8 config_bwp_mask;
+ u8 range;
+ u8 pmu_cmd_normal;
+ u8 pmu_cmd_suspend;
+};
+
+struct bmi160_regs bmi160_regs[] = {
+ [BMI160_ACCEL] = {
+ .data = BMI160_REG_DATA_ACCEL_XOUT_L,
+ .config = BMI160_REG_ACCEL_CONFIG,
+ .config_odr_mask = BMI160_ACCEL_CONFIG_ODR_MASK,
+ .config_bwp_mask = BMI160_ACCEL_CONFIG_BWP_MASK,
+ .range = BMI160_REG_ACCEL_RANGE,
+ .pmu_cmd_normal = BMI160_CMD_ACCEL_PM_NORMAL,
+ .pmu_cmd_suspend = BMI160_CMD_ACCEL_PM_SUSPEND,
+ },
+ [BMI160_GYRO] = {
+ .data = BMI160_REG_DATA_GYRO_XOUT_L,
+ .config = BMI160_REG_GYRO_CONFIG,
+ .config_odr_mask = BMI160_GYRO_CONFIG_ODR_MASK,
+ .config_bwp_mask = BMI160_GYRO_CONFIG_BWP_MASK,
+ .range = BMI160_REG_GYRO_RANGE,
+ .pmu_cmd_normal = BMI160_CMD_GYRO_PM_NORMAL,
+ .pmu_cmd_suspend = BMI160_CMD_GYRO_PM_SUSPEND,
+ },
+};
+
+struct bmi160_pmu_time {
+ unsigned long min;
+ unsigned long max;
+};
+
+struct bmi160_pmu_time bmi160_pmu_time[] = {
+ [BMI160_ACCEL] = {
+ .min = BMI160_ACCEL_PMU_MIN_SLEEP,
+ .max = BMI160_ACCEL_PMU_MAX_SLEEP
+ },
+ [BMI160_GYRO] = {
+ .min = BMI160_GYRO_PMU_MIN_SLEEP,
+ .max = BMI160_GYRO_PMU_MIN_SLEEP,
+ },
+};
+
+struct bmi160_scale {
+ u8 bits;
+ int uscale;
+};
+
+struct bmi160_odr {
+ u8 bits;
+ int odr;
+ int uodr;
+};
+
+static const struct bmi160_scale bmi160_accel_scale[] = {
+ { BMI160_ACCEL_RANGE_2G, 598},
+ { BMI160_ACCEL_RANGE_4G, 1197},
+ { BMI160_ACCEL_RANGE_8G, 2394},
+ { BMI160_ACCEL_RANGE_16G, 4788},
+};
+
+static const struct bmi160_scale bmi160_gyro_scale[] = {
+ { BMI160_GYRO_RANGE_2000DPS, 1065},
+ { BMI160_GYRO_RANGE_1000DPS, 532},
+ { BMI160_GYRO_RANGE_500DPS, 266},
+ { BMI160_GYRO_RANGE_250DPS, 133},
+ { BMI160_GYRO_RANGE_125DPS, 66},
+
+};
+
+struct bmi160_scale_item {
+ const struct bmi160_scale *tbl;
+ int num;
+};
+
+static const struct bmi160_scale_item bmi160_scale_table[] = {
+ [BMI160_ACCEL] = {
+ .tbl = bmi160_accel_scale,
+ .num = ARRAY_SIZE(bmi160_accel_scale),
+ },
+ [BMI160_GYRO] = {
+ .tbl = bmi160_gyro_scale,
+ .num = ARRAY_SIZE(bmi160_gyro_scale),
+ },
+};
+
+static const struct bmi160_odr bmi160_accel_odr[] = {
+ {0x01, 0, 78125},
+ {0x02, 1, 5625},
+ {0x03, 3, 125},
+ {0x04, 6, 25},
+ {0x05, 12, 5},
+ {0x06, 25, 0},
+ {0x07, 50, 0},
+ {0x08, 100, 0},
+ {0x09, 200, 0},
+ {0x0A, 400, 0},
+ {0x0B, 800, 0},
+ {0x0C, 1600, 0},
+};
+
+static const struct bmi160_odr bmi160_gyro_odr[] = {
+ {0x06, 25, 0},
+ {0x07, 50, 0},
+ {0x08, 100, 0},
+ {0x09, 200, 0},
+ {0x0A, 400, 0},
+ {0x0B, 8000, 0},
+ {0x0C, 1600, 0},
+ {0x0D, 3200, 0},
+};
+
+struct bmi160_odr_item {
+ const struct bmi160_odr *tbl;
+ int num;
+};
+
+static const struct bmi160_odr_item bmi160_odr_table[] = {
+ [BMI160_ACCEL] = {
+ .tbl = bmi160_accel_odr,
+ .num = ARRAY_SIZE(bmi160_accel_odr),
+ },
+ [BMI160_GYRO] = {
+ .tbl = bmi160_gyro_odr,
+ .num = ARRAY_SIZE(bmi160_gyro_odr),
+ },
+};
+
+static const struct iio_chan_spec bmi160_channels[] = {
+ BMI160_CHANNEL(IIO_ACCEL, X, BMI160_SCAN_ACCEL_X),
+ BMI160_CHANNEL(IIO_ACCEL, Y, BMI160_SCAN_ACCEL_Y),
+ BMI160_CHANNEL(IIO_ACCEL, Z, BMI160_SCAN_ACCEL_Z),
+ BMI160_CHANNEL(IIO_ANGL_VEL, X, BMI160_SCAN_GYRO_X),
+ BMI160_CHANNEL(IIO_ANGL_VEL, Y, BMI160_SCAN_GYRO_Y),
+ BMI160_CHANNEL(IIO_ANGL_VEL, Z, BMI160_SCAN_GYRO_Z),
+ IIO_CHAN_SOFT_TIMESTAMP(BMI160_SCAN_TIMESTAMP),
+};
+
+static enum bmi160_sensor_type bmi160_to_sensor(enum iio_chan_type iio_type)
+{
+ switch (iio_type) {
+ case IIO_ACCEL:
+ return BMI160_ACCEL;
+ case IIO_ANGL_VEL:
+ return BMI160_GYRO;
+ default:
+ return -EINVAL;
+ }
+}
+
+static
+int bmi160_set_mode(struct bmi160_data *data, enum bmi160_sensor_type t,
+ int mode)
+{
+ int ret;
+ u8 cmd;
+
+ if (mode)
+ cmd = bmi160_regs[t].pmu_cmd_normal;
+ else
+ cmd = bmi160_regs[t].pmu_cmd_suspend;
+
+ ret = regmap_write(data->regmap, BMI160_REG_CMD, cmd);
+ if (ret < 0)
+ return ret;
+
+ usleep_range(bmi160_pmu_time[t].min, bmi160_pmu_time[t].max);
+
+ return 0;
+}
+
+static
+int bmi160_set_scale(struct bmi160_data *data, enum bmi160_sensor_type t,
+ int uscale)
+{
+ int i;
+
+ for (i = 0; i < bmi160_scale_table[t].num; i++)
+ if (bmi160_scale_table[t].tbl[i].uscale == uscale)
+ break;
+
+ if (i == bmi160_scale_table[t].num)
+ return -EINVAL;
+
+ return regmap_write(data->regmap, bmi160_regs[t].range,
+ bmi160_scale_table[t].tbl[i].bits);
+}
+
+static
+int bmi160_get_scale(struct bmi160_data *data, enum bmi160_sensor_type t,
+ int *uscale)
+{
+ int i, ret, val;
+
+ ret = regmap_read(data->regmap, bmi160_regs[t].range, &val);
+ if (ret < 0)
+ return ret;
+
+ for (i = 0; i < bmi160_scale_table[t].num; i++)
+ if (bmi160_scale_table[t].tbl[i].bits == val) {
+ *uscale = bmi160_scale_table[t].tbl[i].uscale;
+ return 0;
+ }
+
+ return -EINVAL;
+}
+
+static int bmi160_get_data(struct bmi160_data *data, int chan_type,
+ int axis, int *val)
+{
+ u8 reg;
+ int ret;
+ __le16 sample;
+ enum bmi160_sensor_type t = bmi160_to_sensor(chan_type);
+
+ reg = bmi160_regs[t].data + (axis - IIO_MOD_X) * 2;
+
+ ret = regmap_bulk_read(data->regmap, reg, &sample, sizeof(sample));
+ if (ret < 0)
+ return ret;
+
+ *val = sign_extend32(le16_to_cpu(sample), 15);
+
+ return 0;
+}
+
+static
+int bmi160_set_odr(struct bmi160_data *data, enum bmi160_sensor_type t,
+ int odr, int uodr)
+{
+ int i;
+
+ for (i = 0; i < bmi160_odr_table[t].num; i++)
+ if (bmi160_odr_table[t].tbl[i].odr == odr &&
+ bmi160_odr_table[t].tbl[i].uodr == uodr)
+ break;
+
+ if (i >= bmi160_odr_table[t].num)
+ return -EINVAL;
+
+ return regmap_update_bits(data->regmap,
+ bmi160_regs[t].config,
+ bmi160_odr_table[t].tbl[i].bits,
+ bmi160_regs[t].config_odr_mask);
+}
+
+static int bmi160_get_odr(struct bmi160_data *data, enum bmi160_sensor_type t,
+ int *odr, int *uodr)
+{
+ int i, val, ret;
+
+ ret = regmap_read(data->regmap, bmi160_regs[t].config, &val);
+ if (ret < 0)
+ return ret;
+
+ val &= bmi160_regs[t].config_odr_mask;
+
+ for (i = 0; i < bmi160_odr_table[t].num; i++)
+ if (val == bmi160_odr_table[t].tbl[i].bits)
+ break;
+
+ if (i >= bmi160_odr_table[t].num)
+ return -EINVAL;
+
+ *odr = bmi160_odr_table[t].tbl[i].odr;
+ *uodr = bmi160_odr_table[t].tbl[i].uodr;
+
+ return 0;
+}
+
+static irqreturn_t bmi160_trigger_handler(int irq, void *p)
+{
+ struct iio_poll_func *pf = p;
+ struct iio_dev *indio_dev = pf->indio_dev;
+ struct bmi160_data *data = iio_priv(indio_dev);
+ s16 buf[16]; /* 3 sens x 3 axis x s16 + 3 x s16 pad + 4 x s16 tstamp */
+ int i, ret, sample, j = 0, base = BMI160_REG_DATA_MAGN_XOUT_L;
+
+ for_each_set_bit(i, indio_dev->active_scan_mask,
+ indio_dev->masklength) {
+ ret = regmap_bulk_read(data->regmap, base + 2 * i, &sample,
+ sizeof(sample));
+ if (ret < 0)
+ goto done;
+ buf[j++] = sample;
+ }
+
+ iio_push_to_buffers_with_timestamp(indio_dev, buf, iio_get_time_ns());
+done:
+ iio_trigger_notify_done(indio_dev->trig);
+ return IRQ_HANDLED;
+}
+
+static int bmi160_read_raw(struct iio_dev *indio_dev,
+ struct iio_chan_spec const *chan,
+ int *val, int *val2, long mask)
+{
+ int ret;
+ struct bmi160_data *data = iio_priv(indio_dev);
+
+ switch (mask) {
+ case IIO_CHAN_INFO_RAW:
+ ret = bmi160_get_data(data, chan->type, chan->channel2, val);
+ if (ret < 0)
+ return ret;
+ return IIO_VAL_INT;
+ case IIO_CHAN_INFO_SCALE:
+ *val = 0;
+ ret = bmi160_get_scale(data,
+ bmi160_to_sensor(chan->type), val2);
+ return ret < 0 ? ret : IIO_VAL_INT_PLUS_MICRO;
+ case IIO_CHAN_INFO_SAMP_FREQ:
+ ret = bmi160_get_odr(data, bmi160_to_sensor(chan->type),
+ val, val2);
+ return ret < 0 ? ret : IIO_VAL_INT_PLUS_MICRO;
+ default:
+ return -EINVAL;
+ }
+
+ return 0;
+}
+
+static int bmi160_write_raw(struct iio_dev *indio_dev,
+ struct iio_chan_spec const *chan,
+ int val, int val2, long mask)
+{
+ struct bmi160_data *data = iio_priv(indio_dev);
+
+ switch (mask) {
+ case IIO_CHAN_INFO_SCALE:
+ return bmi160_set_scale(data,
+ bmi160_to_sensor(chan->type), val2);
+ break;
+ case IIO_CHAN_INFO_SAMP_FREQ:
+ return bmi160_set_odr(data, bmi160_to_sensor(chan->type),
+ val, val2);
+ default:
+ return -EINVAL;
+ }
+
+ return 0;
+}
+
+static const struct iio_info bmi160_info = {
+ .driver_module = THIS_MODULE,
+ .read_raw = bmi160_read_raw,
+ .write_raw = bmi160_write_raw,
+};
+
+static const char *bmi160_match_acpi_device(struct device *dev)
+{
+ const struct acpi_device_id *id;
+
+ id = acpi_match_device(dev->driver->acpi_match_table, dev);
+ if (!id)
+ return NULL;
+
+ return dev_name(dev);
+}
+
+static int bmi160_chip_init(struct bmi160_data *data, bool use_spi)
+{
+ int ret;
+ unsigned int val;
+ struct device *dev = regmap_get_device(data->regmap);
+
+ ret = regmap_write(data->regmap, BMI160_REG_CMD, BMI160_CMD_SOFTRESET);
+ if (ret < 0)
+ return ret;
+
+ usleep_range(BMI160_SOFTRESET_SLEEP, BMI160_SOFTRESET_SLEEP + 1);
+
+ /* CS rising edge is needed before starting SPI, so do a dummy read */
+ if (use_spi) {
+ ret = regmap_read(data->regmap, BMI160_REG_DUMMY, &val);
+ if (ret < 0)
+ return ret;
+ }
+
+ ret = regmap_read(data->regmap, BMI160_REG_CHIP_ID, &val);
+ if (ret < 0) {
+ dev_err(dev, "Error reading chip id\n");
+ return ret;
+ }
+ if (val != BMI160_CHIP_ID_VAL) {
+ dev_err(dev, "Wrong chip id, got %x expected %x\n",
+ val, BMI160_CHIP_ID_VAL);
+ return -ENODEV;
+ }
+
+ ret = bmi160_set_mode(data, BMI160_ACCEL, 1);
+ if (ret < 0)
+ return ret;
+
+ ret = bmi160_set_mode(data, BMI160_GYRO, 1);
+ if (ret < 0)
+ return ret;
+
+ return 0;
+}
+
+static void bmi160_chip_uninit(struct bmi160_data *data)
+{
+ bmi160_set_mode(data, BMI160_GYRO, 0);
+ bmi160_set_mode(data, BMI160_ACCEL, 0);
+}
+
+int bmi160_core_probe(struct device *dev, struct regmap *regmap,
+ const char *name, bool use_spi)
+{
+ struct iio_dev *indio_dev;
+ struct bmi160_data *data;
+ int ret;
+
+ 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;
+
+ ret = bmi160_chip_init(data, use_spi);
+ if (ret < 0)
+ return ret;
+
+ if (!name && ACPI_HANDLE(dev))
+ name = bmi160_match_acpi_device(dev);
+
+ indio_dev->dev.parent = dev;
+ indio_dev->channels = bmi160_channels;
+ indio_dev->num_channels = ARRAY_SIZE(bmi160_channels);
+ indio_dev->name = name;
+ indio_dev->modes = INDIO_DIRECT_MODE;
+ indio_dev->info = &bmi160_info;
+
+ ret = iio_triggered_buffer_setup(indio_dev, NULL,
+ bmi160_trigger_handler, NULL);
+ if (ret < 0)
+ goto uninit;
+
+ ret = iio_device_register(indio_dev);
+ if (ret < 0)
+ goto buffer_cleanup;
+
+ return 0;
+uninit:
+ bmi160_chip_uninit(data);
+buffer_cleanup:
+ iio_triggered_buffer_cleanup(indio_dev);
+ return ret;
+}
+EXPORT_SYMBOL_GPL(bmi160_core_probe);
+
+void bmi160_core_remove(struct device *dev)
+{
+ struct iio_dev *indio_dev = dev_get_drvdata(dev);
+ struct bmi160_data *data = iio_priv(indio_dev);
+
+ iio_device_unregister(indio_dev);
+ iio_triggered_buffer_cleanup(indio_dev);
+ bmi160_chip_uninit(data);
+}
+EXPORT_SYMBOL_GPL(bmi160_core_remove);
+
+MODULE_AUTHOR("Daniel Baluta <[email protected]");
+MODULE_DESCRIPTION("Bosch BMI160 driver");
+MODULE_LICENSE("GPL v2");
diff --git a/drivers/iio/imu/bmi160/bmi160_i2c.c b/drivers/iio/imu/bmi160/bmi160_i2c.c
new file mode 100644
index 0000000..af1feac
--- /dev/null
+++ b/drivers/iio/imu/bmi160/bmi160_i2c.c
@@ -0,0 +1,79 @@
+/*
+ * BMI160 - Bosch IMU, I2C bits
+ *
+ * Copyright (c) 2016, Intel Corporation.
+ *
+ * This file is subject to the terms and conditions of version 2 of
+ * the GNU General Public License. See the file COPYING in the main
+ * directory of this archive for more details.
+ *
+ * 7-bit I2C slave address is:
+ * - 0x68 if SDO is pulled to GND
+ * - 0x69 if SDO is pulled to VDDIO
+ */
+#include <linux/i2c.h>
+#include <linux/regmap.h>
+#include <linux/acpi.h>
+
+#include "bmi160.h"
+
+#define BMI160_I2C_DRV_NAME "bmi160_i2c"
+
+static const struct regmap_config bmi160_regmap_config = {
+ .reg_bits = 8,
+ .val_bits = 8,
+};
+
+static int bmi160_i2c_probe(struct i2c_client *client,
+ const struct i2c_device_id *id)
+{
+ struct regmap *regmap;
+ const char *name = NULL;
+
+ regmap = devm_regmap_init_i2c(client, &bmi160_regmap_config);
+ if (IS_ERR(regmap)) {
+ dev_err(&client->dev, "Failed to register i2c regmap %d\n",
+ (int)PTR_ERR(regmap));
+ return PTR_ERR(regmap);
+ }
+
+ if (id)
+ name = id->name;
+
+ return bmi160_core_probe(&client->dev, regmap, name, false);
+}
+
+static int bmi160_i2c_remove(struct i2c_client *client)
+{
+ bmi160_core_remove(&client->dev);
+
+ return 0;
+}
+
+static const struct i2c_device_id bmi160_i2c_id[] = {
+ {"bmi160", 0},
+ {}
+};
+MODULE_DEVICE_TABLE(i2c, bmi160_i2c_id);
+
+static const struct acpi_device_id bmi160_acpi_match[] = {
+ {"BMI0160", 0},
+ { },
+};
+MODULE_DEVICE_TABLE(acpi, bmi160_acpi_match);
+
+static struct i2c_driver bmi160_i2c_driver = {
+ .driver = {
+ .name = BMI160_I2C_DRV_NAME,
+ .acpi_match_table = ACPI_PTR(bmi160_acpi_match),
+ },
+ .probe = bmi160_i2c_probe,
+ .remove = bmi160_i2c_remove,
+ .id_table = bmi160_i2c_id,
+};
+
+module_i2c_driver(bmi160_i2c_driver);
+
+MODULE_AUTHOR("Daniel Baluta <[email protected]>");
+MODULE_DESCRIPTION("BMI160 I2C driver");
+MODULE_LICENSE("GPL v2");
diff --git a/drivers/iio/imu/bmi160/bmi160_spi.c b/drivers/iio/imu/bmi160/bmi160_spi.c
new file mode 100644
index 0000000..444b723
--- /dev/null
+++ b/drivers/iio/imu/bmi160/bmi160_spi.c
@@ -0,0 +1,71 @@
+/*
+ * BMI160 - Bosch IMU, SPI bits
+ *
+ * Copyright (c) 2016, Intel Corporation.
+ *
+ * This file is subject to the terms and conditions of version 2 of
+ * the GNU General Public License. See the file COPYING in the main
+ * directory of this archive for more details.
+ *
+ */
+#include <linux/spi/spi.h>
+#include <linux/regmap.h>
+#include <linux/acpi.h>
+
+#include "bmi160.h"
+
+#define BMI160_SPI_DRV_NAME "bmi160_spi"
+
+static const struct regmap_config bmi160_regmap_config = {
+ .reg_bits = 8,
+ .val_bits = 8,
+};
+
+static int bmi160_spi_probe(struct spi_device *spi)
+{
+ struct regmap *regmap;
+ const struct spi_device_id *id = spi_get_device_id(spi);
+
+ regmap = devm_regmap_init_spi(spi, &bmi160_regmap_config);
+ if (IS_ERR(regmap)) {
+ dev_err(&spi->dev, "Failed to register spi regmap %d\n",
+ (int)PTR_ERR(regmap));
+ return PTR_ERR(regmap);
+ }
+ return bmi160_core_probe(&spi->dev, regmap, id->name, true);
+}
+
+static int bmi160_spi_remove(struct spi_device *spi)
+{
+ bmi160_core_remove(&spi->dev);
+
+ return 0;
+}
+
+static const struct spi_device_id bmi160_spi_id[] = {
+ {"bmi160", 0},
+ {}
+};
+
+MODULE_DEVICE_TABLE(spi, bmi160_spi_id);
+
+static const struct acpi_device_id bmi160_acpi_match[] = {
+ {"BMI0160", 0},
+ { },
+};
+MODULE_DEVICE_TABLE(acpi, bmi160_acpi_match);
+
+static struct spi_driver bmi160_spi_driver = {
+ .probe = bmi160_spi_probe,
+ .remove = bmi160_spi_remove,
+ .id_table = bmi160_spi_id,
+ .driver = {
+ .acpi_match_table = ACPI_PTR(bmi160_acpi_match),
+ .name = BMI160_SPI_DRV_NAME,
+ },
+};
+module_spi_driver(bmi160_spi_driver);
+
+MODULE_AUTHOR("Daniel Baluta <[email protected]");
+MODULE_DESCRIPTION("Bosch BMI160 SPI driver");
+MODULE_LICENSE("GPL v2");
--
2.5.0


2016-04-01 14:11:58

by kernel test robot

[permalink] [raw]
Subject: Re: [PATCH] iio: imu: Add initial support for Bosch BMI160

Hi Daniel,

[auto build test ERROR on iio/togreg]
[also build test ERROR on v4.6-rc1 next-20160401]
[if your patch is applied to the wrong git tree, please drop us a note to help improving the system]

url: https://github.com/0day-ci/linux/commits/Daniel-Baluta/iio-imu-Add-initial-support-for-Bosch-BMI160/20160401-203058
base: https://git.kernel.org/pub/scm/linux/kernel/git/jic23/iio.git togreg
config: sparc-allmodconfig (attached as .config)
reproduce:
wget https://git.kernel.org/cgit/linux/kernel/git/wfg/lkp-tests.git/plain/sbin/make.cross -O ~/bin/make.cross
chmod +x ~/bin/make.cross
# save the attached .config to linux build tree
make.cross ARCH=sparc

All error/warnings (new ones prefixed by >>):

>> drivers/iio/imu/bmi160/bmi160_i2c.c:57:1: warning: data definition has no type or storage class
MODULE_DEVICE_TABLE(i2c, bmi160_i2c_id);
^
>> drivers/iio/imu/bmi160/bmi160_i2c.c:57:1: error: type defaults to 'int' in declaration of 'MODULE_DEVICE_TABLE' [-Werror=implicit-int]
>> drivers/iio/imu/bmi160/bmi160_i2c.c:57:1: warning: parameter names (without types) in function declaration
drivers/iio/imu/bmi160/bmi160_i2c.c:63:1: warning: data definition has no type or storage class
MODULE_DEVICE_TABLE(acpi, bmi160_acpi_match);
^
drivers/iio/imu/bmi160/bmi160_i2c.c:63:1: error: type defaults to 'int' in declaration of 'MODULE_DEVICE_TABLE' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_i2c.c:63:1: warning: parameter names (without types) in function declaration
In file included from include/linux/i2c.h:30:0,
from drivers/iio/imu/bmi160/bmi160_i2c.c:14:
include/linux/device.h:1332:1: warning: data definition has no type or storage class
module_init(__driver##_init); \
^
>> include/linux/i2c.h:666:2: note: in expansion of macro 'module_driver'
module_driver(__i2c_driver, i2c_add_driver, \
^
>> drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: note: in expansion of macro 'module_i2c_driver'
module_i2c_driver(bmi160_i2c_driver);
^
>> include/linux/device.h:1332:1: error: type defaults to 'int' in declaration of 'module_init' [-Werror=implicit-int]
module_init(__driver##_init); \
^
>> include/linux/i2c.h:666:2: note: in expansion of macro 'module_driver'
module_driver(__i2c_driver, i2c_add_driver, \
^
>> drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: note: in expansion of macro 'module_i2c_driver'
module_i2c_driver(bmi160_i2c_driver);
^
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: warning: parameter names (without types) in function declaration
In file included from include/linux/i2c.h:30:0,
from drivers/iio/imu/bmi160/bmi160_i2c.c:14:
include/linux/device.h:1337:1: warning: data definition has no type or storage class
module_exit(__driver##_exit);
^
>> include/linux/i2c.h:666:2: note: in expansion of macro 'module_driver'
module_driver(__i2c_driver, i2c_add_driver, \
^
>> drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: note: in expansion of macro 'module_i2c_driver'
module_i2c_driver(bmi160_i2c_driver);
^
>> include/linux/device.h:1337:1: error: type defaults to 'int' in declaration of 'module_exit' [-Werror=implicit-int]
module_exit(__driver##_exit);
^
>> include/linux/i2c.h:666:2: note: in expansion of macro 'module_driver'
module_driver(__i2c_driver, i2c_add_driver, \
^
>> drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: note: in expansion of macro 'module_i2c_driver'
module_i2c_driver(bmi160_i2c_driver);
^
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: warning: parameter names (without types) in function declaration
>> drivers/iio/imu/bmi160/bmi160_i2c.c:77:15: error: expected declaration specifiers or '...' before string constant
MODULE_AUTHOR("Daniel Baluta <[email protected]>");
^
drivers/iio/imu/bmi160/bmi160_i2c.c:78:20: error: expected declaration specifiers or '...' before string constant
MODULE_DESCRIPTION("BMI160 I2C driver");
^
drivers/iio/imu/bmi160/bmi160_i2c.c:79:16: error: expected declaration specifiers or '...' before string constant
MODULE_LICENSE("GPL v2");
^
In file included from include/linux/i2c.h:30:0,
from drivers/iio/imu/bmi160/bmi160_i2c.c:14:
drivers/iio/imu/bmi160/bmi160_i2c.c:75:19: warning: 'bmi160_i2c_driver_init' defined but not used [-Wunused-function]
module_i2c_driver(bmi160_i2c_driver);
^
include/linux/device.h:1328:19: note: in definition of macro 'module_driver'
static int __init __driver##_init(void) \
^
>> drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: note: in expansion of macro 'module_i2c_driver'
module_i2c_driver(bmi160_i2c_driver);
^
drivers/iio/imu/bmi160/bmi160_i2c.c:75:19: warning: 'bmi160_i2c_driver_exit' defined but not used [-Wunused-function]
module_i2c_driver(bmi160_i2c_driver);
^
include/linux/device.h:1333:20: note: in definition of macro 'module_driver'
static void __exit __driver##_exit(void) \
^
>> drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: note: in expansion of macro 'module_i2c_driver'
module_i2c_driver(bmi160_i2c_driver);
^
cc1: some warnings being treated as errors
--
>> drivers/iio/imu/bmi160/bmi160_spi.c:50:1: warning: data definition has no type or storage class
MODULE_DEVICE_TABLE(spi, bmi160_spi_id);
^
>> drivers/iio/imu/bmi160/bmi160_spi.c:50:1: error: type defaults to 'int' in declaration of 'MODULE_DEVICE_TABLE' [-Werror=implicit-int]
>> drivers/iio/imu/bmi160/bmi160_spi.c:50:1: warning: parameter names (without types) in function declaration
drivers/iio/imu/bmi160/bmi160_spi.c:56:1: warning: data definition has no type or storage class
MODULE_DEVICE_TABLE(acpi, bmi160_acpi_match);
^
drivers/iio/imu/bmi160/bmi160_spi.c:56:1: error: type defaults to 'int' in declaration of 'MODULE_DEVICE_TABLE' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_spi.c:56:1: warning: parameter names (without types) in function declaration
In file included from include/linux/spi/spi.h:18:0,
from drivers/iio/imu/bmi160/bmi160_spi.c:11:
include/linux/device.h:1332:1: warning: data definition has no type or storage class
module_init(__driver##_init); \
^
>> include/linux/spi/spi.h:283:2: note: in expansion of macro 'module_driver'
module_driver(__spi_driver, spi_register_driver, \
^
>> drivers/iio/imu/bmi160/bmi160_spi.c:67:1: note: in expansion of macro 'module_spi_driver'
module_spi_driver(bmi160_spi_driver);
^
>> include/linux/device.h:1332:1: error: type defaults to 'int' in declaration of 'module_init' [-Werror=implicit-int]
module_init(__driver##_init); \
^
>> include/linux/spi/spi.h:283:2: note: in expansion of macro 'module_driver'
module_driver(__spi_driver, spi_register_driver, \
^
>> drivers/iio/imu/bmi160/bmi160_spi.c:67:1: note: in expansion of macro 'module_spi_driver'
module_spi_driver(bmi160_spi_driver);
^
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: warning: parameter names (without types) in function declaration
In file included from include/linux/spi/spi.h:18:0,
from drivers/iio/imu/bmi160/bmi160_spi.c:11:
include/linux/device.h:1337:1: warning: data definition has no type or storage class
module_exit(__driver##_exit);
^
>> include/linux/spi/spi.h:283:2: note: in expansion of macro 'module_driver'
module_driver(__spi_driver, spi_register_driver, \
^
>> drivers/iio/imu/bmi160/bmi160_spi.c:67:1: note: in expansion of macro 'module_spi_driver'
module_spi_driver(bmi160_spi_driver);
^
>> include/linux/device.h:1337:1: error: type defaults to 'int' in declaration of 'module_exit' [-Werror=implicit-int]
module_exit(__driver##_exit);
^
>> include/linux/spi/spi.h:283:2: note: in expansion of macro 'module_driver'
module_driver(__spi_driver, spi_register_driver, \
^
>> drivers/iio/imu/bmi160/bmi160_spi.c:67:1: note: in expansion of macro 'module_spi_driver'
module_spi_driver(bmi160_spi_driver);
^
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: warning: parameter names (without types) in function declaration
>> drivers/iio/imu/bmi160/bmi160_spi.c:69:15: error: expected declaration specifiers or '...' before string constant
MODULE_AUTHOR("Daniel Baluta <[email protected]");
^
drivers/iio/imu/bmi160/bmi160_spi.c:70:20: error: expected declaration specifiers or '...' before string constant
MODULE_DESCRIPTION("Bosch BMI160 SPI driver");
^
drivers/iio/imu/bmi160/bmi160_spi.c:71:16: error: expected declaration specifiers or '...' before string constant
MODULE_LICENSE("GPL v2");
^
In file included from include/linux/spi/spi.h:18:0,
from drivers/iio/imu/bmi160/bmi160_spi.c:11:
drivers/iio/imu/bmi160/bmi160_spi.c:67:19: warning: 'bmi160_spi_driver_init' defined but not used [-Wunused-function]
module_spi_driver(bmi160_spi_driver);
^
include/linux/device.h:1328:19: note: in definition of macro 'module_driver'
static int __init __driver##_init(void) \
^
>> drivers/iio/imu/bmi160/bmi160_spi.c:67:1: note: in expansion of macro 'module_spi_driver'
module_spi_driver(bmi160_spi_driver);
^
drivers/iio/imu/bmi160/bmi160_spi.c:67:19: warning: 'bmi160_spi_driver_exit' defined but not used [-Wunused-function]
module_spi_driver(bmi160_spi_driver);
^
include/linux/device.h:1333:20: note: in definition of macro 'module_driver'
static void __exit __driver##_exit(void) \
^
>> drivers/iio/imu/bmi160/bmi160_spi.c:67:1: note: in expansion of macro 'module_spi_driver'
module_spi_driver(bmi160_spi_driver);
^
cc1: some warnings being treated as errors

vim +57 drivers/iio/imu/bmi160/bmi160_i2c.c

51 }
52
53 static const struct i2c_device_id bmi160_i2c_id[] = {
54 {"bmi160", 0},
55 {}
56 };
> 57 MODULE_DEVICE_TABLE(i2c, bmi160_i2c_id);
58
59 static const struct acpi_device_id bmi160_acpi_match[] = {
60 {"BMI0160", 0},
61 { },
62 };
> 63 MODULE_DEVICE_TABLE(acpi, bmi160_acpi_match);
64
65 static struct i2c_driver bmi160_i2c_driver = {
66 .driver = {
67 .name = BMI160_I2C_DRV_NAME,
68 .acpi_match_table = ACPI_PTR(bmi160_acpi_match),
69 },
70 .probe = bmi160_i2c_probe,
71 .remove = bmi160_i2c_remove,
72 .id_table = bmi160_i2c_id,
73 };
74
> 75 module_i2c_driver(bmi160_i2c_driver);
76
> 77 MODULE_AUTHOR("Daniel Baluta <[email protected]>");
78 MODULE_DESCRIPTION("BMI160 I2C driver");
79 MODULE_LICENSE("GPL v2");

---
0-DAY kernel test infrastructure Open Source Technology Center
https://lists.01.org/pipermail/kbuild-all Intel Corporation


Attachments:
(No filename) (10.81 kB)
.config.gz (43.86 kB)
Download all attachments

2016-04-01 14:28:19

by Peter Meerwald-Stadler

[permalink] [raw]
Subject: Re: [PATCH] iio: imu: Add initial support for Bosch BMI160


> BMI160 is an Inertial Measurement Unit (IMU) which provides acceleration
> and angular rate measurement. It also offers a secondary I2C interface
> for connecting a magnetometer sensor (usually BMM160).
>
> Current driver offers support for accelerometer and gyroscope readings
> via sysfs or via buffer interface using an external trigger (e.g.
> hrtimer). Data is retrieved from IMU via I2C or SPI interface.

comments below

> Datasheet is at:
> http://www.mouser.com/ds/2/783/BST-BMI160-DS000-07-786474.pdf
>
> Signed-off-by: Daniel Baluta <[email protected]>
> ---
> drivers/iio/imu/Kconfig | 2 +
> drivers/iio/imu/Makefile | 1 +
> drivers/iio/imu/bmi160/Kconfig | 32 ++
> drivers/iio/imu/bmi160/Makefile | 6 +
> drivers/iio/imu/bmi160/bmi160.h | 8 +
> drivers/iio/imu/bmi160/bmi160_core.c | 588 +++++++++++++++++++++++++++++++++++
> drivers/iio/imu/bmi160/bmi160_i2c.c | 79 +++++
> drivers/iio/imu/bmi160/bmi160_spi.c | 71 +++++
> 8 files changed, 787 insertions(+)
> create mode 100644 drivers/iio/imu/bmi160/Kconfig
> create mode 100644 drivers/iio/imu/bmi160/Makefile
> create mode 100644 drivers/iio/imu/bmi160/bmi160.h
> create mode 100644 drivers/iio/imu/bmi160/bmi160_core.c
> create mode 100644 drivers/iio/imu/bmi160/bmi160_i2c.c
> create mode 100644 drivers/iio/imu/bmi160/bmi160_spi.c
>
> diff --git a/drivers/iio/imu/Kconfig b/drivers/iio/imu/Kconfig
> index 5e610f7..1f1ad41 100644
> --- a/drivers/iio/imu/Kconfig
> +++ b/drivers/iio/imu/Kconfig
> @@ -25,6 +25,8 @@ config ADIS16480
> Say yes here to build support for Analog Devices ADIS16375, ADIS16480,
> ADIS16485, ADIS16488 inertial sensors.
>
> +source "drivers/iio/imu/bmi160/Kconfig"
> +
> config KMX61
> tristate "Kionix KMX61 6-axis accelerometer and magnetometer"
> depends on I2C
> diff --git a/drivers/iio/imu/Makefile b/drivers/iio/imu/Makefile
> index e1e6e3d..c71bcd3 100644
> --- a/drivers/iio/imu/Makefile
> +++ b/drivers/iio/imu/Makefile
> @@ -13,6 +13,7 @@ adis_lib-$(CONFIG_IIO_ADIS_LIB_BUFFER) += adis_trigger.o
> adis_lib-$(CONFIG_IIO_ADIS_LIB_BUFFER) += adis_buffer.o
> obj-$(CONFIG_IIO_ADIS_LIB) += adis_lib.o
>
> +obj-y += bmi160/
> obj-y += inv_mpu6050/
>
> obj-$(CONFIG_KMX61) += kmx61.o
> diff --git a/drivers/iio/imu/bmi160/Kconfig b/drivers/iio/imu/bmi160/Kconfig
> new file mode 100644
> index 0000000..adb512f
> --- /dev/null
> +++ b/drivers/iio/imu/bmi160/Kconfig
> @@ -0,0 +1,32 @@
> +#
> +# BMI160 IMU driver
> +#
> +
> +config BMI160
> + tristate
> + select IIO_BUFFER
> + select IIO_TRIGGERED_BUFFER
> +
> +config BMI160_I2C
> + tristate "Bosch BMI160 I2C driver"
> + depends on I2C
> + select BMI160
> + select REGMAP_I2C
> + help
> + If you say yes you get support BMI160 IMU on I2C with accelerometer,
> + gyroscope and external BMG160 magnetometer.

get support _for_

> +
> + This driver can also be built as a module. If so, the module will be
> + called bmi160_i2c.
> +
> +config BMI160_SPI
> + tristate "Bosch BMI160 SPI driver"
> + depends on SPI
> + select BMI160
> + select REGMAP_SPI
> + help
> + If you say yes you get support BMI160 IMU on SPI with accelerometer,

get support _for_

> + gyroscope and external BMG160 magnetometer.
> +
> + This driver can also be built as a module. If so, the module will be
> + called bmi160_i2c.

bmi160_spi

> diff --git a/drivers/iio/imu/bmi160/Makefile b/drivers/iio/imu/bmi160/Makefile
> new file mode 100644
> index 0000000..10365e4
> --- /dev/null
> +++ b/drivers/iio/imu/bmi160/Makefile
> @@ -0,0 +1,6 @@
> +#
> +# Makefile for Bosch BMI160 IMU
> +#
> +obj-$(CONFIG_BMI160) += bmi160_core.o
> +obj-$(CONFIG_BMI160_I2C) += bmi160_i2c.o
> +obj-$(CONFIG_BMI160_SPI) += bmi160_spi.o
> diff --git a/drivers/iio/imu/bmi160/bmi160.h b/drivers/iio/imu/bmi160/bmi160.h
> new file mode 100644
> index 0000000..c5f7b2d
> --- /dev/null
> +++ b/drivers/iio/imu/bmi160/bmi160.h
> @@ -0,0 +1,8 @@
> +#ifndef BMI160_H_
> +#define BMI160_H_
> +
> +int bmi160_core_probe(struct device *dev, struct regmap *regmap,
> + const char *name, bool use_spi);
> +void bmi160_core_remove(struct device *dev);
> +
> +#endif /* BMI160_H_ */
> diff --git a/drivers/iio/imu/bmi160/bmi160_core.c b/drivers/iio/imu/bmi160/bmi160_core.c
> new file mode 100644
> index 0000000..d6ce643
> --- /dev/null
> +++ b/drivers/iio/imu/bmi160/bmi160_core.c
> @@ -0,0 +1,588 @@
> +/*
> + * BMI160 - Bosch IMU (accel, gyro plus external magnetometer)
> + *
> + * Copyright (c) 2016, Intel Corporation.
> + *
> + * This file is subject to the terms and conditions of version 2 of
> + * the GNU General Public License. See the file COPYING in the main
> + * directory of this archive for more details.
> + *
> + * IIO core driver for BMI160, with support for I2C/SPI busses
> + *
> + * TODO: magnetometer, interrupts, hardware FIFO
> + */
> +#include <linux/module.h>
> +#include <linux/regmap.h>
> +#include <linux/acpi.h>
> +#include <linux/delay.h>
> +
> +#include <linux/iio/iio.h>
> +#include <linux/iio/triggered_buffer.h>
> +#include <linux/iio/trigger_consumer.h>
> +#include <linux/iio/buffer.h>
> +
> +#include "bmi160.h"
> +
> +#define BMI160_REG_CHIP_ID 0x00
> +#define BMI160_CHIP_ID_VAL 0xD1
> +
> +#define BMI160_REG_PMU_STATUS 0x03
> +
> +/* X axis data low byte address, the rest can be obtained using axis offset */
> +#define BMI160_REG_DATA_MAGN_XOUT_L 0x04
> +#define BMI160_REG_DATA_GYRO_XOUT_L 0x0C
> +#define BMI160_REG_DATA_ACCEL_XOUT_L 0x12
> +
> +#define BMI160_REG_ACCEL_CONFIG 0x40
> +#define BMI160_ACCEL_CONFIG_ODR_MASK GENMASK(3, 0)
> +#define BMI160_ACCEL_CONFIG_BWP_MASK GENMASK(6, 4)
> +
> +#define BMI160_REG_ACCEL_RANGE 0x41
> +#define BMI160_ACCEL_RANGE_2G 0x03
> +#define BMI160_ACCEL_RANGE_4G 0x05
> +#define BMI160_ACCEL_RANGE_8G 0x08
> +#define BMI160_ACCEL_RANGE_16G 0x0C
> +
> +#define BMI160_REG_GYRO_CONFIG 0x42
> +#define BMI160_GYRO_CONFIG_ODR_MASK GENMASK(3, 0)
> +#define BMI160_GYRO_CONFIG_BWP_MASK GENMASK(5, 4)
> +
> +#define BMI160_REG_GYRO_RANGE 0x43
> +#define BMI160_GYRO_RANGE_2000DPS 0x00
> +#define BMI160_GYRO_RANGE_1000DPS 0x01
> +#define BMI160_GYRO_RANGE_500DPS 0x02
> +#define BMI160_GYRO_RANGE_250DPS 0x03
> +#define BMI160_GYRO_RANGE_125DPS 0x04
> +
> +#define BMI160_REG_CMD 0x7E
> +#define BMI160_CMD_ACCEL_PM_SUSPEND 0x10
> +#define BMI160_CMD_ACCEL_PM_NORMAL 0x11
> +#define BMI160_CMD_ACCEL_PM_LOW_POWER 0x12
> +#define BMI160_CMD_GYRO_PM_SUSPEND 0x14
> +#define BMI160_CMD_GYRO_PM_NORMAL 0x15
> +#define BMI160_CMD_GYRO_PM_FAST_STARTUP 0x17
> +#define BMI160_CMD_SOFTRESET 0xB6
> +
> +#define BMI160_REG_DUMMY 0x7F
> +
> +#define BMI160_ACCEL_PMU_MIN_SLEEP 3200 /* usec */
> +#define BMI160_ACCEL_PMU_MAX_SLEEP 3800
> +#define BMI160_GYRO_PMU_MIN_SLEEP 55000
> +#define BMI160_GYRO_PMU_MAX_SLEEP 80000
> +#define BMI160_SOFTRESET_SLEEP 1000

all in usec?

> +
> +#define BMI160_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_SAMP_FREQ), \
> + .scan_index = _index, \
> + .scan_type = { \
> + .sign = 's', \
> + .realbits = 16, \
> + .storagebits = 16, \
> + .shift = 0, \

no need to specify shift

> + .endianness = IIO_LE, \
> + }, \
> +}
> +
> +/* scan indexes follow DATA register order */
> +enum bmi160_scan_axis {
> + BMI160_SCAN_EXT_MAGN_X = 0,
> + BMI160_SCAN_EXT_MAGN_Y,
> + BMI160_SCAN_EXT_MAGN_Z,
> + BMI160_SCAN_RHALL,
> + BMI160_SCAN_GYRO_X,
> + BMI160_SCAN_GYRO_Y,
> + BMI160_SCAN_GYRO_Z,
> + BMI160_SCAN_ACCEL_X,
> + BMI160_SCAN_ACCEL_Y,
> + BMI160_SCAN_ACCEL_Z,
> + BMI160_SCAN_TIMESTAMP,
> +};
> +
> +enum bmi160_sensor_type {
> + BMI160_ACCEL = 0,
> + BMI160_GYRO,
> + BMI160_EXT_MAGN,
> + BMI160_NUM_SENSORS /* must be last */
> +};
> +
> +struct bmi160_data {
> + struct regmap *regmap;
> +};
> +
> +struct bmi160_regs {
> + u8 data; /* LSB byte register for X-axis */
> + u8 config;
> + u8 config_odr_mask;
> + u8 config_bwp_mask;
> + u8 range;
> + u8 pmu_cmd_normal;
> + u8 pmu_cmd_suspend;
> +};
> +
> +struct bmi160_regs bmi160_regs[] = {
> + [BMI160_ACCEL] = {
> + .data = BMI160_REG_DATA_ACCEL_XOUT_L,
> + .config = BMI160_REG_ACCEL_CONFIG,
> + .config_odr_mask = BMI160_ACCEL_CONFIG_ODR_MASK,
> + .config_bwp_mask = BMI160_ACCEL_CONFIG_BWP_MASK,
> + .range = BMI160_REG_ACCEL_RANGE,
> + .pmu_cmd_normal = BMI160_CMD_ACCEL_PM_NORMAL,
> + .pmu_cmd_suspend = BMI160_CMD_ACCEL_PM_SUSPEND,
> + },
> + [BMI160_GYRO] = {
> + .data = BMI160_REG_DATA_GYRO_XOUT_L,
> + .config = BMI160_REG_GYRO_CONFIG,
> + .config_odr_mask = BMI160_GYRO_CONFIG_ODR_MASK,
> + .config_bwp_mask = BMI160_GYRO_CONFIG_BWP_MASK,
> + .range = BMI160_REG_GYRO_RANGE,
> + .pmu_cmd_normal = BMI160_CMD_GYRO_PM_NORMAL,
> + .pmu_cmd_suspend = BMI160_CMD_GYRO_PM_SUSPEND,
> + },
> +};
> +
> +struct bmi160_pmu_time {
> + unsigned long min;
> + unsigned long max;
> +};
> +
> +struct bmi160_pmu_time bmi160_pmu_time[] = {
> + [BMI160_ACCEL] = {
> + .min = BMI160_ACCEL_PMU_MIN_SLEEP,
> + .max = BMI160_ACCEL_PMU_MAX_SLEEP
> + },
> + [BMI160_GYRO] = {
> + .min = BMI160_GYRO_PMU_MIN_SLEEP,
> + .max = BMI160_GYRO_PMU_MIN_SLEEP,
> + },
> +};
> +
> +struct bmi160_scale {
> + u8 bits;
> + int uscale;
> +};
> +
> +struct bmi160_odr {
> + u8 bits;
> + int odr;
> + int uodr;
> +};
> +
> +static const struct bmi160_scale bmi160_accel_scale[] = {
> + { BMI160_ACCEL_RANGE_2G, 598},
> + { BMI160_ACCEL_RANGE_4G, 1197},
> + { BMI160_ACCEL_RANGE_8G, 2394},
> + { BMI160_ACCEL_RANGE_16G, 4788},
> +};
> +
> +static const struct bmi160_scale bmi160_gyro_scale[] = {
> + { BMI160_GYRO_RANGE_2000DPS, 1065},
> + { BMI160_GYRO_RANGE_1000DPS, 532},
> + { BMI160_GYRO_RANGE_500DPS, 266},
> + { BMI160_GYRO_RANGE_250DPS, 133},
> + { BMI160_GYRO_RANGE_125DPS, 66},
> +

remove newline

> +};
> +
> +struct bmi160_scale_item {
> + const struct bmi160_scale *tbl;
> + int num;
> +};
> +
> +static const struct bmi160_scale_item bmi160_scale_table[] = {
> + [BMI160_ACCEL] = {
> + .tbl = bmi160_accel_scale,
> + .num = ARRAY_SIZE(bmi160_accel_scale),
> + },
> + [BMI160_GYRO] = {
> + .tbl = bmi160_gyro_scale,
> + .num = ARRAY_SIZE(bmi160_gyro_scale),
> + },
> +};
> +
> +static const struct bmi160_odr bmi160_accel_odr[] = {
> + {0x01, 0, 78125},
> + {0x02, 1, 5625},
> + {0x03, 3, 125},
> + {0x04, 6, 25},
> + {0x05, 12, 5},
> + {0x06, 25, 0},
> + {0x07, 50, 0},
> + {0x08, 100, 0},
> + {0x09, 200, 0},
> + {0x0A, 400, 0},
> + {0x0B, 800, 0},
> + {0x0C, 1600, 0},
> +};
> +
> +static const struct bmi160_odr bmi160_gyro_odr[] = {
> + {0x06, 25, 0},
> + {0x07, 50, 0},
> + {0x08, 100, 0},
> + {0x09, 200, 0},
> + {0x0A, 400, 0},
> + {0x0B, 8000, 0},
> + {0x0C, 1600, 0},
> + {0x0D, 3200, 0},
> +};
> +
> +struct bmi160_odr_item {
> + const struct bmi160_odr *tbl;
> + int num;
> +};
> +
> +static const struct bmi160_odr_item bmi160_odr_table[] = {
> + [BMI160_ACCEL] = {
> + .tbl = bmi160_accel_odr,
> + .num = ARRAY_SIZE(bmi160_accel_odr),
> + },
> + [BMI160_GYRO] = {
> + .tbl = bmi160_gyro_odr,
> + .num = ARRAY_SIZE(bmi160_gyro_odr),
> + },
> +};
> +
> +static const struct iio_chan_spec bmi160_channels[] = {
> + BMI160_CHANNEL(IIO_ACCEL, X, BMI160_SCAN_ACCEL_X),
> + BMI160_CHANNEL(IIO_ACCEL, Y, BMI160_SCAN_ACCEL_Y),
> + BMI160_CHANNEL(IIO_ACCEL, Z, BMI160_SCAN_ACCEL_Z),
> + BMI160_CHANNEL(IIO_ANGL_VEL, X, BMI160_SCAN_GYRO_X),
> + BMI160_CHANNEL(IIO_ANGL_VEL, Y, BMI160_SCAN_GYRO_Y),
> + BMI160_CHANNEL(IIO_ANGL_VEL, Z, BMI160_SCAN_GYRO_Z),
> + IIO_CHAN_SOFT_TIMESTAMP(BMI160_SCAN_TIMESTAMP),
> +};
> +
> +static enum bmi160_sensor_type bmi160_to_sensor(enum iio_chan_type iio_type)
> +{
> + switch (iio_type) {
> + case IIO_ACCEL:
> + return BMI160_ACCEL;
> + case IIO_ANGL_VEL:
> + return BMI160_GYRO;
> + default:
> + return -EINVAL;
> + }
> +}
> +
> +static
> +int bmi160_set_mode(struct bmi160_data *data, enum bmi160_sensor_type t,
> + int mode)

mode could be bool?

> +{
> + int ret;
> + u8 cmd;
> +
> + if (mode)
> + cmd = bmi160_regs[t].pmu_cmd_normal;
> + else
> + cmd = bmi160_regs[t].pmu_cmd_suspend;
> +
> + ret = regmap_write(data->regmap, BMI160_REG_CMD, cmd);
> + if (ret < 0)
> + return ret;
> +
> + usleep_range(bmi160_pmu_time[t].min, bmi160_pmu_time[t].max);
> +
> + return 0;
> +}
> +
> +static
> +int bmi160_set_scale(struct bmi160_data *data, enum bmi160_sensor_type t,
> + int uscale)
> +{
> + int i;
> +
> + for (i = 0; i < bmi160_scale_table[t].num; i++)
> + if (bmi160_scale_table[t].tbl[i].uscale == uscale)
> + break;
> +
> + if (i == bmi160_scale_table[t].num)
> + return -EINVAL;
> +
> + return regmap_write(data->regmap, bmi160_regs[t].range,
> + bmi160_scale_table[t].tbl[i].bits);
> +}
> +
> +static
> +int bmi160_get_scale(struct bmi160_data *data, enum bmi160_sensor_type t,
> + int *uscale)
> +{
> + int i, ret, val;
> +
> + ret = regmap_read(data->regmap, bmi160_regs[t].range, &val);
> + if (ret < 0)
> + return ret;
> +
> + for (i = 0; i < bmi160_scale_table[t].num; i++)
> + if (bmi160_scale_table[t].tbl[i].bits == val) {
> + *uscale = bmi160_scale_table[t].tbl[i].uscale;
> + return 0;
> + }
> +
> + return -EINVAL;
> +}
> +
> +static int bmi160_get_data(struct bmi160_data *data, int chan_type,
> + int axis, int *val)
> +{
> + u8 reg;
> + int ret;
> + __le16 sample;
> + enum bmi160_sensor_type t = bmi160_to_sensor(chan_type);
> +
> + reg = bmi160_regs[t].data + (axis - IIO_MOD_X) * 2;

2 is sizeof(sample)

> +
> + ret = regmap_bulk_read(data->regmap, reg, &sample, sizeof(sample));
> + if (ret < 0)
> + return ret;
> +
> + *val = sign_extend32(le16_to_cpu(sample), 15);
> +
> + return 0;
> +}
> +
> +static
> +int bmi160_set_odr(struct bmi160_data *data, enum bmi160_sensor_type t,
> + int odr, int uodr)
> +{
> + int i;
> +
> + for (i = 0; i < bmi160_odr_table[t].num; i++)
> + if (bmi160_odr_table[t].tbl[i].odr == odr &&
> + bmi160_odr_table[t].tbl[i].uodr == uodr)
> + break;
> +
> + if (i >= bmi160_odr_table[t].num)
> + return -EINVAL;
> +
> + return regmap_update_bits(data->regmap,
> + bmi160_regs[t].config,
> + bmi160_odr_table[t].tbl[i].bits,
> + bmi160_regs[t].config_odr_mask);
> +}
> +
> +static int bmi160_get_odr(struct bmi160_data *data, enum bmi160_sensor_type t,
> + int *odr, int *uodr)
> +{
> + int i, val, ret;
> +
> + ret = regmap_read(data->regmap, bmi160_regs[t].config, &val);
> + if (ret < 0)
> + return ret;
> +
> + val &= bmi160_regs[t].config_odr_mask;
> +
> + for (i = 0; i < bmi160_odr_table[t].num; i++)
> + if (val == bmi160_odr_table[t].tbl[i].bits)
> + break;
> +
> + if (i >= bmi160_odr_table[t].num)
> + return -EINVAL;
> +
> + *odr = bmi160_odr_table[t].tbl[i].odr;
> + *uodr = bmi160_odr_table[t].tbl[i].uodr;
> +
> + return 0;
> +}
> +
> +static irqreturn_t bmi160_trigger_handler(int irq, void *p)
> +{
> + struct iio_poll_func *pf = p;
> + struct iio_dev *indio_dev = pf->indio_dev;
> + struct bmi160_data *data = iio_priv(indio_dev);
> + s16 buf[16]; /* 3 sens x 3 axis x s16 + 3 x s16 pad + 4 x s16 tstamp */
> + int i, ret, sample, j = 0, base = BMI160_REG_DATA_MAGN_XOUT_L;
> +
> + for_each_set_bit(i, indio_dev->active_scan_mask,
> + indio_dev->masklength) {
> + ret = regmap_bulk_read(data->regmap, base + 2 * i, &sample,
> + sizeof(sample));

sizeof(sample) is sizeof(int), but I think this should be 2 or better
sizeof(__le16)

sample should be __le16

do
base + 2*sizeof(sample)
then

> + if (ret < 0)
> + goto done;
> + buf[j++] = sample;
> + }
> +
> + iio_push_to_buffers_with_timestamp(indio_dev, buf, iio_get_time_ns());
> +done:
> + iio_trigger_notify_done(indio_dev->trig);
> + return IRQ_HANDLED;
> +}
> +
> +static int bmi160_read_raw(struct iio_dev *indio_dev,
> + struct iio_chan_spec const *chan,
> + int *val, int *val2, long mask)
> +{
> + int ret;
> + struct bmi160_data *data = iio_priv(indio_dev);
> +
> + switch (mask) {
> + case IIO_CHAN_INFO_RAW:
> + ret = bmi160_get_data(data, chan->type, chan->channel2, val);
> + if (ret < 0)
> + return ret;
> + return IIO_VAL_INT;
> + case IIO_CHAN_INFO_SCALE:
> + *val = 0;
> + ret = bmi160_get_scale(data,
> + bmi160_to_sensor(chan->type), val2);
> + return ret < 0 ? ret : IIO_VAL_INT_PLUS_MICRO;
> + case IIO_CHAN_INFO_SAMP_FREQ:
> + ret = bmi160_get_odr(data, bmi160_to_sensor(chan->type),
> + val, val2);
> + return ret < 0 ? ret : IIO_VAL_INT_PLUS_MICRO;
> + default:
> + return -EINVAL;
> + }
> +
> + return 0;
> +}
> +
> +static int bmi160_write_raw(struct iio_dev *indio_dev,
> + struct iio_chan_spec const *chan,
> + int val, int val2, long mask)
> +{
> + struct bmi160_data *data = iio_priv(indio_dev);
> +
> + switch (mask) {
> + case IIO_CHAN_INFO_SCALE:
> + return bmi160_set_scale(data,
> + bmi160_to_sensor(chan->type), val2);
> + break;
> + case IIO_CHAN_INFO_SAMP_FREQ:
> + return bmi160_set_odr(data, bmi160_to_sensor(chan->type),
> + val, val2);
> + default:
> + return -EINVAL;
> + }
> +
> + return 0;
> +}
> +
> +static const struct iio_info bmi160_info = {
> + .driver_module = THIS_MODULE,
> + .read_raw = bmi160_read_raw,
> + .write_raw = bmi160_write_raw,
> +};
> +
> +static const char *bmi160_match_acpi_device(struct device *dev)
> +{
> + const struct acpi_device_id *id;
> +
> + id = acpi_match_device(dev->driver->acpi_match_table, dev);
> + if (!id)
> + return NULL;
> +
> + return dev_name(dev);
> +}
> +
> +static int bmi160_chip_init(struct bmi160_data *data, bool use_spi)
> +{
> + int ret;
> + unsigned int val;
> + struct device *dev = regmap_get_device(data->regmap);
> +
> + ret = regmap_write(data->regmap, BMI160_REG_CMD, BMI160_CMD_SOFTRESET);
> + if (ret < 0)
> + return ret;
> +
> + usleep_range(BMI160_SOFTRESET_SLEEP, BMI160_SOFTRESET_SLEEP + 1);
> +
> + /* CS rising edge is needed before starting SPI, so do a dummy read */
> + if (use_spi) {
> + ret = regmap_read(data->regmap, BMI160_REG_DUMMY, &val);
> + if (ret < 0)
> + return ret;
> + }
> +
> + ret = regmap_read(data->regmap, BMI160_REG_CHIP_ID, &val);
> + if (ret < 0) {
> + dev_err(dev, "Error reading chip id\n");
> + return ret;
> + }
> + if (val != BMI160_CHIP_ID_VAL) {
> + dev_err(dev, "Wrong chip id, got %x expected %x\n",
> + val, BMI160_CHIP_ID_VAL);
> + return -ENODEV;
> + }
> +
> + ret = bmi160_set_mode(data, BMI160_ACCEL, 1);

1 -> true

> + if (ret < 0)
> + return ret;
> +
> + ret = bmi160_set_mode(data, BMI160_GYRO, 1);
> + if (ret < 0)
> + return ret;
> +
> + return 0;
> +}
> +
> +static void bmi160_chip_uninit(struct bmi160_data *data)
> +{
> + bmi160_set_mode(data, BMI160_GYRO, 0);
> + bmi160_set_mode(data, BMI160_ACCEL, 0);
> +}
> +
> +int bmi160_core_probe(struct device *dev, struct regmap *regmap,
> + const char *name, bool use_spi)
> +{
> + struct iio_dev *indio_dev;
> + struct bmi160_data *data;
> + int ret;
> +
> + 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;
> +
> + ret = bmi160_chip_init(data, use_spi);
> + if (ret < 0)
> + return ret;
> +
> + if (!name && ACPI_HANDLE(dev))
> + name = bmi160_match_acpi_device(dev);
> +
> + indio_dev->dev.parent = dev;
> + indio_dev->channels = bmi160_channels;
> + indio_dev->num_channels = ARRAY_SIZE(bmi160_channels);
> + indio_dev->name = name;
> + indio_dev->modes = INDIO_DIRECT_MODE;
> + indio_dev->info = &bmi160_info;
> +
> + ret = iio_triggered_buffer_setup(indio_dev, NULL,
> + bmi160_trigger_handler, NULL);
> + if (ret < 0)
> + goto uninit;
> +
> + ret = iio_device_register(indio_dev);
> + if (ret < 0)
> + goto buffer_cleanup;
> +
> + return 0;
> +uninit:
> + bmi160_chip_uninit(data);
> +buffer_cleanup:
> + iio_triggered_buffer_cleanup(indio_dev);
> + return ret;
> +}
> +EXPORT_SYMBOL_GPL(bmi160_core_probe);
> +
> +void bmi160_core_remove(struct device *dev)
> +{
> + struct iio_dev *indio_dev = dev_get_drvdata(dev);
> + struct bmi160_data *data = iio_priv(indio_dev);
> +
> + iio_device_unregister(indio_dev);
> + iio_triggered_buffer_cleanup(indio_dev);
> + bmi160_chip_uninit(data);
> +}
> +EXPORT_SYMBOL_GPL(bmi160_core_remove);
> +
> +MODULE_AUTHOR("Daniel Baluta <[email protected]");
> +MODULE_DESCRIPTION("Bosch BMI160 driver");
> +MODULE_LICENSE("GPL v2");
> diff --git a/drivers/iio/imu/bmi160/bmi160_i2c.c b/drivers/iio/imu/bmi160/bmi160_i2c.c
> new file mode 100644
> index 0000000..af1feac
> --- /dev/null
> +++ b/drivers/iio/imu/bmi160/bmi160_i2c.c
> @@ -0,0 +1,79 @@
> +/*
> + * BMI160 - Bosch IMU, I2C bits
> + *
> + * Copyright (c) 2016, Intel Corporation.
> + *
> + * This file is subject to the terms and conditions of version 2 of
> + * the GNU General Public License. See the file COPYING in the main
> + * directory of this archive for more details.
> + *
> + * 7-bit I2C slave address is:
> + * - 0x68 if SDO is pulled to GND
> + * - 0x69 if SDO is pulled to VDDIO
> + */
> +#include <linux/i2c.h>
> +#include <linux/regmap.h>
> +#include <linux/acpi.h>
> +
> +#include "bmi160.h"
> +
> +#define BMI160_I2C_DRV_NAME "bmi160_i2c"
> +
> +static const struct regmap_config bmi160_regmap_config = {

could this be shared between i2c and spi?

> + .reg_bits = 8,
> + .val_bits = 8,
> +};
> +
> +static int bmi160_i2c_probe(struct i2c_client *client,
> + const struct i2c_device_id *id)
> +{
> + struct regmap *regmap;
> + const char *name = NULL;
> +
> + regmap = devm_regmap_init_i2c(client, &bmi160_regmap_config);
> + if (IS_ERR(regmap)) {
> + dev_err(&client->dev, "Failed to register i2c regmap %d\n",
> + (int)PTR_ERR(regmap));
> + return PTR_ERR(regmap);
> + }
> +
> + if (id)
> + name = id->name;
> +
> + return bmi160_core_probe(&client->dev, regmap, name, false);
> +}
> +
> +static int bmi160_i2c_remove(struct i2c_client *client)
> +{
> + bmi160_core_remove(&client->dev);
> +
> + return 0;
> +}
> +
> +static const struct i2c_device_id bmi160_i2c_id[] = {
> + {"bmi160", 0},
> + {}
> +};
> +MODULE_DEVICE_TABLE(i2c, bmi160_i2c_id);
> +
> +static const struct acpi_device_id bmi160_acpi_match[] = {
> + {"BMI0160", 0},
> + { },
> +};
> +MODULE_DEVICE_TABLE(acpi, bmi160_acpi_match);
> +
> +static struct i2c_driver bmi160_i2c_driver = {
> + .driver = {
> + .name = BMI160_I2C_DRV_NAME,
> + .acpi_match_table = ACPI_PTR(bmi160_acpi_match),
> + },
> + .probe = bmi160_i2c_probe,
> + .remove = bmi160_i2c_remove,
> + .id_table = bmi160_i2c_id,
> +};
> +
> +module_i2c_driver(bmi160_i2c_driver);
> +
> +MODULE_AUTHOR("Daniel Baluta <[email protected]>");
> +MODULE_DESCRIPTION("BMI160 I2C driver");
> +MODULE_LICENSE("GPL v2");
> diff --git a/drivers/iio/imu/bmi160/bmi160_spi.c b/drivers/iio/imu/bmi160/bmi160_spi.c
> new file mode 100644
> index 0000000..444b723
> --- /dev/null
> +++ b/drivers/iio/imu/bmi160/bmi160_spi.c
> @@ -0,0 +1,71 @@
> +/*
> + * BMI160 - Bosch IMU, SPI bits
> + *
> + * Copyright (c) 2016, Intel Corporation.
> + *
> + * This file is subject to the terms and conditions of version 2 of
> + * the GNU General Public License. See the file COPYING in the main
> + * directory of this archive for more details.
> + *
> + */
> +#include <linux/spi/spi.h>
> +#include <linux/regmap.h>
> +#include <linux/acpi.h>
> +
> +#include "bmi160.h"
> +
> +#define BMI160_SPI_DRV_NAME "bmi160_spi"
> +
> +static const struct regmap_config bmi160_regmap_config = {
> + .reg_bits = 8,
> + .val_bits = 8,
> +};
> +
> +static int bmi160_spi_probe(struct spi_device *spi)
> +{
> + struct regmap *regmap;
> + const struct spi_device_id *id = spi_get_device_id(spi);
> +
> + regmap = devm_regmap_init_spi(spi, &bmi160_regmap_config);
> + if (IS_ERR(regmap)) {
> + dev_err(&spi->dev, "Failed to register spi regmap %d\n",
> + (int)PTR_ERR(regmap));
> + return PTR_ERR(regmap);
> + }
> + return bmi160_core_probe(&spi->dev, regmap, id->name, true);
> +}
> +
> +static int bmi160_spi_remove(struct spi_device *spi)
> +{
> + bmi160_core_remove(&spi->dev);
> +
> + return 0;
> +}
> +
> +static const struct spi_device_id bmi160_spi_id[] = {
> + {"bmi160", 0},
> + {}
> +};
> +
> +MODULE_DEVICE_TABLE(spi, bmi160_spi_id);
> +
> +static const struct acpi_device_id bmi160_acpi_match[] = {
> + {"BMI0160", 0},
> + { },
> +};
> +MODULE_DEVICE_TABLE(acpi, bmi160_acpi_match);
> +
> +static struct spi_driver bmi160_spi_driver = {
> + .probe = bmi160_spi_probe,
> + .remove = bmi160_spi_remove,
> + .id_table = bmi160_spi_id,
> + .driver = {
> + .acpi_match_table = ACPI_PTR(bmi160_acpi_match),
> + .name = BMI160_SPI_DRV_NAME,
> + },
> +};
> +module_spi_driver(bmi160_spi_driver);
> +
> +MODULE_AUTHOR("Daniel Baluta <[email protected]");
> +MODULE_DESCRIPTION("Bosch BMI160 SPI driver");
> +MODULE_LICENSE("GPL v2");
>

--

Peter Meerwald-Stadler
+43-664-2444418 (mobile)

2016-04-01 18:04:18

by kernel test robot

[permalink] [raw]
Subject: Re: [PATCH] iio: imu: Add initial support for Bosch BMI160

Hi Daniel,

[auto build test WARNING on iio/togreg]
[also build test WARNING on v4.6-rc1 next-20160401]
[if your patch is applied to the wrong git tree, please drop us a note to help improving the system]

url: https://github.com/0day-ci/linux/commits/Daniel-Baluta/iio-imu-Add-initial-support-for-Bosch-BMI160/20160401-203058
base: https://git.kernel.org/pub/scm/linux/kernel/git/jic23/iio.git togreg
config: parisc-allyesconfig (attached as .config)
reproduce:
wget https://git.kernel.org/cgit/linux/kernel/git/wfg/lkp-tests.git/plain/sbin/make.cross -O ~/bin/make.cross
chmod +x ~/bin/make.cross
# save the attached .config to linux build tree
make.cross ARCH=parisc

All warnings (new ones prefixed by >>):

drivers/iio/imu/bmi160/bmi160_i2c.c:57:1: warning: data definition has no type or storage class
MODULE_DEVICE_TABLE(i2c, bmi160_i2c_id);
^
drivers/iio/imu/bmi160/bmi160_i2c.c:57:1: error: type defaults to 'int' in declaration of 'MODULE_DEVICE_TABLE' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_i2c.c:57:1: warning: parameter names (without types) in function declaration
drivers/iio/imu/bmi160/bmi160_i2c.c:63:1: warning: data definition has no type or storage class
MODULE_DEVICE_TABLE(acpi, bmi160_acpi_match);
^
drivers/iio/imu/bmi160/bmi160_i2c.c:63:1: error: type defaults to 'int' in declaration of 'MODULE_DEVICE_TABLE' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_i2c.c:63:1: warning: parameter names (without types) in function declaration
In file included from include/linux/i2c.h:30:0,
from drivers/iio/imu/bmi160/bmi160_i2c.c:14:
include/linux/device.h:1332:1: warning: data definition has no type or storage class
module_init(__driver##_init); \
^
include/linux/i2c.h:666:2: note: in expansion of macro 'module_driver'
module_driver(__i2c_driver, i2c_add_driver, \
^
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: note: in expansion of macro 'module_i2c_driver'
module_i2c_driver(bmi160_i2c_driver);
^
include/linux/device.h:1332:1: error: type defaults to 'int' in declaration of 'module_init' [-Werror=implicit-int]
module_init(__driver##_init); \
^
include/linux/i2c.h:666:2: note: in expansion of macro 'module_driver'
module_driver(__i2c_driver, i2c_add_driver, \
^
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: note: in expansion of macro 'module_i2c_driver'
module_i2c_driver(bmi160_i2c_driver);
^
In file included from include/linux/linkage.h:6:0,
from include/linux/kernel.h:6,
from include/linux/list.h:8,
from include/linux/kobject.h:20,
from include/linux/device.h:17,
from include/linux/i2c.h:30,
from drivers/iio/imu/bmi160/bmi160_i2c.c:14:
include/linux/export.h:36:30: warning: parameter names (without types) in function declaration
#define THIS_MODULE ((struct module *)0)
^
>> include/linux/i2c.h:610:22: note: in expansion of macro 'THIS_MODULE'
i2c_register_driver(THIS_MODULE, driver)
^
>> include/linux/device.h:1330:9: note: in expansion of macro 'i2c_add_driver'
return __register(&(__driver) , ##__VA_ARGS__); \
^
include/linux/i2c.h:666:2: note: in expansion of macro 'module_driver'
module_driver(__i2c_driver, i2c_add_driver, \
^
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: note: in expansion of macro 'module_i2c_driver'
module_i2c_driver(bmi160_i2c_driver);
^
In file included from include/linux/i2c.h:30:0,
from drivers/iio/imu/bmi160/bmi160_i2c.c:14:
include/linux/device.h:1337:1: warning: data definition has no type or storage class
module_exit(__driver##_exit);
^
include/linux/i2c.h:666:2: note: in expansion of macro 'module_driver'
module_driver(__i2c_driver, i2c_add_driver, \
^
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: note: in expansion of macro 'module_i2c_driver'
module_i2c_driver(bmi160_i2c_driver);
^
include/linux/device.h:1337:1: error: type defaults to 'int' in declaration of 'module_exit' [-Werror=implicit-int]
module_exit(__driver##_exit);
^
include/linux/i2c.h:666:2: note: in expansion of macro 'module_driver'
module_driver(__i2c_driver, i2c_add_driver, \
^
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: note: in expansion of macro 'module_i2c_driver'
module_i2c_driver(bmi160_i2c_driver);
^
In file included from include/linux/linkage.h:6:0,
from include/linux/kernel.h:6,
from include/linux/list.h:8,
from include/linux/kobject.h:20,
from include/linux/device.h:17,
from include/linux/i2c.h:30,
from drivers/iio/imu/bmi160/bmi160_i2c.c:14:
include/linux/export.h:36:30: warning: parameter names (without types) in function declaration
#define THIS_MODULE ((struct module *)0)
^
>> include/linux/i2c.h:610:22: note: in expansion of macro 'THIS_MODULE'
i2c_register_driver(THIS_MODULE, driver)
^
>> include/linux/device.h:1330:9: note: in expansion of macro 'i2c_add_driver'
return __register(&(__driver) , ##__VA_ARGS__); \
^
include/linux/i2c.h:666:2: note: in expansion of macro 'module_driver'
module_driver(__i2c_driver, i2c_add_driver, \
^
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: note: in expansion of macro 'module_i2c_driver'
module_i2c_driver(bmi160_i2c_driver);
^
drivers/iio/imu/bmi160/bmi160_i2c.c:77:15: error: expected declaration specifiers or '...' before string constant
MODULE_AUTHOR("Daniel Baluta <[email protected]>");
^
drivers/iio/imu/bmi160/bmi160_i2c.c:78:20: error: expected declaration specifiers or '...' before string constant
MODULE_DESCRIPTION("BMI160 I2C driver");
^
drivers/iio/imu/bmi160/bmi160_i2c.c:79:16: error: expected declaration specifiers or '...' before string constant
MODULE_LICENSE("GPL v2");
^
In file included from include/linux/i2c.h:30:0,
from drivers/iio/imu/bmi160/bmi160_i2c.c:14:
drivers/iio/imu/bmi160/bmi160_i2c.c:75:19: warning: 'bmi160_i2c_driver_init' defined but not used [-Wunused-function]
module_i2c_driver(bmi160_i2c_driver);
^
include/linux/device.h:1328:19: note: in definition of macro 'module_driver'
static int __init __driver##_init(void) \
^
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: note: in expansion of macro 'module_i2c_driver'
module_i2c_driver(bmi160_i2c_driver);
^
cc1: some warnings being treated as errors
--
drivers/iio/imu/bmi160/bmi160_spi.c:50:1: warning: data definition has no type or storage class
MODULE_DEVICE_TABLE(spi, bmi160_spi_id);
^
drivers/iio/imu/bmi160/bmi160_spi.c:50:1: error: type defaults to 'int' in declaration of 'MODULE_DEVICE_TABLE' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_spi.c:50:1: warning: parameter names (without types) in function declaration
drivers/iio/imu/bmi160/bmi160_spi.c:56:1: warning: data definition has no type or storage class
MODULE_DEVICE_TABLE(acpi, bmi160_acpi_match);
^
drivers/iio/imu/bmi160/bmi160_spi.c:56:1: error: type defaults to 'int' in declaration of 'MODULE_DEVICE_TABLE' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_spi.c:56:1: warning: parameter names (without types) in function declaration
In file included from include/linux/spi/spi.h:18:0,
from drivers/iio/imu/bmi160/bmi160_spi.c:11:
include/linux/device.h:1332:1: warning: data definition has no type or storage class
module_init(__driver##_init); \
^
include/linux/spi/spi.h:283:2: note: in expansion of macro 'module_driver'
module_driver(__spi_driver, spi_register_driver, \
^
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: note: in expansion of macro 'module_spi_driver'
module_spi_driver(bmi160_spi_driver);
^
include/linux/device.h:1332:1: error: type defaults to 'int' in declaration of 'module_init' [-Werror=implicit-int]
module_init(__driver##_init); \
^
include/linux/spi/spi.h:283:2: note: in expansion of macro 'module_driver'
module_driver(__spi_driver, spi_register_driver, \
^
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: note: in expansion of macro 'module_spi_driver'
module_spi_driver(bmi160_spi_driver);
^
In file included from include/linux/linkage.h:6:0,
from include/linux/kernel.h:6,
from include/linux/list.h:8,
from include/linux/kobject.h:20,
from include/linux/device.h:17,
from include/linux/spi/spi.h:18,
from drivers/iio/imu/bmi160/bmi160_spi.c:11:
include/linux/export.h:36:30: warning: parameter names (without types) in function declaration
#define THIS_MODULE ((struct module *)0)
^
>> include/linux/spi/spi.h:272:24: note: in expansion of macro 'THIS_MODULE'
__spi_register_driver(THIS_MODULE, driver)
^
>> include/linux/device.h:1330:9: note: in expansion of macro 'spi_register_driver'
return __register(&(__driver) , ##__VA_ARGS__); \
^
include/linux/spi/spi.h:283:2: note: in expansion of macro 'module_driver'
module_driver(__spi_driver, spi_register_driver, \
^
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: note: in expansion of macro 'module_spi_driver'
module_spi_driver(bmi160_spi_driver);
^
In file included from include/linux/spi/spi.h:18:0,
from drivers/iio/imu/bmi160/bmi160_spi.c:11:
include/linux/device.h:1337:1: warning: data definition has no type or storage class
module_exit(__driver##_exit);
^
include/linux/spi/spi.h:283:2: note: in expansion of macro 'module_driver'
module_driver(__spi_driver, spi_register_driver, \
^
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: note: in expansion of macro 'module_spi_driver'
module_spi_driver(bmi160_spi_driver);
^
include/linux/device.h:1337:1: error: type defaults to 'int' in declaration of 'module_exit' [-Werror=implicit-int]
module_exit(__driver##_exit);
^
include/linux/spi/spi.h:283:2: note: in expansion of macro 'module_driver'
module_driver(__spi_driver, spi_register_driver, \
^
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: note: in expansion of macro 'module_spi_driver'
module_spi_driver(bmi160_spi_driver);
^
In file included from include/linux/linkage.h:6:0,
from include/linux/kernel.h:6,
from include/linux/list.h:8,
from include/linux/kobject.h:20,
from include/linux/device.h:17,
from include/linux/spi/spi.h:18,
from drivers/iio/imu/bmi160/bmi160_spi.c:11:
include/linux/export.h:36:30: warning: parameter names (without types) in function declaration
#define THIS_MODULE ((struct module *)0)
^
>> include/linux/spi/spi.h:272:24: note: in expansion of macro 'THIS_MODULE'
__spi_register_driver(THIS_MODULE, driver)
^
>> include/linux/device.h:1330:9: note: in expansion of macro 'spi_register_driver'
return __register(&(__driver) , ##__VA_ARGS__); \
^
include/linux/spi/spi.h:283:2: note: in expansion of macro 'module_driver'
module_driver(__spi_driver, spi_register_driver, \
^
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: note: in expansion of macro 'module_spi_driver'
module_spi_driver(bmi160_spi_driver);
^
drivers/iio/imu/bmi160/bmi160_spi.c:69:15: error: expected declaration specifiers or '...' before string constant
MODULE_AUTHOR("Daniel Baluta <[email protected]");
^
drivers/iio/imu/bmi160/bmi160_spi.c:70:20: error: expected declaration specifiers or '...' before string constant
MODULE_DESCRIPTION("Bosch BMI160 SPI driver");
^
drivers/iio/imu/bmi160/bmi160_spi.c:71:16: error: expected declaration specifiers or '...' before string constant
MODULE_LICENSE("GPL v2");
^
In file included from include/linux/spi/spi.h:18:0,
from drivers/iio/imu/bmi160/bmi160_spi.c:11:
drivers/iio/imu/bmi160/bmi160_spi.c:67:19: warning: 'bmi160_spi_driver_init' defined but not used [-Wunused-function]
module_spi_driver(bmi160_spi_driver);
^
include/linux/device.h:1328:19: note: in definition of macro 'module_driver'
static int __init __driver##_init(void) \
^
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: note: in expansion of macro 'module_spi_driver'
module_spi_driver(bmi160_spi_driver);
^
cc1: some warnings being treated as errors

vim +/THIS_MODULE +610 include/linux/i2c.h

c7036673 Hans Verkuil 2009-06-19 594
^1da177e Linus Torvalds 2005-04-16 595
^1da177e Linus Torvalds 2005-04-16 596 /* ----- functions exported by i2c.o */
^1da177e Linus Torvalds 2005-04-16 597
^1da177e Linus Torvalds 2005-04-16 598 /* administration...
^1da177e Linus Torvalds 2005-04-16 599 */
23af8400 Jean Delvare 2009-06-19 600 #if defined(CONFIG_I2C) || defined(CONFIG_I2C_MODULE)
^1da177e Linus Torvalds 2005-04-16 601 extern int i2c_add_adapter(struct i2c_adapter *);
71546300 Lars-Peter Clausen 2013-03-09 602 extern void i2c_del_adapter(struct i2c_adapter *);
6e13e641 David Brownell 2007-05-01 603 extern int i2c_add_numbered_adapter(struct i2c_adapter *);
^1da177e Linus Torvalds 2005-04-16 604
de59cf9e Greg Kroah-Hartman 2005-12-06 605 extern int i2c_register_driver(struct module *, struct i2c_driver *);
b3e82096 Jean Delvare 2007-05-01 606 extern void i2c_del_driver(struct i2c_driver *);
^1da177e Linus Torvalds 2005-04-16 607
eb5589a8 Paul Gortmaker 2011-05-27 608 /* use a define to avoid include chaining to get THIS_MODULE */
eb5589a8 Paul Gortmaker 2011-05-27 609 #define i2c_add_driver(driver) \
eb5589a8 Paul Gortmaker 2011-05-27 @610 i2c_register_driver(THIS_MODULE, driver)
de59cf9e Greg Kroah-Hartman 2005-12-06 611
e48d3319 Jean Delvare 2008-01-27 612 extern struct i2c_client *i2c_use_client(struct i2c_client *client);
e48d3319 Jean Delvare 2008-01-27 613 extern void i2c_release_client(struct i2c_client *client);
^1da177e Linus Torvalds 2005-04-16 614
^1da177e Linus Torvalds 2005-04-16 615 /* call the i2c_client->command() of all attached clients with
^1da177e Linus Torvalds 2005-04-16 616 * the given arguments */
^1da177e Linus Torvalds 2005-04-16 617 extern void i2c_clients_command(struct i2c_adapter *adap,
^1da177e Linus Torvalds 2005-04-16 618 unsigned int cmd, void *arg);

:::::: The code at line 610 was first introduced by commit
:::::: eb5589a8f0dab7e29021344228856339e6a1249c include: convert various register fcns to macros to avoid include chaining

:::::: TO: Paul Gortmaker <[email protected]>
:::::: CC: Paul Gortmaker <[email protected]>

---
0-DAY kernel test infrastructure Open Source Technology Center
https://lists.01.org/pipermail/kbuild-all Intel Corporation


Attachments:
(No filename) (15.24 kB)
.config.gz (42.79 kB)
Download all attachments

2016-04-01 19:55:02

by kernel test robot

[permalink] [raw]
Subject: Re: [PATCH] iio: imu: Add initial support for Bosch BMI160

Hi Daniel,

[auto build test ERROR on iio/togreg]
[also build test ERROR on v4.6-rc1 next-20160401]
[if your patch is applied to the wrong git tree, please drop us a note to help improving the system]

url: https://github.com/0day-ci/linux/commits/Daniel-Baluta/iio-imu-Add-initial-support-for-Bosch-BMI160/20160401-203058
base: https://git.kernel.org/pub/scm/linux/kernel/git/jic23/iio.git togreg
config: sh-allyesconfig (attached as .config)
reproduce:
wget https://git.kernel.org/cgit/linux/kernel/git/wfg/lkp-tests.git/plain/sbin/make.cross -O ~/bin/make.cross
chmod +x ~/bin/make.cross
# save the attached .config to linux build tree
make.cross ARCH=sh

All errors (new ones prefixed by >>):

drivers/iio/imu/bmi160/bmi160_i2c.c:57:1: warning: data definition has no type or storage class [enabled by default]
drivers/iio/imu/bmi160/bmi160_i2c.c:57:1: error: type defaults to 'int' in declaration of 'MODULE_DEVICE_TABLE' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_i2c.c:57:1: warning: parameter names (without types) in function declaration [enabled by default]
drivers/iio/imu/bmi160/bmi160_i2c.c:63:1: warning: data definition has no type or storage class [enabled by default]
drivers/iio/imu/bmi160/bmi160_i2c.c:63:1: error: type defaults to 'int' in declaration of 'MODULE_DEVICE_TABLE' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_i2c.c:63:1: warning: parameter names (without types) in function declaration [enabled by default]
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: warning: data definition has no type or storage class [enabled by default]
>> drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: error: type defaults to 'int' in declaration of 'module_init' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: warning: parameter names (without types) in function declaration [enabled by default]
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: warning: data definition has no type or storage class [enabled by default]
>> drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: error: type defaults to 'int' in declaration of 'module_exit' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: warning: parameter names (without types) in function declaration [enabled by default]
drivers/iio/imu/bmi160/bmi160_i2c.c:77:15: error: expected declaration specifiers or '...' before string constant
drivers/iio/imu/bmi160/bmi160_i2c.c:78:20: error: expected declaration specifiers or '...' before string constant
drivers/iio/imu/bmi160/bmi160_i2c.c:79:16: error: expected declaration specifiers or '...' before string constant
drivers/iio/imu/bmi160/bmi160_i2c.c:75:1: warning: 'bmi160_i2c_driver_init' defined but not used [-Wunused-function]
cc1: some warnings being treated as errors
--
drivers/iio/imu/bmi160/bmi160_spi.c:50:1: warning: data definition has no type or storage class [enabled by default]
drivers/iio/imu/bmi160/bmi160_spi.c:50:1: error: type defaults to 'int' in declaration of 'MODULE_DEVICE_TABLE' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_spi.c:50:1: warning: parameter names (without types) in function declaration [enabled by default]
drivers/iio/imu/bmi160/bmi160_spi.c:56:1: warning: data definition has no type or storage class [enabled by default]
drivers/iio/imu/bmi160/bmi160_spi.c:56:1: error: type defaults to 'int' in declaration of 'MODULE_DEVICE_TABLE' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_spi.c:56:1: warning: parameter names (without types) in function declaration [enabled by default]
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: warning: data definition has no type or storage class [enabled by default]
>> drivers/iio/imu/bmi160/bmi160_spi.c:67:1: error: type defaults to 'int' in declaration of 'module_init' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: warning: parameter names (without types) in function declaration [enabled by default]
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: warning: data definition has no type or storage class [enabled by default]
>> drivers/iio/imu/bmi160/bmi160_spi.c:67:1: error: type defaults to 'int' in declaration of 'module_exit' [-Werror=implicit-int]
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: warning: parameter names (without types) in function declaration [enabled by default]
drivers/iio/imu/bmi160/bmi160_spi.c:69:15: error: expected declaration specifiers or '...' before string constant
drivers/iio/imu/bmi160/bmi160_spi.c:70:20: error: expected declaration specifiers or '...' before string constant
drivers/iio/imu/bmi160/bmi160_spi.c:71:16: error: expected declaration specifiers or '...' before string constant
drivers/iio/imu/bmi160/bmi160_spi.c:67:1: warning: 'bmi160_spi_driver_init' defined but not used [-Wunused-function]
cc1: some warnings being treated as errors

vim +75 drivers/iio/imu/bmi160/bmi160_i2c.c

51 }
52
53 static const struct i2c_device_id bmi160_i2c_id[] = {
54 {"bmi160", 0},
55 {}
56 };
> 57 MODULE_DEVICE_TABLE(i2c, bmi160_i2c_id);
58
59 static const struct acpi_device_id bmi160_acpi_match[] = {
60 {"BMI0160", 0},
61 { },
62 };
63 MODULE_DEVICE_TABLE(acpi, bmi160_acpi_match);
64
65 static struct i2c_driver bmi160_i2c_driver = {
66 .driver = {
67 .name = BMI160_I2C_DRV_NAME,
68 .acpi_match_table = ACPI_PTR(bmi160_acpi_match),
69 },
70 .probe = bmi160_i2c_probe,
71 .remove = bmi160_i2c_remove,
72 .id_table = bmi160_i2c_id,
73 };
74
> 75 module_i2c_driver(bmi160_i2c_driver);
76
77 MODULE_AUTHOR("Daniel Baluta <[email protected]>");
78 MODULE_DESCRIPTION("BMI160 I2C driver");

---
0-DAY kernel test infrastructure Open Source Technology Center
https://lists.01.org/pipermail/kbuild-all Intel Corporation


Attachments:
(No filename) (5.75 kB)
.config.gz (37.77 kB)
Download all attachments

2016-04-03 08:53:22

by Jonathan Cameron

[permalink] [raw]
Subject: Re: [PATCH] iio: imu: Add initial support for Bosch BMI160

On 01/04/16 13:31, Daniel Baluta wrote:
> BMI160 is an Inertial Measurement Unit (IMU) which provides acceleration
> and angular rate measurement. It also offers a secondary I2C interface
> for connecting a magnetometer sensor (usually BMM160).
>
> Current driver offers support for accelerometer and gyroscope readings
> via sysfs or via buffer interface using an external trigger (e.g.
> hrtimer). Data is retrieved from IMU via I2C or SPI interface.
>
> Datasheet is at:
> http://www.mouser.com/ds/2/783/BST-BMI160-DS000-07-786474.pdf
>
> Signed-off-by: Daniel Baluta <[email protected]>
A few bits inline. Mostly around the trigger handler...

J
> ---
> drivers/iio/imu/Kconfig | 2 +
> drivers/iio/imu/Makefile | 1 +
> drivers/iio/imu/bmi160/Kconfig | 32 ++
> drivers/iio/imu/bmi160/Makefile | 6 +
> drivers/iio/imu/bmi160/bmi160.h | 8 +
> drivers/iio/imu/bmi160/bmi160_core.c | 588 +++++++++++++++++++++++++++++++++++
> drivers/iio/imu/bmi160/bmi160_i2c.c | 79 +++++
> drivers/iio/imu/bmi160/bmi160_spi.c | 71 +++++
> 8 files changed, 787 insertions(+)
> create mode 100644 drivers/iio/imu/bmi160/Kconfig
> create mode 100644 drivers/iio/imu/bmi160/Makefile
> create mode 100644 drivers/iio/imu/bmi160/bmi160.h
> create mode 100644 drivers/iio/imu/bmi160/bmi160_core.c
> create mode 100644 drivers/iio/imu/bmi160/bmi160_i2c.c
> create mode 100644 drivers/iio/imu/bmi160/bmi160_spi.c
>
> diff --git a/drivers/iio/imu/Kconfig b/drivers/iio/imu/Kconfig
> index 5e610f7..1f1ad41 100644
> --- a/drivers/iio/imu/Kconfig
> +++ b/drivers/iio/imu/Kconfig
> @@ -25,6 +25,8 @@ config ADIS16480
> Say yes here to build support for Analog Devices ADIS16375, ADIS16480,
> ADIS16485, ADIS16488 inertial sensors.
>
> +source "drivers/iio/imu/bmi160/Kconfig"
> +
> config KMX61
> tristate "Kionix KMX61 6-axis accelerometer and magnetometer"
> depends on I2C
> diff --git a/drivers/iio/imu/Makefile b/drivers/iio/imu/Makefile
> index e1e6e3d..c71bcd3 100644
> --- a/drivers/iio/imu/Makefile
> +++ b/drivers/iio/imu/Makefile
> @@ -13,6 +13,7 @@ adis_lib-$(CONFIG_IIO_ADIS_LIB_BUFFER) += adis_trigger.o
> adis_lib-$(CONFIG_IIO_ADIS_LIB_BUFFER) += adis_buffer.o
> obj-$(CONFIG_IIO_ADIS_LIB) += adis_lib.o
>
> +obj-y += bmi160/
> obj-y += inv_mpu6050/
>
> obj-$(CONFIG_KMX61) += kmx61.o
> diff --git a/drivers/iio/imu/bmi160/Kconfig b/drivers/iio/imu/bmi160/Kconfig
> new file mode 100644
> index 0000000..adb512f
> --- /dev/null
> +++ b/drivers/iio/imu/bmi160/Kconfig
> @@ -0,0 +1,32 @@
> +#
> +# BMI160 IMU driver
> +#
> +
> +config BMI160
> + tristate
> + select IIO_BUFFER
> + select IIO_TRIGGERED_BUFFER
> +
> +config BMI160_I2C
> + tristate "Bosch BMI160 I2C driver"
> + depends on I2C
> + select BMI160
> + select REGMAP_I2C
> + help
> + If you say yes you get support BMI160 IMU on I2C with accelerometer,
> + gyroscope and external BMG160 magnetometer.
> +
> + This driver can also be built as a module. If so, the module will be
> + called bmi160_i2c.
> +
> +config BMI160_SPI
> + tristate "Bosch BMI160 SPI driver"
> + depends on SPI
> + select BMI160
> + select REGMAP_SPI
> + help
> + If you say yes you get support BMI160 IMU on SPI with accelerometer,
> + gyroscope and external BMG160 magnetometer.
> +
> + This driver can also be built as a module. If so, the module will be
> + called bmi160_i2c.
> diff --git a/drivers/iio/imu/bmi160/Makefile b/drivers/iio/imu/bmi160/Makefile
> new file mode 100644
> index 0000000..10365e4
> --- /dev/null
> +++ b/drivers/iio/imu/bmi160/Makefile
> @@ -0,0 +1,6 @@
> +#
> +# Makefile for Bosch BMI160 IMU
> +#
> +obj-$(CONFIG_BMI160) += bmi160_core.o
> +obj-$(CONFIG_BMI160_I2C) += bmi160_i2c.o
> +obj-$(CONFIG_BMI160_SPI) += bmi160_spi.o
> diff --git a/drivers/iio/imu/bmi160/bmi160.h b/drivers/iio/imu/bmi160/bmi160.h
> new file mode 100644
> index 0000000..c5f7b2d
> --- /dev/null
> +++ b/drivers/iio/imu/bmi160/bmi160.h
> @@ -0,0 +1,8 @@
> +#ifndef BMI160_H_
> +#define BMI160_H_
> +
> +int bmi160_core_probe(struct device *dev, struct regmap *regmap,
> + const char *name, bool use_spi);
> +void bmi160_core_remove(struct device *dev);
> +
> +#endif /* BMI160_H_ */
> diff --git a/drivers/iio/imu/bmi160/bmi160_core.c b/drivers/iio/imu/bmi160/bmi160_core.c
> new file mode 100644
> index 0000000..d6ce643
> --- /dev/null
> +++ b/drivers/iio/imu/bmi160/bmi160_core.c
> @@ -0,0 +1,588 @@
> +/*
> + * BMI160 - Bosch IMU (accel, gyro plus external magnetometer)
> + *
> + * Copyright (c) 2016, Intel Corporation.
> + *
> + * This file is subject to the terms and conditions of version 2 of
> + * the GNU General Public License. See the file COPYING in the main
> + * directory of this archive for more details.
> + *
> + * IIO core driver for BMI160, with support for I2C/SPI busses
> + *
> + * TODO: magnetometer, interrupts, hardware FIFO
> + */
> +#include <linux/module.h>
> +#include <linux/regmap.h>
> +#include <linux/acpi.h>
> +#include <linux/delay.h>
> +
> +#include <linux/iio/iio.h>
> +#include <linux/iio/triggered_buffer.h>
> +#include <linux/iio/trigger_consumer.h>
> +#include <linux/iio/buffer.h>
> +
> +#include "bmi160.h"
> +
> +#define BMI160_REG_CHIP_ID 0x00
> +#define BMI160_CHIP_ID_VAL 0xD1
> +
> +#define BMI160_REG_PMU_STATUS 0x03
> +
> +/* X axis data low byte address, the rest can be obtained using axis offset */
> +#define BMI160_REG_DATA_MAGN_XOUT_L 0x04
> +#define BMI160_REG_DATA_GYRO_XOUT_L 0x0C
> +#define BMI160_REG_DATA_ACCEL_XOUT_L 0x12
> +
> +#define BMI160_REG_ACCEL_CONFIG 0x40
> +#define BMI160_ACCEL_CONFIG_ODR_MASK GENMASK(3, 0)
> +#define BMI160_ACCEL_CONFIG_BWP_MASK GENMASK(6, 4)
> +
> +#define BMI160_REG_ACCEL_RANGE 0x41
> +#define BMI160_ACCEL_RANGE_2G 0x03
> +#define BMI160_ACCEL_RANGE_4G 0x05
> +#define BMI160_ACCEL_RANGE_8G 0x08
> +#define BMI160_ACCEL_RANGE_16G 0x0C
> +
> +#define BMI160_REG_GYRO_CONFIG 0x42
> +#define BMI160_GYRO_CONFIG_ODR_MASK GENMASK(3, 0)
> +#define BMI160_GYRO_CONFIG_BWP_MASK GENMASK(5, 4)
> +
> +#define BMI160_REG_GYRO_RANGE 0x43
> +#define BMI160_GYRO_RANGE_2000DPS 0x00
> +#define BMI160_GYRO_RANGE_1000DPS 0x01
> +#define BMI160_GYRO_RANGE_500DPS 0x02
> +#define BMI160_GYRO_RANGE_250DPS 0x03
> +#define BMI160_GYRO_RANGE_125DPS 0x04
> +
> +#define BMI160_REG_CMD 0x7E
> +#define BMI160_CMD_ACCEL_PM_SUSPEND 0x10
> +#define BMI160_CMD_ACCEL_PM_NORMAL 0x11
> +#define BMI160_CMD_ACCEL_PM_LOW_POWER 0x12
> +#define BMI160_CMD_GYRO_PM_SUSPEND 0x14
> +#define BMI160_CMD_GYRO_PM_NORMAL 0x15
> +#define BMI160_CMD_GYRO_PM_FAST_STARTUP 0x17
> +#define BMI160_CMD_SOFTRESET 0xB6
> +
> +#define BMI160_REG_DUMMY 0x7F
> +
> +#define BMI160_ACCEL_PMU_MIN_SLEEP 3200 /* usec */
> +#define BMI160_ACCEL_PMU_MAX_SLEEP 3800
> +#define BMI160_GYRO_PMU_MIN_SLEEP 55000
> +#define BMI160_GYRO_PMU_MAX_SLEEP 80000
> +#define BMI160_SOFTRESET_SLEEP 1000
> +
> +#define BMI160_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_SAMP_FREQ), \
> + .scan_index = _index, \
> + .scan_type = { \
> + .sign = 's', \
> + .realbits = 16, \
> + .storagebits = 16, \
> + .shift = 0, \
> + .endianness = IIO_LE, \
> + }, \
> +}
> +
> +/* scan indexes follow DATA register order */
> +enum bmi160_scan_axis {
> + BMI160_SCAN_EXT_MAGN_X = 0,
> + BMI160_SCAN_EXT_MAGN_Y,
> + BMI160_SCAN_EXT_MAGN_Z,
> + BMI160_SCAN_RHALL,
Given the ordering in here is arbitary, why include the unsupported elements
at this stage? Don't suppose it does any harm though.
> + BMI160_SCAN_GYRO_X,
> + BMI160_SCAN_GYRO_Y,
> + BMI160_SCAN_GYRO_Z,
> + BMI160_SCAN_ACCEL_X,
> + BMI160_SCAN_ACCEL_Y,
> + BMI160_SCAN_ACCEL_Z,
> + BMI160_SCAN_TIMESTAMP,
> +};
> +
> +enum bmi160_sensor_type {
> + BMI160_ACCEL = 0,
> + BMI160_GYRO,
> + BMI160_EXT_MAGN,
> + BMI160_NUM_SENSORS /* must be last */
> +};
> +
> +struct bmi160_data {
> + struct regmap *regmap;
> +};
> +
> +struct bmi160_regs {
> + u8 data; /* LSB byte register for X-axis */
> + u8 config;
> + u8 config_odr_mask;
> + u8 config_bwp_mask;
> + u8 range;
> + u8 pmu_cmd_normal;
> + u8 pmu_cmd_suspend;
> +};
> +
> +struct bmi160_regs bmi160_regs[] = {
> + [BMI160_ACCEL] = {
> + .data = BMI160_REG_DATA_ACCEL_XOUT_L,
> + .config = BMI160_REG_ACCEL_CONFIG,
> + .config_odr_mask = BMI160_ACCEL_CONFIG_ODR_MASK,
> + .config_bwp_mask = BMI160_ACCEL_CONFIG_BWP_MASK,
> + .range = BMI160_REG_ACCEL_RANGE,
> + .pmu_cmd_normal = BMI160_CMD_ACCEL_PM_NORMAL,
> + .pmu_cmd_suspend = BMI160_CMD_ACCEL_PM_SUSPEND,
> + },
> + [BMI160_GYRO] = {
> + .data = BMI160_REG_DATA_GYRO_XOUT_L,
> + .config = BMI160_REG_GYRO_CONFIG,
> + .config_odr_mask = BMI160_GYRO_CONFIG_ODR_MASK,
> + .config_bwp_mask = BMI160_GYRO_CONFIG_BWP_MASK,
> + .range = BMI160_REG_GYRO_RANGE,
> + .pmu_cmd_normal = BMI160_CMD_GYRO_PM_NORMAL,
> + .pmu_cmd_suspend = BMI160_CMD_GYRO_PM_SUSPEND,
> + },
> +};
> +
> +struct bmi160_pmu_time {
> + unsigned long min;
> + unsigned long max;
> +};
> +
> +struct bmi160_pmu_time bmi160_pmu_time[] = {
> + [BMI160_ACCEL] = {
> + .min = BMI160_ACCEL_PMU_MIN_SLEEP,
> + .max = BMI160_ACCEL_PMU_MAX_SLEEP
> + },
> + [BMI160_GYRO] = {
> + .min = BMI160_GYRO_PMU_MIN_SLEEP,
> + .max = BMI160_GYRO_PMU_MIN_SLEEP,
> + },
> +};
> +
> +struct bmi160_scale {
> + u8 bits;
> + int uscale;
> +};
> +
> +struct bmi160_odr {
> + u8 bits;
> + int odr;
> + int uodr;
> +};
> +
> +static const struct bmi160_scale bmi160_accel_scale[] = {
> + { BMI160_ACCEL_RANGE_2G, 598},
> + { BMI160_ACCEL_RANGE_4G, 1197},
> + { BMI160_ACCEL_RANGE_8G, 2394},
> + { BMI160_ACCEL_RANGE_16G, 4788},
> +};
> +
> +static const struct bmi160_scale bmi160_gyro_scale[] = {
> + { BMI160_GYRO_RANGE_2000DPS, 1065},
> + { BMI160_GYRO_RANGE_1000DPS, 532},
> + { BMI160_GYRO_RANGE_500DPS, 266},
> + { BMI160_GYRO_RANGE_250DPS, 133},
> + { BMI160_GYRO_RANGE_125DPS, 66},
> +
> +};
> +
> +struct bmi160_scale_item {
> + const struct bmi160_scale *tbl;
> + int num;
> +};
> +
> +static const struct bmi160_scale_item bmi160_scale_table[] = {
> + [BMI160_ACCEL] = {
> + .tbl = bmi160_accel_scale,
> + .num = ARRAY_SIZE(bmi160_accel_scale),
> + },
> + [BMI160_GYRO] = {
> + .tbl = bmi160_gyro_scale,
> + .num = ARRAY_SIZE(bmi160_gyro_scale),
> + },
> +};
> +
> +static const struct bmi160_odr bmi160_accel_odr[] = {
> + {0x01, 0, 78125},
> + {0x02, 1, 5625},
> + {0x03, 3, 125},
> + {0x04, 6, 25},
> + {0x05, 12, 5},
> + {0x06, 25, 0},
> + {0x07, 50, 0},
> + {0x08, 100, 0},
> + {0x09, 200, 0},
> + {0x0A, 400, 0},
> + {0x0B, 800, 0},
> + {0x0C, 1600, 0},
> +};
> +
> +static const struct bmi160_odr bmi160_gyro_odr[] = {
> + {0x06, 25, 0},
> + {0x07, 50, 0},
> + {0x08, 100, 0},
> + {0x09, 200, 0},
> + {0x0A, 400, 0},
> + {0x0B, 8000, 0},
> + {0x0C, 1600, 0},
> + {0x0D, 3200, 0},
> +};
> +
> +struct bmi160_odr_item {
> + const struct bmi160_odr *tbl;
> + int num;
> +};
> +
> +static const struct bmi160_odr_item bmi160_odr_table[] = {
> + [BMI160_ACCEL] = {
> + .tbl = bmi160_accel_odr,
> + .num = ARRAY_SIZE(bmi160_accel_odr),
> + },
> + [BMI160_GYRO] = {
> + .tbl = bmi160_gyro_odr,
> + .num = ARRAY_SIZE(bmi160_gyro_odr),
> + },
> +};
> +
> +static const struct iio_chan_spec bmi160_channels[] = {
> + BMI160_CHANNEL(IIO_ACCEL, X, BMI160_SCAN_ACCEL_X),
> + BMI160_CHANNEL(IIO_ACCEL, Y, BMI160_SCAN_ACCEL_Y),
> + BMI160_CHANNEL(IIO_ACCEL, Z, BMI160_SCAN_ACCEL_Z),
> + BMI160_CHANNEL(IIO_ANGL_VEL, X, BMI160_SCAN_GYRO_X),
> + BMI160_CHANNEL(IIO_ANGL_VEL, Y, BMI160_SCAN_GYRO_Y),
> + BMI160_CHANNEL(IIO_ANGL_VEL, Z, BMI160_SCAN_GYRO_Z),
> + IIO_CHAN_SOFT_TIMESTAMP(BMI160_SCAN_TIMESTAMP),
> +};
> +
> +static enum bmi160_sensor_type bmi160_to_sensor(enum iio_chan_type iio_type)
> +{
> + switch (iio_type) {
> + case IIO_ACCEL:
> + return BMI160_ACCEL;
> + case IIO_ANGL_VEL:
> + return BMI160_GYRO;
> + default:
> + return -EINVAL;
> + }
> +}
> +
> +static
> +int bmi160_set_mode(struct bmi160_data *data, enum bmi160_sensor_type t,
> + int mode)
> +{
> + int ret;
> + u8 cmd;
> +
> + if (mode)
> + cmd = bmi160_regs[t].pmu_cmd_normal;
> + else
> + cmd = bmi160_regs[t].pmu_cmd_suspend;
> +
> + ret = regmap_write(data->regmap, BMI160_REG_CMD, cmd);
> + if (ret < 0)
> + return ret;
> +
> + usleep_range(bmi160_pmu_time[t].min, bmi160_pmu_time[t].max);
> +
> + return 0;
> +}
> +
> +static
> +int bmi160_set_scale(struct bmi160_data *data, enum bmi160_sensor_type t,
> + int uscale)
> +{
> + int i;
> +
> + for (i = 0; i < bmi160_scale_table[t].num; i++)
> + if (bmi160_scale_table[t].tbl[i].uscale == uscale)
> + break;
> +
> + if (i == bmi160_scale_table[t].num)
> + return -EINVAL;
> +
> + return regmap_write(data->regmap, bmi160_regs[t].range,
> + bmi160_scale_table[t].tbl[i].bits);
> +}
> +
> +static
> +int bmi160_get_scale(struct bmi160_data *data, enum bmi160_sensor_type t,
> + int *uscale)
> +{
> + int i, ret, val;
> +
> + ret = regmap_read(data->regmap, bmi160_regs[t].range, &val);
> + if (ret < 0)
> + return ret;
> +
> + for (i = 0; i < bmi160_scale_table[t].num; i++)
> + if (bmi160_scale_table[t].tbl[i].bits == val) {
> + *uscale = bmi160_scale_table[t].tbl[i].uscale;
> + return 0;
> + }
> +
> + return -EINVAL;
> +}
> +
> +static int bmi160_get_data(struct bmi160_data *data, int chan_type,
> + int axis, int *val)
> +{
> + u8 reg;
> + int ret;
> + __le16 sample;
> + enum bmi160_sensor_type t = bmi160_to_sensor(chan_type);
> +
> + reg = bmi160_regs[t].data + (axis - IIO_MOD_X) * 2;
> +
> + ret = regmap_bulk_read(data->regmap, reg, &sample, sizeof(sample));
This looks better for sample than in the trigger handler below.
> + if (ret < 0)
> + return ret;
> +
> + *val = sign_extend32(le16_to_cpu(sample), 15);
> +
> + return 0;
> +}
> +
> +static
> +int bmi160_set_odr(struct bmi160_data *data, enum bmi160_sensor_type t,
> + int odr, int uodr)
> +{
> + int i;
> +
> + for (i = 0; i < bmi160_odr_table[t].num; i++)
> + if (bmi160_odr_table[t].tbl[i].odr == odr &&
> + bmi160_odr_table[t].tbl[i].uodr == uodr)
> + break;
> +
> + if (i >= bmi160_odr_table[t].num)
> + return -EINVAL;
> +
> + return regmap_update_bits(data->regmap,
> + bmi160_regs[t].config,
> + bmi160_odr_table[t].tbl[i].bits,
> + bmi160_regs[t].config_odr_mask);
> +}
> +
> +static int bmi160_get_odr(struct bmi160_data *data, enum bmi160_sensor_type t,
> + int *odr, int *uodr)
> +{
> + int i, val, ret;
> +
> + ret = regmap_read(data->regmap, bmi160_regs[t].config, &val);
> + if (ret < 0)
> + return ret;
> +
> + val &= bmi160_regs[t].config_odr_mask;
> +
> + for (i = 0; i < bmi160_odr_table[t].num; i++)
> + if (val == bmi160_odr_table[t].tbl[i].bits)
> + break;
> +
> + if (i >= bmi160_odr_table[t].num)
> + return -EINVAL;
> +
> + *odr = bmi160_odr_table[t].tbl[i].odr;
> + *uodr = bmi160_odr_table[t].tbl[i].uodr;
> +
> + return 0;
> +}
> +
> +static irqreturn_t bmi160_trigger_handler(int irq, void *p)
> +{
> + struct iio_poll_func *pf = p;
> + struct iio_dev *indio_dev = pf->indio_dev;
> + struct bmi160_data *data = iio_priv(indio_dev);
> + s16 buf[16]; /* 3 sens x 3 axis x s16 + 3 x s16 pad + 4 x s16 tstamp */
> + int i, ret, sample, j = 0, base = BMI160_REG_DATA_MAGN_XOUT_L;
> +
> + for_each_set_bit(i, indio_dev->active_scan_mask,
> + indio_dev->masklength) {
Unless I'm missing something this could pass a stack variable into a
dma transfer - where alignment needs to be right...

Also, a fixed integer size would probably be wise for sample.

> + ret = regmap_bulk_read(data->regmap, base + 2 * i, &sample,
> + sizeof(sample));
> + if (ret < 0)
> + goto done;
> + buf[j++] = sample;
> + }
> +
> + iio_push_to_buffers_with_timestamp(indio_dev, buf, iio_get_time_ns());
> +done:
> + iio_trigger_notify_done(indio_dev->trig);
> + return IRQ_HANDLED;
> +}
> +
> +static int bmi160_read_raw(struct iio_dev *indio_dev,
> + struct iio_chan_spec const *chan,
> + int *val, int *val2, long mask)
> +{
> + int ret;
> + struct bmi160_data *data = iio_priv(indio_dev);
> +
> + switch (mask) {
> + case IIO_CHAN_INFO_RAW:
> + ret = bmi160_get_data(data, chan->type, chan->channel2, val);
> + if (ret < 0)
> + return ret;
> + return IIO_VAL_INT;
> + case IIO_CHAN_INFO_SCALE:
> + *val = 0;
> + ret = bmi160_get_scale(data,
> + bmi160_to_sensor(chan->type), val2);
> + return ret < 0 ? ret : IIO_VAL_INT_PLUS_MICRO;
> + case IIO_CHAN_INFO_SAMP_FREQ:
> + ret = bmi160_get_odr(data, bmi160_to_sensor(chan->type),
> + val, val2);
> + return ret < 0 ? ret : IIO_VAL_INT_PLUS_MICRO;
> + default:
> + return -EINVAL;
> + }
> +
> + return 0;
> +}
> +
> +static int bmi160_write_raw(struct iio_dev *indio_dev,
> + struct iio_chan_spec const *chan,
> + int val, int val2, long mask)
> +{
> + struct bmi160_data *data = iio_priv(indio_dev);
> +
> + switch (mask) {
> + case IIO_CHAN_INFO_SCALE:
> + return bmi160_set_scale(data,
> + bmi160_to_sensor(chan->type), val2);
> + break;
> + case IIO_CHAN_INFO_SAMP_FREQ:
> + return bmi160_set_odr(data, bmi160_to_sensor(chan->type),
> + val, val2);
> + default:
> + return -EINVAL;
> + }
> +
> + return 0;
> +}
> +
> +static const struct iio_info bmi160_info = {
> + .driver_module = THIS_MODULE,
> + .read_raw = bmi160_read_raw,
> + .write_raw = bmi160_write_raw,
> +};
> +
> +static const char *bmi160_match_acpi_device(struct device *dev)
> +{
> + const struct acpi_device_id *id;
> +
> + id = acpi_match_device(dev->driver->acpi_match_table, dev);
> + if (!id)
> + return NULL;
> +
> + return dev_name(dev);
> +}
> +
> +static int bmi160_chip_init(struct bmi160_data *data, bool use_spi)
> +{
> + int ret;
> + unsigned int val;
> + struct device *dev = regmap_get_device(data->regmap);
> +
> + ret = regmap_write(data->regmap, BMI160_REG_CMD, BMI160_CMD_SOFTRESET);
> + if (ret < 0)
> + return ret;
> +
> + usleep_range(BMI160_SOFTRESET_SLEEP, BMI160_SOFTRESET_SLEEP + 1);
> +
> + /* CS rising edge is needed before starting SPI, so do a dummy read */
Is this documented? Seems a little 'interesting'!
> + if (use_spi) {
> + ret = regmap_read(data->regmap, BMI160_REG_DUMMY, &val);
> + if (ret < 0)
> + return ret;
> + }
> +
> + ret = regmap_read(data->regmap, BMI160_REG_CHIP_ID, &val);
> + if (ret < 0) {
> + dev_err(dev, "Error reading chip id\n");
> + return ret;
> + }
> + if (val != BMI160_CHIP_ID_VAL) {
> + dev_err(dev, "Wrong chip id, got %x expected %x\n",
> + val, BMI160_CHIP_ID_VAL);
> + return -ENODEV;
> + }
> +
> + ret = bmi160_set_mode(data, BMI160_ACCEL, 1);
> + if (ret < 0)
> + return ret;
> +
> + ret = bmi160_set_mode(data, BMI160_GYRO, 1);
> + if (ret < 0)
> + return ret;
> +
> + return 0;
> +}
> +
> +static void bmi160_chip_uninit(struct bmi160_data *data)
> +{
> + bmi160_set_mode(data, BMI160_GYRO, 0);
> + bmi160_set_mode(data, BMI160_ACCEL, 0);
> +}
> +
> +int bmi160_core_probe(struct device *dev, struct regmap *regmap,
> + const char *name, bool use_spi)
> +{
> + struct iio_dev *indio_dev;
> + struct bmi160_data *data;
> + int ret;
> +
> + 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;
> +
> + ret = bmi160_chip_init(data, use_spi);
> + if (ret < 0)
> + return ret;
> +
> + if (!name && ACPI_HANDLE(dev))
> + name = bmi160_match_acpi_device(dev);
> +
> + indio_dev->dev.parent = dev;
> + indio_dev->channels = bmi160_channels;
> + indio_dev->num_channels = ARRAY_SIZE(bmi160_channels);
> + indio_dev->name = name;
> + indio_dev->modes = INDIO_DIRECT_MODE;
> + indio_dev->info = &bmi160_info;
> +
> + ret = iio_triggered_buffer_setup(indio_dev, NULL,
> + bmi160_trigger_handler, NULL);
> + if (ret < 0)
> + goto uninit;
> +
> + ret = iio_device_register(indio_dev);
> + if (ret < 0)
> + goto buffer_cleanup;
> +
> + return 0;
> +uninit:
> + bmi160_chip_uninit(data);
> +buffer_cleanup:
> + iio_triggered_buffer_cleanup(indio_dev);
> + return ret;
> +}
> +EXPORT_SYMBOL_GPL(bmi160_core_probe);
> +
> +void bmi160_core_remove(struct device *dev)
> +{
> + struct iio_dev *indio_dev = dev_get_drvdata(dev);
> + struct bmi160_data *data = iio_priv(indio_dev);
> +
> + iio_device_unregister(indio_dev);
> + iio_triggered_buffer_cleanup(indio_dev);
> + bmi160_chip_uninit(data);
> +}
> +EXPORT_SYMBOL_GPL(bmi160_core_remove);
> +
> +MODULE_AUTHOR("Daniel Baluta <[email protected]");
> +MODULE_DESCRIPTION("Bosch BMI160 driver");
> +MODULE_LICENSE("GPL v2");
> diff --git a/drivers/iio/imu/bmi160/bmi160_i2c.c b/drivers/iio/imu/bmi160/bmi160_i2c.c
> new file mode 100644
> index 0000000..af1feac
> --- /dev/null
> +++ b/drivers/iio/imu/bmi160/bmi160_i2c.c
> @@ -0,0 +1,79 @@
> +/*
> + * BMI160 - Bosch IMU, I2C bits
> + *
> + * Copyright (c) 2016, Intel Corporation.
> + *
> + * This file is subject to the terms and conditions of version 2 of
> + * the GNU General Public License. See the file COPYING in the main
> + * directory of this archive for more details.
> + *
> + * 7-bit I2C slave address is:
> + * - 0x68 if SDO is pulled to GND
> + * - 0x69 if SDO is pulled to VDDIO
> + */
> +#include <linux/i2c.h>
> +#include <linux/regmap.h>
> +#include <linux/acpi.h>
> +
> +#include "bmi160.h"
> +
> +#define BMI160_I2C_DRV_NAME "bmi160_i2c"
Could just use it inline given the one location in which it's used.
> +
> +static const struct regmap_config bmi160_regmap_config = {
> + .reg_bits = 8,
> + .val_bits = 8,
> +};
Could share the regmap config between the two drivers by moving it to the
core.. Not sure it's worth bothering though.
> +
> +static int bmi160_i2c_probe(struct i2c_client *client,
> + const struct i2c_device_id *id)
> +{
> + struct regmap *regmap;
> + const char *name = NULL;
> +
> + regmap = devm_regmap_init_i2c(client, &bmi160_regmap_config);
> + if (IS_ERR(regmap)) {
> + dev_err(&client->dev, "Failed to register i2c regmap %d\n",
> + (int)PTR_ERR(regmap));
> + return PTR_ERR(regmap);
> + }
> +
> + if (id)
> + name = id->name;
> +
> + return bmi160_core_probe(&client->dev, regmap, name, false);
> +}
> +
> +static int bmi160_i2c_remove(struct i2c_client *client)
> +{
> + bmi160_core_remove(&client->dev);
> +
> + return 0;
> +}
> +
> +static const struct i2c_device_id bmi160_i2c_id[] = {
> + {"bmi160", 0},
> + {}
> +};
> +MODULE_DEVICE_TABLE(i2c, bmi160_i2c_id);
> +
> +static const struct acpi_device_id bmi160_acpi_match[] = {
> + {"BMI0160", 0},
> + { },
> +};
> +MODULE_DEVICE_TABLE(acpi, bmi160_acpi_match);
> +
> +static struct i2c_driver bmi160_i2c_driver = {
> + .driver = {
> + .name = BMI160_I2C_DRV_NAME,
> + .acpi_match_table = ACPI_PTR(bmi160_acpi_match),
> + },
> + .probe = bmi160_i2c_probe,
> + .remove = bmi160_i2c_remove,
> + .id_table = bmi160_i2c_id,
> +};
> +
No blank line here - at least be consistent!
> +module_i2c_driver(bmi160_i2c_driver);
> +
> +MODULE_AUTHOR("Daniel Baluta <[email protected]>");
> +MODULE_DESCRIPTION("BMI160 I2C driver");
> +MODULE_LICENSE("GPL v2");
> diff --git a/drivers/iio/imu/bmi160/bmi160_spi.c b/drivers/iio/imu/bmi160/bmi160_spi.c
> new file mode 100644
> index 0000000..444b723
> --- /dev/null
> +++ b/drivers/iio/imu/bmi160/bmi160_spi.c
> @@ -0,0 +1,71 @@
> +/*
> + * BMI160 - Bosch IMU, SPI bits
> + *
> + * Copyright (c) 2016, Intel Corporation.
> + *
> + * This file is subject to the terms and conditions of version 2 of
> + * the GNU General Public License. See the file COPYING in the main
> + * directory of this archive for more details.
> + *
No need for this blank line ;)
> + */
> +#include <linux/spi/spi.h>
> +#include <linux/regmap.h>
> +#include <linux/acpi.h>
> +
> +#include "bmi160.h"
> +
> +#define BMI160_SPI_DRV_NAME "bmi160_spi"
Again, could just put the string inline without any loss of readability.
> +
> +static const struct regmap_config bmi160_regmap_config = {
> + .reg_bits = 8,
> + .val_bits = 8,
> +};
> +
> +static int bmi160_spi_probe(struct spi_device *spi)
> +{
> + struct regmap *regmap;
> + const struct spi_device_id *id = spi_get_device_id(spi);
> +
> + regmap = devm_regmap_init_spi(spi, &bmi160_regmap_config);
> + if (IS_ERR(regmap)) {
> + dev_err(&spi->dev, "Failed to register spi regmap %d\n",
> + (int)PTR_ERR(regmap));
> + return PTR_ERR(regmap);
> + }
> + return bmi160_core_probe(&spi->dev, regmap, id->name, true);
> +}
> +
> +static int bmi160_spi_remove(struct spi_device *spi)
> +{
> + bmi160_core_remove(&spi->dev);
> +
> + return 0;
> +}
> +
> +static const struct spi_device_id bmi160_spi_id[] = {
> + {"bmi160", 0},
> + {}
> +};
> +
> +MODULE_DEVICE_TABLE(spi, bmi160_spi_id);
> +
> +static const struct acpi_device_id bmi160_acpi_match[] = {
> + {"BMI0160", 0},
> + { },
> +};
> +MODULE_DEVICE_TABLE(acpi, bmi160_acpi_match);
> +
> +static struct spi_driver bmi160_spi_driver = {
> + .probe = bmi160_spi_probe,
> + .remove = bmi160_spi_remove,
> + .id_table = bmi160_spi_id,
> + .driver = {
> + .acpi_match_table = ACPI_PTR(bmi160_acpi_match),
> + .name = BMI160_SPI_DRV_NAME,
> + },
> +};
> +module_spi_driver(bmi160_spi_driver);
> +
> +MODULE_AUTHOR("Daniel Baluta <[email protected]");
> +MODULE_DESCRIPTION("Bosch BMI160 SPI driver");
> +MODULE_LICENSE("GPL v2");
>

2016-04-05 08:17:20

by Daniel Baluta

[permalink] [raw]
Subject: Re: [PATCH] iio: imu: Add initial support for Bosch BMI160

On Fri, Apr 1, 2016 at 5:28 PM, Peter Meerwald-Stadler
<[email protected]> wrote:
>
>> BMI160 is an Inertial Measurement Unit (IMU) which provides acceleration
>> and angular rate measurement. It also offers a secondary I2C interface
>> for connecting a magnetometer sensor (usually BMM160).
>>
>> Current driver offers support for accelerometer and gyroscope readings
>> via sysfs or via buffer interface using an external trigger (e.g.
>> hrtimer). Data is retrieved from IMU via I2C or SPI interface.
>
> comments below

Hi Peter,

Agree with all your comments. Will fix in v2.

thanks!

2016-04-05 08:28:52

by Daniel Baluta

[permalink] [raw]
Subject: Re: [PATCH] iio: imu: Add initial support for Bosch BMI160

On Sun, Apr 3, 2016 at 11:53 AM, Jonathan Cameron <[email protected]> wrote:
> On 01/04/16 13:31, Daniel Baluta wrote:
>> BMI160 is an Inertial Measurement Unit (IMU) which provides acceleration
>> and angular rate measurement. It also offers a secondary I2C interface
>> for connecting a magnetometer sensor (usually BMM160).
>>
>> Current driver offers support for accelerometer and gyroscope readings
>> via sysfs or via buffer interface using an external trigger (e.g.
>> hrtimer). Data is retrieved from IMU via I2C or SPI interface.
>>
>> Datasheet is at:
>> http://www.mouser.com/ds/2/783/BST-BMI160-DS000-07-786474.pdf
>>
>> Signed-off-by: Daniel Baluta <[email protected]>
> A few bits inline. Mostly around the trigger handler...

Answers inline . Thanks a lot for review!

<snip>

>> +/* scan indexes follow DATA register order */
>> +enum bmi160_scan_axis {
>> + BMI160_SCAN_EXT_MAGN_X = 0,
>> + BMI160_SCAN_EXT_MAGN_Y,
>> + BMI160_SCAN_EXT_MAGN_Z,
>> + BMI160_SCAN_RHALL,
> Given the ordering in here is arbitary, why include the unsupported elements
> at this stage? Don't suppose it does any harm though.

This is not exactly arbitrarily. The ordering of these elements matters
because this is the layout in memory for DATA registers. But I see
how removing the references for unsupported elements will still work
but the code it's more readable like that. So I prefer to keep them.

<snip>

>> + reg = bmi160_regs[t].data + (axis - IIO_MOD_X) * 2;
>> +
>> + ret = regmap_bulk_read(data->regmap, reg, &sample, sizeof(sample));
> This looks better for sample than in the trigger handler below.

I'm not sure I understand this, but lets go to the trigger handler below :).


<snip>

>> +static irqreturn_t bmi160_trigger_handler(int irq, void *p)
>> +{
>> + struct iio_poll_func *pf = p;
>> + struct iio_dev *indio_dev = pf->indio_dev;
>> + struct bmi160_data *data = iio_priv(indio_dev);
>> + s16 buf[16]; /* 3 sens x 3 axis x s16 + 3 x s16 pad + 4 x s16 tstamp */
>> + int i, ret, sample, j = 0, base = BMI160_REG_DATA_MAGN_XOUT_L;
>> +
>> + for_each_set_bit(i, indio_dev->active_scan_mask,
>> + indio_dev->masklength) {
> Unless I'm missing something this could pass a stack variable into a
> dma transfer - where alignment needs to be right...
>
> Also, a fixed integer size would probably be wise for sample.
>
>> + ret = regmap_bulk_read(data->regmap, base + 2 * i, &sample,
>> + sizeof(sample));

Hmm, like sizeof(__le16) right instead of sizeof(sample)? Each call to
regmap_bulk_read
here should read one axis - 2 bytes, so I think I get it. Hopefully,
will see it in v2.


>> + usleep_range(BMI160_SOFTRESET_SLEEP, BMI160_SOFTRESET_SLEEP + 1);
>> +
>> + /* CS rising edge is needed before starting SPI, so do a dummy read */
> Is this documented? Seems a little 'interesting'!

Yes, will add a reference to data sheet in v2.



>> +#define BMI160_I2C_DRV_NAME "bmi160_i2c"
> Could just use it inline given the one location in which it's used.

Ok.

>> +
>> +static const struct regmap_config bmi160_regmap_config = {
>> + .reg_bits = 8,
>> + .val_bits = 8,
>> +};
> Could share the regmap config between the two drivers by moving it to the
> core.. Not sure it's worth bothering though.

Will fix. Also Peter mentioned this.

thanks,
Daniel.