driver/sensor: add LIS2DS12 sensor support
Add support to STM LIS2DS12 3-axis accelerometer driver.
The driver support I2C and SPI bus communication and both
polling and drdy trigger mode.
Currently it uses high resolution only as power mode.
Signed-off-by: Armando Visconti <armando.visconti@st.com>
diff --git a/drivers/sensor/CMakeLists.txt b/drivers/sensor/CMakeLists.txt
index ff72725..139a955 100644
--- a/drivers/sensor/CMakeLists.txt
+++ b/drivers/sensor/CMakeLists.txt
@@ -21,6 +21,7 @@
add_subdirectory_ifdef(CONFIG_HTS221 hts221)
add_subdirectory_ifdef(CONFIG_ISL29035 isl29035)
add_subdirectory_ifdef(CONFIG_LIS2DH lis2dh)
+add_subdirectory_ifdef(CONFIG_LIS2DS12 lis2ds12)
add_subdirectory_ifdef(CONFIG_LIS2MDL lis2mdl)
add_subdirectory_ifdef(CONFIG_LIS3DH lis3dh)
add_subdirectory_ifdef(CONFIG_LIS3MDL lis3mdl)
diff --git a/drivers/sensor/Kconfig b/drivers/sensor/Kconfig
index dd4e7e5..8e66a46 100644
--- a/drivers/sensor/Kconfig
+++ b/drivers/sensor/Kconfig
@@ -71,6 +71,8 @@
source "drivers/sensor/lis2dh/Kconfig"
+source "drivers/sensor/lis2ds12/Kconfig"
+
source "drivers/sensor/lis2mdl/Kconfig"
source "drivers/sensor/lis3dh/Kconfig"
diff --git a/drivers/sensor/lis2ds12/CMakeLists.txt b/drivers/sensor/lis2ds12/CMakeLists.txt
new file mode 100644
index 0000000..5ffe7dc
--- /dev/null
+++ b/drivers/sensor/lis2ds12/CMakeLists.txt
@@ -0,0 +1,6 @@
+zephyr_library()
+
+zephyr_library_sources_ifdef(CONFIG_LIS2DS12 lis2ds12)
+zephyr_library_sources_ifdef(CONFIG_LIS2DS12 lis2ds12_i2c.c)
+zephyr_library_sources_ifdef(CONFIG_LIS2DS12 lis2ds12_spi.c)
+zephyr_library_sources_ifdef(CONFIG_LIS2DS12_TRIGGER lis2ds12_trigger.c)
diff --git a/drivers/sensor/lis2ds12/Kconfig b/drivers/sensor/lis2ds12/Kconfig
new file mode 100644
index 0000000..3b520b0
--- /dev/null
+++ b/drivers/sensor/lis2ds12/Kconfig
@@ -0,0 +1,90 @@
+# ST Microelectronics LIS2DS12 3-axis accelerometer driver
+#
+# Copyright (c) 2019 STMicroelectronics
+#
+# SPDX-License-Identifier: Apache-2.0
+#
+
+menuconfig LIS2DS12
+ bool "LIS2DS12 I2C/SPI accelerometer sensor driver"
+ depends on (I2C && HAS_DTS_I2C) || (SPI && HAS_DTS_SPI)
+ help
+ Enable driver for LIS2DS12 accelerometer sensor driver
+
+if LIS2DS12
+
+choice LIS2DS12_TRIGGER_MODE
+ prompt "Trigger mode"
+ help
+ Specify the type of triggering to be used by the driver.
+
+config LIS2DS12_TRIGGER_NONE
+ bool "No trigger"
+
+config LIS2DS12_TRIGGER_GLOBAL_THREAD
+ bool "Use global thread"
+ depends on GPIO
+ select LIS2DS12_TRIGGER
+
+config LIS2DS12_TRIGGER_OWN_THREAD
+ bool "Use own thread"
+ depends on GPIO
+ select LIS2DS12_TRIGGER
+
+endchoice
+
+config LIS2DS12_TRIGGER
+ bool
+
+config LIS2DS12_THREAD_PRIORITY
+ int "Thread priority"
+ depends on LIS2DS12_TRIGGER_OWN_THREAD
+ default 10
+ help
+ Priority of thread used by the driver to handle interrupts.
+
+config LIS2DS12_THREAD_STACK_SIZE
+ int "Thread stack size"
+ depends on LIS2DS12_TRIGGER_OWN_THREAD
+ default 1024
+ help
+ Stack size of thread used by the driver to handle interrupts.
+
+config LIS2DS12_ENABLE_TEMP
+ bool "Enable temperature"
+ help
+ Enable/disable temperature
+
+menu "Attributes"
+
+config LIS2DS12_FS
+ int "Accelerometer full-scale range"
+ default 0
+ help
+ Specify the default accelerometer full-scale range.
+ An X value for the config represents a range of +/- X G. Valid values
+ are:
+ 0: Full Scale selected at runtime
+ 2: +/- 2g
+ 4: +/- 4g
+ 8: +/- 8g
+ 16: +/- 16g
+
+config LIS2DS12_ODR
+ int "Accelerometer Output data rate frequency"
+ range 0 10
+ default 0
+ help
+ Specify the default accelerometer output data rate expressed in
+ samples per second (Hz).
+ 0: ODR selected at runtime
+ 1: 12.5Hz
+ 2: 25Hz
+ 3: 50Hz
+ 4: 100Hz
+ 5: 200Hz
+ 6: 400Hz
+ 7: 800Hz
+endmenu
+
+endif # LIS2DS12
diff --git a/drivers/sensor/lis2ds12/lis2ds12.c b/drivers/sensor/lis2ds12/lis2ds12.c
new file mode 100644
index 0000000..b4519af
--- /dev/null
+++ b/drivers/sensor/lis2ds12/lis2ds12.c
@@ -0,0 +1,317 @@
+/* ST Microelectronics LIS2DS12 3-axis accelerometer driver
+ *
+ * Copyright (c) 2019 STMicroelectronics
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Datasheet:
+ * https://www.st.com/resource/en/datasheet/lis2ds12.pdf
+ */
+
+#include <sensor.h>
+#include <kernel.h>
+#include <device.h>
+#include <init.h>
+#include <string.h>
+#include <misc/byteorder.h>
+#include <misc/__assert.h>
+#include <logging/log.h>
+
+#include "lis2ds12.h"
+
+#define LOG_LEVEL CONFIG_SENSOR_LOG_LEVEL
+LOG_MODULE_REGISTER(LIS2DS12);
+
+static struct lis2ds12_data lis2ds12_data;
+
+static struct lis2ds12_config lis2ds12_config = {
+ .comm_master_dev_name = DT_ST_LIS2DS12_0_BUS_NAME,
+#if defined(DT_ST_LIS2DS12_BUS_SPI)
+ .bus_init = lis2ds12_spi_init,
+#elif defined(DT_ST_LIS2DS12_BUS_I2C)
+ .bus_init = lis2ds12_i2c_init,
+#else
+#error "BUS MACRO NOT DEFINED IN DTS"
+#endif
+};
+
+#if defined(LIS2DS12_ODR_RUNTIME)
+static const u16_t lis2ds12_hr_odr_map[] = {0, 12, 25, 50, 100, 200, 400, 800};
+
+static int lis2ds12_freq_to_odr_val(u16_t freq)
+{
+ size_t i;
+
+ for (i = 0; i < ARRAY_SIZE(lis2ds12_hr_odr_map); i++) {
+ if (freq == lis2ds12_hr_odr_map[i]) {
+ return i;
+ }
+ }
+
+ return -EINVAL;
+}
+
+static int lis2ds12_accel_odr_set(struct device *dev, u16_t freq)
+{
+ struct lis2ds12_data *data = dev->driver_data;
+ int odr;
+
+ odr = lis2ds12_freq_to_odr_val(freq);
+ if (odr < 0) {
+ return odr;
+ }
+
+ if (data->hw_tf->update_reg(data,
+ LIS2DS12_REG_CTRL1,
+ LIS2DS12_MASK_CTRL1_ODR,
+ odr << LIS2DS12_SHIFT_CTRL1_ODR) < 0) {
+ LOG_DBG("failed to set accelerometer sampling rate");
+ return -EIO;
+ }
+
+ return 0;
+}
+#endif
+
+#ifdef LIS2DS12_FS_RUNTIME
+static const u16_t lis2ds12_accel_fs_map[] = {2, 16, 4, 8};
+static const u16_t lis2ds12_accel_fs_sens[] = {1, 8, 2, 4};
+
+static int lis2ds12_accel_range_to_fs_val(s32_t range)
+{
+ size_t i;
+
+ for (i = 0; i < ARRAY_SIZE(lis2ds12_accel_fs_map); i++) {
+ if (range == lis2ds12_accel_fs_map[i]) {
+ return i;
+ }
+ }
+
+ return -EINVAL;
+}
+
+static int lis2ds12_accel_range_set(struct device *dev, s32_t range)
+{
+ int fs;
+ struct lis2ds12_data *data = dev->driver_data;
+
+ fs = lis2ds12_accel_range_to_fs_val(range);
+ if (fs < 0) {
+ return fs;
+ }
+
+ if (data->hw_tf->update_reg(data,
+ LIS2DS12_REG_CTRL1,
+ LIS2DS12_MASK_CTRL1_FS,
+ fs << LIS2DS12_SHIFT_CTRL1_FS) < 0) {
+ LOG_DBG("failed to set accelerometer full-scale");
+ return -EIO;
+ }
+
+ data->gain = (float)(lis2ds12_accel_fs_sens[fs] * GAIN_XL);
+ return 0;
+}
+#endif
+
+static int lis2ds12_accel_config(struct device *dev, enum sensor_channel chan,
+ enum sensor_attribute attr,
+ const struct sensor_value *val)
+{
+ switch (attr) {
+#ifdef LIS2DS12_FS_RUNTIME
+ case SENSOR_ATTR_FULL_SCALE:
+ return lis2ds12_accel_range_set(dev, sensor_ms2_to_g(val));
+#endif
+#ifdef LIS2DS12_ODR_RUNTIME
+ case SENSOR_ATTR_SAMPLING_FREQUENCY:
+ return lis2ds12_accel_odr_set(dev, val->val1);
+#endif
+ default:
+ LOG_DBG("Accel attribute not supported.");
+ return -ENOTSUP;
+ }
+
+ return 0;
+}
+
+static int lis2ds12_attr_set(struct device *dev, enum sensor_channel chan,
+ enum sensor_attribute attr,
+ const struct sensor_value *val)
+{
+ switch (chan) {
+ case SENSOR_CHAN_ACCEL_XYZ:
+ return lis2ds12_accel_config(dev, chan, attr, val);
+ default:
+ LOG_WRN("attr_set() not supported on this channel.");
+ return -ENOTSUP;
+ }
+
+ return 0;
+}
+
+static int lis2ds12_sample_fetch_accel(struct device *dev)
+{
+ struct lis2ds12_data *data = dev->driver_data;
+ u8_t buf[6];
+
+ if (data->hw_tf->read_data(data, LIS2DS12_REG_OUTX_L,
+ buf, sizeof(buf)) < 0) {
+ LOG_DBG("failed to read sample");
+ return -EIO;
+ }
+
+ data->sample_x = (s16_t)((u16_t)(buf[0]) | ((u16_t)(buf[1]) << 8));
+ data->sample_y = (s16_t)((u16_t)(buf[2]) | ((u16_t)(buf[3]) << 8));
+ data->sample_z = (s16_t)((u16_t)(buf[4]) | ((u16_t)(buf[5]) << 8));
+
+ return 0;
+}
+
+static int lis2ds12_sample_fetch(struct device *dev, enum sensor_channel chan)
+{
+ switch (chan) {
+ case SENSOR_CHAN_ACCEL_XYZ:
+ lis2ds12_sample_fetch_accel(dev);
+ break;
+#if defined(CONFIG_LIS2DS12_ENABLE_TEMP)
+ case SENSOR_CHAN_DIE_TEMP:
+ lis2ds12_sample_fetch_temp(dev);
+ break;
+#endif
+ case SENSOR_CHAN_ALL:
+ lis2ds12_sample_fetch_accel(dev);
+#if defined(CONFIG_LIS2DS12_ENABLE_TEMP)
+ lis2ds12_sample_fetch_temp(dev);
+#endif
+ break;
+ default:
+ return -ENOTSUP;
+ }
+
+ return 0;
+}
+
+static inline void lis2ds12_convert(struct sensor_value *val, int raw_val,
+ float gain)
+{
+ s64_t dval;
+
+ /* Gain is in mg/LSB */
+ /* Convert to m/s^2 */
+ dval = ((s64_t)raw_val * gain * SENSOR_G) / 1000;
+ val->val1 = dval / 1000000LL;
+ val->val2 = dval % 1000000LL;
+}
+
+static inline int lis2ds12_get_channel(enum sensor_channel chan,
+ struct sensor_value *val,
+ struct lis2ds12_data *data,
+ float gain)
+{
+ switch (chan) {
+ case SENSOR_CHAN_ACCEL_X:
+ lis2ds12_convert(val, data->sample_x, gain);
+ break;
+ case SENSOR_CHAN_ACCEL_Y:
+ lis2ds12_convert(val, data->sample_y, gain);
+ break;
+ case SENSOR_CHAN_ACCEL_Z:
+ lis2ds12_convert(val, data->sample_z, gain);
+ break;
+ case SENSOR_CHAN_ACCEL_XYZ:
+ lis2ds12_convert(val, data->sample_x, gain);
+ lis2ds12_convert(val + 1, data->sample_y, gain);
+ lis2ds12_convert(val + 2, data->sample_z, gain);
+ break;
+ default:
+ return -ENOTSUP;
+ }
+
+ return 0;
+}
+
+static int lis2ds12_channel_get(struct device *dev,
+ enum sensor_channel chan,
+ struct sensor_value *val)
+{
+ struct lis2ds12_data *data = dev->driver_data;
+
+ return lis2ds12_get_channel(chan, val, data, data->gain);
+}
+
+static const struct sensor_driver_api lis2ds12_api_funcs = {
+ .attr_set = lis2ds12_attr_set,
+#if defined(CONFIG_LIS2DS12_TRIGGER)
+ .trigger_set = lis2ds12_trigger_set,
+#endif
+ .sample_fetch = lis2ds12_sample_fetch,
+ .channel_get = lis2ds12_channel_get,
+};
+
+static int lis2ds12_init(struct device *dev)
+{
+ const struct lis2ds12_config * const config = dev->config->config_info;
+ struct lis2ds12_data *data = dev->driver_data;
+ u8_t chip_id;
+
+ data->comm_master = device_get_binding(config->comm_master_dev_name);
+ if (!data->comm_master) {
+ LOG_DBG("master not found: %s",
+ config->comm_master_dev_name);
+ return -EINVAL;
+ }
+
+ config->bus_init(dev);
+
+ /* s/w reset the sensor */
+ if (data->hw_tf->write_reg(data,
+ LIS2DS12_REG_CTRL2,
+ LIS2DS12_SOFT_RESET) < 0) {
+ LOG_DBG("s/w reset fail");
+ return -EIO;
+ }
+
+ if (data->hw_tf->read_reg(data, LIS2DS12_REG_WHO_AM_I, &chip_id) < 0) {
+ LOG_DBG("failed reading chip id");
+ return -EIO;
+ }
+
+ if (chip_id != LIS2DS12_VAL_WHO_AM_I) {
+ LOG_DBG("invalid chip id 0x%x", chip_id);
+ return -EIO;
+ }
+
+ LOG_DBG("chip id 0x%x", chip_id);
+
+#ifdef CONFIG_LIS2DS12_TRIGGER
+ if (lis2ds12_trigger_init(dev) < 0) {
+ LOG_ERR("Failed to initialize triggers.");
+ return -EIO;
+ }
+#endif
+
+ /* set sensor default odr */
+ if (data->hw_tf->update_reg(data,
+ LIS2DS12_REG_CTRL1,
+ LIS2DS12_MASK_CTRL1_ODR,
+ LIS2DS12_DEFAULT_ODR) < 0) {
+ LOG_DBG("failed setting odr");
+ return -EIO;
+ }
+
+ /* set sensor default scale */
+ if (data->hw_tf->update_reg(data,
+ LIS2DS12_REG_CTRL1,
+ LIS2DS12_MASK_CTRL1_FS,
+ LIS2DS12_DEFAULT_FS) < 0) {
+ LOG_DBG("failed setting scale");
+ return -EIO;
+ }
+ data->gain = LIS2DS12_DEFAULT_GAIN;
+
+ return 0;
+}
+
+DEVICE_AND_API_INIT(lis2ds12, DT_ST_LIS2DS12_0_LABEL, lis2ds12_init,
+ &lis2ds12_data, &lis2ds12_config, POST_KERNEL,
+ CONFIG_SENSOR_INIT_PRIORITY, &lis2ds12_api_funcs);
diff --git a/drivers/sensor/lis2ds12/lis2ds12.h b/drivers/sensor/lis2ds12/lis2ds12.h
new file mode 100644
index 0000000..90e6e26
--- /dev/null
+++ b/drivers/sensor/lis2ds12/lis2ds12.h
@@ -0,0 +1,142 @@
+/* ST Microelectronics LIS2DS12 3-axis accelerometer driver
+ *
+ * Copyright (c) 2019 STMicroelectronics
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Datasheet:
+ * https://www.st.com/resource/en/datasheet/lis2ds12.pdf
+ */
+
+#ifndef ZEPHYR_DRIVERS_SENSOR_LIS2DS12_LIS2DS12_H_
+#define ZEPHYR_DRIVERS_SENSOR_LIS2DS12_LIS2DS12_H_
+
+#include <zephyr/types.h>
+#include <sensor.h>
+#include <gpio.h>
+
+#define LIS2DS12_REG_WHO_AM_I 0x0F
+#define LIS2DS12_VAL_WHO_AM_I 0x43
+
+#define LIS2DS12_REG_CTRL1 0x20
+#define LIS2DS12_MASK_CTRL1_ODR (BIT(7) | BIT(6) | \
+ BIT(5) | BIT(4))
+#define LIS2DS12_SHIFT_CTRL1_ODR 4
+#define LIS2DS12_MASK_CTRL1_FS (BIT(3) | BIT(2))
+#define LIS2DS12_SHIFT_CTRL1_FS 2
+#define LIS2DS12_MASK_CTRL1_HF_ODR BIT(1)
+#define LIS2DS12_MASK_CTRL1_HF_BDU BIT(0)
+
+#define LIS2DS12_REG_CTRL2 0x21
+#define LIS2DS12_SOFT_RESET 0x40
+
+#define LIS2DS12_REG_CTRL3 0x22
+#define LIS2DS12_SHIFT_LIR 0x02
+#define LIS2DS12_MASK_LIR 0x04
+
+#define LIS2DS12_REG_CTRL4 0x23
+#define LIS2DS12_SHIFT_INT1_DRDY 0x00
+#define LIS2DS12_MASK_INT1_DRDY 0x01
+
+#define LIS2DS12_REG_OUT_T 0x26
+
+#define LIS2DS12_REG_STATUS 0x27
+#define LIS2DS12_INT_DRDY 0x01
+
+#define LIS2DS12_REG_OUTX_L 0x28
+#define LIS2DS12_REG_OUTX_H 0x29
+#define LIS2DS12_REG_OUTY_L 0x2A
+#define LIS2DS12_REG_OUTY_H 0x2B
+#define LIS2DS12_REG_OUTZ_L 0x2C
+#define LIS2DS12_REG_OUTZ_H 0x2D
+
+
+#if (CONFIG_LIS2DS12_ODR == 0)
+#define LIS2DS12_ODR_RUNTIME 1
+#define LIS2DS12_DEFAULT_ODR 0
+#else
+#define LIS2DS12_DEFAULT_ODR (CONFIG_LIS2DS12_ODR << 4)
+#endif
+
+/* Accel sensor sensitivity unit is 0.061 mg/LSB */
+#define GAIN_XL (61LL / 1000.0)
+
+#if CONFIG_LIS2DS12_FS == 0
+#define LIS2DS12_FS_RUNTIME 1
+#define LIS2DS12_DEFAULT_FS (0 << 2)
+#define LIS2DS12_DEFAULT_GAIN GAIN_XL
+#elif CONFIG_LIS2DS12_FS == 2
+#define LIS2DS12_DEFAULT_FS (0 << 2)
+#define LIS2DS12_DEFAULT_GAIN GAIN_XL
+#elif CONFIG_LIS2DS12_FS == 4
+#define LIS2DS12_DEFAULT_FS (2 << 2)
+#define LIS2DS12_DEFAULT_GAIN (2.0 * GAIN_XL)
+#elif CONFIG_LIS2DS12_FS == 8
+#define LIS2DS12_DEFAULT_FS (3 << 2)
+#define LIS2DS12_DEFAULT_GAIN (4.0 * GAIN_XL)
+#elif CONFIG_LIS2DS12_FS == 16
+#define LIS2DS12_DEFAULT_FS (1 << 2)
+#define LIS2DS12_DEFAULT_GAIN (8.0 * GAIN_XL)
+#else
+#error "Bad LIS2DS12 FS value (should be 0, 2, 4, 8, 16)"
+#endif
+
+struct lis2ds12_config {
+ char *comm_master_dev_name;
+ int (*bus_init)(struct device *dev);
+};
+
+struct lis2ds12_data;
+
+struct lis2ds12_transfer_function {
+ int (*read_data)(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t *value, u8_t len);
+ int (*write_data)(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t *value, u8_t len);
+ int (*read_reg)(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t *value);
+ int (*write_reg)(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t value);
+ int (*update_reg)(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t mask, u8_t value);
+};
+
+struct lis2ds12_data {
+ struct device *comm_master;
+ int sample_x;
+ int sample_y;
+ int sample_z;
+ float gain;
+ const struct lis2ds12_transfer_function *hw_tf;
+
+#ifdef CONFIG_LIS2DS12_TRIGGER
+ struct device *gpio;
+ struct gpio_callback gpio_cb;
+
+ struct sensor_trigger data_ready_trigger;
+ sensor_trigger_handler_t data_ready_handler;
+
+#if defined(CONFIG_LIS2DS12_TRIGGER_OWN_THREAD)
+ K_THREAD_STACK_MEMBER(thread_stack, CONFIG_LIS2DS12_THREAD_STACK_SIZE);
+ struct k_thread thread;
+ struct k_sem trig_sem;
+#elif defined(CONFIG_LIS2DS12_TRIGGER_GLOBAL_THREAD)
+ struct k_work work;
+ struct device *dev;
+#endif
+
+#endif /* CONFIG_LIS2DS12_TRIGGER */
+};
+
+int lis2ds12_spi_init(struct device *dev);
+int lis2ds12_i2c_init(struct device *dev);
+
+#ifdef CONFIG_LIS2DS12_TRIGGER
+int lis2ds12_trigger_set(struct device *dev,
+ const struct sensor_trigger *trig,
+ sensor_trigger_handler_t handler);
+
+int lis2ds12_trigger_init(struct device *dev);
+#endif
+
+#endif /* ZEPHYR_DRIVERS_SENSOR_LIS2DS12_LIS2DS12_H_ */
diff --git a/drivers/sensor/lis2ds12/lis2ds12_i2c.c b/drivers/sensor/lis2ds12/lis2ds12_i2c.c
new file mode 100644
index 0000000..d1458e6
--- /dev/null
+++ b/drivers/sensor/lis2ds12/lis2ds12_i2c.c
@@ -0,0 +1,75 @@
+/* ST Microelectronics LIS2DS12 3-axis accelerometer driver
+ *
+ * Copyright (c) 2019 STMicroelectronics
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Datasheet:
+ * https://www.st.com/resource/en/datasheet/lis2ds12.pdf
+ */
+
+#include <string.h>
+#include <i2c.h>
+#include <logging/log.h>
+
+#include "lis2ds12.h"
+
+#ifdef DT_ST_LIS2DS12_BUS_I2C
+
+static u16_t lis2ds12_i2c_slave_addr = DT_ST_LIS2DS12_0_BASE_ADDRESS;
+
+#define LOG_LEVEL CONFIG_SENSOR_LOG_LEVEL
+LOG_MODULE_DECLARE(LIS2DS12);
+
+static int lis2ds12_i2c_read_data(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t *value, u8_t len)
+{
+ return i2c_burst_read(data->comm_master, lis2ds12_i2c_slave_addr,
+ reg_addr, value, len);
+}
+
+static int lis2ds12_i2c_write_data(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t *value, u8_t len)
+{
+ return i2c_burst_write(data->comm_master, lis2ds12_i2c_slave_addr,
+ reg_addr, value, len);
+}
+
+static int lis2ds12_i2c_read_reg(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t *value)
+{
+ return i2c_reg_read_byte(data->comm_master, lis2ds12_i2c_slave_addr,
+ reg_addr, value);
+}
+
+static int lis2ds12_i2c_write_reg(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t value)
+{
+ return i2c_reg_write_byte(data->comm_master, lis2ds12_i2c_slave_addr,
+ reg_addr, value);
+}
+
+static int lis2ds12_i2c_update_reg(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t mask, u8_t value)
+{
+ return i2c_reg_update_byte(data->comm_master, lis2ds12_i2c_slave_addr,
+ reg_addr, mask, value);
+}
+
+static const struct lis2ds12_transfer_function lis2ds12_i2c_transfer_fn = {
+ .read_data = lis2ds12_i2c_read_data,
+ .write_data = lis2ds12_i2c_write_data,
+ .read_reg = lis2ds12_i2c_read_reg,
+ .write_reg = lis2ds12_i2c_write_reg,
+ .update_reg = lis2ds12_i2c_update_reg,
+};
+
+int lis2ds12_i2c_init(struct device *dev)
+{
+ struct lis2ds12_data *data = dev->driver_data;
+
+ data->hw_tf = &lis2ds12_i2c_transfer_fn;
+
+ return 0;
+}
+#endif /* DT_ST_LIS2DS12_BUS_I2C */
diff --git a/drivers/sensor/lis2ds12/lis2ds12_spi.c b/drivers/sensor/lis2ds12/lis2ds12_spi.c
new file mode 100644
index 0000000..51b069e
--- /dev/null
+++ b/drivers/sensor/lis2ds12/lis2ds12_spi.c
@@ -0,0 +1,182 @@
+/* ST Microelectronics LIS2DS12 3-axis accelerometer driver
+ *
+ * Copyright (c) 2019 STMicroelectronics
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Datasheet:
+ * https://www.st.com/resource/en/datasheet/lis2ds12.pdf
+ */
+
+
+#include <string.h>
+#include <spi.h>
+#include "lis2ds12.h"
+#include <logging/log.h>
+
+#ifdef DT_ST_LIS2DS12_BUS_SPI
+
+#define LIS2DS12_SPI_READ (1 << 7)
+
+#define LOG_LEVEL CONFIG_SENSOR_LOG_LEVEL
+LOG_MODULE_DECLARE(LIS2DS12);
+
+#if defined(CONFIG_LIS2DS12_SPI_GPIO_CS)
+static struct spi_cs_control lis2ds12_cs_ctrl;
+#endif
+
+static struct spi_config lis2ds12_spi_conf = {
+ .frequency = DT_ST_LIS2DS12_0_SPI_MAX_FREQUENCY,
+ .operation = (SPI_OP_MODE_MASTER | SPI_MODE_CPOL |
+ SPI_MODE_CPHA | SPI_WORD_SET(8) | SPI_LINES_SINGLE),
+ .slave = DT_ST_LIS2DS12_0_BASE_ADDRESS,
+ .cs = NULL,
+};
+
+static int lis2ds12_raw_read(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t *value, u8_t len)
+{
+ struct spi_config *spi_cfg = &lis2ds12_spi_conf;
+ u8_t buffer_tx[2] = { reg_addr | LIS2DS12_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 = value,
+ .len = len,
+ }
+ };
+ const struct spi_buf_set rx = {
+ .buffers = rx_buf,
+ .count = 2
+ };
+
+
+ if (len > 64) {
+ return -EIO;
+ }
+
+ if (spi_transceive(data->comm_master, spi_cfg, &tx, &rx)) {
+ return -EIO;
+ }
+
+ return 0;
+}
+
+static int lis2ds12_raw_write(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t *value, u8_t len)
+{
+ struct spi_config *spi_cfg = &lis2ds12_spi_conf;
+ u8_t buffer_tx[1] = { reg_addr & ~LIS2DS12_SPI_READ };
+ 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 (spi_write(data->comm_master, spi_cfg, &tx)) {
+ return -EIO;
+ }
+
+ return 0;
+}
+
+static int lis2ds12_spi_read_data(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t *value, u8_t len)
+{
+ return lis2ds12_raw_read(data, reg_addr, value, len);
+}
+
+static int lis2ds12_spi_write_data(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t *value, u8_t len)
+{
+ return lis2ds12_raw_write(data, reg_addr, value, len);
+}
+
+static int lis2ds12_spi_read_reg(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t *value)
+{
+ return lis2ds12_raw_read(data, reg_addr, value, 1);
+}
+
+static int lis2ds12_spi_write_reg(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t value)
+{
+ u8_t tmp_val = value;
+
+ return lis2ds12_raw_write(data, reg_addr, &tmp_val, 1);
+}
+
+static int lis2ds12_spi_update_reg(struct lis2ds12_data *data, u8_t reg_addr,
+ u8_t mask, u8_t value)
+{
+ u8_t tmp_val;
+
+ lis2ds12_raw_read(data, reg_addr, &tmp_val, 1);
+ tmp_val = (tmp_val & ~mask) | (value & mask);
+
+ return lis2ds12_raw_write(data, reg_addr, &tmp_val, 1);
+}
+
+static const struct lis2ds12_transfer_function lis2ds12_spi_transfer_fn = {
+ .read_data = lis2ds12_spi_read_data,
+ .write_data = lis2ds12_spi_write_data,
+ .read_reg = lis2ds12_spi_read_reg,
+ .write_reg = lis2ds12_spi_write_reg,
+ .update_reg = lis2ds12_spi_update_reg,
+};
+
+int lis2ds12_spi_init(struct device *dev)
+{
+ struct lis2ds12_data *data = dev->driver_data;
+
+ data->hw_tf = &lis2ds12_spi_transfer_fn;
+
+#if defined(CONFIG_LIS2DS12_SPI_GPIO_CS)
+ /* handle SPI CS thru GPIO if it is the case */
+ if (IS_ENABLED(CONFIG_LIS2DS12_SPI_GPIO_CS)) {
+ lis2ds12_cs_ctrl.gpio_dev = device_get_binding(
+ CONFIG_LIS2DS12_SPI_GPIO_CS_DRV_NAME);
+ if (!lis2ds12_cs_ctrl.gpio_dev) {
+ LOG_ERR("Unable to get GPIO SPI CS device");
+ return -ENODEV;
+ }
+
+ lis2ds12_cs_ctrl.gpio_pin = CONFIG_LIS2DS12_SPI_GPIO_CS_PIN;
+ lis2ds12_cs_ctrl.delay = 0;
+
+ lis2ds12_spi_conf.cs = &lis2ds12_cs_ctrl;
+
+ LOG_DBG("SPI GPIO CS configured on %s:%u",
+ CONFIG_LIS2DS12_SPI_GPIO_CS_DRV_NAME,
+ CONFIG_LIS2DS12_SPI_GPIO_CS_PIN);
+ }
+#endif
+
+ return 0;
+}
+#endif /* DT_ST_LIS2DS12_BUS_SPI */
diff --git a/drivers/sensor/lis2ds12/lis2ds12_trigger.c b/drivers/sensor/lis2ds12/lis2ds12_trigger.c
new file mode 100644
index 0000000..a85f09f
--- /dev/null
+++ b/drivers/sensor/lis2ds12/lis2ds12_trigger.c
@@ -0,0 +1,192 @@
+/* ST Microelectronics LIS2DS12 3-axis accelerometer driver
+ *
+ * Copyright (c) 2019 STMicroelectronics
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Datasheet:
+ * https://www.st.com/resource/en/datasheet/lis2ds12.pdf
+ */
+
+#include <device.h>
+#include <i2c.h>
+#include <misc/__assert.h>
+#include <misc/util.h>
+#include <kernel.h>
+#include <sensor.h>
+
+#include "lis2ds12.h"
+
+#define LOG_LEVEL CONFIG_SENSOR_LOG_LEVEL
+#include <logging/log.h>
+LOG_MODULE_DECLARE(LIS2DS12);
+
+static void lis2ds12_gpio_callback(struct device *dev,
+ struct gpio_callback *cb, u32_t pins)
+{
+ struct lis2ds12_data *data =
+ CONTAINER_OF(cb, struct lis2ds12_data, gpio_cb);
+
+ ARG_UNUSED(pins);
+
+ gpio_pin_disable_callback(dev, DT_ST_LIS2DS12_0_IRQ_GPIOS_PIN);
+
+#if defined(CONFIG_LIS2DS12_TRIGGER_OWN_THREAD)
+ k_sem_give(&data->trig_sem);
+#elif defined(CONFIG_LIS2DS12_TRIGGER_GLOBAL_THREAD)
+ k_work_submit(&data->work);
+#endif
+}
+
+static void lis2ds12_handle_drdy_int(struct device *dev)
+{
+ struct lis2ds12_data *data = dev->driver_data;
+
+ if (data->data_ready_handler != NULL) {
+ data->data_ready_handler(dev, &data->data_ready_trigger);
+ }
+}
+
+static void lis2ds12_handle_int(void *arg)
+{
+ struct device *dev = arg;
+ struct lis2ds12_data *data = dev->driver_data;
+ u8_t status;
+
+ if (data->hw_tf->read_reg(data, LIS2DS12_REG_STATUS, &status) < 0) {
+ LOG_ERR("status reading error");
+ return;
+ }
+
+ if (status & LIS2DS12_INT_DRDY) {
+ lis2ds12_handle_drdy_int(dev);
+ }
+
+ gpio_pin_enable_callback(data->gpio, DT_ST_LIS2DS12_0_IRQ_GPIOS_PIN);
+}
+
+#ifdef CONFIG_LIS2DS12_TRIGGER_OWN_THREAD
+static void lis2ds12_thread(int dev_ptr, int unused)
+{
+ struct device *dev = INT_TO_POINTER(dev_ptr);
+ struct lis2ds12_data *data = dev->driver_data;
+
+ ARG_UNUSED(unused);
+
+ while (1) {
+ k_sem_take(&data->trig_sem, K_FOREVER);
+ lis2ds12_handle_int(dev);
+ }
+}
+#endif
+
+#ifdef CONFIG_LIS2DS12_TRIGGER_GLOBAL_THREAD
+static void lis2ds12_work_cb(struct k_work *work)
+{
+ struct lis2ds12_data *data =
+ CONTAINER_OF(work, struct lis2ds12_data, work);
+
+ lis2ds12_handle_int(data->dev);
+}
+#endif
+
+static int lis2ds12_init_interrupt(struct device *dev)
+{
+ struct lis2ds12_data *data = dev->driver_data;
+
+ /* Enable latched mode */
+ if (data->hw_tf->update_reg(data,
+ LIS2DS12_REG_CTRL3,
+ LIS2DS12_MASK_LIR,
+ (1 << LIS2DS12_SHIFT_LIR)) < 0) {
+ LOG_ERR("Could not enable LIR mode.");
+ return -EIO;
+ }
+
+ /* enable data-ready interrupt */
+ if (data->hw_tf->update_reg(data,
+ LIS2DS12_REG_CTRL4,
+ LIS2DS12_MASK_INT1_DRDY,
+ (1 << LIS2DS12_SHIFT_INT1_DRDY)) < 0) {
+ LOG_ERR("Could not enable data-ready interrupt.");
+ return -EIO;
+ }
+
+ return 0;
+}
+
+int lis2ds12_trigger_init(struct device *dev)
+{
+ struct lis2ds12_data *data = dev->driver_data;
+
+ /* setup data ready gpio interrupt */
+ data->gpio = device_get_binding(DT_ST_LIS2DS12_0_IRQ_GPIOS_CONTROLLER);
+ if (data->gpio == NULL) {
+ LOG_ERR("Cannot get pointer to %s device.",
+ DT_ST_LIS2DS12_0_IRQ_GPIOS_CONTROLLER);
+ return -EINVAL;
+ }
+
+ gpio_pin_configure(data->gpio, DT_ST_LIS2DS12_0_IRQ_GPIOS_PIN,
+ GPIO_DIR_IN | GPIO_INT | GPIO_INT_EDGE |
+ GPIO_INT_ACTIVE_HIGH | GPIO_INT_DEBOUNCE);
+
+ gpio_init_callback(&data->gpio_cb,
+ lis2ds12_gpio_callback,
+ BIT(DT_ST_LIS2DS12_0_IRQ_GPIOS_PIN));
+
+ if (gpio_add_callback(data->gpio, &data->gpio_cb) < 0) {
+ LOG_ERR("Could not set gpio callback.");
+ return -EIO;
+ }
+
+#if defined(CONFIG_LIS2DS12_TRIGGER_OWN_THREAD)
+ k_sem_init(&data->trig_sem, 0, UINT_MAX);
+
+ k_thread_create(&data->thread, data->thread_stack,
+ CONFIG_LIS2DS12_THREAD_STACK_SIZE,
+ (k_thread_entry_t)lis2ds12_thread, dev,
+ 0, NULL, K_PRIO_COOP(CONFIG_LIS2DS12_THREAD_PRIORITY),
+ 0, 0);
+#elif defined(CONFIG_LIS2DS12_TRIGGER_GLOBAL_THREAD)
+ data->work.handler = lis2ds12_work_cb;
+ data->dev = dev;
+#endif
+
+ gpio_pin_enable_callback(data->gpio, DT_ST_LIS2DS12_0_IRQ_GPIOS_PIN);
+
+ return 0;
+}
+
+int lis2ds12_trigger_set(struct device *dev,
+ const struct sensor_trigger *trig,
+ sensor_trigger_handler_t handler)
+{
+ struct lis2ds12_data *data = dev->driver_data;
+ u8_t buf[6];
+
+ __ASSERT_NO_MSG(trig->type == SENSOR_TRIG_DATA_READY);
+
+ gpio_pin_disable_callback(data->gpio, DT_ST_LIS2DS12_0_IRQ_GPIOS_PIN);
+
+ data->data_ready_handler = handler;
+ if (handler == NULL) {
+ LOG_WRN("lis2ds12: no handler");
+ return 0;
+ }
+
+ /* re-trigger lost interrupt */
+ if (data->hw_tf->read_data(data, LIS2DS12_REG_OUTX_L,
+ buf, sizeof(buf)) < 0) {
+ LOG_ERR("status reading error");
+ return -EIO;
+ }
+
+ data->data_ready_trigger = *trig;
+
+ lis2ds12_init_interrupt(dev);
+ gpio_pin_enable_callback(data->gpio, DT_ST_LIS2DS12_0_IRQ_GPIOS_PIN);
+
+ return 0;
+}
+
diff --git a/dts/bindings/sensor/st,lis2ds12-i2c.yaml b/dts/bindings/sensor/st,lis2ds12-i2c.yaml
new file mode 100644
index 0000000..3e7e0c9
--- /dev/null
+++ b/dts/bindings/sensor/st,lis2ds12-i2c.yaml
@@ -0,0 +1,24 @@
+#
+# Copyright (c) 2019 STMicroelectronics
+#
+# SPDX-License-Identifier: Apache-2.0
+#
+---
+title: STMicroelectronics MEMS sensors LIS2DS12
+version: 0.1
+
+description: >
+ This binding gives a base representation of LIS2DS12 3-axis accelerometer
+
+inherits:
+ !include i2c-device.yaml
+
+properties:
+ compatible:
+ constraint: "st,lis2ds12"
+
+ irq-gpios:
+ type: compound
+ category: required
+ generation: define, use-prop-name
+...
diff --git a/dts/bindings/sensor/st,lis2ds12-spi.yaml b/dts/bindings/sensor/st,lis2ds12-spi.yaml
new file mode 100644
index 0000000..364930b
--- /dev/null
+++ b/dts/bindings/sensor/st,lis2ds12-spi.yaml
@@ -0,0 +1,25 @@
+#
+# Copyright (c) 2019 STMicroelectronics
+#
+# SPDX-License-Identifier: Apache-2.0
+#
+---
+title: STMicroelectronics MEMS sensors LIS2DS12 SPI
+version: 0.1
+
+description: >
+ This binding gives a base representation of LIS2DS12 3-axis accelerometer
+ accessed through SPI bus
+
+inherits:
+ !include spi-device.yaml
+
+properties:
+ compatible:
+ constraint: "st,lis2ds12"
+
+ irq-gpios:
+ type: compound
+ category: required
+ generation: define, use-prop-name
+...
diff --git a/tests/drivers/build_all/dts_fixup.h b/tests/drivers/build_all/dts_fixup.h
index 08bae0a..0924d23 100644
--- a/tests/drivers/build_all/dts_fixup.h
+++ b/tests/drivers/build_all/dts_fixup.h
@@ -158,6 +158,15 @@
#define DT_SENSIRION_SHT3XD_0_BUS_NAME ""
#endif
+#ifndef DT_ST_LIS2DS12_0_LABEL
+#define DT_ST_LIS2DS12_0_LABEL ""
+#define DT_ST_LIS2DS12_0_BUS_NAME ""
+#define DT_ST_LIS2DS12_0_BASE_ADDRESS 0x19
+#define DT_ST_LIS2DS12_0_IRQ_GPIOS_CONTROLLER ""
+#define DT_ST_LIS2DS12_0_IRQ_GPIOS_PIN 0
+#define DT_ST_LIS2DS12_BUS_I2C 1
+#endif
+
#ifndef DT_LIS3DH_DEV_NAME
#define DT_LIS3DH_DEV_NAME ""
#define DT_LIS3DH_I2C_ADDRESS 0x19
@@ -219,6 +228,16 @@
#define DT_LIS2DH_INT2_GPIO_PIN 1
#endif
+#ifndef DT_ST_LIS2DS12_0_LABEL
+#define DT_ST_LIS2DS12_0_LABEL ""
+#define DT_ST_LIS2DS12_0_BUS_NAME ""
+#define DT_ST_LIS2DS12_0_SPI_MAX_FREQUENCY 100000
+#define DT_ST_LIS2DS12_0_BASE_ADDRESS 1
+#define DT_ST_LIS2DS12_0_IRQ_GPIOS_CONTROLLER ""
+#define DT_ST_LIS2DS12_0_IRQ_GPIOS_PIN 0
+#define DT_ST_LIS2DS12_BUS_SPI 1
+#endif
+
#ifndef DT_MICROCHIP_ENC28J60_0_LABEL
#define DT_MICROCHIP_ENC28J60_0_BASE_ADDRESS 0
#define DT_MICROCHIP_ENC28J60_0_BUS_NAME ""
diff --git a/tests/drivers/build_all/sensors_i_z.conf b/tests/drivers/build_all/sensors_i_z.conf
index f0cb73b..49700ef 100644
--- a/tests/drivers/build_all/sensors_i_z.conf
+++ b/tests/drivers/build_all/sensors_i_z.conf
@@ -7,6 +7,7 @@
CONFIG_SENSOR_LOG_LEVEL_DBG=y
CONFIG_ISL29035=y
CONFIG_LIS2DH=y
+CONFIG_LIS2DS12=y
CONFIG_LIS2MDL=y
CONFIG_LIS3DH=y
CONFIG_LIS3MDL=y
diff --git a/tests/drivers/build_all/sensors_trigger_i_z.conf b/tests/drivers/build_all/sensors_trigger_i_z.conf
index dd8bf8e..978a6bb 100644
--- a/tests/drivers/build_all/sensors_trigger_i_z.conf
+++ b/tests/drivers/build_all/sensors_trigger_i_z.conf
@@ -8,6 +8,8 @@
CONFIG_ISL29035_TRIGGER_OWN_THREAD=y
CONFIG_LIS2DH=y
CONFIG_LIS2DH_TRIGGER_OWN_THREAD=y
+CONFIG_LIS2DS12=y
+CONFIG_LIS2DS12_TRIGGER_OWN_THREAD=y
CONFIG_LIS2MDL=y
CONFIG_LIS2MDL_TRIGGER_OWN_THREAD=y
CONFIG_LIS3DH=y