drivers:iio:stm:accel: add support to h3lis331dl STMEMS accel sensor

Add support to the h3lis331dl STMEMS accel sensor with the
following basic features:
 - Accel raw data read
 - Buffered data read
 - Trigger support

h3lis331dl driver include support for H3LIS331DL and LIS331DLH
STMEMS accel sensor devices.

Signed-off-by: Mario Tesi <mario.tesi@st.com>
Change-Id: Ic8553294d1e646aa048b3f4be294d8d6d3916035
Reviewed-on: https://gerrit.st.com/c/linuxandroidopen/stm-ldd-iio/+/296337
Tested-by: CITOOLS <MDG-smet-aci-reviews@list.st.com>
Reviewed-by: Matteo DAMENO <matteo.dameno@st.com>
This commit is contained in:
Mario Tesi 2023-03-16 17:10:26 +01:00 committed by Matteo DAMENO
parent 6798553410
commit 9cd00ee4c2
9 changed files with 1356 additions and 0 deletions

View File

@ -0,0 +1,45 @@
* h3lis331dl driver for accel MEMS sensors
Required properties for the spi bindings:
- compatible: must be one of:
"st,h3lis331dl"
"st,lis331dlh"
- reg: the chipselect index
- spi-max-frequency: maximal bus speed, should be set to 10000000 unless
constrained by external circuitry
Optional properties:
- st,drdy-int-pin: the pin on the package that will be used to signal
"data ready" (valid values: 1 or 2, default: 1).
- interrupts: interrupt mapping for IRQ. It should be configured with
flags IRQ_TYPE_LEVEL_HIGH.
Refer to interrupt-controller/interrupts.txt for generic
interrupt client node bindings.
- drive-open-drain: interrupt pin open drain setting (valid values: 0 or 1,
default: 0).
Example for an i2c device node:
h3lis331dl@18 {
compatible = "st,lis331dlh-accel";
reg = <0x18>;
interrupt-parent = <&gpio0>;
interrupts = <0 IRQ_TYPE_LEVEL_HIGH>;
st,drdy-int-pin = <1>;
};
Example for an spi device node:
h3lis331dl-accel@0 {
compatible = "st,h3lis331dl";
reg = <0x0>;
spi-max-frequency = <1000000>;
interrupt-parent = <&gpio0>;
interrupts = <0 IRQ_TYPE_LEVEL_HIGH>;
st,drdy-int-pin = <1>;
};

View File

@ -189,4 +189,29 @@ config IIO_ST_LIS2DUXS12_I3C
select REGMAP_I3C
depends on IIO_ST_LIS2DUXS12
config IIO_ST_H3LIS331DL
tristate "STMicroelectronics H3LIS331DL/LIS331DLH sensor"
depends on (I2C || SPI)
select IIO_BUFFER
select IIO_KFIFO_BUF
select IIO_TRIGGERED_BUFFER
select IIO_ST_H3LIS331DL_I2C if (I2C)
select IIO_ST_H3LIS331DL_SPI if (SPI_MASTER)
help
Say yes here to build support for STMicroelectronics H3LIS331DL and
LIS331DLH accelerometer sensors.
To compile this driver as a module, choose M here: the module
will be called st_h3lis331dl.
config IIO_ST_H3LIS331DL_I2C
tristate
select REGMAP_I2C
depends on IIO_ST_H3LIS331DL
config IIO_ST_H3LIS331DL_SPI
tristate
select REGMAP_SPI
depends on IIO_ST_H3LIS331DL
endmenu

View File

@ -42,3 +42,9 @@ obj-$(CONFIG_IIO_ST_LIS2DUXS12) += st_lis2duxs12.o
obj-$(CONFIG_IIO_ST_LIS2DUXS12_I2C) += st_lis2duxs12_i2c.o
obj-$(CONFIG_IIO_ST_LIS2DUXS12_SPI) += st_lis2duxs12_spi.o
obj-$(CONFIG_IIO_ST_LIS2DUXS12_I3C) += st_lis2duxs12_i3c.o
st_h3lis331dl-y := st_h3lis331dl_core.o st_h3lis331dl_buffer.o
obj-$(CONFIG_IIO_ST_H3LIS331DL) += st_h3lis331dl.o
obj-$(CONFIG_IIO_ST_H3LIS331DL_I2C) += st_h3lis331dl_i2c.o
obj-$(CONFIG_IIO_ST_H3LIS331DL_SPI) += st_h3lis331dl_spi.o

View File

