driver/sensors: lis2dh: Fix I2C and SPI bus communication

Add I2C and SPI bus communication routines in separate files,
and register one or the other as read/write callbacks based
on bus selection in DTS.

This commit is fixing issue #22348 as well, as the SPI part
is handling in the proper way the CS GPIO part.

Signed-off-by: Armando Visconti <armando.visconti@st.com>
diff --git a/drivers/sensor/lis2dh/CMakeLists.txt b/drivers/sensor/lis2dh/CMakeLists.txt
index 41abacb..25a4a22 100644
--- a/drivers/sensor/lis2dh/CMakeLists.txt
+++ b/drivers/sensor/lis2dh/CMakeLists.txt
@@ -3,4 +3,6 @@
 zephyr_library()
 
 zephyr_library_sources_ifdef(CONFIG_LIS2DH lis2dh.c)
+zephyr_library_sources_ifdef(CONFIG_LIS2DH lis2dh_i2c.c)
+zephyr_library_sources_ifdef(CONFIG_LIS2DH lis2dh_spi.c)
 zephyr_library_sources_ifdef(CONFIG_LIS2DH_TRIGGER lis2dh_trigger.c)
diff --git a/drivers/sensor/lis2dh/lis2dh.c b/drivers/sensor/lis2dh/lis2dh.c
index 6e34f30..f32b844 100644
--- a/drivers/sensor/lis2dh/lis2dh.c
+++ b/drivers/sensor/lis2dh/lis2dh.c
@@ -34,56 +34,6 @@
 #endif
 };
 
-#if defined(DT_ST_LIS2DH_BUS_SPI)
-int lis2dh_spi_access(struct lis2dh_data *ctx, u8_t cmd,
-		      void *data, size_t length)
-{
-	const struct spi_buf buf[2] = {
-		{
-			.buf = &cmd,
-			.len = 1
-		},
-		{
-			.buf = data,
-			.len = length
-		}
-	};
-	const struct spi_buf_set tx = {
-		.buffers = buf,
-		.count = 2
-	};
-
-	if (cmd & LIS2DH_SPI_READ_BIT) {
-		const struct spi_buf_set rx = {
-			.buffers = buf,
-			.count = 2
-		};
-
-		return spi_transceive(ctx->spi, &ctx->spi_cfg, &tx, &rx);
-	}
-
-	return spi_write(ctx->spi, &ctx->spi_cfg, &tx);
-}
-#endif
-
-int lis2dh_reg_field_update(struct device *dev, u8_t reg_addr,
-			    u8_t pos, u8_t mask, u8_t val)
-{
-	int status;
-	u8_t old_val;
-
-	/* just to remove gcc warning */
-	old_val = 0U;
-
-	status = lis2dh_reg_read_byte(dev, reg_addr, &old_val);
-	if (status < 0) {
-		return status;
-	}
-
-	return lis2dh_reg_write_byte(dev, reg_addr,
-				     (old_val & ~mask) | ((val << pos) & mask));
-}
-
 static void lis2dh_convert(s16_t raw_val, u32_t scale,
 			   struct sensor_value *val)
 {
@@ -146,9 +96,9 @@
 	 * since status and all accel data register addresses are consecutive,
 	 * a burst read can be used to read all the samples
 	 */
-	status = lis2dh_burst_read(dev, LIS2DH_REG_STATUS,
-				   lis2dh->sample.raw,
-				   sizeof(lis2dh->sample.raw));
+	status = lis2dh->hw_tf->read_data(dev, LIS2DH_REG_STATUS,
+					  lis2dh->sample.raw,
+					  sizeof(lis2dh->sample.raw));
 	if (status < 0) {
 		LOG_WRN("Could not read accel axis data");
 		return status;
@@ -161,13 +111,7 @@
 		*sample = sys_le16_to_cpu(*sample);
 	}
 
-	LOG_INF("status=0x%x x=%d y=%d z=%d", lis2dh->sample.status,
-		    lis2dh->sample.xyz[0], lis2dh->sample.xyz[1],
-		    lis2dh->sample.xyz[2]);
-
-	if (lis2dh->sample.status & LIS2DH_STATUS_OVR_MASK) {
-		return -EBADMSG;
-	} else if (lis2dh->sample.status & LIS2DH_STATUS_DRDY_MASK) {
+	if (lis2dh->sample.status & LIS2DH_STATUS_DRDY_MASK) {
 		return 0;
 	}
 
@@ -202,13 +146,14 @@
 	int odr;
 	int status;
 	u8_t value;
+	struct lis2dh_data *data = dev->driver_data;
 
 	odr = lis2dh_freq_to_odr_val(freq);
 	if (odr < 0) {
 		return odr;
 	}
 
-	status = lis2dh_reg_read_byte(dev, LIS2DH_REG_CTRL1, &value);
+	status = data->hw_tf->read_reg(dev, LIS2DH_REG_CTRL1, &value);
 	if (status < 0) {
 		return status;
 	}
@@ -224,9 +169,9 @@
 		odr--;
 	}
 
-	return lis2dh_reg_write_byte(dev, LIS2DH_REG_CTRL1,
-				  (value & ~LIS2DH_ODR_MASK) |
-				  LIS2DH_ODR_RATE(odr));
+	return data->hw_tf->write_reg(dev, LIS2DH_REG_CTRL1,
+				      (value & ~LIS2DH_ODR_MASK) |
+				      LIS2DH_ODR_RATE(odr));
 }
 #endif
 
