drivers/sensor: lis2dw12: Add multi-instance support

This commit aligns lis2dw12 sensor driver to latest multi
instance sensor driver model.

In particular it makes use of the stmemsc common routines
and move ctx handler inside struct config, so that the
bus_init routines can be totally avoided.

Signed-off-by: Armando Visconti <armando.visconti@st.com>
diff --git a/drivers/sensor/lis2dw12/CMakeLists.txt b/drivers/sensor/lis2dw12/CMakeLists.txt
index 55967b2..336a096 100644
--- a/drivers/sensor/lis2dw12/CMakeLists.txt
+++ b/drivers/sensor/lis2dw12/CMakeLists.txt
@@ -7,6 +7,6 @@
 zephyr_library()
 
 zephyr_library_sources_ifdef(CONFIG_LIS2DW12            lis2dw12)
-zephyr_library_sources_ifdef(CONFIG_LIS2DW12            lis2dw12_i2c.c)
-zephyr_library_sources_ifdef(CONFIG_LIS2DW12            lis2dw12_spi.c)
 zephyr_library_sources_ifdef(CONFIG_LIS2DW12_TRIGGER    lis2dw12_trigger.c)
+
+zephyr_library_include_directories(../stmemsc)
diff --git a/drivers/sensor/lis2dw12/lis2dw12.c b/drivers/sensor/lis2dw12/lis2dw12.c
index 36d6a12..09cb417 100644
--- a/drivers/sensor/lis2dw12/lis2dw12.c
+++ b/drivers/sensor/lis2dw12/lis2dw12.c
@@ -36,9 +36,10 @@
 	int err;
 	struct lis2dw12_data *lis2dw12 = dev->data;
 	const struct lis2dw12_device_config *cfg = dev->config;
+	stmdev_ctx_t *ctx = (stmdev_ctx_t *)&cfg->ctx;
 	uint8_t shift_gain = 0U;
 
