iio: imu: Add support to ASM330LHH

Added support to STM ASM330LHH IMU sensor (6-axis acc + gyro)
    - continuous mode support
    - i2c support
    - spi support
    - sw fifo mode support
    - temperature
diff --git a/driver/iio/imu/st_asm330lhh/Kconfig b/driver/iio/imu/st_asm330lhh/Kconfig
new file mode 100644
index 0000000..092cc48
--- /dev/null
+++ b/driver/iio/imu/st_asm330lhh/Kconfig
@@ -0,0 +1,23 @@
+
+config IIO_ST_ASM330LHH
+	tristate "STMicroelectronics ASM330LHH sensor"
+	depends on (I2C || SPI)
+	select IIO_BUFFER
+	select IIO_KFIFO_BUF
+	select IIO_ST_ASM330LHH_I2C if (I2C)
+	select IIO_ST_ASM330LHH_SPI if (SPI_MASTER)
+	help
+	  Say yes here to build support for STMicroelectronics ASM330LHH imu
+	  sensor.
+
+	  To compile this driver as a module, choose M here: the module
+	  will be called st_asm330lhh.
+
+config IIO_ST_ASM330LHH_I2C
+	tristate
+	depends on IIO_ST_ASM330LHH
+
+config IIO_ST_ASM330LHH_SPI
+	tristate
+	depends on IIO_ST_ASM330LHH
+
diff --git a/driver/iio/imu/st_asm330lhh/Makefile b/driver/iio/imu/st_asm330lhh/Makefile
new file mode 100644
index 0000000..7af80de
--- /dev/null
+++ b/driver/iio/imu/st_asm330lhh/Makefile
@@ -0,0 +1,5 @@
+st_asm330lhh-y := st_asm330lhh_core.o st_asm330lhh_buffer.o
+
+obj-$(CONFIG_IIO_ST_ASM330LHH) += st_asm330lhh.o
+obj-$(CONFIG_IIO_ST_ASM330LHH_I2C) += st_asm330lhh_i2c.o
+obj-$(CONFIG_IIO_ST_ASM330LHH_SPI) += st_asm330lhh_spi.o
diff --git a/driver/iio/imu/st_asm330lhh/st_asm330lhh.h b/driver/iio/imu/st_asm330lhh/st_asm330lhh.h
new file mode 100644
index 0000000..52b293f
--- /dev/null
+++ b/driver/iio/imu/st_asm330lhh/st_asm330lhh.h
@@ -0,0 +1,238 @@
+/*
+ * STMicroelectronics st_asm330lhh sensor driver
+ *
+ * Copyright 2018 STMicroelectronics Inc.
+ *
+ * Lorenzo Bianconi <lorenzo.bianconi@st.com>
+ *
+ * Licensed under the GPL-2.
+ */
+
+#ifndef ST_ASM330LHH_H
+#define ST_ASM330LHH_H
+
+#include <linux/device.h>
+#include <linux/iio/iio.h>
+
+#define ST_ASM330LHH_REVISION		"2.0.1"
+#define ST_ASM330LHH_PATCH		"1"
+
+#define ST_ASM330LHH_VERSION		"v"	\
+	ST_ASM330LHH_REVISION			\
+	"-"					\
+	ST_ASM330LHH_PATCH
+
+#define ST_ASM330LHH_DEV_NAME		"asm330lhh"
+
+#define ST_ASM330LHH_SAMPLE_SIZE	6
+#define ST_ASM330LHH_TS_SAMPLE_SIZE	4
+#define ST_ASM330LHH_TAG_SIZE		1
+#define ST_ASM330LHH_FIFO_SAMPLE_SIZE	(ST_ASM330LHH_SAMPLE_SIZE + \
+					 ST_ASM330LHH_TAG_SIZE)
+#define ST_ASM330LHH_MAX_FIFO_DEPTH	416
+
+#define ST_ASM330LHH_REG_FIFO_BATCH_ADDR	0x09
+#define ST_ASM330LHH_REG_FIFO_CTRL4_ADDR	0x0a
+#define ST_ASM330LHH_REG_STATUS_ADDR		0x1e
+#define ST_ASM330LHH_REG_STATUS_TDA		BIT(2)
+#define ST_ASM330LHH_REG_OUT_TEMP_L_ADDR	0x20
+#define ST_ASM330LHH_REG_OUT_TEMP_H_ADDR	0x21
+
+#define ST_ASM330LHH_MAX_ODR			416
+
+/* Define Custom events for FIFO flush */
+#define CUSTOM_IIO_EV_DIR_FIFO_EMPTY (IIO_EV_DIR_NONE + 1)
+#define CUSTOM_IIO_EV_DIR_FIFO_DATA (IIO_EV_DIR_NONE + 2)
+#define CUSTOM_IIO_EV_TYPE_FIFO_FLUSH (IIO_EV_TYPE_CHANGE + 1)
+
+#define ST_ASM330LHH_CHANNEL(chan_type, addr, mod, ch2, scan_idx,	\
+			   rb, sb, sg)					\
+{									\
+	.type = chan_type,						\
+	.address = addr,						\
+	.modified = mod,						\
+	.channel2 = ch2,						\
+	.info_mask_separate = BIT(IIO_CHAN_INFO_RAW) |			\
+			      BIT(IIO_CHAN_INFO_SCALE),			\
+	.info_mask_shared_by_all = BIT(IIO_CHAN_INFO_SAMP_FREQ),	\
+	.scan_index = scan_idx,						\
+	.scan_type = {							\
+		.sign = sg,						\
+		.realbits = rb,						\
+		.storagebits = sb,					\
+		.endianness = IIO_LE,					\
+	},								\
+}
+
+static const struct iio_event_spec st_asm330lhh_flush_event = {
+	.type = CUSTOM_IIO_EV_TYPE_FIFO_FLUSH,
+	.dir = IIO_EV_DIR_EITHER,
+};
+
+#define ST_ASM330LHH_FLUSH_CHANNEL(dtype)		\
+{							\
+	.type = dtype,					\
+	.modified = 0,					\
+	.scan_index = -1,				\
+	.indexed = -1,					\
+	.event_spec = &st_asm330lhh_flush_event,	\
+	.num_event_specs = 1,				\
+}
+
+#define ST_ASM330LHH_RX_MAX_LENGTH	8
+#define ST_ASM330LHH_TX_MAX_LENGTH	8
+
+struct st_asm330lhh_transfer_buffer {
+	u8 rx_buf[ST_ASM330LHH_RX_MAX_LENGTH];
+	u8 tx_buf[ST_ASM330LHH_TX_MAX_LENGTH] ____cacheline_aligned;
+};
+
+struct st_asm330lhh_transfer_function {
+	int (*read)(struct device *dev, u8 addr, int len, u8 *data);
+	int (*write)(struct device *dev, u8 addr, int len, u8 *data);
+};
+
+struct st_asm330lhh_reg {
+	u8 addr;
+	u8 mask;
+};
+
+struct st_asm330lhh_odr {
+	u16 hz;
+	u8 val;
+};
+
+#define ST_ASM330LHH_ODR_LIST_SIZE	7
+struct st_asm330lhh_odr_table_entry {
+	struct st_asm330lhh_reg reg;
+	struct st_asm330lhh_odr odr_avl[ST_ASM330LHH_ODR_LIST_SIZE];
+};
+
+struct st_asm330lhh_fs {
+	u32 gain;
+	u8 val;
+};
+
+#define ST_ASM330LHH_FS_ACC_LIST_SIZE		4
+#define ST_ASM330LHH_FS_GYRO_LIST_SIZE		6
+#define ST_ASM330LHH_FS_TEMP_LIST_SIZE		1
+#define ST_ASM330LHH_FS_LIST_SIZE		6
+struct st_asm330lhh_fs_table_entry {
+	u32 size;
+	struct st_asm330lhh_reg reg;
+	struct st_asm330lhh_fs fs_avl[ST_ASM330LHH_FS_LIST_SIZE];
+};
+
+enum st_asm330lhh_sensor_id {
+	ST_ASM330LHH_ID_ACC,
+	ST_ASM330LHH_ID_GYRO,
+	ST_ASM330LHH_ID_TEMP,
+	ST_ASM330LHH_ID_MAX,
+};
+
+enum st_asm330lhh_fifo_mode {
+	ST_ASM330LHH_FIFO_BYPASS = 0x0,
+	ST_ASM330LHH_FIFO_CONT = 0x6,
+};
+
+enum {
+	ST_ASM330LHH_HW_FLUSH,
+	ST_ASM330LHH_HW_OPERATIONAL,
+};
+
+/**
+ * struct st_asm330lhh_sensor - ST IMU sensor instance
+ * @id: Sensor identifier.
+ * @hw: Pointer to instance of struct st_asm330lhh_hw.
+ * @gain: Configured sensor sensitivity.
+ * @odr: Output data rate of the sensor [Hz].
+ * @watermark: Sensor watermark level.
+ * @batch_mask: Sensor mask for FIFO batching register
+ */
+struct st_asm330lhh_sensor {
+	enum st_asm330lhh_sensor_id id;
+	struct st_asm330lhh_hw *hw;
+
+	u32 gain;
+	u16 odr;
+	u32 offset;
+
+	__le16 old_data;
+
+	u8 std_samples;
+	u8 std_level;
+
+	u16 watermark;
+	u8 batch_mask;
+	u8 batch_addr;
+};
+
+/**
+ * struct st_asm330lhh_hw - ST IMU MEMS hw instance
+ * @dev: Pointer to instance of struct device (I2C or SPI).
+ * @irq: Device interrupt line (I2C or SPI).
+ * @lock: Mutex to protect read and write operations.
+ * @fifo_lock: Mutex to prevent concurrent access to the hw FIFO.
+ * @fifo_mode: FIFO operating mode supported by the device.
+ * @state: hw operational state.
+ * @enable_mask: Enabled sensor bitmask.
+ * @ts_offset: Hw timestamp offset.
+ * @hw_ts: Latest hw timestamp from the sensor.
+ * @ts: Latest timestamp from irq handler.
+ * @delta_ts: Delta time between two consecutive interrupts.
+ * @iio_devs: Pointers to acc/gyro iio_dev instances.
+ * @tf: Transfer function structure used by I/O operations.
+ * @tb: Transfer buffers used by SPI I/O operations.
+ */
+struct st_asm330lhh_hw {
+	struct device *dev;
+	int irq;
+
+	struct mutex lock;
+	struct mutex fifo_lock;
+
+	enum st_asm330lhh_fifo_mode fifo_mode;
+	unsigned long state;
+	u8 enable_mask;
+
+	s64 ts_offset;
+	s64 hw_ts;
+	s64 delta_ts;
+	s64 ts;
+	s64 tsample;
+	s64 hw_ts_old;
+	s64 delta_hw_ts;
+
+	/* Timestamp sample ODR */
+	u16 odr;
+
+	struct iio_dev *iio_devs[ST_ASM330LHH_ID_MAX];
+
+	const struct st_asm330lhh_transfer_function *tf;
+	struct st_asm330lhh_transfer_buffer tb;
+};
+
+extern const struct dev_pm_ops st_asm330lhh_pm_ops;
+
+int st_asm330lhh_probe(struct device *dev, int irq,
+		       const struct st_asm330lhh_transfer_function *tf_ops);
+int st_asm330lhh_sensor_set_enable(struct st_asm330lhh_sensor *sensor,
+				   bool enable);
+int st_asm330lhh_fifo_setup(struct st_asm330lhh_hw *hw);
+int st_asm330lhh_write_with_mask(struct st_asm330lhh_hw *hw, u8 addr, u8 mask,
+				 u8 val);
+int st_asm330lhh_get_odr_val(enum st_asm330lhh_sensor_id id, u16 odr, u8 *val);
+ssize_t st_asm330lhh_flush_fifo(struct device *dev,
+				struct device_attribute *attr,
+				const char *buf, size_t size);
+ssize_t st_asm330lhh_get_max_watermark(struct device *dev,
+				       struct device_attribute *attr, char *buf);
+ssize_t st_asm330lhh_get_watermark(struct device *dev,
+				   struct device_attribute *attr, char *buf);
+ssize_t st_asm330lhh_set_watermark(struct device *dev,
+				   struct device_attribute *attr,
+				   const char *buf, size_t size);
+int st_asm330lhh_set_fifo_mode(struct st_asm330lhh_hw *hw,
+			       enum st_asm330lhh_fifo_mode fifo_mode);
+int st_asm330lhh_suspend_fifo(struct st_asm330lhh_hw *hw);
+#endif /* ST_ASM330LHH_H */
diff --git a/driver/iio/imu/st_asm330lhh/st_asm330lhh_buffer.c b/driver/iio/imu/st_asm330lhh/st_asm330lhh_buffer.c
new file mode 100644
index 0000000..af8c5ba
--- /dev/null
+++ b/driver/iio/imu/st_asm330lhh/st_asm330lhh_buffer.c
@@ -0,0 +1,531 @@
+/*
+ * STMicroelectronics st_asm330lhh FIFO buffer library driver
+ *
+ * Copyright 2018 STMicroelectronics Inc.
+ *
+ * Lorenzo Bianconi <lorenzo.bianconi@st.com>
+ *
+ * Licensed under the GPL-2.
+ */
+#include <linux/module.h>
+#include <linux/interrupt.h>
+#include <linux/irq.h>
+#include <linux/iio/kfifo_buf.h>
+#include <linux/iio/events.h>
+#include <asm/unaligned.h>
+#include <linux/of.h>
+
+#include "st_asm330lhh.h"
+
+#define ST_ASM330LHH_REG_FIFO_THL_ADDR		0x07
+#define ST_ASM330LHH_REG_FIFO_LEN_MASK		GENMASK(8, 0)
+#define ST_ASM330LHH_REG_FIFO_MODE_MASK		GENMASK(2, 0)
+#define ST_ASM330LHH_REG_DEC_TS_MASK		GENMASK(7, 6)
+#define ST_ASM330LHH_REG_HLACTIVE_ADDR		0x12
+#define ST_ASM330LHH_REG_HLACTIVE_MASK		BIT(5)
+#define ST_ASM330LHH_REG_PP_OD_ADDR		0x12
+#define ST_ASM330LHH_REG_PP_OD_MASK		BIT(4)
+#define ST_ASM330LHH_REG_FIFO_DIFFL_ADDR	0x3a
+#define ST_ASM330LHH_REG_TS0_ADDR		0x40
+#define ST_ASM330LHH_REG_TS2_ADDR		0x42
+#define ST_ASM330LHH_REG_FIFO_OUT_TAG_ADDR	0x78
+#define ST_ASM330LHH_GYRO_TAG			0x01
+#define ST_ASM330LHH_ACC_TAG			0x02
+#define ST_ASM330LHH_TS_TAG			0x04
+
+#define ST_ASM330LHH_TS_DELTA_NS		25000ULL /* 25us/LSB */
+
+static inline s64 st_asm330lhh_get_time_ns(void)
+{
+	struct timespec ts;
+
+	get_monotonic_boottime(&ts);
+	return timespec_to_ns(&ts);
+}
+
+#define ST_ASM330LHH_EWMA_LEVEL			120
+#define ST_ASM330LHH_EWMA_DIV			128
+static inline s64 st_asm330lhh_ewma(s64 old, s64 new, int weight)
+{
+	s64 diff, incr;
+
+	diff = new - old;
+	incr = div_s64((ST_ASM330LHH_EWMA_DIV - weight) * diff,
+		       ST_ASM330LHH_EWMA_DIV);
+
+	return old + incr;
+}
+
+static inline int st_asm330lhh_reset_hwts(struct st_asm330lhh_hw *hw)
+{
+	u8 data = 0xaa;
+
+	hw->ts = st_asm330lhh_get_time_ns();
+	hw->ts_offset = hw->ts;
+	hw->hw_ts_old = 0ull;
+	hw->tsample = 0ull;
+
+	return hw->tf->write(hw->dev, ST_ASM330LHH_REG_TS2_ADDR, sizeof(data),
+			     &data);
+}
+
+int st_asm330lhh_set_fifo_mode(struct st_asm330lhh_hw *hw,
+			       enum st_asm330lhh_fifo_mode fifo_mode)
+{
+	int err;
+
+	err = st_asm330lhh_write_with_mask(hw, ST_ASM330LHH_REG_FIFO_CTRL4_ADDR,
+					   ST_ASM330LHH_REG_FIFO_MODE_MASK,
+					   fifo_mode);
+	if (err < 0)
+		return err;
+
+	hw->fifo_mode = fifo_mode;
+
+	return 0;
+}
+
+static int st_asm330lhh_set_sensor_batching_odr(struct st_asm330lhh_sensor *sensor,
+						bool enable)
+{
+	struct st_asm330lhh_hw *hw = sensor->hw;
+	u8 data = 0;
+	int err;
+
+	if (enable) {
+		err = st_asm330lhh_get_odr_val(sensor->id, sensor->odr, &data);
+		if (err < 0)
+			return err;
+	}
+
+	return st_asm330lhh_write_with_mask(hw,
+					    sensor->batch_addr,
+					    sensor->batch_mask, data);
+}
+
+static u16 st_asm330lhh_ts_odr(struct st_asm330lhh_hw *hw)
+{
+	struct st_asm330lhh_sensor *sensor;
+	u16 odr = 0;
+	u8 i;
+
+	for (i = 0; i < ST_ASM330LHH_ID_MAX; i++) {
+		if (!hw->iio_devs[i])
+			continue;
+
+		sensor = iio_priv(hw->iio_devs[i]);
+		if (hw->enable_mask & BIT(sensor->id))
+			odr = max_t(u16, odr, sensor->odr);
+	}
+
+	return odr;
+}
+
+static int st_asm330lhh_update_watermark(struct st_asm330lhh_sensor *sensor,
+					 u16 watermark)
+{
+	u16 fifo_watermark = ST_ASM330LHH_MAX_FIFO_DEPTH, cur_watermark = 0;
+	struct st_asm330lhh_hw *hw = sensor->hw;
+	struct st_asm330lhh_sensor *cur_sensor;
+	__le16 wdata;
+	int i, err;
+	u8 data;
+
+	for (i = 0; i < ST_ASM330LHH_ID_MAX; i++) {
+		cur_sensor = iio_priv(hw->iio_devs[i]);
+
+		if (!(hw->enable_mask & BIT(cur_sensor->id)))
+			continue;
+
+		cur_watermark = (cur_sensor == sensor) ? watermark
+						       : cur_sensor->watermark;
+
+		fifo_watermark = min_t(u16, fifo_watermark, cur_watermark);
+	}
+
+	fifo_watermark = max_t(u16, fifo_watermark, 2);
+	mutex_lock(&hw->lock);
+
+	err = hw->tf->read(hw->dev, ST_ASM330LHH_REG_FIFO_THL_ADDR + 1,
+			   sizeof(data), &data);
+	if (err < 0)
+		goto out;
+
+	fifo_watermark = ((data << 8) & ~ST_ASM330LHH_REG_FIFO_LEN_MASK) |
+			 (fifo_watermark & ST_ASM330LHH_REG_FIFO_LEN_MASK);
+	wdata = cpu_to_le16(fifo_watermark);
+	err = hw->tf->write(hw->dev, ST_ASM330LHH_REG_FIFO_THL_ADDR,
+			    sizeof(wdata), (u8 *)&wdata);
+
+out:
+	mutex_unlock(&hw->lock);
+
+	return err < 0 ? err : 0;
+}
+
+static inline void st_asm330lhh_sync_hw_ts(struct st_asm330lhh_hw *hw, s64 ts)
+{
+	s64 delta = ts - hw->hw_ts;
+
+	hw->ts_offset = st_asm330lhh_ewma(hw->ts_offset, delta,
+					  ST_ASM330LHH_EWMA_LEVEL);
+}
+
+static struct iio_dev *st_asm330lhh_get_iiodev_from_tag(struct st_asm330lhh_hw *hw,
+							u8 tag)
+{
+	struct iio_dev *iio_dev;
+
+	switch (tag) {
+	case ST_ASM330LHH_GYRO_TAG:
+		iio_dev = hw->iio_devs[ST_ASM330LHH_ID_GYRO];
+		break;
+	case ST_ASM330LHH_ACC_TAG:
+		iio_dev = hw->iio_devs[ST_ASM330LHH_ID_ACC];
+		break;
+	default:
+		iio_dev = NULL;
+		break;
+	}
+
+	return iio_dev;
+}
+
+static int st_asm330lhh_read_fifo(struct st_asm330lhh_hw *hw)
+{
+	u8 iio_buf[ALIGN(ST_ASM330LHH_SAMPLE_SIZE, sizeof(s64)) + sizeof(s64)];
+	u8 buf[6 * ST_ASM330LHH_FIFO_SAMPLE_SIZE], tag, *ptr;
+	s64 ts_delta_hw_ts = 0, ts_irq;
+	s64 ts_delta_offs;
+	int i, err, read_len, word_len, fifo_len;
+	struct st_asm330lhh_sensor *sensor;
+	struct iio_dev *iio_dev;
+	__le16 fifo_status;
+	u16 fifo_depth;
+	u32 val;
+	int ts_processed = 0;
+	s64 hw_ts = 0ull, delta_hw_ts, cpu_timestamp;
+
+	ts_irq = hw->ts - hw->delta_ts;
+
+	do
+	{
+		err = hw->tf->read(hw->dev, ST_ASM330LHH_REG_FIFO_DIFFL_ADDR,
+				   sizeof(fifo_status), (u8 *)&fifo_status);
+		if (err < 0)
+			return err;
+
+		fifo_depth = le16_to_cpu(fifo_status) & ST_ASM330LHH_REG_FIFO_LEN_MASK;
+		if (!fifo_depth)
+			return 0;
+
+		read_len = 0;
+		fifo_len = fifo_depth * ST_ASM330LHH_FIFO_SAMPLE_SIZE;
+		while (read_len < fifo_len) {
+			word_len = min_t(int, fifo_len - read_len, sizeof(buf));
+			err = hw->tf->read(hw->dev,
+					   ST_ASM330LHH_REG_FIFO_OUT_TAG_ADDR,
+					   word_len, buf);
+			if (err < 0)
+				return err;
+
+			for (i = 0; i < word_len; i += ST_ASM330LHH_FIFO_SAMPLE_SIZE) {
+				ptr = &buf[i + ST_ASM330LHH_TAG_SIZE];
+				tag = buf[i] >> 3;
+
+				if (tag == ST_ASM330LHH_TS_TAG) {
+					val = get_unaligned_le32(ptr);
+					hw->hw_ts = val * ST_ASM330LHH_TS_DELTA_NS;
+					ts_delta_hw_ts = hw->hw_ts - hw->hw_ts_old;
+					hw_ts += ts_delta_hw_ts;
+					ts_delta_offs =
+						div_s64(hw->delta_hw_ts * ST_ASM330LHH_MAX_ODR, hw->odr);
+
+					hw->ts_offset = st_asm330lhh_ewma(hw->ts_offset, ts_irq -
+						hw->hw_ts + ts_delta_offs, ST_ASM330LHH_EWMA_LEVEL);
+
+					ts_irq += (hw->hw_ts + ts_delta_offs);
+					hw->hw_ts_old = hw->hw_ts;
+					ts_processed++;
+
+					if (!hw->tsample)
+						hw->tsample =
+							hw->ts_offset + (hw->hw_ts + ts_delta_offs);
+					else
+						hw->tsample =
+							hw->tsample + (ts_delta_hw_ts + ts_delta_offs);
+				} else {
+					iio_dev = st_asm330lhh_get_iiodev_from_tag(hw, tag);
+					if (!iio_dev)
+						continue;
+
+					sensor = iio_priv(iio_dev);
+					if (sensor->std_samples < sensor->std_level) {
+						sensor->std_samples++;
+						continue;
+					}
+
+					sensor = iio_priv(iio_dev);
+
+					/* Check if timestamp is in the future. */
+					cpu_timestamp = st_asm330lhh_get_time_ns();
+
+					/* Avoid samples in the future. */
+					if (hw->tsample > cpu_timestamp)
+						hw->tsample = cpu_timestamp;
+
+					memcpy(iio_buf, ptr, ST_ASM330LHH_SAMPLE_SIZE);
+					iio_push_to_buffers_with_timestamp(iio_dev,
+									   iio_buf,
+									   hw->tsample);
+				}
+			}
+			read_len += word_len;
+		}
+
+		delta_hw_ts = div_s64(hw->delta_ts - hw_ts, ts_processed);
+		delta_hw_ts = div_s64(delta_hw_ts * hw->odr, ST_ASM330LHH_MAX_ODR);
+		hw->delta_hw_ts = st_asm330lhh_ewma(hw->delta_hw_ts,
+							delta_hw_ts,
+							ST_ASM330LHH_EWMA_LEVEL);
+	} while(read_len);
+
+	return read_len;
+}
+
+ssize_t st_asm330lhh_get_max_watermark(struct device *dev,
+				       struct device_attribute *attr, char *buf)
+{
+	return sprintf(buf, "%d\n", ST_ASM330LHH_MAX_FIFO_DEPTH);
+}
+
+ssize_t st_asm330lhh_get_watermark(struct device *dev,
+				   struct device_attribute *attr, char *buf)
+{
+	struct iio_dev *iio_dev = dev_get_drvdata(dev);
+	struct st_asm330lhh_sensor *sensor = iio_priv(iio_dev);
+
+	return sprintf(buf, "%d\n", sensor->watermark);
+}
+
+ssize_t st_asm330lhh_set_watermark(struct device *dev,
+				   struct device_attribute *attr,
+				   const char *buf, size_t size)
+{
+	struct iio_dev *iio_dev = dev_get_drvdata(dev);
+	struct st_asm330lhh_sensor *sensor = iio_priv(iio_dev);
+	int err, val;
+
+	mutex_lock(&iio_dev->mlock);
+	if (iio_buffer_enabled(iio_dev)) {
+		err = -EBUSY;
+		goto out;
+	}
+
+	err = kstrtoint(buf, 10, &val);
+	if (err < 0)
+		goto out;
+
+	err = st_asm330lhh_update_watermark(sensor, val);
+	if (err < 0)
+		goto out;
+
+	sensor->watermark = val;
+
+out:
+	mutex_unlock(&iio_dev->mlock);
+
+	return err < 0 ? err : size;
+}
+
+ssize_t st_asm330lhh_flush_fifo(struct device *dev,
+				struct device_attribute *attr,
+				const char *buf, size_t size)
+{
+	struct iio_dev *iio_dev = dev_get_drvdata(dev);
+	struct st_asm330lhh_sensor *sensor = iio_priv(iio_dev);
+	struct st_asm330lhh_hw *hw = sensor->hw;
+	s64 type, event;
+	int count;
+	s64 ts;
+
+	mutex_lock(&hw->fifo_lock);
+	ts = st_asm330lhh_get_time_ns();
+	hw->delta_ts = ts - hw->ts;
+	hw->ts = ts;
+	set_bit(ST_ASM330LHH_HW_FLUSH, &hw->state);
+
+	count = st_asm330lhh_read_fifo(hw);
+
+	mutex_unlock(&hw->fifo_lock);
+
+	type = count > 0 ? CUSTOM_IIO_EV_DIR_FIFO_DATA : CUSTOM_IIO_EV_DIR_FIFO_EMPTY;
+	event = IIO_UNMOD_EVENT_CODE(iio_dev->channels[0].type, -1,
+				     CUSTOM_IIO_EV_TYPE_FIFO_FLUSH, type);
+	iio_push_event(iio_dev, event, st_asm330lhh_get_time_ns());
+
+	return size;
+}
+
+int st_asm330lhh_suspend_fifo(struct st_asm330lhh_hw *hw)
+{
+	int err;
+
+	mutex_lock(&hw->fifo_lock);
+
+	st_asm330lhh_read_fifo(hw);
+	err = st_asm330lhh_set_fifo_mode(hw, ST_ASM330LHH_FIFO_BYPASS);
+
+	mutex_unlock(&hw->fifo_lock);
+
+	return err;
+}
+
+static int st_asm330lhh_update_fifo(struct iio_dev *iio_dev, bool enable)
+{
+	struct st_asm330lhh_sensor *sensor = iio_priv(iio_dev);
+	struct st_asm330lhh_hw *hw = sensor->hw;
+	int err;
+
+	mutex_lock(&hw->fifo_lock);
+
+	err = st_asm330lhh_sensor_set_enable(sensor, enable);
+	if (err < 0)
+		goto out;
+
+	err = st_asm330lhh_set_sensor_batching_odr(sensor, enable);
+	if (err < 0)
+		goto out;
+
+	err = st_asm330lhh_update_watermark(sensor, sensor->watermark);
+	if (err < 0)
+		goto out;
+
+	hw->odr = st_asm330lhh_ts_odr(hw);
+
+	if (enable && hw->fifo_mode == ST_ASM330LHH_FIFO_BYPASS) {
+		st_asm330lhh_reset_hwts(hw);
+		err = st_asm330lhh_set_fifo_mode(hw, ST_ASM330LHH_FIFO_CONT);
+	} else if (!hw->enable_mask) {
+		err = st_asm330lhh_set_fifo_mode(hw, ST_ASM330LHH_FIFO_BYPASS);
+	}
+
+out:
+	mutex_unlock(&hw->fifo_lock);
+
+	return err;
+}
+
+static irqreturn_t st_asm330lhh_handler_irq(int irq, void *private)
+{
+	struct st_asm330lhh_hw *hw = (struct st_asm330lhh_hw *)private;
+	s64 ts = st_asm330lhh_get_time_ns();
+
+	hw->delta_ts = ts - hw->ts;
+	hw->ts = ts;
+
+	return IRQ_WAKE_THREAD;
+}
+
+static irqreturn_t st_asm330lhh_handler_thread(int irq, void *private)
+{
+	struct st_asm330lhh_hw *hw = (struct st_asm330lhh_hw *)private;
+
+	mutex_lock(&hw->fifo_lock);
+
+	st_asm330lhh_read_fifo(hw);
+	clear_bit(ST_ASM330LHH_HW_FLUSH, &hw->state);
+
+	mutex_unlock(&hw->fifo_lock);
+
+	return IRQ_HANDLED;
+}
+
+static int st_asm330lhh_buffer_preenable(struct iio_dev *iio_dev)
+{
+	return st_asm330lhh_update_fifo(iio_dev, true);
+}
+
+static int st_asm330lhh_buffer_postdisable(struct iio_dev *iio_dev)
+{
+	return st_asm330lhh_update_fifo(iio_dev, false);
+}
+
+static const struct iio_buffer_setup_ops st_asm330lhh_buffer_ops = {
+	.preenable = st_asm330lhh_buffer_preenable,
+	.postdisable = st_asm330lhh_buffer_postdisable,
+};
+
+static int st_asm330lhh_fifo_init(struct st_asm330lhh_hw *hw)
+{
+	return st_asm330lhh_write_with_mask(hw, ST_ASM330LHH_REG_FIFO_CTRL4_ADDR,
+					    ST_ASM330LHH_REG_DEC_TS_MASK, 1);
+}
+
+int st_asm330lhh_fifo_setup(struct st_asm330lhh_hw *hw)
+{
+	struct device_node *np = hw->dev->of_node;
+	struct iio_buffer *buffer;
+	unsigned long irq_type;
+	bool irq_active_low;
+	int i, err;
+
+	irq_type = irqd_get_trigger_type(irq_get_irq_data(hw->irq));
+
+	switch (irq_type) {
+	case IRQF_TRIGGER_HIGH:
+	case IRQF_TRIGGER_RISING:
+		irq_active_low = false;
+		break;
+	case IRQF_TRIGGER_LOW:
+	case IRQF_TRIGGER_FALLING:
+		irq_active_low = true;
+		break;
+	default:
+		dev_info(hw->dev, "mode %lx unsupported\n", irq_type);
+		return -EINVAL;
+	}
+
+	err = st_asm330lhh_write_with_mask(hw, ST_ASM330LHH_REG_HLACTIVE_ADDR,
+					   ST_ASM330LHH_REG_HLACTIVE_MASK,
+					   irq_active_low);
+	if (err < 0)
+		return err;
+
+	if (np && of_property_read_bool(np, "drive-open-drain")) {
+		err = st_asm330lhh_write_with_mask(hw,
+					ST_ASM330LHH_REG_PP_OD_ADDR,
+					ST_ASM330LHH_REG_PP_OD_MASK, 1);
+		if (err < 0)
+			return err;
+
+		irq_type |= IRQF_SHARED;
+	}
+
+	err = devm_request_threaded_irq(hw->dev, hw->irq,
+					st_asm330lhh_handler_irq,
+					st_asm330lhh_handler_thread,
+					irq_type | IRQF_ONESHOT,
+					"asm330lhh", hw);
+	if (err) {
+		dev_err(hw->dev, "failed to request trigger irq %d\n",
+			hw->irq);
+		return err;
+	}
+
+	for (i = ST_ASM330LHH_ID_ACC; i < ST_ASM330LHH_ID_MAX; i++) {
+		if (!hw->iio_devs[i])
+			continue;
+
+		buffer = devm_iio_kfifo_allocate(hw->dev);
+		if (!buffer)
+			return -ENOMEM;
+
+		iio_device_attach_buffer(hw->iio_devs[i], buffer);
+		hw->iio_devs[i]->modes |= INDIO_BUFFER_SOFTWARE;
+		hw->iio_devs[i]->setup_ops = &st_asm330lhh_buffer_ops;
+	}
+
+	return st_asm330lhh_fifo_init(hw);
+}
+
diff --git a/driver/iio/imu/st_asm330lhh/st_asm330lhh_core.c b/driver/iio/imu/st_asm330lhh/st_asm330lhh_core.c
new file mode 100644
index 0000000..9d9ee20
--- /dev/null
+++ b/driver/iio/imu/st_asm330lhh/st_asm330lhh_core.c
@@ -0,0 +1,824 @@
+/*
+ * STMicroelectronics st_asm330lhh sensor driver
+ *
+ * Copyright 2018 STMicroelectronics Inc.
+ *
+ * Lorenzo Bianconi <lorenzo.bianconi@st.com>
+ *
+ * Licensed under the GPL-2.
+ */
+
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/delay.h>
+#include <linux/iio/iio.h>
+#include <linux/iio/sysfs.h>
+#include <linux/pm.h>
+#include <linux/version.h>
+#include <linux/of.h>
+
+#include <linux/platform_data/st_sensors_pdata.h>
+
+#include "st_asm330lhh.h"
+
+#define ST_ASM330LHH_REG_INT1_ADDR		0x0d
+#define ST_ASM330LHH_REG_INT2_ADDR		0x0e
+#define ST_ASM330LHH_REG_FIFO_CTRL4_ADDR	0x0a
+#define ST_ASM330LHH_REG_FIFO_FTH_IRQ_MASK	BIT(3)
+#define ST_ASM330LHH_REG_WHOAMI_ADDR		0x0f
+#define ST_ASM330LHH_WHOAMI_VAL			0x6b
+#define ST_ASM330LHH_REG_CTRL1_XL_ADDR		0x10
+#define ST_ASM330LHH_REG_CTRL2_G_ADDR		0x11
+#define ST_ASM330LHH_REG_RESET_ADDR		0x12
+#define ST_ASM330LHH_REG_RESET_MASK		BIT(0)
+#define ST_ASM330LHH_REG_BDU_ADDR		0x12
+#define ST_ASM330LHH_REG_BDU_MASK		BIT(6)
+#define ST_ASM330LHH_REG_INT2_ON_INT1_ADDR	0x13
+#define ST_ASM330LHH_REG_INT2_ON_INT1_MASK	BIT(5)
+#define ST_ASM330LHH_REG_ROUNDING_ADDR		0x14
+#define ST_ASM330LHH_REG_ROUNDING_MASK		GENMASK(6, 5)
+#define ST_ASM330LHH_REG_TIMESTAMP_EN_ADDR	0x19
+#define ST_ASM330LHH_REG_TIMESTAMP_EN_MASK	BIT(5)
+
+#define ST_ASM330LHH_REG_GYRO_OUT_X_L_ADDR	0x22
+#define ST_ASM330LHH_REG_GYRO_OUT_Y_L_ADDR	0x24
+#define ST_ASM330LHH_REG_GYRO_OUT_Z_L_ADDR	0x26
+
+#define ST_ASM330LHH_REG_ACC_OUT_X_L_ADDR	0x28
+#define ST_ASM330LHH_REG_ACC_OUT_Y_L_ADDR	0x2a
+#define ST_ASM330LHH_REG_ACC_OUT_Z_L_ADDR	0x2c
+
+#define ST_ASM330LHH_REG_LIR_ADDR		0x56
+#define ST_ASM330LHH_REG_LIR_MASK		BIT(0)
+
+#define ST_ASM330LHH_ACC_FS_2G_GAIN		IIO_G_TO_M_S_2(61)
+#define ST_ASM330LHH_ACC_FS_4G_GAIN		IIO_G_TO_M_S_2(122)
+#define ST_ASM330LHH_ACC_FS_8G_GAIN		IIO_G_TO_M_S_2(244)
+#define ST_ASM330LHH_ACC_FS_16G_GAIN		IIO_G_TO_M_S_2(488)
+
+#define ST_ASM330LHH_GYRO_FS_125_GAIN		IIO_DEGREE_TO_RAD(4375)
+#define ST_ASM330LHH_GYRO_FS_250_GAIN		IIO_DEGREE_TO_RAD(8750)
+#define ST_ASM330LHH_GYRO_FS_500_GAIN		IIO_DEGREE_TO_RAD(17500)
+#define ST_ASM330LHH_GYRO_FS_1000_GAIN		IIO_DEGREE_TO_RAD(35000)
+#define ST_ASM330LHH_GYRO_FS_2000_GAIN		IIO_DEGREE_TO_RAD(70000)
+#define ST_ASM330LHH_GYRO_FS_4000_GAIN		IIO_DEGREE_TO_RAD(140000)
+
+/* Temperature in uC */
+#define ST_ASM330LHH_TEMP_GAIN			256
+#define ST_ASM330LHH_TEMP_FS_GAIN		(1000000 / ST_ASM330LHH_TEMP_GAIN)
+#define ST_ASM330LHH_OFFSET			(6400)
+
+struct st_asm330lhh_std_entry {
+	u16 odr;
+	u8 val;
+};
+
+/* Minimal number of sample to be discarded */
+struct st_asm330lhh_std_entry st_asm330lhh_std_table[] = {
+	{  13,  2 },
+	{  26,  3 },
+	{  52,  4 },
+	{ 104,  6 },
+	{ 208,  8 },
+	{ 416, 18 },
+};
+
+static const struct st_asm330lhh_odr_table_entry st_asm330lhh_odr_table[] = {
+	[ST_ASM330LHH_ID_ACC] = {
+		.reg = {
+			.addr = ST_ASM330LHH_REG_CTRL1_XL_ADDR,
+			.mask = GENMASK(7, 4),
+		},
+		.odr_avl[0] = {   0, 0x00 },
+		.odr_avl[1] = {  13, 0x01 },
+		.odr_avl[2] = {  26, 0x02 },
+		.odr_avl[3] = {  52, 0x03 },
+		.odr_avl[4] = { 104, 0x04 },
+		.odr_avl[5] = { 208, 0x05 },
+		.odr_avl[6] = { 416, 0x06 },
+	},
+	[ST_ASM330LHH_ID_GYRO] = {
+		.reg = {
+			.addr = ST_ASM330LHH_REG_CTRL2_G_ADDR,
+			.mask = GENMASK(7, 4),
+		},
+		.odr_avl[0] = {   0, 0x00 },
+		.odr_avl[1] = {  13, 0x01 },
+		.odr_avl[2] = {  26, 0x02 },
+		.odr_avl[3] = {  52, 0x03 },
+		.odr_avl[4] = { 104, 0x04 },
+		.odr_avl[5] = { 208, 0x05 },
+		.odr_avl[6] = { 416, 0x06 },
+	},
+	[ST_ASM330LHH_ID_TEMP] = {
+		.odr_avl[0] = {   0, 0x00 },
+		.odr_avl[1] = {  52, 0x01 },
+	}
+};
+
+static const struct st_asm330lhh_fs_table_entry st_asm330lhh_fs_table[] = {
+	[ST_ASM330LHH_ID_ACC] = {
+		.reg = {
+			.addr = ST_ASM330LHH_REG_CTRL1_XL_ADDR,
+			.mask = GENMASK(3, 2),
+		},
+		.size = ST_ASM330LHH_FS_ACC_LIST_SIZE,
+		.fs_avl[0] = {  ST_ASM330LHH_ACC_FS_2G_GAIN, 0x0 },
+		.fs_avl[1] = {  ST_ASM330LHH_ACC_FS_4G_GAIN, 0x2 },
+		.fs_avl[2] = {  ST_ASM330LHH_ACC_FS_8G_GAIN, 0x3 },
+		.fs_avl[3] = { ST_ASM330LHH_ACC_FS_16G_GAIN, 0x1 },
+	},
+	[ST_ASM330LHH_ID_GYRO] = {
+		.reg = {
+			.addr = ST_ASM330LHH_REG_CTRL2_G_ADDR,
+			.mask = GENMASK(3, 0),
+		},
+		.size = ST_ASM330LHH_FS_GYRO_LIST_SIZE,
+		.fs_avl[0] = {  ST_ASM330LHH_GYRO_FS_125_GAIN, 0x2 },
+		.fs_avl[1] = {  ST_ASM330LHH_GYRO_FS_250_GAIN, 0x0 },
+		.fs_avl[2] = {  ST_ASM330LHH_GYRO_FS_500_GAIN, 0x4 },
+		.fs_avl[3] = { ST_ASM330LHH_GYRO_FS_1000_GAIN, 0x8 },
+		.fs_avl[4] = { ST_ASM330LHH_GYRO_FS_2000_GAIN, 0xC },
+		.fs_avl[5] = { ST_ASM330LHH_GYRO_FS_4000_GAIN, 0x1 },
+	},
+	[ST_ASM330LHH_ID_TEMP] = {
+		.size = ST_ASM330LHH_FS_TEMP_LIST_SIZE,
+		.fs_avl[0] = {  ST_ASM330LHH_TEMP_FS_GAIN, 0x0 },
+	}
+};
+
+static const struct iio_chan_spec st_asm330lhh_acc_channels[] = {
+	ST_ASM330LHH_CHANNEL(IIO_ACCEL, ST_ASM330LHH_REG_ACC_OUT_X_L_ADDR,
+			   1, IIO_MOD_X, 0, 16, 16, 's'),
+	ST_ASM330LHH_CHANNEL(IIO_ACCEL, ST_ASM330LHH_REG_ACC_OUT_Y_L_ADDR,
+			   1, IIO_MOD_Y, 1, 16, 16, 's'),
+	ST_ASM330LHH_CHANNEL(IIO_ACCEL, ST_ASM330LHH_REG_ACC_OUT_Z_L_ADDR,
+			   1, IIO_MOD_Z, 2, 16, 16, 's'),
+	ST_ASM330LHH_FLUSH_CHANNEL(IIO_ACCEL),
+	IIO_CHAN_SOFT_TIMESTAMP(3),
+};
+
+static const struct iio_chan_spec st_asm330lhh_gyro_channels[] = {
+	ST_ASM330LHH_CHANNEL(IIO_ANGL_VEL, ST_ASM330LHH_REG_GYRO_OUT_X_L_ADDR,
+			   1, IIO_MOD_X, 0, 16, 16, 's'),
+	ST_ASM330LHH_CHANNEL(IIO_ANGL_VEL, ST_ASM330LHH_REG_GYRO_OUT_Y_L_ADDR,
+			   1, IIO_MOD_Y, 1, 16, 16, 's'),
+	ST_ASM330LHH_CHANNEL(IIO_ANGL_VEL, ST_ASM330LHH_REG_GYRO_OUT_Z_L_ADDR,
+			   1, IIO_MOD_Z, 2, 16, 16, 's'),
+	ST_ASM330LHH_FLUSH_CHANNEL(IIO_ANGL_VEL),
+	IIO_CHAN_SOFT_TIMESTAMP(3),
+};
+
+static const struct iio_chan_spec st_asm330lhh_temp_channels[] = {
+	{
+		.type = IIO_TEMP,
+		.address = ST_ASM330LHH_REG_OUT_TEMP_L_ADDR,
+		.info_mask_separate = BIT(IIO_CHAN_INFO_RAW)
+				| BIT(IIO_CHAN_INFO_OFFSET)
+				| BIT(IIO_CHAN_INFO_SCALE),
+		.scan_index = -1,
+	},
+};
+
+int st_asm330lhh_write_with_mask(struct st_asm330lhh_hw *hw, u8 addr, u8 mask,
+				 u8 val)
+{
+	u8 data;
+	int err;
+
+	mutex_lock(&hw->lock);
+
+	err = hw->tf->read(hw->dev, addr, sizeof(data), &data);
+	if (err < 0) {
+		dev_err(hw->dev, "failed to read %02x register\n", addr);
+		goto out;
+	}
+
+	data = (data & ~mask) | ((val << __ffs(mask)) & mask);
+
+	err = hw->tf->write(hw->dev, addr, sizeof(data), &data);
+	if (err < 0)
+		dev_err(hw->dev, "failed to write %02x register\n", addr);
+
+out:
+	mutex_unlock(&hw->lock);
+
+	return err;
+}
+
+static int st_asm330lhh_check_whoami(struct st_asm330lhh_hw *hw)
+{
+	int err;
+	u8 data;
+
+	err = hw->tf->read(hw->dev, ST_ASM330LHH_REG_WHOAMI_ADDR, sizeof(data),
+			   &data);
+	if (err < 0) {
+		dev_err(hw->dev, "failed to read whoami register\n");
+		return err;
+	}
+
+	if (data != ST_ASM330LHH_WHOAMI_VAL) {
+		dev_err(hw->dev, "unsupported whoami [%02x]\n", data);
+		return -ENODEV;
+	}
+
+	return 0;
+}
+
+static int st_asm330lhh_set_full_scale(struct st_asm330lhh_sensor *sensor,
+				       u32 gain)
+{
+	enum st_asm330lhh_sensor_id id = sensor->id;
+	int i, err;
+	u8 val;
+
+	for (i = 0; i < st_asm330lhh_fs_table[id].size; i++)
+		if (st_asm330lhh_fs_table[id].fs_avl[i].gain == gain)
+			break;
+
+	if (i == st_asm330lhh_fs_table[id].size)
+		return -EINVAL;
+
+	val = st_asm330lhh_fs_table[id].fs_avl[i].val;
+	err = st_asm330lhh_write_with_mask(sensor->hw,
+					st_asm330lhh_fs_table[id].reg.addr,
+					st_asm330lhh_fs_table[id].reg.mask,
+					val);
+	if (err < 0)
+		return err;
+
+	sensor->gain = gain;
+
+	return 0;
+}
+
+int st_asm330lhh_get_odr_val(enum st_asm330lhh_sensor_id id, u16 odr, u8 *val)
+{
+	int i;
+
+	for (i = 0; i < ST_ASM330LHH_ODR_LIST_SIZE; i++)
+		if (st_asm330lhh_odr_table[id].odr_avl[i].hz >= odr)
+			break;
+
+	if (i == ST_ASM330LHH_ODR_LIST_SIZE)
+		return -EINVAL;
+
+	*val = st_asm330lhh_odr_table[id].odr_avl[i].val;
+
+	return 0;
+}
+
+static int st_asm330lhh_set_std_level(struct st_asm330lhh_sensor *sensor,
+			u16 odr)
+{
+	int i;
+
+	for (i = 0; i < ARRAY_SIZE(st_asm330lhh_std_table); i++)
+		if (st_asm330lhh_std_table[i].odr == odr)
+			break;
+
+	if (i == ARRAY_SIZE(st_asm330lhh_std_table))
+		return -EINVAL;
+
+	sensor->std_level = st_asm330lhh_std_table[i].val;
+	sensor->std_samples = 0;
+
+	return 0;
+}
+
+static int st_asm330lhh_set_odr(struct st_asm330lhh_sensor *sensor, u16 odr)
+{
+	struct st_asm330lhh_hw *hw = sensor->hw;
+	u8 val;
+
+	if (st_asm330lhh_get_odr_val(sensor->id, odr, &val) < 0)
+		return -EINVAL;
+
+	return st_asm330lhh_write_with_mask(hw,
+				st_asm330lhh_odr_table[sensor->id].reg.addr,
+				st_asm330lhh_odr_table[sensor->id].reg.mask, val);
+}
+
+int st_asm330lhh_sensor_set_enable(struct st_asm330lhh_sensor *sensor,
+				   bool enable)
+{
+	u16 odr = enable ? sensor->odr : 0;
+	int err;
+
+	if (sensor->id != ST_ASM330LHH_ID_TEMP) {
+		err = st_asm330lhh_set_odr(sensor, odr);
+		if (err < 0)
+			return err;
+	}
+
+	if (enable)
+		sensor->hw->enable_mask |= BIT(sensor->id);
+	else
+		sensor->hw->enable_mask &= ~BIT(sensor->id);
+
+	return 0;
+}
+
+static int st_asm330lhh_read_oneshot(struct st_asm330lhh_sensor *sensor,
+				     u8 addr, int *val)
+{
+	int err, delay;
+	__le16 data;
+
+	if (sensor->id == ST_ASM330LHH_ID_TEMP) {
+		u8 status;
+
+		mutex_lock(&sensor->hw->fifo_lock);
+		err = sensor->hw->tf->read(sensor->hw->dev,
+					   ST_ASM330LHH_REG_STATUS_ADDR, sizeof(status), &status);
+		if (err < 0)
+			goto unlock;
+
+		if (status & ST_ASM330LHH_REG_STATUS_TDA) {
+			err = sensor->hw->tf->read(sensor->hw->dev, addr, sizeof(data),
+					   (u8 *)&data);
+			if (err < 0)
+				goto unlock;
+
+			sensor->old_data = data;
+		} else
+			data = sensor->old_data;
+unlock:
+		mutex_unlock(&sensor->hw->fifo_lock);
+
+	} else {
+		err = st_asm330lhh_sensor_set_enable(sensor, true);
+		if (err < 0)
+			return err;
+
+		delay = 1000000 / sensor->odr;
+		usleep_range(delay, 2 * delay);
+
+		err = sensor->hw->tf->read(sensor->hw->dev, addr, sizeof(data),
+					   (u8 *)&data);
+		if (err < 0)
+			return err;
+
+		st_asm330lhh_sensor_set_enable(sensor, false);
+	}
+
+	*val = (s16)data;
+
+	return IIO_VAL_INT;
+}
+
+static int st_asm330lhh_read_raw(struct iio_dev *iio_dev,
+				 struct iio_chan_spec const *ch,
+				 int *val, int *val2, long mask)
+{
+	struct st_asm330lhh_sensor *sensor = iio_priv(iio_dev);
+	int ret;
+
+	switch (mask) {
+	case IIO_CHAN_INFO_RAW:
+		mutex_lock(&iio_dev->mlock);
+		if (iio_buffer_enabled(iio_dev)) {
+			ret = -EBUSY;
+			mutex_unlock(&iio_dev->mlock);
+			break;
+		}
+		ret = st_asm330lhh_read_oneshot(sensor, ch->address, val);
+		mutex_unlock(&iio_dev->mlock);
+		break;
+	case IIO_CHAN_INFO_OFFSET:
+		switch (ch->type) {
+		case IIO_TEMP:
+			*val = sensor->offset;
+			ret = IIO_VAL_INT;
+			break;
+		default:
+			return -EINVAL;
+		}
+		break;
+	case IIO_CHAN_INFO_SAMP_FREQ:
+		*val = sensor->odr;
+		ret = IIO_VAL_INT;
+		break;
+	case IIO_CHAN_INFO_SCALE:
+		switch (ch->type) {
+		case IIO_TEMP:
+			*val = 1;
+			*val2 = ST_ASM330LHH_TEMP_GAIN;
+			ret = IIO_VAL_FRACTIONAL;
+			break;
+		case IIO_ACCEL:
+		case IIO_ANGL_VEL:
+			*val = 0;
+			*val2 = sensor->gain;
+			ret = IIO_VAL_INT_PLUS_MICRO;
+			break;
+		default:
+			return -EINVAL;
+		}
+		break;
+	default:
+		ret = -EINVAL;
+		break;
+	}
+
+	return ret;
+}
+
+static int st_asm330lhh_write_raw(struct iio_dev *iio_dev,
+				  struct iio_chan_spec const *chan,
+				  int val, int val2, long mask)
+{
+	struct st_asm330lhh_sensor *sensor = iio_priv(iio_dev);
+	int err;
+
+	mutex_lock(&iio_dev->mlock);
+
+	switch (mask) {
+	case IIO_CHAN_INFO_SCALE:
+		err = st_asm330lhh_set_full_scale(sensor, val2);
+		break;
+	case IIO_CHAN_INFO_SAMP_FREQ: {
+		u8 data;
+
+		err = st_asm330lhh_set_std_level(sensor, val);
+		if (err < 0)
+			break;
+
+		err = st_asm330lhh_get_odr_val(sensor->id, val, &data);
+		if (!err)
+			sensor->odr = val;
+
+		err = st_asm330lhh_set_odr(sensor, sensor->odr);
+		break;
+	}
+	default:
+		err = -EINVAL;
+		break;
+	}
+
+	mutex_unlock(&iio_dev->mlock);
+
+	return err;
+}
+
+static ssize_t
+st_asm330lhh_sysfs_sampling_frequency_avail(struct device *dev,
+					    struct device_attribute *attr,
+					    char *buf)
+{
+	struct st_asm330lhh_sensor *sensor = iio_priv(dev_get_drvdata(dev));
+	enum st_asm330lhh_sensor_id id = sensor->id;
+	int i, len = 0;
+
+	for (i = 1; i < ST_ASM330LHH_ODR_LIST_SIZE; i++)
+		len += scnprintf(buf + len, PAGE_SIZE - len, "%d ",
+				 st_asm330lhh_odr_table[id].odr_avl[i].hz);
+	buf[len - 1] = '\n';
+
+	return len;
+}
+
+static ssize_t st_asm330lhh_sysfs_scale_avail(struct device *dev,
+					      struct device_attribute *attr,
+					      char *buf)
+{
+	struct st_asm330lhh_sensor *sensor = iio_priv(dev_get_drvdata(dev));
+	enum st_asm330lhh_sensor_id id = sensor->id;
+	int i, len = 0;
+
+	for (i = 0; i < st_asm330lhh_fs_table[id].size; i++)
+		len += scnprintf(buf + len, PAGE_SIZE - len, "0.%06u ",
+				 st_asm330lhh_fs_table[id].fs_avl[i].gain);
+	buf[len - 1] = '\n';
+
+	return len;
+}
+
+static IIO_DEV_ATTR_SAMP_FREQ_AVAIL(st_asm330lhh_sysfs_sampling_frequency_avail);
+static IIO_DEVICE_ATTR(in_accel_scale_available, 0444,
+		       st_asm330lhh_sysfs_scale_avail, NULL, 0);
+static IIO_DEVICE_ATTR(in_anglvel_scale_available, 0444,
+		       st_asm330lhh_sysfs_scale_avail, NULL, 0);
+static IIO_DEVICE_ATTR(in_temp_scale_available, 0444,
+		       st_asm330lhh_sysfs_scale_avail, NULL, 0);
+static IIO_DEVICE_ATTR(hwfifo_watermark_max, 0444,
+		       st_asm330lhh_get_max_watermark, NULL, 0);
+static IIO_DEVICE_ATTR(hwfifo_flush, 0200, NULL, st_asm330lhh_flush_fifo, 0);
+static IIO_DEVICE_ATTR(hwfifo_watermark, 0644, st_asm330lhh_get_watermark,
+		       st_asm330lhh_set_watermark, 0);
+
+static struct attribute *st_asm330lhh_acc_attributes[] = {
+	&iio_dev_attr_sampling_frequency_available.dev_attr.attr,
+	&iio_dev_attr_in_accel_scale_available.dev_attr.attr,
+	&iio_dev_attr_hwfifo_watermark_max.dev_attr.attr,
+	&iio_dev_attr_hwfifo_watermark.dev_attr.attr,
+	&iio_dev_attr_hwfifo_flush.dev_attr.attr,
+	NULL,
+};
+
+static const struct attribute_group st_asm330lhh_acc_attribute_group = {
+	.attrs = st_asm330lhh_acc_attributes,
+};
+
+static const struct iio_info st_asm330lhh_acc_info = {
+	.driver_module = THIS_MODULE,
+	.attrs = &st_asm330lhh_acc_attribute_group,
+	.read_raw = st_asm330lhh_read_raw,
+	.write_raw = st_asm330lhh_write_raw,
+};
+
+static struct attribute *st_asm330lhh_gyro_attributes[] = {
+	&iio_dev_attr_sampling_frequency_available.dev_attr.attr,
+	&iio_dev_attr_in_anglvel_scale_available.dev_attr.attr,
+	&iio_dev_attr_hwfifo_watermark_max.dev_attr.attr,
+	&iio_dev_attr_hwfifo_watermark.dev_attr.attr,
+	&iio_dev_attr_hwfifo_flush.dev_attr.attr,
+	NULL,
+};
+
+static const struct attribute_group st_asm330lhh_gyro_attribute_group = {
+	.attrs = st_asm330lhh_gyro_attributes,
+};
+
+static const struct iio_info st_asm330lhh_gyro_info = {
+	.driver_module = THIS_MODULE,
+	.attrs = &st_asm330lhh_gyro_attribute_group,
+	.read_raw = st_asm330lhh_read_raw,
+	.write_raw = st_asm330lhh_write_raw,
+};
+
+static struct attribute *st_asm330lhh_temp_attributes[] = {
+	&iio_dev_attr_sampling_frequency_available.dev_attr.attr,
+	&iio_dev_attr_in_temp_scale_available.dev_attr.attr,
+	&iio_dev_attr_hwfifo_watermark_max.dev_attr.attr,
+	&iio_dev_attr_hwfifo_watermark.dev_attr.attr,
+	&iio_dev_attr_hwfifo_flush.dev_attr.attr,
+	NULL,
+};
+
+static const struct attribute_group st_asm330lhh_temp_attribute_group = {
+	.attrs = st_asm330lhh_temp_attributes,
+};
+
+static const struct iio_info st_asm330lhh_temp_info = {
+	.driver_module = THIS_MODULE,
+	.attrs = &st_asm330lhh_temp_attribute_group,
+	.read_raw = st_asm330lhh_read_raw,
+	.write_raw = st_asm330lhh_write_raw,
+};
+
+static const unsigned long st_asm330lhh_available_scan_masks[] = { 0x7, 0x0 };
+
+static int st_asm330lhh_of_get_drdy_pin(struct st_asm330lhh_hw *hw, int *drdy_pin)
+{
+	struct device_node *np = hw->dev->of_node;
+
+	if (!np)
+		return -EINVAL;
+
+	return of_property_read_u32(np, "st,drdy-int-pin", drdy_pin);
+}
+
+static int st_asm330lhh_get_drdy_reg(struct st_asm330lhh_hw *hw, u8 *drdy_reg)
+{
+	int err = 0, drdy_pin;
+
+	if (st_asm330lhh_of_get_drdy_pin(hw, &drdy_pin) < 0) {
+		struct st_sensors_platform_data *pdata;
+		struct device *dev = hw->dev;
+
+		pdata = (struct st_sensors_platform_data *)dev->platform_data;
+		drdy_pin = pdata ? pdata->drdy_int_pin : 1;
+	}
+
+	switch (drdy_pin) {
+	case 1:
+		*drdy_reg = ST_ASM330LHH_REG_INT1_ADDR;
+		break;
+	case 2:
+		*drdy_reg = ST_ASM330LHH_REG_INT2_ADDR;
+		break;
+	default:
+		dev_err(hw->dev, "unsupported data ready pin\n");
+		err = -EINVAL;
+		break;
+	}
+
+	return err;
+}
+
+static int st_asm330lhh_init_device(struct st_asm330lhh_hw *hw)
+{
+	u8 drdy_int_reg;
+	int err;
+
+	err = st_asm330lhh_write_with_mask(hw, ST_ASM330LHH_REG_RESET_ADDR,
+					   ST_ASM330LHH_REG_RESET_MASK, 1);
+	if (err < 0)
+		return err;
+
+	msleep(200);
+
+	/* latch interrupts */
+	err = st_asm330lhh_write_with_mask(hw, ST_ASM330LHH_REG_LIR_ADDR,
+					   ST_ASM330LHH_REG_LIR_MASK, 1);
+	if (err < 0)
+		return err;
+
+	/* enable Block Data Update */
+	err = st_asm330lhh_write_with_mask(hw, ST_ASM330LHH_REG_BDU_ADDR,
+					   ST_ASM330LHH_REG_BDU_MASK, 1);
+	if (err < 0)
+		return err;
+
+	err = st_asm330lhh_write_with_mask(hw, ST_ASM330LHH_REG_ROUNDING_ADDR,
+					   ST_ASM330LHH_REG_ROUNDING_MASK, 3);
+	if (err < 0)
+		return err;
+
+	/* init timestamp engine */
+	err = st_asm330lhh_write_with_mask(hw, ST_ASM330LHH_REG_TIMESTAMP_EN_ADDR,
+					   ST_ASM330LHH_REG_TIMESTAMP_EN_MASK, 1);
+	if (err < 0)
+		return err;
+
+	/* enable FIFO watermak interrupt */
+	err = st_asm330lhh_get_drdy_reg(hw, &drdy_int_reg);
+	if (err < 0)
+		return err;
+
+	return st_asm330lhh_write_with_mask(hw, drdy_int_reg,
+					    ST_ASM330LHH_REG_FIFO_FTH_IRQ_MASK, 1);
+}
+
+static struct iio_dev *st_asm330lhh_alloc_iiodev(struct st_asm330lhh_hw *hw,
+						 enum st_asm330lhh_sensor_id id)
+{
+	struct st_asm330lhh_sensor *sensor;
+	struct iio_dev *iio_dev;
+
+	iio_dev = devm_iio_device_alloc(hw->dev, sizeof(*sensor));
+	if (!iio_dev)
+		return NULL;
+
+	iio_dev->modes = INDIO_DIRECT_MODE;
+	iio_dev->dev.parent = hw->dev;
+	iio_dev->available_scan_masks = st_asm330lhh_available_scan_masks;
+
+	sensor = iio_priv(iio_dev);
+	sensor->id = id;
+	sensor->hw = hw;
+	sensor->odr = st_asm330lhh_odr_table[id].odr_avl[1].hz;
+	sensor->gain = st_asm330lhh_fs_table[id].fs_avl[0].gain;
+	sensor->watermark = 1;
+	sensor->old_data = 0;
+
+	switch (id) {
+	case ST_ASM330LHH_ID_ACC:
+		iio_dev->channels = st_asm330lhh_acc_channels;
+		iio_dev->num_channels = ARRAY_SIZE(st_asm330lhh_acc_channels);
+		iio_dev->name = "asm330lhh_accel";
+		iio_dev->info = &st_asm330lhh_acc_info;
+		sensor->batch_addr = ST_ASM330LHH_REG_FIFO_BATCH_ADDR;
+		sensor->batch_mask = GENMASK(3, 0);
+		sensor->offset = 0;
+		break;
+	case ST_ASM330LHH_ID_GYRO:
+		iio_dev->channels = st_asm330lhh_gyro_channels;
+		iio_dev->num_channels = ARRAY_SIZE(st_asm330lhh_gyro_channels);
+		iio_dev->name = "asm330lhh_gyro";
+		iio_dev->info = &st_asm330lhh_gyro_info;
+		sensor->batch_addr = ST_ASM330LHH_REG_FIFO_BATCH_ADDR;
+		sensor->batch_mask = GENMASK(7, 4);
+		sensor->offset = 0;
+		break;
+	case ST_ASM330LHH_ID_TEMP:
+		iio_dev->channels = st_asm330lhh_temp_channels;
+		iio_dev->num_channels = ARRAY_SIZE(st_asm330lhh_temp_channels);
+		iio_dev->name = "asm330lhh_temp";
+		iio_dev->info = &st_asm330lhh_temp_info;
+		sensor->offset = ST_ASM330LHH_OFFSET;
+		break;
+	default:
+		return NULL;
+	}
+
+	return iio_dev;
+}
+
+int st_asm330lhh_probe(struct device *dev, int irq,
+		       const struct st_asm330lhh_transfer_function *tf_ops)
+{
+	struct st_asm330lhh_hw *hw;
+	int i, err;
+
+	hw = devm_kzalloc(dev, sizeof(*hw), GFP_KERNEL);
+	if (!hw)
+		return -ENOMEM;
+
+	dev_set_drvdata(dev, (void *)hw);
+
+	mutex_init(&hw->lock);
+	mutex_init(&hw->fifo_lock);
+
+	hw->dev = dev;
+	hw->irq = irq;
+	hw->tf = tf_ops;
+
+	dev_info(hw->dev, "Ver: %s\n", ST_ASM330LHH_VERSION);
+	err = st_asm330lhh_check_whoami(hw);
+	if (err < 0)
+		return err;
+
+	err = st_asm330lhh_init_device(hw);
+	if (err < 0)
+		return err;
+
+	for (i = 0; i < ST_ASM330LHH_ID_MAX; i++) {
+		hw->iio_devs[i] = st_asm330lhh_alloc_iiodev(hw, i);
+		if (!hw->iio_devs[i])
+			return -ENOMEM;
+	}
+
+	if (hw->irq > 0) {
+		err = st_asm330lhh_fifo_setup(hw);
+		if (err < 0)
+			return err;
+	}
+
+	for (i = 0; i < ST_ASM330LHH_ID_MAX; i++) {
+		if (!hw->iio_devs[i])
+			continue;
+
+		err = devm_iio_device_register(hw->dev, hw->iio_devs[i]);
+		if (err)
+			return err;
+	}
+
+	dev_info(hw->dev, "probe ok\n");
+
+	return 0;
+}
+EXPORT_SYMBOL(st_asm330lhh_probe);
+
+static int __maybe_unused st_asm330lhh_suspend(struct device *dev)
+{
+	struct st_asm330lhh_hw *hw = dev_get_drvdata(dev);
+	struct st_asm330lhh_sensor *sensor;
+	int i, err = 0;
+
+	for (i = 0; i < ST_ASM330LHH_ID_MAX; i++) {
+		if (!hw->iio_devs[i])
+			continue;
+
+		sensor = iio_priv(hw->iio_devs[i]);
+
+		if (!(hw->enable_mask & BIT(sensor->id)))
+			continue;
+
+		err = st_asm330lhh_set_odr(sensor, 0);
+		if (err < 0)
+			return err;
+	}
+
+	if (hw->enable_mask)
+		err = st_asm330lhh_suspend_fifo(hw);
+
+	return err;
+}
+
+static int __maybe_unused st_asm330lhh_resume(struct device *dev)
+{
+	struct st_asm330lhh_hw *hw = dev_get_drvdata(dev);
+	struct st_asm330lhh_sensor *sensor;
+	int i, err = 0;
+
+	for (i = 0; i < ST_ASM330LHH_ID_MAX; i++) {
+		if (!hw->iio_devs[i])
+			continue;
+
+		sensor = iio_priv(hw->iio_devs[i]);
+		if (!(hw->enable_mask & BIT(sensor->id)))
+			continue;
+
+		err = st_asm330lhh_set_odr(sensor, sensor->odr);
+		if (err < 0)
+			return err;
+	}
+
+	if (hw->enable_mask)
+		err = st_asm330lhh_set_fifo_mode(hw, ST_ASM330LHH_FIFO_CONT);
+
+	return err;
+}
+
+const struct dev_pm_ops st_asm330lhh_pm_ops = {
+	SET_SYSTEM_SLEEP_PM_OPS(st_asm330lhh_suspend, st_asm330lhh_resume)
+};
+EXPORT_SYMBOL(st_asm330lhh_pm_ops);
+
+MODULE_AUTHOR("Lorenzo Bianconi <lorenzo.bianconi@st.com>");
+MODULE_DESCRIPTION("STMicroelectronics st_asm330lhh driver");
+MODULE_LICENSE("GPL v2");
+MODULE_VERSION(ST_ASM330LHH_VERSION);
diff --git a/driver/iio/imu/st_asm330lhh/st_asm330lhh_i2c.c b/driver/iio/imu/st_asm330lhh/st_asm330lhh_i2c.c
new file mode 100644
index 0000000..4875097
--- /dev/null
+++ b/driver/iio/imu/st_asm330lhh/st_asm330lhh_i2c.c
@@ -0,0 +1,94 @@
+/*
+ * STMicroelectronics st_asm330lhh i2c driver
+ *
+ * Copyright 2018 STMicroelectronics Inc.
+ *
+ * Lorenzo Bianconi <lorenzo.bianconi@st.com>
+ *
+ * Licensed under the GPL-2.
+ */
+
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/i2c.h>
+#include <linux/slab.h>
+#include <linux/of.h>
+
+#include "st_asm330lhh.h"
+
+static int st_asm330lhh_i2c_read(struct device *dev, u8 addr, int len, u8 *data)
+{
+	struct i2c_client *client = to_i2c_client(dev);
+	struct i2c_msg msg[2];
+
+	msg[0].addr = client->addr;
+	msg[0].flags = client->flags;
+	msg[0].len = 1;
+	msg[0].buf = &addr;
+
+	msg[1].addr = client->addr;
+	msg[1].flags = client->flags | I2C_M_RD;
+	msg[1].len = len;
+	msg[1].buf = data;
+
+	return i2c_transfer(client->adapter, msg, 2);
+}
+
+static int st_asm330lhh_i2c_write(struct device *dev, u8 addr, int len, u8 *data)
+{
+	struct i2c_client *client = to_i2c_client(dev);
+	struct i2c_msg msg;
+	u8 send[len + 1];
+
+	send[0] = addr;
+	memcpy(&send[1], data, len * sizeof(u8));
+
+	msg.addr = client->addr;
+	msg.flags = client->flags;
+	msg.len = len + 1;
+	msg.buf = send;
+
+	return i2c_transfer(client->adapter, &msg, 1);
+}
+
+static const struct st_asm330lhh_transfer_function st_asm330lhh_transfer_fn = {
+	.read = st_asm330lhh_i2c_read,
+	.write = st_asm330lhh_i2c_write,
+};
+
+static int st_asm330lhh_i2c_probe(struct i2c_client *client,
+				const struct i2c_device_id *id)
+{
+	return st_asm330lhh_probe(&client->dev, client->irq,
+				&st_asm330lhh_transfer_fn);
+}
+
+static const struct of_device_id st_asm330lhh_i2c_of_match[] = {
+	{
+		.compatible = "st,asm330lhh",
+	},
+	{},
+};
+MODULE_DEVICE_TABLE(of, st_asm330lhh_i2c_of_match);
+
+static const struct i2c_device_id st_asm330lhh_i2c_id_table[] = {
+	{ ST_ASM330LHH_DEV_NAME },
+	{},
+};
+MODULE_DEVICE_TABLE(i2c, st_asm330lhh_i2c_id_table);
+
+static struct i2c_driver st_asm330lhh_driver = {
+	.driver = {
+		.name = "st_asm330lhh_i2c",
+		.pm = &st_asm330lhh_pm_ops,
+		.of_match_table = of_match_ptr(st_asm330lhh_i2c_of_match),
+	},
+	.probe = st_asm330lhh_i2c_probe,
+	.id_table = st_asm330lhh_i2c_id_table,
+};
+module_i2c_driver(st_asm330lhh_driver);
+
+MODULE_AUTHOR("Lorenzo Bianconi <lorenzo.bianconi@st.com>");
+MODULE_DESCRIPTION("STMicroelectronics st_asm330lhh i2c driver");
+MODULE_LICENSE("GPL v2");
+MODULE_VERSION(ST_ASM330LHH_VERSION);
diff --git a/driver/iio/imu/st_asm330lhh/st_asm330lhh_spi.c b/driver/iio/imu/st_asm330lhh/st_asm330lhh_spi.c
new file mode 100644
index 0000000..07b8400
--- /dev/null
+++ b/driver/iio/imu/st_asm330lhh/st_asm330lhh_spi.c
@@ -0,0 +1,109 @@
+/*
+ * STMicroelectronics st_asm330lhh spi driver
+ *
+ * Copyright 2018 STMicroelectronics Inc.
+ *
+ * Lorenzo Bianconi <lorenzo.bianconi@st.com>
+ *
+ * Licensed under the GPL-2.
+ */
+
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/spi/spi.h>
+#include <linux/slab.h>
+#include <linux/of.h>
+
+#include "st_asm330lhh.h"
+
+#define SENSORS_SPI_READ	BIT(7)
+
+static int st_asm330lhh_spi_read(struct device *dev, u8 addr, int len,
+			       u8 *data)
+{
+	struct spi_device *spi = to_spi_device(dev);
+	struct st_asm330lhh_hw *hw = spi_get_drvdata(spi);
+	int err;
+
+	struct spi_transfer xfers[] = {
+		{
+			.tx_buf = hw->tb.tx_buf,
+			.bits_per_word = 8,
+			.len = 1,
+		},
+		{
+			.rx_buf = hw->tb.rx_buf,
+			.bits_per_word = 8,
+			.len = len,
+		}
+	};
+
+	hw->tb.tx_buf[0] = addr | SENSORS_SPI_READ;
+
+	err = spi_sync_transfer(spi, xfers,  ARRAY_SIZE(xfers));
+	if (err < 0)
+		return err;
+
+	memcpy(data, hw->tb.rx_buf, len * sizeof(u8));
+
+	return len;
+}
+
+static int st_asm330lhh_spi_write(struct device *dev, u8 addr, int len,
+				u8 *data)
+{
+	struct st_asm330lhh_hw *hw;
+	struct spi_device *spi;
+
+	if (len >= ST_ASM330LHH_TX_MAX_LENGTH)
+		return -ENOMEM;
+
+	spi = to_spi_device(dev);
+	hw = spi_get_drvdata(spi);
+
+	hw->tb.tx_buf[0] = addr;
+	memcpy(&hw->tb.tx_buf[1], data, len);
+
+	return spi_write(spi, hw->tb.tx_buf, len + 1);
+}
+
+static const struct st_asm330lhh_transfer_function st_asm330lhh_transfer_fn = {
+	.read = st_asm330lhh_spi_read,
+	.write = st_asm330lhh_spi_write,
+};
+
+static int st_asm330lhh_spi_probe(struct spi_device *spi)
+{
+	return st_asm330lhh_probe(&spi->dev, spi->irq,
+				&st_asm330lhh_transfer_fn);
+}
+
+static const struct of_device_id st_asm330lhh_spi_of_match[] = {
+	{
+		.compatible = "st,asm330lhh",
+	},
+	{},
+};
+MODULE_DEVICE_TABLE(of, st_asm330lhh_spi_of_match);
+
+static const struct spi_device_id st_asm330lhh_spi_id_table[] = {
+	{ ST_ASM330LHH_DEV_NAME },
+	{},
+};
+MODULE_DEVICE_TABLE(spi, st_asm330lhh_spi_id_table);
+
+static struct spi_driver st_asm330lhh_driver = {
+	.driver = {
+		.name = "st_asm330lhh_spi",
+		.pm = &st_asm330lhh_pm_ops,
+		.of_match_table = of_match_ptr(st_asm330lhh_spi_of_match),
+	},
+	.probe = st_asm330lhh_spi_probe,
+	.id_table = st_asm330lhh_spi_id_table,
+};
+module_spi_driver(st_asm330lhh_driver);
+
+MODULE_AUTHOR("Lorenzo Bianconi <lorenzo.bianconi@st.com>");
+MODULE_DESCRIPTION("STMicroelectronics st_asm330lhh spi driver");
+MODULE_LICENSE("GPL v2");
+MODULE_VERSION(ST_ASM330LHH_VERSION);