@ -0,0 +1,261 @@
/* SPDX-License-Identifier: GPL-2.0-only */
/*
* STMicroelectronics st_h3lis331dl sensor driver
*
* MEMS Software Solutions Team
*
* Copyright 2023 STMicroelectronics Inc.
*/
#ifndef ST_H3LIS331DL_H
#define ST_H3LIS331DL_H
#include <linux/bitfield.h>
#include <linux/device.h>
#include <linux/iio/iio.h>
#include <linux/delay.h>
#include <linux/regmap.h>
#define ST_H3LIS331DL_DEV_NAME "h3lis331dl"
#define ST_LIS331DLH_DEV_NAME "lis331dlh"
#define ST_H3LIS331DL_REG_WHO_AM_I_ADDR 0x0f
#define ST_H3LIS331DL_WHO_AM_I_VAL 0x32
#define ST_H3LIS331DL_CTRL_REG1_ADDR 0x20
#define ST_H3LIS331DL_EN_MASK GENMASK(2, 0)
#define ST_H3LIS331DL_DR_MASK GENMASK(4, 3)
#define ST_H3LIS331DL_PM_MASK GENMASK(7, 5)
#define ST_H3LIS331DL_CTRL_REG2_ADDR 0x21
#define ST_H3LIS331DL_BOOT_MASK BIT(7)
#define ST_H3LIS331DL_CTRL_REG3_ADDR 0x22
#define ST_H3LIS331DL_I1CFG_MASK GENMASK(1, 0)
#define ST_H3LIS331DL_LIR1_MASK BIT(2)
#define ST_H3LIS331DL_I2CFG_MASK GENMASK(4, 3)
#define ST_H3LIS331DL_LIR2_MASK BIT(5)
#define ST_H3LIS331DL_PP_OD_MASK BIT(6)
#define ST_H3LIS331DL_IHL_MASK BIT(7)
#define ST_H3LIS331DL_CFG_DRDY_VAL 0x02
#define ST_H3LIS331DL_CTRL_REG4_ADDR 0x23
#define ST_H3LIS331DL_FS_MASK GENMASK(5, 4)
#define ST_H3LIS331DL_BLE_MASK BIT(6)
#define ST_H3LIS331DL_BDU_MASK BIT(7)
#define ST_H3LIS331DL_STATUS_REG_ADDR 0x27
#define ST_H3LIS331DL_ZYXDA_MASK BIT(3)
#define ST_H3LIS331DL_REG_OUTX_L_ADDR 0x28
#define ST_H3LIS331DL_REG_OUTY_L_ADDR 0x2a
#define ST_H3LIS331DL_REG_OUTZ_L_ADDR 0x2c
#define ST_H3LIS331DL_SAMPLE_SIZE 6
/* enable reading address with auto increment */
#define ST_H3LIS331DL_AUTO_INCREMENT(_addr) (0x80 | _addr)
#define ST_H3LIS331DL_DATA_CHANNEL(chan_type, addr, mod, ch2, scan_idx, \
rb, sb, sg, ex_info) \
{ \
.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, \
}, \
.ext_info = ex_info, \
}
#define ST_H3LIS331DL_SHIFT_VAL(val, mask) (((val) << __ffs(mask)) & (mask))
#define ST_H3LIS331DL_ACC_SENSOR_ID 0
#define ST_H3LIS331DL_ODR_LIST_SIZE 8
#define ST_H3LIS331DL_FS_LIST_SIZE 3
/**
* struct st_h3lis331dl_reg - Generic sensor register description (addr + mask)
* @addr: Address of register.
* @mask: Bitmask register for proper usage.
*/
struct st_h3lis331dl_reg {
u8 addr;
u8 mask;
};
/**
* struct st_h3lis331dl_odr - Single ODR entry
* @hz: Most significant part of the sensor ODR (Hz).
* @val: ODR register value.
*/
struct st_h3lis331dl_odr {
int hz;
u8 val;
};
/**
* struct st_h3lis331dl_odr_table_entry - Sensor ODR table
* @size: Size of ODR table.
* @reg: ODR register.
* @odr_avl: Array of supported ODR value.
*/
struct st_h3lis331dl_odr_table_entry {
u8 size;
struct st_h3lis331dl_reg reg;
struct st_h3lis331dl_odr odr_avl[ST_H3LIS331DL_ODR_LIST_SIZE];
};
/**
* struct st_h3lis331dl_fs - Full Scale sensor table entry
* @gain: Sensor sensitivity.
* @val: FS register value.
*/
struct st_h3lis331dl_fs {
u32 gain;
u8 val;
};
/**
* struct st_h3lis331dl_fs_table_entry - Full Scale sensor table
* @size: Full Scale sensor table size.
* @reg: Register description for FS settings.
* @fs_avl: Full Scale list entries.
*/
struct st_h3lis331dl_fs_table_entry {
u8 size;
struct st_h3lis331dl_reg reg;
struct st_h3lis331dl_fs fs_avl[ST_H3LIS331DL_FS_LIST_SIZE];
};
#define ST_H3LIS331DL_ACC_FS_100G_GAIN IIO_G_TO_M_S_2(784000)
#define ST_H3LIS331DL_ACC_FS_200G_GAIN IIO_G_TO_M_S_2(1568000)
#define ST_H3LIS331DL_ACC_FS_400G_GAIN IIO_G_TO_M_S_2(3136000)
/**
* struct st_h3lis331dl_sensor - ST IMU sensor instance
* @is: Sensor id.
* @name: Sensor name.
* @hw: Pointer to instance of struct st_h3lis331dl_hw.
* @trig: Trigger used by IIO event sensors.
* @odr: Sensor odr.
* @gain: Configured sensor sensitivity.
* @offset: Sensor data offset.
* @decimator: Sensor decimator
* @dec_counter: Sensor decimator counter
*/
struct st_h3lis331dl_sensor {
int id;
char name[32];
struct st_h3lis331dl_hw *hw;
struct iio_trigger *trig;
int odr;
u32 gain;
u32 offset;
u8 decimator;
u8 dec_counter;
};
/**
* struct st_h3lis331dl_hw - ST IMU MEMS hw instance
* @dev: Pointer to instance of struct device (I2C or SPI).
* @irq: Device interrupt line (I2C or SPI).
* @regmap: Register map of the device.
* @int_pin: Save interrupt pin used by sensor.
* @lock: Mutex to protect read and write operations.
* @enable_mask: Enabled sensor bitmask.
* @ts: hw timestamp value always monotonic where the most
* significant 8byte are incremented at every disable/enable.
* @iio_devs: Pointers to acc/gyro iio_dev instances.
* @vdd_supply: Voltage regulator for VDD.
* @vddio_supply: Voltage regulator for VDDIIO.
* @orientation: Sensor chip orientation relative to main hardware.
* @self_test: Self test start and read result.
* @selftest_available: Reports self test available for this sensor.
*/
struct st_h3lis331dl_hw {
struct device *dev;
int irq;
struct regmap *regmap;
int int_pin;
struct mutex lock;
u64 enable_mask;
u64 requested_mask;
s64 ts;
struct iio_dev *iio_devs;
struct regulator *vdd_supply;
struct regulator *vddio_supply;
struct iio_mount_matrix orientation;
};
extern const struct dev_pm_ops st_h3lis331dl_pm_ops;
static inline int __st_h3lis331dl_write_with_mask(struct st_h3lis331dl_hw *hw,
unsigned int addr,
unsigned int mask,
unsigned int data)
{
int err;
unsigned int val = ST_H3LIS331DL_SHIFT_VAL(data, mask);
err = regmap_update_bits(hw->regmap, addr, mask, val);
return err;
}
static inline int
st_h3lis331dl_update_bits_locked(struct st_h3lis331dl_hw *hw, unsigned int addr,
unsigned int mask, unsigned int val)
{
int err;
mutex_lock(&hw->lock);
err = __st_h3lis331dl_write_with_mask(hw, addr, mask, val);
mutex_unlock(&hw->lock);
return err;
}
/* use when mask is constant */
static inline int
st_h3lis331dl_write_with_mask_locked(struct st_h3lis331dl_hw *hw,
unsigned int addr,
unsigned int mask,
unsigned int data)
{
int err;
unsigned int val = ST_H3LIS331DL_SHIFT_VAL(mask, data);
mutex_lock(&hw->lock);
err = regmap_update_bits(hw->regmap, addr, mask, val);
mutex_unlock(&hw->lock);
return err;
}
static inline s64 st_h3lis331dl_get_time_ns(struct iio_dev *iio_dev)
{
return iio_get_time_ns(iio_dev);
}
int st_h3lis331dl_probe(struct device *dev, int irq, int hw_id,
struct regmap *regmap);
int st_h3lis331dl_sensor_set_enable(struct st_h3lis331dl_sensor *sensor,
bool enable);
int st_h3lis331dl_trigger_setup(struct st_h3lis331dl_hw *hw);
int st_h3lis331dl_allocate_triggered_buffer(struct st_h3lis331dl_hw *hw);
#endif /* ST_H3LIS331DL_H */