-	err = lis2dw12_full_scale_set(lis2dw12->ctx, fs);
+	err = lis2dw12_full_scale_set(ctx, fs);
 
 	if (cfg->pm == LIS2DW12_CONT_LOW_PWR_12bit) {
 		shift_gain = LIS2DW12_SHFT_GAIN_NOLP1;
@@ -60,13 +61,13 @@
  */
 static int lis2dw12_set_odr(const struct device *dev, uint16_t odr)
 {
-	struct lis2dw12_data *lis2dw12 = dev->data;
+	const struct lis2dw12_device_config *cfg = dev->config;
+	stmdev_ctx_t *ctx = (stmdev_ctx_t *)&cfg->ctx;
 	uint8_t val;
 
 	/* check if power off */
 	if (odr == 0U) {
-		return lis2dw12_data_rate_set(lis2dw12->ctx,
-					      LIS2DW12_XL_ODR_OFF);
+		return lis2dw12_data_rate_set(ctx, LIS2DW12_XL_ODR_OFF);
 	}
 
 	val =  LIS2DW12_ODR_TO_REG(odr);
@@ -75,7 +76,7 @@
 		return -ENOTSUP;
 	}
 
-	return lis2dw12_data_rate_set(lis2dw12->ctx, val);
+	return lis2dw12_data_rate_set(ctx, val);
 }
 
 static inline void lis2dw12_convert(struct sensor_value *val, int raw_val,
@@ -180,11 +181,12 @@
 {
 	struct lis2dw12_data *lis2dw12 = dev->data;
 	const struct lis2dw12_device_config *cfg = dev->config;
+	stmdev_ctx_t *ctx = (stmdev_ctx_t *)&cfg->ctx;
 	uint8_t shift;
 	int16_t buf[3];
 
 	/* fetch raw data sample */
-	if (lis2dw12_acceleration_raw_get(lis2dw12->ctx, buf) < 0) {
+	if (lis2dw12_acceleration_raw_get(ctx, buf) < 0) {
 		LOG_DBG("Failed to fetch raw data sample");
 		return -EIO;
 	}
@@ -212,31 +214,11 @@
 	.channel_get = lis2dw12_channel_get,
 };
 
-static int lis2dw12_init_interface(const struct device *dev)
-{
-	struct lis2dw12_data *lis2dw12 = dev->data;
-	const struct lis2dw12_device_config *cfg = dev->config;
-
-	lis2dw12->bus = device_get_binding(cfg->bus_name);
-	if (!lis2dw12->bus) {
-		LOG_DBG("master bus not found: %s", cfg->bus_name);
-		return -EINVAL;
-	}
-
-#if DT_ANY_INST_ON_BUS_STATUS_OKAY(spi)
-	lis2dw12_spi_init(dev);
-#elif DT_ANY_INST_ON_BUS_STATUS_OKAY(i2c)
-	lis2dw12_i2c_init(dev);
-#else
-#error "BUS MACRO NOT DEFINED IN DTS"
-#endif
-
-	return 0;
-}
-
-static int lis2dw12_set_power_mode(struct lis2dw12_data *lis2dw12,
+static int lis2dw12_set_power_mode(const struct device *dev,
 				    lis2dw12_mode_t pm)
 {
+	const struct lis2dw12_device_config *cfg = dev->config;
+	stmdev_ctx_t *ctx = (stmdev_ctx_t *)&cfg->ctx;
 	uint8_t regval = LIS2DW12_CONT_LOW_PWR_12bit;
 
 	switch (pm) {
@@ -251,21 +233,17 @@
 		break;
 	}
 
-	return lis2dw12_write_reg(lis2dw12->ctx, LIS2DW12_CTRL1, &regval, 1);
+	return lis2dw12_write_reg(ctx, LIS2DW12_CTRL1, &regval, 1);
 }
 
 static int lis2dw12_init(const struct device *dev)
 {
-	struct lis2dw12_data *lis2dw12 = dev->data;
 	const struct lis2dw12_device_config *cfg = dev->config;
+	stmdev_ctx_t *ctx = (stmdev_ctx_t *)&cfg->ctx;
 	uint8_t wai;
 
-	if (lis2dw12_init_interface(dev)) {
-		return -EINVAL;
-	}
-
 	/* check chip ID */
-	if (lis2dw12_device_id_get(lis2dw12->ctx, &wai) < 0) {
+	if (lis2dw12_device_id_get(ctx, &wai) < 0) {
 		return -EIO;
 	}
 
@@ -275,20 +253,19 @@
 	}
 
 	/* reset device */
-	if (lis2dw12_reset_set(lis2dw12->ctx, PROPERTY_ENABLE) < 0) {
+	if (lis2dw12_reset_set(ctx, PROPERTY_ENABLE) < 0) {
 		return -EIO;
 	}
 
 	k_busy_wait(100);
 
-	if (lis2dw12_block_data_update_set(lis2dw12->ctx,
-					   PROPERTY_ENABLE) < 0) {
+	if (lis2dw12_block_data_update_set(ctx, PROPERTY_ENABLE) < 0) {
 		return -EIO;
 	}
 
 	/* set power mode */
 	LOG_DBG("power-mode is %d", cfg->pm);
-	if (lis2dw12_set_power_mode(lis2dw12, cfg->pm)) {
+	if (lis2dw12_set_power_mode(dev, cfg->pm)) {
 		return -EIO;
 	}
 
@@ -314,26 +291,112 @@
 	return 0;
 }
 
-const struct lis2dw12_device_config lis2dw12_cfg = {
-	.bus_name = DT_INST_BUS_LABEL(0),
-	.pm = DT_INST_PROP(0, power_mode),
-	.range = DT_INST_PROP(0, range),
-#ifdef CONFIG_LIS2DW12_TRIGGER
-	.gpio_int = GPIO_DT_SPEC_INST_GET_OR(0, irq_gpios, {0}),
-	.int_pin = DT_INST_PROP(0, int_pin),
+#if DT_NUM_INST_STATUS_OKAY(DT_DRV_COMPAT) == 0
+#warning "LIS2DW12 driver enabled without any devices"
+#endif
+
+/*
+ * Device creation macro, shared by LIS2DW12_DEFINE_SPI() and
+ * LIS2DW12_DEFINE_I2C().
+ */
+
+#define LIS2DW12_DEVICE_INIT(inst)					\
+	DEVICE_DT_INST_DEFINE(inst,					\
+			    lis2dw12_init,				\
+			    NULL,					\
+			    &lis2dw12_data_##inst,			\
+			    &lis2dw12_config_##inst,			\
+			    POST_KERNEL,				\
+			    CONFIG_SENSOR_INIT_PRIORITY,		\
+			    &lis2dw12_driver_api);
+
+/*
+ * Instantiation macros used when a device is on a SPI bus.
+ */
 
 #ifdef CONFIG_LIS2DW12_TAP
-	.tap_mode = DT_INST_PROP(0, tap_mode),
-	.tap_threshold = DT_INST_PROP(0, tap_threshold),
-	.tap_shock = DT_INST_PROP(0, tap_shock),
-	.tap_latency = DT_INST_PROP(0, tap_latency),
-	.tap_quiet = DT_INST_PROP(0, tap_quiet),
+#define LIS2DW12_CONFIG_TAP(inst)					\
+	.tap_mode = DT_INST_PROP(inst, tap_mode),			\
+	.tap_threshold = DT_INST_PROP(inst, tap_threshold),		\
+	.tap_shock = DT_INST_PROP(inst, tap_shock),			\
+	.tap_latency = DT_INST_PROP(inst, tap_latency),			\
+	.tap_quiet = DT_INST_PROP(inst, tap_quiet),
+#else
+#define LIS2DW12_CONFIG_TAP(inst)
 #endif /* CONFIG_LIS2DW12_TAP */
+
+#ifdef CONFIG_LIS2DW12_TRIGGER
+#define LIS2DW12_CFG_IRQ(inst) \
+	.gpio_int = GPIO_DT_SPEC_INST_GET(inst, irq_gpios),		\
+	.int_pin = DT_INST_PROP(inst, int_pin),
+#else
+#define LIS2DW12_CFG_IRQ(inst)
 #endif /* CONFIG_LIS2DW12_TRIGGER */
-};
 
-struct lis2dw12_data lis2dw12_data;
+#define LIS2DW12_SPI_OPERATION (SPI_WORD_SET(8) |			\
+				SPI_OP_MODE_MASTER |			\
+				SPI_MODE_CPOL |				\
+				SPI_MODE_CPHA)				\
 
-DEVICE_DT_INST_DEFINE(0, lis2dw12_init, NULL,
-	     &lis2dw12_data, &lis2dw12_cfg, POST_KERNEL,
-	     CONFIG_SENSOR_INIT_PRIORITY, &lis2dw12_driver_api);
+#define LIS2DW12_CONFIG_SPI(inst)					\
+	{								\
+		.ctx = {						\
+			.read_reg =					\
+			   (stmdev_read_ptr) stmemsc_spi_read,		\
+			.write_reg =					\
+			   (stmdev_write_ptr) stmemsc_spi_write,	\
+			.handle =					\
+			   (void *)&lis2dw12_config_##inst.stmemsc_cfg,	\
+		},							\
+		.stmemsc_cfg.spi = {					\
+			.bus = DEVICE_DT_GET(DT_INST_BUS(inst)),	\
+			.spi_cfg = SPI_CONFIG_DT_INST(inst,		\
+					   LIS2DW12_SPI_OPERATION,	\
+					   0),				\
+		},							\
+		.pm = DT_INST_PROP(inst, power_mode),			\
+		.range = DT_INST_PROP(inst, range),			\
+		LIS2DW12_CONFIG_TAP(inst)				\
+		COND_CODE_1(DT_INST_NODE_HAS_PROP(inst, irq_gpios),	\
+			(LIS2DW12_CFG_IRQ(inst)), ())			\
+	}
+
+/*
+ * Instantiation macros used when a device is on an I2C bus.
+ */
+
+#define LIS2DW12_CONFIG_I2C(inst)					\
+	{								\
+		.ctx = {						\
+			.read_reg =					\
+			   (stmdev_read_ptr) stmemsc_i2c_read,		\
+			.write_reg =					\
+			   (stmdev_write_ptr) stmemsc_i2c_write,	\
+			.handle =					\
+			   (void *)&lis2dw12_config_##inst.stmemsc_cfg,	\
+		},							\
+		.stmemsc_cfg.i2c = {					\
+			.bus = DEVICE_DT_GET(DT_INST_BUS(inst)),	\
+			.i2c_slv_addr = DT_INST_REG_ADDR(inst),		\
+		},							\
+		.pm = DT_INST_PROP(inst, power_mode),			\
+		.range = DT_INST_PROP(inst, range),			\
+		LIS2DW12_CONFIG_TAP(inst)				\
+		COND_CODE_1(DT_INST_NODE_HAS_PROP(inst, irq_gpios),	\
+			(LIS2DW12_CFG_IRQ(inst)), ())			\
+	}
+
+/*
+ * Main instantiation macro. Use of COND_CODE_1() selects the right
+ * bus-specific macro at preprocessor time.
+ */
+
+#define LIS2DW12_DEFINE(inst)						\
+	static struct lis2dw12_data lis2dw12_data_##inst;		\
+	static const struct lis2dw12_device_config lis2dw12_config_##inst =	\
+	COND_CODE_1(DT_INST_ON_BUS(inst, spi),				\
+		    (LIS2DW12_CONFIG_SPI(inst)),			\
+		    (LIS2DW12_CONFIG_I2C(inst)));			\
+	LIS2DW12_DEVICE_INIT(inst)
+
+DT_INST_FOREACH_STATUS_OKAY(LIS2DW12_DEFINE)
diff --git a/drivers/sensor/lis2dw12/lis2dw12.h b/drivers/sensor/lis2dw12/lis2dw12.h
index 06ca2d5..599fea2 100644
--- a/drivers/sensor/lis2dw12/lis2dw12.h
+++ b/drivers/sensor/lis2dw12/lis2dw12.h
@@ -15,8 +15,17 @@
 #include <drivers/gpio.h>
 #include <sys/util.h>
 #include <drivers/sensor.h>
+#include <stmemsc.h>
 #include "lis2dw12_reg.h"
 
+#if DT_ANY_INST_ON_BUS_STATUS_OKAY(spi)
+#include <drivers/spi.h>
+#endif /* DT_ANY_INST_ON_BUS_STATUS_OKAY(spi) */
+
+#if DT_ANY_INST_ON_BUS_STATUS_OKAY(i2c)
+#include <drivers/i2c.h>
+#endif /* DT_ANY_INST_ON_BUS_STATUS_OKAY(i2c) */
+
 /* Return ODR reg value based on data rate set */
 #define LIS2DW12_ODR_TO_REG(_odr) \
 	((_odr <= 1) ? LIS2DW12_XL_ODR_1Hz6_LP_ONLY : \
@@ -48,7 +57,15 @@
  * @int_pin: Sensor int pin (int1/int2).
  */
 struct lis2dw12_device_config {
-	const char *bus_name;
+	stmdev_ctx_t ctx;
+	union {
+#if DT_ANY_INST_ON_BUS_STATUS_OKAY(i2c)
+		const struct stmemsc_cfg_i2c i2c;
+#endif
+#if DT_ANY_INST_ON_BUS_STATUS_OKAY(spi)
+		const struct stmemsc_cfg_spi spi;
+#endif
+	} stmemsc_cfg;
 	lis2dw12_mode_t pm;
 	uint8_t range;
 #ifdef CONFIG_LIS2DW12_TRIGGER
@@ -64,18 +81,13 @@
 #endif /* CONFIG_LIS2DW12_TRIGGER */
 };
 
-/* sensor data forward declaration (member definition is below) */
-struct lis2dw12_data;
-
 /* sensor data */
 struct lis2dw12_data {
-	const struct device *bus;
 	int16_t acc[3];
 
 	 /* save sensitivity */
 	uint16_t gain;
 
-	stmdev_ctx_t *ctx;
 #ifdef CONFIG_LIS2DW12_TRIGGER
 	const struct device *dev;
 
@@ -93,14 +105,8 @@
 	struct k_work work;
 #endif /* CONFIG_LIS2DW12_TRIGGER_GLOBAL_THREAD */
 #endif /* CONFIG_LIS2DW12_TRIGGER */
-#if DT_INST_SPI_DEV_HAS_CS_GPIOS(0)
-	struct spi_cs_control cs_ctrl;
-#endif
 };
 
-int lis2dw12_i2c_init(const struct device *dev);
-int lis2dw12_spi_init(const struct device *dev);
-
 #ifdef CONFIG_LIS2DW12_TRIGGER
 int lis2dw12_init_interrupt(const struct device *dev);
 int lis2dw12_trigger_set(const struct device *dev,
diff --git a/drivers/sensor/lis2dw12/lis2dw12_i2c.c b/drivers/sensor/lis2dw12/lis2dw12_i2c.c
deleted file mode 100644
index b9587f5..0000000
--- a/drivers/sensor/lis2dw12/lis2dw12_i2c.c
+++ /dev/null
@@ -1,53 +0,0 @@
-/* ST Microelectronics LIS2DW12 3-axis accelerometer driver
- *
- * Copyright (c) 2019 STMicroelectronics
- *
- * SPDX-License-Identifier: Apache-2.0
- *
- * Datasheet:
- * https://www.st.com/resource/en/datasheet/lis2dw12.pdf
- */
-
-#define DT_DRV_COMPAT st_lis2dw12
-
-#include <string.h>
-#include <drivers/i2c.h>
-#include <logging/log.h>
-
-#include "lis2dw12.h"
-
-#if DT_ANY_INST_ON_BUS_STATUS_OKAY(i2c)
-
-static uint16_t lis2dw12_i2c_slave_addr = DT_INST_REG_ADDR(0);
-
-LOG_MODULE_DECLARE(LIS2DW12, CONFIG_SENSOR_LOG_LEVEL);
-
-static int lis2dw12_i2c_read(struct lis2dw12_data *data, uint8_t reg_addr,
-				 uint8_t *value, uint16_t len)
-{
-	return i2c_burst_read(data->bus, lis2dw12_i2c_slave_addr,
-			      reg_addr, value, len);
-}
-
-static int lis2dw12_i2c_write(struct lis2dw12_data *data, uint8_t reg_addr,
-				  uint8_t *value, uint16_t len)
-{
-	return i2c_burst_write(data->bus, lis2dw12_i2c_slave_addr,
-			       reg_addr, value, len);
-}
-
-stmdev_ctx_t lis2dw12_i2c_ctx = {
-	.read_reg = (stmdev_read_ptr) lis2dw12_i2c_read,
-	.write_reg = (stmdev_write_ptr) lis2dw12_i2c_write,
-};
-
-int lis2dw12_i2c_init(const struct device *dev)
-{
-	struct lis2dw12_data *data = dev->data;
-
-	data->ctx = &lis2dw12_i2c_ctx;
-	data->ctx->handle = data;
-
-	return 0;
-}
-#endif /* DT_ANY_INST_ON_BUS_STATUS_OKAY(i2c) */
diff --git a/drivers/sensor/lis2dw12/lis2dw12_spi.c b/drivers/sensor/lis2dw12/lis2dw12_spi.c
deleted file mode 100644
index 0b18974..0000000
--- a/drivers/sensor/lis2dw12/lis2dw12_spi.c
+++ /dev/null
@@ -1,129 +0,0 @@
-/* ST Microelectronics LIS2DW12 3-axis accelerometer driver
- *
- * Copyright (c) 2019 STMicroelectronics
- *
- * SPDX-License-Identifier: Apache-2.0
- *
- * Datasheet:
- * https://www.st.com/resource/en/datasheet/lis2dw12.pdf
- */
-
-#define DT_DRV_COMPAT st_lis2dw12
-
-
-#include <string.h>
-#include "lis2dw12.h"
-#include <logging/log.h>
-
-#if DT_ANY_INST_ON_BUS_STATUS_OKAY(spi)
-
-#define LIS2DW12_SPI_READ		(1 << 7)
-
-LOG_MODULE_DECLARE(LIS2DW12, CONFIG_SENSOR_LOG_LEVEL);
-
-static struct spi_config lis2dw12_spi_conf = {
-	.frequency = DT_INST_PROP(0, spi_max_frequency),
-	.operation = (SPI_OP_MODE_MASTER | SPI_MODE_CPOL |
-		      SPI_MODE_CPHA | SPI_WORD_SET(8) | SPI_LINES_SINGLE),
-	.slave     = DT_INST_REG_ADDR(0),
-	.cs        = NULL,
-};
-
-static int lis2dw12_spi_read(struct lis2dw12_data *ctx, uint8_t reg,
-			    uint8_t *data, uint16_t len)
-{
-	struct spi_config *spi_cfg = &lis2dw12_spi_conf;
-	uint8_t buffer_tx[2] = { reg | LIS2DW12_SPI_READ, 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 = data,
-			.len = len,
-		}
-	};
-	const struct spi_buf_set rx = {
-		.buffers = rx_buf,
-		.count = 2
-	};
-
-	if (spi_transceive(ctx->bus, spi_cfg, &tx, &rx)) {
-		return -EIO;
-	}
-
-	return 0;
-}
-
-static int lis2dw12_spi_write(struct lis2dw12_data *ctx, uint8_t reg,
-			     uint8_t *data, uint16_t len)
-{
-	struct spi_config *spi_cfg = &lis2dw12_spi_conf;
-	uint8_t buffer_tx[1] = { reg & ~LIS2DW12_SPI_READ };
-	const struct spi_buf tx_buf[2] = {
-		{
-			.buf = buffer_tx,
-			.len = 1,
-		},
-		{
-			.buf = data,
-			.len = len,
-		}
-	};
-	const struct spi_buf_set tx = {
-		.buffers = tx_buf,
-		.count = 2
-	};
-
-
-	if (spi_write(ctx->bus, spi_cfg, &tx)) {
-		return -EIO;
-	}
-
-	return 0;
-}
-
-stmdev_ctx_t lis2dw12_spi_ctx = {
-	.read_reg = (stmdev_read_ptr) lis2dw12_spi_read,
-	.write_reg = (stmdev_write_ptr) lis2dw12_spi_write,
-};
-
-int lis2dw12_spi_init(const struct device *dev)
-{
-	struct lis2dw12_data *data = dev->data;
-
-	data->ctx = &lis2dw12_spi_ctx;
-	data->ctx->handle = data;
-
-#if DT_INST_SPI_DEV_HAS_CS_GPIOS(0)
-	/* handle SPI CS thru GPIO if it is the case */
-	data->cs_ctrl.gpio_dev = device_get_binding(
-		DT_INST_SPI_DEV_CS_GPIOS_LABEL(0));
-	if (!data->cs_ctrl.gpio_dev) {
-		LOG_ERR("Unable to get GPIO SPI CS device");
-		return -ENODEV;
-	}
-
-	data->cs_ctrl.gpio_pin = DT_INST_SPI_DEV_CS_GPIOS_PIN(0);
-	data->cs_ctrl.gpio_dt_flags = DT_INST_SPI_DEV_CS_GPIOS_FLAGS(0);
-	data->cs_ctrl.delay = 0U;
-
-	lis2dw12_spi_conf.cs = &data->cs_ctrl;
-
-	LOG_DBG("SPI GPIO CS configured on %s:%u",
-		    DT_INST_SPI_DEV_CS_GPIOS_LABEL(0),
-		    DT_INST_SPI_DEV_CS_GPIOS_PIN(0));
-#endif
-
-	return 0;
-}
-#endif /* DT_ANY_INST_ON_BUS_STATUS_OKAY(spi) */
diff --git a/drivers/sensor/lis2dw12/lis2dw12_trigger.c b/drivers/sensor/lis2dw12/lis2dw12_trigger.c
index 8c7e2ca..c9b26e8 100644
--- a/drivers/sensor/lis2dw12/lis2dw12_trigger.c
+++ b/drivers/sensor/lis2dw12/lis2dw12_trigger.c
@@ -26,13 +26,12 @@
 			       enum sensor_trigger_type type, int enable)
 {
 	const struct lis2dw12_device_config *cfg = dev->config;
-	struct lis2dw12_data *lis2dw12 = dev->data;
+	stmdev_ctx_t *ctx = (stmdev_ctx_t *)&cfg->ctx;
 	lis2dw12_reg_t int_route;
 
 	if (cfg->int_pin == 1U) {
 		/* set interrupt for pin INT1 */
-		lis2dw12_pin_int1_route_get(lis2dw12->ctx,
-				&int_route.ctrl4_int1_pad_ctrl);
+		lis2dw12_pin_int1_route_get(ctx, &int_route.ctrl4_int1_pad_ctrl);
 
 		switch (type) {
 		case SENSOR_TRIG_DATA_READY:
@@ -51,12 +50,11 @@
 			return -ENOTSUP;
 		}
 
-		return lis2dw12_pin_int1_route_set(lis2dw12->ctx,
+		return lis2dw12_pin_int1_route_set(ctx,
 				&int_route.ctrl4_int1_pad_ctrl);
 	} else {
 		/* set interrupt for pin INT2 */
-		lis2dw12_pin_int2_route_get(lis2dw12->ctx,
-					    &int_route.ctrl5_int2_pad_ctrl);
+		lis2dw12_pin_int2_route_get(ctx, &int_route.ctrl5_int2_pad_ctrl);
 
 		switch (type) {
 		case SENSOR_TRIG_DATA_READY:
@@ -67,7 +65,7 @@
 			return -ENOTSUP;
 		}
 
-		return lis2dw12_pin_int2_route_set(lis2dw12->ctx,
+		return lis2dw12_pin_int2_route_set(ctx,
 				&int_route.ctrl5_int2_pad_ctrl);
 	}
 }
@@ -80,6 +78,7 @@
 			  sensor_trigger_handler_t handler)
 {
 	const struct lis2dw12_device_config *cfg = dev->config;
+	stmdev_ctx_t *ctx = (stmdev_ctx_t *)&cfg->ctx;
 	struct lis2dw12_data *lis2dw12 = dev->data;
 	int16_t raw[3];
 	int state = (handler != NULL) ? PROPERTY_ENABLE : PROPERTY_DISABLE;
@@ -94,7 +93,7 @@
 		lis2dw12->drdy_handler = handler;
 		if (state) {
 			/* dummy read: re-trigger interrupt */
-			lis2dw12_acceleration_raw_get(lis2dw12->ctx, raw);
+			lis2dw12_acceleration_raw_get(ctx, raw);
 		}
 		return lis2dw12_enable_int(dev, SENSOR_TRIG_DATA_READY, state);
 		break;
@@ -172,11 +171,11 @@
  */
 static void lis2dw12_handle_interrupt(const struct device *dev)
 {
-	struct lis2dw12_data *lis2dw12 = dev->data;
 	const struct lis2dw12_device_config *cfg = dev->config;
+	stmdev_ctx_t *ctx = (stmdev_ctx_t *)&cfg->ctx;
 	lis2dw12_all_sources_t sources;
 
-	lis2dw12_all_sources_get(lis2dw12->ctx, &sources);
+	lis2dw12_all_sources_get(ctx, &sources);
 
 	if (sources.status_dup.drdy) {
 		lis2dw12_handle_drdy_int(dev);
@@ -238,35 +237,35 @@
 static int lis2dw12_tap_init(const struct device *dev)
 {
 	const struct lis2dw12_device_config *cfg = dev->config;
-	struct lis2dw12_data *lis2dw12 = dev->data;
+	stmdev_ctx_t *ctx = (stmdev_ctx_t *)&cfg->ctx;
 
 	LOG_DBG("TAP: tap mode is %d", cfg->tap_mode);
-	if (lis2dw12_tap_mode_set(lis2dw12->ctx, cfg->tap_mode) < 0) {
+	if (lis2dw12_tap_mode_set(ctx, cfg->tap_mode) < 0) {
 		LOG_ERR("Failed to select tap trigger mode");
 		return -EIO;
 	}
 
 	LOG_DBG("TAP: ths_x is %02x", cfg->tap_threshold[0]);
-	if (lis2dw12_tap_threshold_x_set(lis2dw12->ctx, cfg->tap_threshold[0]) < 0) {
+	if (lis2dw12_tap_threshold_x_set(ctx, cfg->tap_threshold[0]) < 0) {
 		LOG_ERR("Failed to set tap X axis threshold");
 		return -EIO;
 	}
 
 	LOG_DBG("TAP: ths_y is %02x", cfg->tap_threshold[1]);
-	if (lis2dw12_tap_threshold_y_set(lis2dw12->ctx, cfg->tap_threshold[1]) < 0) {
+	if (lis2dw12_tap_threshold_y_set(ctx, cfg->tap_threshold[1]) < 0) {
 		LOG_ERR("Failed to set tap Y axis threshold");
 		return -EIO;
 	}
 
 	LOG_DBG("TAP: ths_z is %02x", cfg->tap_threshold[2]);
-	if (lis2dw12_tap_threshold_z_set(lis2dw12->ctx, cfg->tap_threshold[2]) < 0) {
+	if (lis2dw12_tap_threshold_z_set(ctx, cfg->tap_threshold[2]) < 0) {
 		LOG_ERR("Failed to set tap Z axis threshold");
 		return -EIO;
 	}
 
 	if (cfg->tap_threshold[0] > 0) {
 		LOG_DBG("TAP: tap_x enabled");
-		if (lis2dw12_tap_detection_on_x_set(lis2dw12->ctx, 1) < 0) {
+		if (lis2dw12_tap_detection_on_x_set(ctx, 1) < 0) {
 			LOG_ERR("Failed to set tap detection on X axis");
 			return -EIO;
 		}
@@ -274,7 +273,7 @@
 
 	if (cfg->tap_threshold[1] > 0) {
 		LOG_DBG("TAP: tap_y enabled");
-		if (lis2dw12_tap_detection_on_y_set(lis2dw12->ctx, 1) < 0) {
+		if (lis2dw12_tap_detection_on_y_set(ctx, 1) < 0) {
 			LOG_ERR("Failed to set tap detection on Y axis");
 			return -EIO;
 		}
@@ -282,26 +281,26 @@
 
 	if (cfg->tap_threshold[2] > 0) {
 		LOG_DBG("TAP: tap_z enabled");
-		if (lis2dw12_tap_detection_on_z_set(lis2dw12->ctx, 1) < 0) {
+		if (lis2dw12_tap_detection_on_z_set(ctx, 1) < 0) {
 			LOG_ERR("Failed to set tap detection on Z axis");
 			return -EIO;
 		}
 	}
 
 	LOG_DBG("TAP: shock is %02x", cfg->tap_shock);
-	if (lis2dw12_tap_shock_set(lis2dw12->ctx, cfg->tap_shock) < 0) {
+	if (lis2dw12_tap_shock_set(ctx, cfg->tap_shock) < 0) {
 		LOG_ERR("Failed to set tap shock duration");
 		return -EIO;
 	}
 
 	LOG_DBG("TAP: latency is %02x", cfg->tap_latency);
-	if (lis2dw12_tap_dur_set(lis2dw12->ctx, cfg->tap_latency) < 0) {
+	if (lis2dw12_tap_dur_set(ctx, cfg->tap_latency) < 0) {
 		LOG_ERR("Failed to set tap latency");
 		return -EIO;
 	}
 
 	LOG_DBG("TAP: quiet time is %02x", cfg->tap_quiet);
-	if (lis2dw12_tap_quiet_set(lis2dw12->ctx, cfg->tap_quiet) < 0) {
+	if (lis2dw12_tap_quiet_set(ctx, cfg->tap_quiet) < 0) {
 		LOG_ERR("Failed to set tap quiet time");
 		return -EIO;
 	}
@@ -314,6 +313,7 @@
 {
 	struct lis2dw12_data *lis2dw12 = dev->data;
 	const struct lis2dw12_device_config *cfg = dev->config;
+	stmdev_ctx_t *ctx = (stmdev_ctx_t *)&cfg->ctx;
 	int ret;
 
 	/* setup data ready gpio interrupt (INT1 or INT2) */
@@ -362,7 +362,7 @@
 	}
 
 	/* enable interrupt on int1/int2 in pulse mode */
-	if (lis2dw12_int_notification_set(lis2dw12->ctx, LIS2DW12_INT_PULSED)) {
+	if (lis2dw12_int_notification_set(ctx, LIS2DW12_INT_PULSED)) {
 		return -EIO;
 	}