@@ -260,10 +205,9 @@
 
 	lis2dh->scale = lis2dh_reg_val_to_scale[fs];
 
-	return lis2dh_reg_field_update(dev, LIS2DH_REG_CTRL4,
-				       LIS2DH_FS_SHIFT,
-				       LIS2DH_FS_MASK,
-				       fs);
+	return lis2dh->hw_tf->update_reg(dev, LIS2DH_REG_CTRL4,
+					 LIS2DH_FS_MASK,
+					 (fs << LIS2DH_FS_SHIFT));
 }
 #endif
 
@@ -323,18 +267,34 @@
 int lis2dh_init(struct device *dev)
 {
 	struct lis2dh_data *lis2dh = dev->driver_data;
+	const struct lis2dh_config *cfg = dev->config->config_info;
 	int status;
+	u8_t id;
 	u8_t raw[6];
 
-	status = lis2dh_bus_configure(dev);
+	lis2dh->bus = device_get_binding(cfg->bus_name);
+	if (!lis2dh->bus) {
+		LOG_ERR("master not found: %s", cfg->bus_name);
+		return -EINVAL;
+	}
+
+	cfg->bus_init(dev);
+
+	status = lis2dh->hw_tf->read_reg(dev, LIS2DH_REG_WAI, &id);
 	if (status < 0) {
+		LOG_ERR("Failed to read chip id.");
 		return status;
 	}
 
+	if (id != LIS2DH_CHIP_ID) {
+		LOG_ERR("Invalid chip ID: %02x\n", id);
+		return -EINVAL;
+	}
+
 	if (IS_ENABLED(DT_INST_0_ST_LIS2DH_DISCONNECT_SDO_SA0_PULL_UP)) {
-		status = lis2dh_reg_field_update(dev, LIS2DH_REG_CTRL0,
-						 LIS2DH_SDO_PU_DISC_SHIFT,
-						 LIS2DH_SDO_PU_DISC_MASK, 1);
+		status = lis2dh->hw_tf->update_reg(dev, LIS2DH_REG_CTRL0,
+						   LIS2DH_SDO_PU_DISC_MASK,
+						   LIS2DH_SDO_PU_DISC_MASK);
 		if (status < 0) {
 			LOG_ERR("Failed to disconnect SDO/SA0 pull-up.");
 			return status;
@@ -349,8 +309,9 @@
 	(void)memset(raw, 0, sizeof(raw));
 	raw[0] = LIS2DH_ACCEL_EN_BITS;
 
-	status = lis2dh_burst_write(dev, LIS2DH_REG_CTRL1, raw,
-				    sizeof(raw));
+	status = lis2dh->hw_tf->write_data(dev, LIS2DH_REG_CTRL1, raw,
+					   sizeof(raw));
+
 	if (status < 0) {
 		LOG_ERR("Failed to reset ctrl registers.");
 		return status;
@@ -358,8 +319,8 @@
 
 	/* set full scale range and store it for later conversion */
 	lis2dh->scale = lis2dh_reg_val_to_scale[LIS2DH_FS_IDX];
-	status = lis2dh_reg_write_byte(dev, LIS2DH_REG_CTRL4,
-				       LIS2DH_FS_BITS | LIS2DH_HR_BIT);
+	status = lis2dh->hw_tf->write_reg(dev, LIS2DH_REG_CTRL4,
+					  LIS2DH_FS_BITS | LIS2DH_HR_BIT);
 	if (status < 0) {
 		LOG_ERR("Failed to set full scale ctrl register.");
 		return status;
@@ -378,13 +339,37 @@
 		    LIS2DH_ODR_IDX, (u8_t)LIS2DH_LP_EN_BIT, lis2dh->scale);
 
 	/* enable accel measurements and set power mode and data rate */
-	return lis2dh_reg_write_byte(dev, LIS2DH_REG_CTRL1,
-				     LIS2DH_ACCEL_EN_BITS | LIS2DH_LP_EN_BIT |
-				     LIS2DH_ODR_BITS);
+	return lis2dh->hw_tf->write_reg(dev, LIS2DH_REG_CTRL1,
+					LIS2DH_ACCEL_EN_BITS | LIS2DH_LP_EN_BIT |
+					LIS2DH_ODR_BITS);
 }
 
-static struct lis2dh_data lis2dh_driver;
+static struct lis2dh_data lis2dh_data;
 
-DEVICE_AND_API_INIT(lis2dh, DT_INST_0_ST_LIS2DH_LABEL, lis2dh_init, &lis2dh_driver,
-		    NULL, POST_KERNEL, CONFIG_SENSOR_INIT_PRIORITY,
+static const struct lis2dh_config lis2dh_config = {
+	.bus_name = DT_INST_0_ST_LIS2DH_BUS_NAME,
+#if defined(DT_ST_LIS2DH_BUS_SPI)
+	.bus_init = lis2dh_spi_init,
+	.spi_conf.frequency = DT_INST_0_ST_LIS2DH_SPI_MAX_FREQUENCY,
+	.spi_conf.operation = (SPI_OP_MODE_MASTER | SPI_MODE_CPOL |
+			       SPI_MODE_CPHA | SPI_WORD_SET(8) |
+			       SPI_LINES_SINGLE),
+	.spi_conf.slave     = DT_INST_0_ST_LIS2DH_BASE_ADDRESS,
+#if defined(DT_INST_0_ST_LIS2DH_CS_GPIOS_CONTROLLER)
+	.gpio_cs_port	    = DT_INST_0_ST_LIS2DH_CS_GPIOS_CONTROLLER,
+	.cs_gpio	    = DT_INST_0_ST_LIS2DH_CS_GPIOS_PIN,
+	.spi_conf.cs        =  &lis2dh_data.cs_ctrl,
+#else
+	.spi_conf.cs        = NULL,
+#endif
+#elif defined(DT_ST_LIS2DH_BUS_I2C)
+	.bus_init = lis2dh_i2c_init,
+	.i2c_slv_addr = DT_INST_0_ST_LIS2DH_BASE_ADDRESS,
+#else
+#error "BUS MACRO NOT DEFINED IN DTS"
+#endif
+};
+
+DEVICE_AND_API_INIT(lis2dh, DT_INST_0_ST_LIS2DH_LABEL, lis2dh_init, &lis2dh_data,
+		    &lis2dh_config, POST_KERNEL, CONFIG_SENSOR_INIT_PRIORITY,
 		    &lis2dh_driver_api);
diff --git a/drivers/sensor/lis2dh/lis2dh.h b/drivers/sensor/lis2dh/lis2dh.h
index ca33f05..6fd6863 100644
--- a/drivers/sensor/lis2dh/lis2dh.h
+++ b/drivers/sensor/lis2dh/lis2dh.h
@@ -18,11 +18,14 @@
 #define LIS2DH_BUS_ADDRESS		DT_INST_0_ST_LIS2DH_BASE_ADDRESS
 #define LIS2DH_BUS_DEV_NAME		DT_INST_0_ST_LIS2DH_BUS_NAME
 
+#define LIS2DH_REG_WAI			0x0f
+#define LIS2DH_CHIP_ID			0x33
+
 #if defined(DT_ST_LIS2DH_BUS_SPI)
 #include <drivers/spi.h>
 
 #define LIS2DH_SPI_READ_BIT		BIT(7)
-#define LIS2DH_SPI_AUTOINC_ADDR		BIT(6)
+#define LIS2DH_SPI_AUTOINC		BIT(6)
 #define LIS2DH_SPI_ADDR_MASK		BIT_MASK(6)
 
 /* LIS2DH supports only SPI mode 0, word size 8 bits, MSB first */
@@ -194,13 +197,38 @@
 	} __packed;
 };
 
+struct lis2dh_config {
+	char *bus_name;
+	int (*bus_init)(struct device *dev);
+#ifdef DT_ST_LIS2DH_BUS_I2C
+	u16_t i2c_slv_addr;
+#elif DT_ST_LIS2DH_BUS_SPI
+	struct spi_config spi_conf;
+#if defined(DT_INST_0_ST_LIS2DH_CS_GPIOS_CONTROLLER)
+	const char *gpio_cs_port;
+	u8_t cs_gpio;
+#endif /* DT_INST_0_ST_LIS2DH_CS_GPIOS_CONTROLLER */
+#endif /* DT_ST_LIS2DH_BUS_SPI */
+
+};
+
+struct lis2dh_transfer_function {
+	int (*read_data)(struct device *dev, u8_t reg_addr,
+			 u8_t *value, u8_t len);
+	int (*write_data)(struct device *dev, u8_t reg_addr,
+			  u8_t *value, u8_t len);
+	int (*read_reg)(struct device *dev, u8_t reg_addr,
+			u8_t *value);
+	int (*write_reg)(struct device *dev, u8_t reg_addr,
+			u8_t value);
+	int (*update_reg)(struct device *dev, u8_t reg_addr,
+			  u8_t mask, u8_t value);
+};
+
 struct lis2dh_data {
-#if defined(DT_ST_LIS2DH_BUS_SPI)
-	struct device *spi;
-	struct spi_config spi_cfg;
-#else
 	struct device *bus;
-#endif
+	const struct lis2dh_transfer_function *hw_tf;
+
 	union lis2dh_sample sample;
 	/* current scaling factor, in micro m/s^2 / lsb */
 	u32_t scale;
@@ -226,6 +254,9 @@
 #endif
 
 #endif /* CONFIG_LIS2DH_TRIGGER */
+#if defined(DT_INST_0_ST_LIS2DH_CS_GPIOS_CONTROLLER)
+	struct spi_cs_control cs_ctrl;
+#endif /* DT_INST_0_ST_LIS2MDL_CS_GPIOS_CONTROLLER */
 };
 
 #if defined(DT_ST_LIS2DH_BUS_SPI)
@@ -233,131 +264,6 @@
 		      void *data, size_t length);
 #endif
 
-static inline int lis2dh_bus_configure(struct device *dev)
-{
-	struct lis2dh_data *lis2dh = dev->driver_data;
-
-#if defined(DT_ST_LIS2DH_BUS_SPI)
-	lis2dh->spi = device_get_binding(LIS2DH_BUS_DEV_NAME);
-	if (lis2dh->spi == NULL) {
-		LOG_ERR("Could not get pointer to %s device",
-			    LIS2DH_BUS_DEV_NAME);
-		return -EINVAL;
-	}
-
-	lis2dh->spi_cfg.operation = LIS2DH_SPI_CFG;
-	lis2dh->spi_cfg.frequency = DT_INST_0_ST_LIS2DH_SPI_MAX_FREQUENCY;
-	lis2dh->spi_cfg.slave = LIS2DH_BUS_ADDRESS;
-
-	return 0;
-#elif defined(DT_ST_LIS2DH_BUS_I2C)
-	lis2dh->bus = device_get_binding(LIS2DH_BUS_DEV_NAME);
-	if (lis2dh->bus == NULL) {
-		LOG_ERR("Could not get pointer to %s device",
-			    LIS2DH_BUS_DEV_NAME);
-		return -EINVAL;
-	}
-
-	return 0;
-#else
-	return -ENODEV;
-#endif
-}
-
-static inline int lis2dh_burst_read(struct device *dev, u8_t start_addr,
-				    u8_t *buf, u8_t num_bytes)
-{
-	struct lis2dh_data *lis2dh = dev->driver_data;
-
-#if defined(DT_ST_LIS2DH_BUS_SPI)
-	start_addr |= LIS2DH_SPI_READ_BIT | LIS2DH_SPI_AUTOINC_ADDR;
-
-	return lis2dh_spi_access(lis2dh, start_addr, buf, num_bytes);
-#elif defined(DT_ST_LIS2DH_BUS_I2C)
-	u8_t addr = start_addr | LIS2DH_AUTOINCREMENT_ADDR;
-
-	return i2c_write_read(lis2dh->bus, LIS2DH_BUS_ADDRESS,
-			      &addr, sizeof(addr),
-			      buf, num_bytes);
-#else
-	return -ENODEV;
-#endif
-}
-
-static inline int lis2dh_reg_read_byte(struct device *dev, u8_t reg_addr,
-				       u8_t *value)
-{
-	struct lis2dh_data *lis2dh = dev->driver_data;
-
-#if defined(DT_ST_LIS2DH_BUS_SPI)
-	reg_addr |= LIS2DH_SPI_READ_BIT;
-
-	return lis2dh_spi_access(lis2dh, reg_addr, value, 1);
-#elif defined(DT_ST_LIS2DH_BUS_I2C)
-	return i2c_reg_read_byte(lis2dh->bus, LIS2DH_BUS_ADDRESS,
-				 reg_addr, value);
-#else
-	return -ENODEV;
-#endif
-}
-
-static inline int lis2dh_burst_write(struct device *dev, u8_t start_addr,
-				     u8_t *buf, u8_t num_bytes)
-{
-	struct lis2dh_data *lis2dh = dev->driver_data;
-
-#if defined(DT_ST_LIS2DH_BUS_SPI)
-	start_addr |= LIS2DH_SPI_AUTOINC_ADDR;
-
-	return lis2dh_spi_access(lis2dh, start_addr, buf, num_bytes);
-#elif defined(DT_ST_LIS2DH_BUS_I2C)
-	/* NRF TWIM is default and does not support burst write.  We
-	 * can't detect whether the I2C master uses TWI or TWIM, so
-	 * use a substitute implementation unconditionally on Nordic.
-	 *
-	 * See Zephyr issue #20154.
-	 */
-	if (IS_ENABLED(CONFIG_I2C_NRFX)) {
-		u8_t buffer[8];
-
-		/* Largest num_bytes used is 6 */
-		__ASSERT((1U + num_bytes) <= sizeof(buffer),
-			 "burst buffer too small");
-		buffer[0] = start_addr | LIS2DH_AUTOINCREMENT_ADDR;
-		memmove(buffer + 1, buf, num_bytes);
-		return i2c_write(lis2dh->bus, buffer, 1 + num_bytes,
-				 LIS2DH_BUS_ADDRESS);
-	}
-	return i2c_burst_write(lis2dh->bus, LIS2DH_BUS_ADDRESS,
-			       start_addr | LIS2DH_AUTOINCREMENT_ADDR,
-			       buf, num_bytes);
-#else
-	return -ENODEV;
-#endif
-}
-
-static inline int lis2dh_reg_write_byte(struct device *dev, u8_t reg_addr,
-					u8_t value)
-{
-	struct lis2dh_data *lis2dh = dev->driver_data;
-
-#if defined(DT_ST_LIS2DH_BUS_SPI)
-	reg_addr &= LIS2DH_SPI_ADDR_MASK;
-
-	return lis2dh_spi_access(lis2dh, reg_addr, &value, 1);
-#elif defined(DT_ST_LIS2DH_BUS_I2C)
-	u8_t tx_buf[2] = {reg_addr, value};
-
-	return i2c_write(lis2dh->bus, tx_buf, sizeof(tx_buf),
-			 LIS2DH_BUS_ADDRESS);
-#else
-	return -ENODEV;
-#endif
-}
-
-int lis2dh_reg_field_update(struct device *dev, u8_t reg_addr,
-			    u8_t pos, u8_t mask, u8_t val);
-
 #ifdef CONFIG_LIS2DH_TRIGGER
 int lis2dh_trigger_set(struct device *dev,
 		       const struct sensor_trigger *trig,
@@ -369,4 +275,8 @@
 			    const struct sensor_value *val);
 #endif
 
+int lis2dh_spi_init(struct device *dev);
+int lis2dh_i2c_init(struct device *dev);
+
+
 #endif /* __SENSOR_LIS2DH__ */
diff --git a/drivers/sensor/lis2dh/lis2dh_i2c.c b/drivers/sensor/lis2dh/lis2dh_i2c.c
new file mode 100644
index 0000000..8fe5595
--- /dev/null
+++ b/drivers/sensor/lis2dh/lis2dh_i2c.c
@@ -0,0 +1,92 @@
+/* ST Microelectronics LIS2DH 3-axis accelerometer driver
+ *
+ * Copyright (c) 2020 STMicroelectronics
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Datasheet:
+ * https://www.st.com/resource/en/datasheet/lis2dh.pdf
+ */
+
+#include <string.h>
+#include <drivers/i2c.h>
+#include <logging/log.h>
+
+#include "lis2dh.h"
+
+#ifdef DT_ST_LIS2DH_BUS_I2C
+
+LOG_MODULE_DECLARE(lis2dh, CONFIG_SENSOR_LOG_LEVEL);
+
+static int lis2dh_i2c_read_data(struct device *dev, u8_t reg_addr,
+				 u8_t *value, u8_t len)
+{
+	struct lis2dh_data *data = dev->driver_data;
+	const struct lis2dh_config *cfg = dev->config->config_info;
+
+	return i2c_burst_read(data->bus, cfg->i2c_slv_addr,
+			      reg_addr | LIS2DH_AUTOINCREMENT_ADDR,
+			      value, len);
+}
+
+static int lis2dh_i2c_write_data(struct device *dev, u8_t reg_addr,
+				  u8_t *value, u8_t len)
+{
+	struct lis2dh_data *data = dev->driver_data;
+	const struct lis2dh_config *cfg = dev->config->config_info;
+
+	return i2c_burst_write(data->bus, cfg->i2c_slv_addr,
+			       reg_addr | LIS2DH_AUTOINCREMENT_ADDR,
+			       value, len);
+}
+
+static int lis2dh_i2c_read_reg(struct device *dev, u8_t reg_addr,
+				u8_t *value)
+{
+	struct lis2dh_data *data = dev->driver_data;
+	const struct lis2dh_config *cfg = dev->config->config_info;
+
+	return i2c_reg_read_byte(data->bus,
+				 cfg->i2c_slv_addr,
+				 reg_addr, value);
+}
+
+static int lis2dh_i2c_write_reg(struct device *dev, u8_t reg_addr,
+				u8_t value)
+{
+	struct lis2dh_data *data = dev->driver_data;
+	const struct lis2dh_config *cfg = dev->config->config_info;
+
+	return i2c_reg_write_byte(data->bus,
+				  cfg->i2c_slv_addr,
+				  reg_addr, value);
+}
+
+static int lis2dh_i2c_update_reg(struct device *dev, u8_t reg_addr,
+				  u8_t mask, u8_t value)
+{
+	struct lis2dh_data *data = dev->driver_data;
+	const struct lis2dh_config *cfg = dev->config->config_info;
+
+	return i2c_reg_update_byte(data->bus,
+				   cfg->i2c_slv_addr,
+				   reg_addr, mask, value);
+}
+
+static const struct lis2dh_transfer_function lis2dh_i2c_transfer_fn = {
+	.read_data = lis2dh_i2c_read_data,
+	.write_data = lis2dh_i2c_write_data,
+	.read_reg  = lis2dh_i2c_read_reg,
+	.write_reg  = lis2dh_i2c_write_reg,
+	.update_reg = lis2dh_i2c_update_reg,
+};
+
+int lis2dh_i2c_init(struct device *dev)
+{
+	struct lis2dh_data *data = dev->driver_data;
+
+	data->hw_tf = &lis2dh_i2c_transfer_fn;
+
+	return 0;
+}
+#endif /* DT_ST_LIS2DH_BUS_I2C */
diff --git a/drivers/sensor/lis2dh/lis2dh_spi.c b/drivers/sensor/lis2dh/lis2dh_spi.c
new file mode 100644
index 0000000..619f139
--- /dev/null
+++ b/drivers/sensor/lis2dh/lis2dh_spi.c
@@ -0,0 +1,173 @@
+/* ST Microelectronics LIS2DH 3-axis accelerometer driver
+ *
+ * Copyright (c) 2020 STMicroelectronics
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Datasheet:
+ * https://www.st.com/resource/en/datasheet/lis2dh.pdf
+ */
+
+#include <string.h>
+#include "lis2dh.h"
+#include <logging/log.h>
+
+#ifdef DT_ST_LIS2DH_BUS_SPI
+
+LOG_MODULE_DECLARE(lis2dh, CONFIG_SENSOR_LOG_LEVEL);
+
+static int lis2dh_raw_read(struct device *dev, u8_t reg_addr,
+			    u8_t *value, u8_t len)
+{
+	struct lis2dh_data *data = dev->driver_data;
+	const struct lis2dh_config *cfg = dev->config->config_info;
+	const struct spi_config *spi_cfg = &cfg->spi_conf;
+	u8_t buffer_tx[2] = { reg_addr | LIS2DH_SPI_READ_BIT, 0 };
+	const struct spi_buf tx_buf = {
+			.buf = buffer_tx,
+			.len = 2,
+	};
+	const struct spi_buf_set tx = {
+		.buffers = &tx_buf,
+		.count = 1
+	};
+	const struct spi_buf rx_buf[2] = {
+		{
+			.buf = NULL,
+			.len = 1,
+		},
+		{
+			.buf = value,
+			.len = len,
+		}
+	};
+	const struct spi_buf_set rx = {
+		.buffers = rx_buf,
+		.count = 2
+	};
+
+
+	if (len > 64) {
+		return -EIO;
+	}
+
+	if (len > 1) {
+		buffer_tx[0] |= LIS2DH_SPI_AUTOINC;
+	}
+
+	if (spi_transceive(data->bus, spi_cfg, &tx, &rx)) {
+		return -EIO;
+	}
+
+	return 0;
+}
+
+static int lis2dh_raw_write(struct device *dev, u8_t reg_addr,
+			     u8_t *value, u8_t len)
+{
+	struct lis2dh_data *data = dev->driver_data;
+	const struct lis2dh_config *cfg = dev->config->config_info;
+	const struct spi_config *spi_cfg = &cfg->spi_conf;
+	u8_t buffer_tx[1] = { reg_addr & ~LIS2DH_SPI_READ_BIT };
+	const struct spi_buf tx_buf[2] = {
+		{
+			.buf = buffer_tx,
+			.len = 1,
+		},
+		{
+			.buf = value,
+			.len = len,
+		}
+	};
+	const struct spi_buf_set tx = {
+		.buffers = tx_buf,
+		.count = 2
+	};
+
+
+	if (len > 64) {
+		return -EIO;
+	}
+
+	if (len > 1) {
+		buffer_tx[0] |= LIS2DH_SPI_AUTOINC;
+	}
+
+	if (spi_write(data->bus, spi_cfg, &tx)) {
+		return -EIO;
+	}
+
+	return 0;
+}
+
+static int lis2dh_spi_read_data(struct device *dev, u8_t reg_addr,
+				 u8_t *value, u8_t len)
+{
+	return lis2dh_raw_read(dev, reg_addr, value, len);
+}
+
+static int lis2dh_spi_write_data(struct device *dev, u8_t reg_addr,
+				  u8_t *value, u8_t len)
+{
+	return lis2dh_raw_write(dev, reg_addr, value, len);
+}
+
+static int lis2dh_spi_read_reg(struct device *dev, u8_t reg_addr,
+				u8_t *value)
+{
+	return lis2dh_raw_read(dev, reg_addr, value, 1);
+}
+
+static int lis2dh_spi_write_reg(struct device *dev, u8_t reg_addr,
+				u8_t value)
+{
+	u8_t tmp_val = value;
+
+	return lis2dh_raw_write(dev, reg_addr, &tmp_val, 1);
+}
+
+static int lis2dh_spi_update_reg(struct device *dev, u8_t reg_addr,
+				  u8_t mask, u8_t value)
+{
+	u8_t tmp_val;
+
+	lis2dh_raw_read(dev, reg_addr, &tmp_val, 1);
+	tmp_val = (tmp_val & ~mask) | (value & mask);
+
+	return lis2dh_raw_write(dev, reg_addr, &tmp_val, 1);
+}
+
+static const struct lis2dh_transfer_function lis2dh_spi_transfer_fn = {
+	.read_data = lis2dh_spi_read_data,
+	.write_data = lis2dh_spi_write_data,
+	.read_reg  = lis2dh_spi_read_reg,
+	.write_reg  = lis2dh_spi_write_reg,
+	.update_reg = lis2dh_spi_update_reg,
+};
+
+int lis2dh_spi_init(struct device *dev)
+{
+	struct lis2dh_data *data = dev->driver_data;
+
+	data->hw_tf = &lis2dh_spi_transfer_fn;
+
+#if defined(DT_INST_0_ST_LIS2DH_CS_GPIOS_CONTROLLER)
+	const struct lis2dh_config *cfg = dev->config->config_info;
+
+	/* handle SPI CS thru GPIO if it is the case */
+	data->cs_ctrl.gpio_dev = device_get_binding(cfg->gpio_cs_port);
+	if (!data->cs_ctrl.gpio_dev) {
+		LOG_ERR("Unable to get GPIO SPI CS device");
+		return -ENODEV;
+	}
+
+	data->cs_ctrl.gpio_pin = cfg->cs_gpio;
+	data->cs_ctrl.delay = 0;
+
+	LOG_DBG("SPI GPIO CS configured on %s:%u",
+		cfg->gpio_cs_port, cfg->cs_gpio);
+#endif
+
+	return 0;
+}
+#endif /* DT_ST_LIS2DH_BUS_SPI */
diff --git a/drivers/sensor/lis2dh/lis2dh_trigger.c b/drivers/sensor/lis2dh/lis2dh_trigger.c
index 8a11e80..1ad86a2 100644
--- a/drivers/sensor/lis2dh/lis2dh_trigger.c
+++ b/drivers/sensor/lis2dh/lis2dh_trigger.c
@@ -39,9 +39,8 @@
 	/* cancel potentially pending trigger */
 	atomic_clear_bit(&lis2dh->trig_flags, TRIGGED_INT1);
 
-	status = lis2dh_reg_field_update(dev, LIS2DH_REG_CTRL3,
-					 LIS2DH_EN_DRDY1_INT1_SHIFT,
-					 LIS2DH_EN_DRDY1_INT1, 0);
+	status = lis2dh->hw_tf->update_reg(dev, LIS2DH_REG_CTRL3,
+					   LIS2DH_EN_DRDY1_INT1, 0);
 
 	lis2dh->handler_drdy = handler;
 	if ((handler == NULL) || (status < 0)) {
@@ -68,14 +67,16 @@
 	int status;
 	u8_t raw[LIS2DH_BUF_SZ];
 	u8_t ctrl1 = 0U;
+	struct lis2dh_data *lis2dh = dev->driver_data;
 
 	/* power down temporarily to align interrupt & data output sampling */
-	status = lis2dh_reg_read_byte(dev, LIS2DH_REG_CTRL1, &ctrl1);
+	status = lis2dh->hw_tf->read_reg(dev, LIS2DH_REG_CTRL1, &ctrl1);
 	if (unlikely(status < 0)) {
 		return status;
 	}
-	status = lis2dh_reg_write_byte(dev, LIS2DH_REG_CTRL1,
-				       ctrl1 & ~LIS2DH_ODR_MASK);
+	status = lis2dh->hw_tf->write_reg(dev, LIS2DH_REG_CTRL1,
+					  ctrl1 & ~LIS2DH_ODR_MASK);
+
 	if (unlikely(status < 0)) {
 		return status;
 	}
@@ -83,7 +84,8 @@
 	LOG_DBG("ctrl1=0x%x @tick=%u", ctrl1, k_cycle_get_32());
 
 	/* empty output data */
-	status = lis2dh_burst_read(dev, LIS2DH_REG_STATUS, raw, sizeof(raw));
+	status = lis2dh->hw_tf->read_data(dev, LIS2DH_REG_STATUS,
+					  raw, sizeof(raw));
 	if (unlikely(status < 0)) {
 		return status;
 	}
@@ -91,14 +93,14 @@
 	setup_int1(dev, true);
 
 	/* re-enable output sampling */
-	status = lis2dh_reg_write_byte(dev, LIS2DH_REG_CTRL1, ctrl1);
+	status = lis2dh->hw_tf->write_reg(dev, LIS2DH_REG_CTRL1, ctrl1);
 	if (unlikely(status < 0)) {
 		return status;
 	}
 
-	return lis2dh_reg_field_update(dev, LIS2DH_REG_CTRL3,
-				       LIS2DH_EN_DRDY1_INT1_SHIFT,
-				       LIS2DH_EN_DRDY1_INT1, 1);
+	return lis2dh->hw_tf->update_reg(dev, LIS2DH_REG_CTRL3,
+					 LIS2DH_EN_DRDY1_INT1,
+					 LIS2DH_EN_DRDY1_INT1);
 }
 
 #if defined(DT_INST_0_ST_LIS2DH_IRQ_GPIOS_CONTROLLER_1)
@@ -130,10 +132,10 @@
 	atomic_clear_bit(&lis2dh->trig_flags, TRIGGED_INT2);
 
 	/* disable all interrupt 2 events */
-	status = lis2dh_reg_write_byte(dev, LIS2DH_REG_INT2_CFG, 0);
+	status = lis2dh->hw_tf->write_reg(dev, LIS2DH_REG_INT2_CFG, 0);
 
 	/* make sure any pending interrupt is cleared */
-	status = lis2dh_reg_read_byte(dev, LIS2DH_REG_INT2_SRC, &reg_val);
+	status = lis2dh->hw_tf->read_reg(dev, LIS2DH_REG_INT2_SRC, &reg_val);
 
 	lis2dh->handler_anymotion = handler;
 	if ((handler == NULL) || (status < 0)) {
@@ -158,8 +160,8 @@
 
 	setup_int2(dev, true);
 
-	return lis2dh_reg_write_byte(dev, LIS2DH_REG_INT2_CFG,
-				     LIS2DH_ANYM_CFG);
+	return lis2dh->hw_tf->write_reg(dev, LIS2DH_REG_INT2_CFG,
+					LIS2DH_ANYM_CFG);
 }
 #endif /* DT_INST_0_ST_LIS2DH_IRQ_GPIOS_CONTROLLER_1 */
 
@@ -182,13 +184,15 @@
 int lis2dh_acc_slope_config(struct device *dev, enum sensor_attribute attr,
 			    const struct sensor_value *val)
 {
+	struct lis2dh_data *lis2dh = dev->driver_data;
 	int status;
 
 	if (attr == SENSOR_ATTR_SLOPE_TH) {
 		u8_t range_g, reg_val;
 		u32_t slope_th_ums2;
 
-		status = lis2dh_reg_read_byte(dev, LIS2DH_REG_CTRL4, &reg_val);
+		status = lis2dh->hw_tf->read_reg(dev, LIS2DH_REG_CTRL4,
+						 &reg_val);
 		if (status < 0) {
 			return status;
 		}
@@ -210,8 +214,8 @@
 		LOG_INF("int2_ths=0x%x range_g=%d ums2=%u", reg_val,
 			    range_g, slope_th_ums2 - 1);
 
-		status = lis2dh_reg_write_byte(dev, LIS2DH_REG_INT2_THS,
-					       reg_val);
+		status = lis2dh->hw_tf->write_reg(dev, LIS2DH_REG_INT2_THS,
+						  reg_val);
 	} else { /* SENSOR_ATTR_SLOPE_DUR */
 		/*
 		 * slope duration is measured in number of samples:
@@ -223,8 +227,8 @@
 
 		LOG_INF("int2_dur=0x%x", val->val1);
 
-		status = lis2dh_reg_write_byte(dev, LIS2DH_REG_INT2_DUR,
-					       val->val1);
+		status = lis2dh->hw_tf->write_reg(dev, LIS2DH_REG_INT2_DUR,
+						  val->val1);
 	}
 
 	return status;
@@ -318,8 +322,8 @@
 		u8_t reg_val;
 
 		/* clear interrupt 2 to de-assert int2 line */
-		status = lis2dh_reg_read_byte(dev, LIS2DH_REG_INT2_SRC,
-					      &reg_val);
+		status = lis2dh->hw_tf->read_reg(dev, LIS2DH_REG_INT2_SRC,
+						 &reg_val);
 		if (status < 0) {
 			LOG_ERR("clearing interrupt 2 failed: %d", status);
 			return;
@@ -367,7 +371,9 @@
 {
 	struct lis2dh_data *lis2dh = dev->driver_data;
 	int status;
+#if defined(DT_INST_0_ST_LIS2DH_IRQ_GPIOS_CONTROLLER_1)
 	u8_t raw[2];
+#endif
 
 	/* setup data ready gpio interrupt */
 	lis2dh->gpio_int1 = device_get_binding(DT_LIS2DH_INT1_GPIO_DEV_NAME);
@@ -377,6 +383,19 @@
 		return -EINVAL;
 	}
 
+#if defined(CONFIG_LIS2DH_TRIGGER_OWN_THREAD)
+	k_sem_init(&lis2dh->gpio_sem, 0, UINT_MAX);
+
+	k_thread_create(&lis2dh->thread, lis2dh->thread_stack,
+			CONFIG_LIS2DH_THREAD_STACK_SIZE,
+			(k_thread_entry_t)lis2dh_thread, dev, NULL, NULL,
+			K_PRIO_COOP(CONFIG_LIS2DH_THREAD_PRIORITY), 0,
+			K_NO_WAIT);
+#elif defined(CONFIG_LIS2DH_TRIGGER_GLOBAL_THREAD)
+	lis2dh->work.handler = lis2dh_work_cb;
+	lis2dh->dev = dev;
+#endif
+
 	/* data ready int1 gpio configuration */
 	status = gpio_pin_configure(lis2dh->gpio_int1, DT_LIS2DH_INT1_GPIOS_PIN,
 				    GPIO_INPUT | DT_LIS2DH_INT1_GPIOS_FLAGS);
@@ -428,21 +447,9 @@
 	}
 
 	LOG_INF("int2 on pin=%d", DT_LIS2DH_INT2_GPIOS_PIN);
-#endif /* DT_INST_0_ST_LIS2DH_IRQ_GPIOS_CONTROLLER_1 */
 
-#if defined(CONFIG_LIS2DH_TRIGGER_OWN_THREAD)
-	k_sem_init(&lis2dh->gpio_sem, 0, UINT_MAX);
-
-	k_thread_create(&lis2dh->thread, lis2dh->thread_stack,
-			CONFIG_LIS2DH_THREAD_STACK_SIZE,
-			(k_thread_entry_t)lis2dh_thread, dev, NULL, NULL,
-			K_PRIO_COOP(CONFIG_LIS2DH_THREAD_PRIORITY), 0, K_NO_WAIT);
-#elif defined(CONFIG_LIS2DH_TRIGGER_GLOBAL_THREAD)
-	lis2dh->work.handler = lis2dh_work_cb;
-	lis2dh->dev = dev;
-#endif
 	/* disable interrupt 2 in case of warm (re)boot */
-	status = lis2dh_reg_write_byte(dev, LIS2DH_REG_INT2_CFG, 0);
+	status = lis2dh->hw_tf->write_reg(dev, LIS2DH_REG_INT2_CFG, 0);
 	if (status < 0) {
 		LOG_ERR("Interrupt 2 disable reg write failed (%d)",
 			    status);
@@ -450,21 +457,26 @@
 	}
 
 	(void)memset(raw, 0, sizeof(raw));
-	status = lis2dh_burst_write(dev, LIS2DH_REG_INT2_THS, raw, sizeof(raw));
+	status = lis2dh->hw_tf->write_data(dev, LIS2DH_REG_INT2_THS,
+					   raw, sizeof(raw));
 	if (status < 0) {
 		LOG_ERR("Burst write to INT2 THS failed (%d)", status);
 		return status;
 	}
 
+	/* enable interrupt 2 on int2 line */
+	status = lis2dh->hw_tf->update_reg(dev, LIS2DH_REG_CTRL6,
+					   LIS2DH_EN_INT2_INT2,
+					   LIS2DH_EN_INT2_INT2);
+
 	/* latch int2 line interrupt */
-	status = lis2dh_reg_write_byte(dev, LIS2DH_REG_CTRL5,
-				       LIS2DH_EN_LIR_INT2);
+	status = lis2dh->hw_tf->write_reg(dev, LIS2DH_REG_CTRL5,
+					  LIS2DH_EN_LIR_INT2);
 	if (status < 0) {
 		LOG_ERR("INT2 latch enable reg write failed (%d)", status);
 		return status;
 	}
+#endif /* DT_INST_0_ST_LIS2DH_IRQ_GPIOS_CONTROLLER_1 */
 
-	/* enable interrupt 2 on int2 line */
-	return lis2dh_reg_write_byte(dev, LIS2DH_REG_CTRL6,
-				     LIS2DH_EN_INT2_INT2);
+	return status;
 }