View File

@ -0,0 +1,255 @@
// SPDX-License-Identifier: GPL-2.0-only
/*
* STMicroelectronics st_h3lis331dl trigger buffer driver
*
* MEMS Software Solutions Team
*
* Copyright 2023 STMicroelectronics Inc.
*/
#include <asm/unaligned.h>
#include <linux/interrupt.h>
#include <linux/iio/buffer.h>
#include <linux/iio/buffer.h>
#include <linux/iio/events.h>
#include <linux/iio/iio.h>
#include <linux/iio/kfifo_buf.h>
#include <linux/iio/sw_trigger.h>
#include <linux/iio/trigger.h>
#include <linux/iio/trigger_consumer.h>
#include <linux/iio/triggered_buffer.h>
#include <linux/irq.h>
#include <linux/module.h>
#include <linux/platform_data/st_sensors_pdata.h>
#include <linux/property.h>
#include <linux/version.h>
#include "st_h3lis331dl.h"
static int st_h3lis331dl_get_int_reg(struct st_h3lis331dl_hw *hw)
{
int err, int_pin;
if (!dev_fwnode(hw->dev))
return -EINVAL;
err = device_property_read_u32(hw->dev, "st,drdy-int-pin", &int_pin);
if (err < 0) {
struct st_sensors_platform_data *pdata;
struct device *dev = hw->dev;
pdata = (struct st_sensors_platform_data *)dev->platform_data;
int_pin = pdata ? pdata->drdy_int_pin : 1;
}
hw->int_pin = int_pin;
return err;
}
static int st_h3lis331dl_buffer_enable(struct iio_dev *iio_dev, bool enable)
{
struct st_h3lis331dl_sensor *sensor = iio_priv(iio_dev);
return st_h3lis331dl_sensor_set_enable(sensor, enable);
}
static irqreturn_t st_h3lis331dl_handler_irq(int irq, void *private)
{
struct st_h3lis331dl_hw *hw = (struct st_h3lis331dl_hw *)private;
hw->ts = st_h3lis331dl_get_time_ns(hw->iio_devs);
return IRQ_WAKE_THREAD;
}
static irqreturn_t st_h3lis331dl_handler_thread(int irq, void *private)
{
struct st_h3lis331dl_hw *hw = (struct st_h3lis331dl_hw *)private;
unsigned int status;
int err;
err = regmap_read(hw->regmap, ST_H3LIS331DL_STATUS_REG_ADDR, &status);
if (err < 0)
return IRQ_HANDLED;
if (status & ST_H3LIS331DL_ZYXDA_MASK) {
struct st_h3lis331dl_sensor *sensor;
sensor = iio_priv(hw->iio_devs);
iio_trigger_poll_chained(sensor->trig);
return IRQ_HANDLED;
}
return IRQ_NONE;
}
static int st_h3lis331dl_fifo_preenable(struct iio_dev *iio_dev)
{
return st_h3lis331dl_buffer_enable(iio_dev, true);
}
static int st_h3lis331dl_fifo_postdisable(struct iio_dev *iio_dev)
{
return st_h3lis331dl_buffer_enable(iio_dev, false);
}
static const struct iio_buffer_setup_ops st_h3lis331dl_buffer_setup_ops = {
.preenable = st_h3lis331dl_fifo_preenable,
.postdisable = st_h3lis331dl_fifo_postdisable,
};
static irqreturn_t st_h3lis331dl_buffer_pollfunc(int irq, void *private)
{
u8 iio_buf[ALIGN(ST_H3LIS331DL_SAMPLE_SIZE, sizeof(s64)) + sizeof(s64) + sizeof(s64)];
struct iio_poll_func *pf = private;
struct iio_dev *indio_dev = pf->indio_dev;
struct st_h3lis331dl_sensor *sensor = iio_priv(indio_dev);
struct st_h3lis331dl_hw *hw = sensor->hw;
int addr = indio_dev->channels[0].address;
int err;
err = regmap_bulk_read(hw->regmap, ST_H3LIS331DL_AUTO_INCREMENT(addr),
&iio_buf, ST_H3LIS331DL_SAMPLE_SIZE);
if (err < 0)
goto out;
if (indio_dev->trig)
iio_push_to_buffers_with_timestamp(indio_dev, iio_buf,
st_h3lis331dl_get_time_ns(indio_dev));
else
iio_push_to_buffers_with_timestamp(indio_dev, iio_buf, hw->ts);
out:
iio_trigger_notify_done(indio_dev->trig);
return IRQ_HANDLED;
}
int st_h3lis331dl_allocate_triggered_buffer(struct st_h3lis331dl_hw *hw)
{
return devm_iio_triggered_buffer_setup(hw->dev,
hw->iio_devs, NULL,
st_h3lis331dl_buffer_pollfunc,
&st_h3lis331dl_buffer_setup_ops);
}
static int st_h3lis331dl_config_interrupt(struct st_h3lis331dl_hw *hw,
bool enable)
{
u8 cfg_mask;
u8 cfg_cfg;
switch (hw->int_pin) {
case 1:
cfg_mask = ST_H3LIS331DL_I1CFG_MASK;
break;
case 2:
cfg_mask = ST_H3LIS331DL_I2CFG_MASK;
break;
default:
return -EINVAL;
}
cfg_cfg = enable ? ST_H3LIS331DL_CFG_DRDY_VAL : 0;
cfg_cfg = ST_H3LIS331DL_SHIFT_VAL(cfg_cfg, cfg_mask);
return regmap_update_bits(hw->regmap, ST_H3LIS331DL_CTRL_REG3_ADDR,
cfg_mask, cfg_cfg);
}
static int st_h3lis331dl_trig_set_state(struct iio_trigger *trig, bool state)
{
struct st_h3lis331dl_hw *hw = iio_trigger_get_drvdata(trig);
dev_dbg(hw->dev, "trigger set %d\n", state);
return st_h3lis331dl_config_interrupt(hw, state);
}
static const struct iio_trigger_ops st_h3lis331dl_trigger_ops = {
.set_trigger_state = st_h3lis331dl_trig_set_state,
};
int st_h3lis331dl_trigger_setup(struct st_h3lis331dl_hw *hw)
{
struct st_h3lis331dl_sensor *sensor;
unsigned long irq_type;
bool irq_active_low;
int err;
err = st_h3lis331dl_get_int_reg(hw);
if (err < 0)
return err;
irq_type = irqd_get_trigger_type(irq_get_irq_data(hw->irq));
switch (irq_type) {
case IRQF_TRIGGER_HIGH:
case IRQF_TRIGGER_NONE:
irq_active_low = false;
break;
case IRQF_TRIGGER_LOW:
irq_active_low = true;
break;
default:
dev_info(hw->dev, "mode %lx unsupported\n", irq_type);
return -EINVAL;
}
err = regmap_update_bits(hw->regmap,
ST_H3LIS331DL_CTRL_REG3_ADDR,
ST_H3LIS331DL_IHL_MASK,
FIELD_PREP(ST_H3LIS331DL_IHL_MASK,
irq_active_low));
if (err < 0)
return err;
if (device_property_read_bool(hw->dev, "drive-open-drain")) {
err = regmap_update_bits(hw->regmap,
ST_H3LIS331DL_CTRL_REG3_ADDR,
ST_H3LIS331DL_PP_OD_MASK,
FIELD_PREP(ST_H3LIS331DL_PP_OD_MASK,
1));
if (err < 0)
return err;
irq_type |= IRQF_SHARED;
}
err = devm_request_threaded_irq(hw->dev, hw->irq,
st_h3lis331dl_handler_irq,
st_h3lis331dl_handler_thread,
irq_type | IRQF_ONESHOT,
ST_H3LIS331DL_DEV_NAME, hw);
if (err) {
dev_err(hw->dev, "failed to request trigger irq %d\n",
hw->irq);
return err;
}
/* attach trigger to iio devs */
sensor = iio_priv(hw->iio_devs);
sensor->trig = devm_iio_trigger_alloc(hw->dev, "st_%s-trigger",
hw->iio_devs->name);
if (!sensor->trig) {
dev_err(hw->dev, "failed to allocate iio trigger.\n");
return -ENOMEM;
}
iio_trigger_set_drvdata(sensor->trig, hw);
sensor->trig->ops = &st_h3lis331dl_trigger_ops;
sensor->trig->dev.parent = hw->dev;
err = devm_iio_trigger_register(hw->dev, sensor->trig);
if (err < 0) {
dev_err(hw->dev, "failed to register iio trigger.\n");
return err;
}
hw->iio_devs->trig = iio_trigger_get(sensor->trig);
return 0;
}

View File

@ -0,0 +1,616 @@
// SPDX-License-Identifier: GPL-2.0-only
/*
* STMicroelectronics st_h3lis331dl sensor driver
*
* MEMS Software Solutions Team
*
* Copyright 2023 STMicroelectronics Inc.
*/
#include <linux/kernel.h>
#include <linux/iio/iio.h>
#include <linux/iio/sysfs.h>
#include <linux/interrupt.h>
#include <linux/module.h>
#include <linux/of_device.h>
#include <linux/pm.h>
#include <linux/property.h>
#include <linux/regulator/consumer.h>
#include <linux/version.h>
#include "st_h3lis331dl.h"
static const struct st_h3lis331dl_odr_table_entry st_h3lis331dl_odr_table = {
.size = ST_H3LIS331DL_ODR_LIST_SIZE,
.reg = {
.addr = ST_H3LIS331DL_CTRL_REG1_ADDR,
.mask = ST_H3LIS331DL_DR_MASK | ST_H3LIS331DL_PM_MASK,
},
.odr_avl[0] = { 0, 0x00 },
.odr_avl[1] = { 1, 0x0c },
.odr_avl[2] = { 2, 0x10 },
.odr_avl[3] = { 5, 0x14 },
.odr_avl[4] = { 10, 0x18 },
.odr_avl[5] = { 50, 0x04 },
.odr_avl[6] = { 100, 0x05 },
.odr_avl[7] = { 400, 0x06 },
};
static const struct st_h3lis331dl_fs_table_entry st_h3lis331dl_fs_table = {
.size = ST_H3LIS331DL_FS_LIST_SIZE,
.reg = {
.addr = ST_H3LIS331DL_CTRL_REG4_ADDR,
.mask = ST_H3LIS331DL_FS_MASK,
},
.fs_avl[0] = {
.gain = ST_H3LIS331DL_ACC_FS_100G_GAIN,
.val = 0x0,
},
.fs_avl[1] = {
.gain = ST_H3LIS331DL_ACC_FS_200G_GAIN,
.val = 0x1,
},
.fs_avl[2] = {
.gain = ST_H3LIS331DL_ACC_FS_400G_GAIN,
.val = 0x2,
},
};
static const inline struct iio_mount_matrix *
st_h3lis331dl_get_mount_matrix(const struct iio_dev *iio_dev,
const struct iio_chan_spec *chan)
{
struct st_h3lis331dl_sensor *sensor = iio_priv(iio_dev);
struct st_h3lis331dl_hw *hw = sensor->hw;
return &hw->orientation;
}
static const struct iio_chan_spec_ext_info st_h3lis331dl_ext_info[] = {
IIO_MOUNT_MATRIX(IIO_SHARED_BY_ALL, st_h3lis331dl_get_mount_matrix),
{},
};
static const struct iio_chan_spec st_h3lis331dl_acc_channels[] = {
ST_H3LIS331DL_DATA_CHANNEL(IIO_ACCEL, ST_H3LIS331DL_REG_OUTX_L_ADDR,
1, IIO_MOD_X, 0, 12, 16, 's', st_h3lis331dl_ext_info),
ST_H3LIS331DL_DATA_CHANNEL(IIO_ACCEL, ST_H3LIS331DL_REG_OUTY_L_ADDR,
1, IIO_MOD_Y, 1, 12, 16, 's', st_h3lis331dl_ext_info),
ST_H3LIS331DL_DATA_CHANNEL(IIO_ACCEL, ST_H3LIS331DL_REG_OUTZ_L_ADDR,
1, IIO_MOD_Z, 2, 12, 16, 's', st_h3lis331dl_ext_info),
IIO_CHAN_SOFT_TIMESTAMP(3),
};
static __maybe_unused int st_h3lis331dl_reg_access(struct iio_dev *iio_dev,
unsigned int reg, unsigned int writeval,
unsigned int *readval)
{
struct st_h3lis331dl_sensor *sensor = iio_priv(iio_dev);
int ret;
ret = iio_device_claim_direct_mode(iio_dev);
if (ret)
return ret;
if (readval == NULL)
ret = regmap_write(sensor->hw->regmap, reg, writeval);
else
ret = regmap_read(sensor->hw->regmap, reg, readval);
iio_device_release_direct_mode(iio_dev);
return (ret < 0) ? ret : 0;
}
static int st_h3lis331dl_check_whoami(struct st_h3lis331dl_hw *hw,
int id)
{
int err, data;
err = regmap_read(hw->regmap, ST_H3LIS331DL_REG_WHO_AM_I_ADDR, &data);
if (err < 0) {
dev_err(hw->dev, "failed to read whoami register\n");
return err;
}
if (data != ST_H3LIS331DL_WHO_AM_I_VAL) {
dev_err(hw->dev, "unsupported whoami [%02x]\n", data);
return -ENODEV;
}
return 0;
}
static int st_h3lis331dl_set_full_scale(struct st_h3lis331dl_sensor *sensor,
u32 gain)
{
struct st_h3lis331dl_hw *hw = sensor->hw;
int i, err;
for (i = 0; i < st_h3lis331dl_fs_table.size; i++)
if (st_h3lis331dl_fs_table.fs_avl[i].gain >= gain)
break;
if (i == st_h3lis331dl_fs_table.size)
return -EINVAL;
err = regmap_update_bits(hw->regmap,
st_h3lis331dl_fs_table.reg.addr,
st_h3lis331dl_fs_table.reg.mask,
ST_H3LIS331DL_SHIFT_VAL(st_h3lis331dl_fs_table.fs_avl[i].val,
st_h3lis331dl_fs_table.reg.mask));
if (err < 0)
return err;
sensor->gain = st_h3lis331dl_fs_table.fs_avl[i].gain;
return 0;
}
int st_h3lis331dl_get_odr_val(int odr, u8 *val)
{
int i;
for (i = 0; i < st_h3lis331dl_odr_table.size; i++) {
if (st_h3lis331dl_odr_table.odr_avl[i].hz >= odr)
break;
}
if (i == st_h3lis331dl_odr_table.size)
return -EINVAL;
*val = st_h3lis331dl_odr_table.odr_avl[i].val;
return st_h3lis331dl_odr_table.odr_avl[i].hz;
}
static int st_h3lis331dl_set_odr(struct st_h3lis331dl_sensor *sensor, int odr)
{
struct st_h3lis331dl_hw *hw = sensor->hw;
u8 val = 0;
int ret;
ret = st_h3lis331dl_get_odr_val(odr, &val);
if (ret < 0)
return ret;
return regmap_update_bits(hw->regmap,
st_h3lis331dl_odr_table.reg.addr,
st_h3lis331dl_odr_table.reg.mask,
ST_H3LIS331DL_SHIFT_VAL(val,
st_h3lis331dl_odr_table.reg.mask));
}
int st_h3lis331dl_sensor_set_enable(struct st_h3lis331dl_sensor *sensor,
bool enable)
{
int odr = enable ? sensor->odr : 0;
int err;
err = st_h3lis331dl_set_odr(sensor, odr);
if (err < 0)
return err;
if (enable)
sensor->hw->enable_mask = BIT_ULL(sensor->id);
else
sensor->hw->enable_mask &= ~BIT_ULL(sensor->id);
return 0;
}
static int st_h3lis331dl_read_oneshot(struct st_h3lis331dl_sensor *sensor,
u8 addr, int *val)
{
struct st_h3lis331dl_hw *hw = sensor->hw;
int err, delay;
__le16 data;
err = st_h3lis331dl_sensor_set_enable(sensor, true);
if (err < 0)
return err;
/* use 10 odrs delay for data valid */
delay = 10000000 / sensor->odr;
usleep_range(delay, 2 * delay);
err = regmap_bulk_read(hw->regmap, addr,
&data, sizeof(data));
if (err < 0)
return err;
err = st_h3lis331dl_sensor_set_enable(sensor, false);
*val = (s16)le16_to_cpu(data);
return IIO_VAL_INT;
}
static int st_h3lis331dl_read_raw(struct iio_dev *iio_dev,
struct iio_chan_spec const *ch,
int *val, int *val2, long mask)
{
struct st_h3lis331dl_sensor *sensor = iio_priv(iio_dev);
int ret;
switch (mask) {
case IIO_CHAN_INFO_RAW:
ret = iio_device_claim_direct_mode(iio_dev);
if (ret)
break;
ret = st_h3lis331dl_read_oneshot(sensor, ch->address, val);
iio_device_release_direct_mode(iio_dev);
break;
case IIO_CHAN_INFO_SAMP_FREQ:
*val = (int)sensor->odr;
ret = IIO_VAL_INT;
break;
case IIO_CHAN_INFO_SCALE:
switch (ch->type) {
case IIO_ACCEL:
*val = 0;
*val2 = sensor->gain;
ret = IIO_VAL_INT_PLUS_NANO;
break;
default:
return -EINVAL;
}
break;
default:
ret = -EINVAL;
break;
}
return ret;
}
static int st_h3lis331dl_write_raw(struct iio_dev *iio_dev,
struct iio_chan_spec const *chan,
int val, int val2, long mask)
{
struct st_h3lis331dl_sensor *sensor = iio_priv(iio_dev);
int err;
switch (mask) {
case IIO_CHAN_INFO_SCALE:
err = iio_device_claim_direct_mode(iio_dev);
if (err)
return err;
err = st_h3lis331dl_set_full_scale(sensor, val2);
iio_device_release_direct_mode(iio_dev);
break;
case IIO_CHAN_INFO_SAMP_FREQ: {
int todr;
u8 data;
todr = st_h3lis331dl_get_odr_val(val, &data);
if (todr < 0)
return todr;
sensor->odr = todr;
if (sensor->hw->enable_mask & BIT(sensor->id)) {
err = st_h3lis331dl_set_odr(sensor, sensor->odr);
if (err < 0)
return err;
}
break;
}
default:
err = -EINVAL;
break;
}
return err;
}
static ssize_t
st_h3lis331dl_sysfs_sampling_freq_avail(struct device *dev,
struct device_attribute *attr,
char *buf)
{
int i, len = 0;
for (i = 1; i < st_h3lis331dl_odr_table.size; i++) {
len += scnprintf(buf + len, PAGE_SIZE - len, "%d ",
st_h3lis331dl_odr_table.odr_avl[i].hz);
}
buf[len - 1] = '\n';
return len;
}
static ssize_t st_h3lis331dl_sysfs_scale_avail(struct device *dev,
struct device_attribute *attr,
char *buf)
{
int i, len = 0;
for (i = 0; i < st_h3lis331dl_fs_table.size; i++)
len += scnprintf(buf + len, PAGE_SIZE - len, "0.%09u ",
st_h3lis331dl_fs_table.fs_avl[i].gain);
buf[len - 1] = '\n';
return len;
}
static IIO_DEV_ATTR_SAMP_FREQ_AVAIL(st_h3lis331dl_sysfs_sampling_freq_avail);
static IIO_DEVICE_ATTR(in_accel_scale_available, 0444,
st_h3lis331dl_sysfs_scale_avail, NULL, 0);
static int st_h3lis331dl_write_raw_get_fmt(struct iio_dev *indio_dev,
struct iio_chan_spec const *chan,
long mask)
{
switch (mask) {
case IIO_CHAN_INFO_SCALE:
if (chan->type == IIO_ACCEL)
return IIO_VAL_INT_PLUS_NANO;
break;
case IIO_CHAN_INFO_SAMP_FREQ:
return IIO_VAL_INT_PLUS_MICRO;
default:
return -EINVAL;
}
return -EINVAL;
}
static struct attribute *st_h3lis331dl_acc_attributes[] = {
&iio_dev_attr_sampling_frequency_available.dev_attr.attr,
&iio_dev_attr_in_accel_scale_available.dev_attr.attr,
NULL,
};
static const struct attribute_group st_h3lis331dl_acc_attribute_group = {
.attrs = st_h3lis331dl_acc_attributes,
};
static const struct iio_info st_h3lis331dl_acc_info = {
.attrs = &st_h3lis331dl_acc_attribute_group,
.read_raw = st_h3lis331dl_read_raw,
.write_raw = st_h3lis331dl_write_raw,
.write_raw_get_fmt = &st_h3lis331dl_write_raw_get_fmt,
#ifdef CONFIG_DEBUG_FS
.debugfs_reg_access = &st_h3lis331dl_reg_access,
#endif /* CONFIG_DEBUG_FS */
};
static const unsigned long st_h3lis331dl_available_scan_masks[] = {
GENMASK(3, 0), 0x0
};
static int st_h3lis331dl_reset_device(struct st_h3lis331dl_hw *hw)
{
int err;
/* re-boot sensor */
err = regmap_update_bits(hw->regmap,
ST_H3LIS331DL_CTRL_REG2_ADDR,
ST_H3LIS331DL_BOOT_MASK,
FIELD_PREP(ST_H3LIS331DL_BOOT_MASK, 1));
if (err < 0)
return err;
usleep_range(5000, 5100);
return 0;
}
static int st_h3lis331dl_init_device(struct st_h3lis331dl_hw *hw)
{
/* enable Block Data Update */
return regmap_update_bits(hw->regmap, ST_H3LIS331DL_CTRL_REG4_ADDR,
ST_H3LIS331DL_BDU_MASK,
FIELD_PREP(ST_H3LIS331DL_BDU_MASK, 1));
}
static struct iio_dev *st_h3lis331dl_alloc_iiodev(struct st_h3lis331dl_hw *hw)
{
struct st_h3lis331dl_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;
sensor = iio_priv(iio_dev);
sensor->id = ST_H3LIS331DL_ACC_SENSOR_ID;
sensor->hw = hw;
sensor->decimator = 0;
sensor->dec_counter = 0;
iio_dev->channels = st_h3lis331dl_acc_channels;
iio_dev->num_channels = ARRAY_SIZE(st_h3lis331dl_acc_channels);
sprintf(sensor->name, "h3lis331dl_accel");
iio_dev->info = &st_h3lis331dl_acc_info;
iio_dev->available_scan_masks = st_h3lis331dl_available_scan_masks;
sensor->gain = st_h3lis331dl_fs_table.fs_avl[0].gain;
sensor->odr = st_h3lis331dl_odr_table.odr_avl[0].hz;
st_h3lis331dl_set_full_scale(sensor, sensor->gain);
iio_dev->name = sensor->name;
return iio_dev;
}
static void st_h3lis331dl_disable_regulator_action(void *_data)
{
struct st_h3lis331dl_hw *hw = _data;
regulator_disable(hw->vddio_supply);
regulator_disable(hw->vdd_supply);
}
static int st_h3lis331dl_power_enable(struct st_h3lis331dl_hw *hw)
{
int err;
hw->vdd_supply = devm_regulator_get(hw->dev, "vdd");
if (IS_ERR(hw->vdd_supply)) {
if (PTR_ERR(hw->vdd_supply) != -EPROBE_DEFER)
dev_err(hw->dev, "Failed to get vdd regulator %d\n",
(int)PTR_ERR(hw->vdd_supply));
return PTR_ERR(hw->vdd_supply);
}
hw->vddio_supply = devm_regulator_get(hw->dev, "vddio");
if (IS_ERR(hw->vddio_supply)) {
if (PTR_ERR(hw->vddio_supply) != -EPROBE_DEFER)
dev_err(hw->dev, "Failed to get vddio regulator %d\n",
(int)PTR_ERR(hw->vddio_supply));
return PTR_ERR(hw->vddio_supply);
}
err = regulator_enable(hw->vdd_supply);
if (err) {
dev_err(hw->dev, "Failed to enable vdd regulator: %d\n", err);
return err;
}
err = regulator_enable(hw->vddio_supply);
if (err) {
regulator_disable(hw->vdd_supply);
return err;
}
err = devm_add_action_or_reset(hw->dev,
st_h3lis331dl_disable_regulator_action,
hw);
if (err) {
dev_err(hw->dev,
"Failed to setup regulator cleanup action %d\n", err);
return err;
}
return 0;
}
int st_h3lis331dl_probe(struct device *dev, int irq, int hw_id,
struct regmap *regmap)
{
struct st_h3lis331dl_hw *hw;
int err;
hw = devm_kzalloc(dev, sizeof(*hw), GFP_KERNEL);
if (!hw)
return -ENOMEM;
dev_set_drvdata(dev, (void *)hw);
mutex_init(&hw->lock);
hw->regmap = regmap;
hw->dev = dev;
hw->irq = irq;
err = st_h3lis331dl_power_enable(hw);
if (err != 0)
return err;
err = st_h3lis331dl_check_whoami(hw, hw_id);
if (err < 0)
return err;
err = st_h3lis331dl_reset_device(hw);
if (err < 0)
return err;
err = st_h3lis331dl_init_device(hw);
if (err < 0)
return err;
#if KERNEL_VERSION(5, 15, 0) <= LINUX_VERSION_CODE
err = iio_read_mount_matrix(hw->dev, &hw->orientation);
#elif KERNEL_VERSION(5, 2, 0) <= LINUX_VERSION_CODE
err = iio_read_mount_matrix(hw->dev, "mount-matrix", &hw->orientation);
#else /* LINUX_VERSION_CODE */
err = of_iio_read_mount_matrix(hw->dev, "mount-matrix",
&hw->orientation);
#endif /* LINUX_VERSION_CODE */
if (err) {
dev_err(dev, "Failed to retrieve mounting matrix %d\n", err);
return err;
}
hw->iio_devs = st_h3lis331dl_alloc_iiodev(hw);
if (!hw->iio_devs)
return -ENOMEM;
err = st_h3lis331dl_allocate_triggered_buffer(hw);
if (err < 0)
return err;
if (hw->irq) {
err = st_h3lis331dl_trigger_setup(hw);
if (err < 0)
return err;
}
err = devm_iio_device_register(hw->dev, hw->iio_devs);
if (err)
return err;
if (device_may_wakeup(dev))
device_init_wakeup(dev, 1);
return 0;
}
EXPORT_SYMBOL(st_h3lis331dl_probe);
static int __maybe_unused st_h3lis331dl_suspend(struct device *dev)
{
struct st_h3lis331dl_hw *hw = dev_get_drvdata(dev);
struct st_h3lis331dl_sensor *sensor;
int err = 0;
sensor = iio_priv(hw->iio_devs);
if (!(hw->enable_mask & BIT_ULL(sensor->id)))
return 0;
err = st_h3lis331dl_set_odr(sensor, 0);
if (err < 0)
return err;
if (device_may_wakeup(dev))
enable_irq_wake(hw->irq);
return err < 0 ? err : 0;
}
static int __maybe_unused st_h3lis331dl_resume(struct device *dev)
{
struct st_h3lis331dl_hw *hw = dev_get_drvdata(dev);
struct st_h3lis331dl_sensor *sensor;
if (device_may_wakeup(dev))
disable_irq_wake(hw->irq);
sensor = iio_priv(hw->iio_devs);
if (!(hw->enable_mask & BIT_ULL(sensor->id)))
return 0;
return st_h3lis331dl_set_odr(sensor, sensor->odr);
}
const struct dev_pm_ops st_h3lis331dl_pm_ops = {
SET_SYSTEM_SLEEP_PM_OPS(st_h3lis331dl_suspend, st_h3lis331dl_resume)
};
EXPORT_SYMBOL(st_h3lis331dl_pm_ops);
MODULE_AUTHOR("MEMS Software Solutions Team");
MODULE_DESCRIPTION("STMicroelectronics st_h3lis331dl driver");
MODULE_LICENSE("GPL v2");

View File

@ -0,0 +1,73 @@
// SPDX-License-Identifier: GPL-2.0-only
/*
* STMicroelectronics st_h3lis331dl i2c driver
*
* MEMS Software Solutions Team
*
* Copyright 2023 STMicroelectronics Inc.
*/
#include <linux/kernel.h>
#include <linux/module.h>
#include <linux/i2c.h>
#include <linux/slab.h>
#include <linux/of.h>
#include "st_h3lis331dl.h"
static const struct regmap_config st_h3lis331dl_i2c_regmap_config = {
.reg_bits = 8,
.val_bits = 8,
};
static int st_h3lis331dl_i2c_probe(struct i2c_client *client,
const struct i2c_device_id *id)
{
int hw_id = id->driver_data;
struct regmap *regmap;
regmap = devm_regmap_init_i2c(client,
&st_h3lis331dl_i2c_regmap_config);
if (IS_ERR(regmap)) {
dev_err(&client->dev,
"Failed to register i2c regmap %d\n",
(int)PTR_ERR(regmap));
return PTR_ERR(regmap);
}
return st_h3lis331dl_probe(&client->dev, client->irq,
hw_id, regmap);
}
static const struct of_device_id st_h3lis331dl_i2c_of_match[] = {
{
.compatible = "st," ST_H3LIS331DL_DEV_NAME,
},
{
.compatible = "st," ST_LIS331DLH_DEV_NAME,
},
{},
};
MODULE_DEVICE_TABLE(of, st_h3lis331dl_i2c_of_match);
static const struct i2c_device_id st_h3lis331dl_i2c_id_table[] = {
{ ST_H3LIS331DL_DEV_NAME },
{ ST_LIS331DLH_DEV_NAME },
{},
};
MODULE_DEVICE_TABLE(i2c, st_h3lis331dl_i2c_id_table);
static struct i2c_driver st_h3lis331dl_driver = {
.driver = {
.name = "st_h3lis331dl_i2c",
.pm = &st_h3lis331dl_pm_ops,
.of_match_table = st_h3lis331dl_i2c_of_match,
},
.probe = st_h3lis331dl_i2c_probe,
.id_table = st_h3lis331dl_i2c_id_table,
};
module_i2c_driver(st_h3lis331dl_driver);
MODULE_AUTHOR("MEMS Software Solutions Team");
MODULE_DESCRIPTION("STMicroelectronics st_h3lis331dl i2c driver");
MODULE_LICENSE("GPL v2");

View File

@ -0,0 +1,72 @@
// SPDX-License-Identifier: GPL-2.0-only
/*
* STMicroelectronics st_h3lis331dl spi driver
*
* MEMS Software Solutions Team
*
* Copyright 2023 STMicroelectronics Inc.
*/
#include <linux/kernel.h>
#include <linux/module.h>
#include <linux/spi/spi.h>
#include <linux/slab.h>
#include <linux/of.h>
#include "st_h3lis331dl.h"
static const struct regmap_config st_h3lis331dl_spi_regmap_config = {
.reg_bits = 8,
.val_bits = 8,
};
static int st_h3lis331dl_spi_probe(struct spi_device *spi)
{
const struct spi_device_id *id = spi_get_device_id(spi);
int hw_id = id->driver_data;
struct regmap *regmap;
regmap = devm_regmap_init_spi(spi,
&st_h3lis331dl_spi_regmap_config);
if (IS_ERR(regmap)) {
dev_err(&spi->dev, "Failed to register spi regmap %d\n",
(int)PTR_ERR(regmap));
return PTR_ERR(regmap);
}
return st_h3lis331dl_probe(&spi->dev, spi->irq, hw_id, regmap);
}
static const struct of_device_id st_h3lis331dl_spi_of_match[] = {
{
.compatible = "st," ST_H3LIS331DL_DEV_NAME,
},
{
.compatible = "st," ST_LIS331DLH_DEV_NAME,
},
{},
};
MODULE_DEVICE_TABLE(of, st_h3lis331dl_spi_of_match);
static const struct spi_device_id st_h3lis331dl_spi_id_table[] = {
{ ST_H3LIS331DL_DEV_NAME },
{ ST_LIS331DLH_DEV_NAME },
{},
};
MODULE_DEVICE_TABLE(spi, st_h3lis331dl_spi_id_table);
static struct spi_driver st_h3lis331dl_driver = {
.driver = {
.name = "st_h3lis331dl_spi",
.pm = &st_h3lis331dl_pm_ops,
.of_match_table = st_h3lis331dl_spi_of_match,
},
.probe = st_h3lis331dl_spi_probe,
.id_table = st_h3lis331dl_spi_id_table,
};
module_spi_driver(st_h3lis331dl_driver);
MODULE_AUTHOR("MEMS Software Solutions Team");
MODULE_DESCRIPTION("STMicroelectronics st_h3lis331dl spi driver");
MODULE_LICENSE("GPL v2");

View File

@ -0,0 +1,3 @@
CONFIG_IIO_ST_H3LIS331DL=m
CONFIG_IIO_ST_H3LIS331DL_I2C=m
CONFIG_IIO_ST_H3LIS331DL_SPI=m