drivers: sensor: adxl345: Updated ADXL345 drv RTIO stream & Trigger func

Updated ADXL345 driver with RTIO stream functionality.
Added Trigger intterupt functionality. RTIO stream is using
FIFO threshold.Together with RTIO stream, RTIO async read
is also implemented.

Signed-off-by: Dimitrije Lilic <dimitrije.lilic@orioninc.com>
This commit is contained in:
Dimitrije Lilic 2024-10-17 16:23:53 +02:00 committed by Anas Nashif
parent 35401fd7a9
commit 86ed9811c4
10 changed files with 1385 additions and 15 deletions

View file

@ -6,3 +6,6 @@
zephyr_library()
zephyr_library_sources(adxl345.c)
zephyr_library_sources_ifdef(CONFIG_ADXL345_TRIGGER adxl345_trigger.c)
zephyr_library_sources_ifdef(CONFIG_SENSOR_ASYNC_API adxl345_rtio.c adxl345_decoder.c)
zephyr_library_sources_ifdef(CONFIG_ADXL345_STREAM adxl345_stream.c adxl345_decoder.c)

View file

@ -9,5 +9,53 @@ config ADXL345
depends on DT_HAS_ADI_ADXL345_ENABLED
select I2C if $(dt_compat_on_bus,$(DT_COMPAT_ADI_ADXL345),i2c)
select SPI if $(dt_compat_on_bus,$(DT_COMPAT_ADI_ADXL345),spi)
select RTIO_WORKQ if SENSOR_ASYNC_API
help
Enable driver for ADXL345 Three-Axis Digital Accelerometer.
choice ADXL345_TRIGGER_MODE
prompt "Trigger mode"
default ADXL345_TRIGGER_NONE
help
Specify the type of triggering used by the driver.
config ADXL345_TRIGGER_NONE
bool "No trigger"
config ADXL345_TRIGGER_GLOBAL_THREAD
bool "Use global thread"
depends on GPIO
select ADXL345_TRIGGER
config ADXL345_TRIGGER_OWN_THREAD
bool "Use own thread"
depends on GPIO
select ADXL345_TRIGGER
endchoice
config ADXL345_STREAM
bool "Use FIFO to stream data"
select ADXL345_TRIGGER
default y
depends on SPI_RTIO
depends on SENSOR_ASYNC_API
help
Use this configuration option to enable streaming sensor data via RTIO.
config ADXL345_TRIGGER
bool
config ADXL345_THREAD_PRIORITY
int "Thread priority"
depends on ADXL345_TRIGGER_OWN_THREAD && ADXL345_TRIGGER
default 10
help
Priority of thread used by the driver to handle interrupts.
config ADXL345_THREAD_STACK_SIZE
int "Thread stack size"
depends on ADXL345_TRIGGER_OWN_THREAD && ADXL345_TRIGGER
default 1024
help
Stack size of thread used by the driver to handle interrupts.

View file

@ -42,7 +42,7 @@ static bool adxl345_bus_is_ready_spi(const union adxl345_bus *bus)
return spi_is_ready_dt(&bus->spi);
}
static int adxl345_reg_access_spi(const struct device *dev, uint8_t cmd, uint8_t reg_addr,
int adxl345_reg_access_spi(const struct device *dev, uint8_t cmd, uint8_t reg_addr,
uint8_t *data, size_t length)
{
const struct adxl345_dev_config *cfg = dev->config;
@ -53,17 +53,20 @@ static int adxl345_reg_access_spi(const struct device *dev, uint8_t cmd, uint8_t
.buffers = buf,
.count = 2,
};
int ret;
if (cmd == ADXL345_READ_CMD) {
tx.count = 1;
return spi_transceive_dt(&cfg->bus.spi, &tx, &rx);
ret = spi_transceive_dt(&cfg->bus.spi, &tx, &rx);
return ret;
} else {
return spi_write_dt(&cfg->bus.spi, &tx);
ret = spi_write_dt(&cfg->bus.spi, &tx);
return ret;
}
}
#endif /* DT_ANY_INST_ON_BUS_STATUS_OKAY(spi) */
static inline int adxl345_reg_access(const struct device *dev, uint8_t cmd, uint8_t addr,
int adxl345_reg_access(const struct device *dev, uint8_t cmd, uint8_t addr,
uint8_t *data, size_t len)
{
const struct adxl345_dev_config *cfg = dev->config;
@ -71,31 +74,50 @@ static inline int adxl345_reg_access(const struct device *dev, uint8_t cmd, uint
return cfg->reg_access(dev, cmd, addr, data, len);
}
static inline int adxl345_reg_write(const struct device *dev, uint8_t addr, uint8_t *data,
int adxl345_reg_write(const struct device *dev, uint8_t addr, uint8_t *data,
uint8_t len)
{
return adxl345_reg_access(dev, ADXL345_WRITE_CMD, addr, data, len);
}
static inline int adxl345_reg_read(const struct device *dev, uint8_t addr, uint8_t *data,
int adxl345_reg_read(const struct device *dev, uint8_t addr, uint8_t *data,
uint8_t len)
{
return adxl345_reg_access(dev, ADXL345_READ_CMD, addr, data, len);
}
static inline int adxl345_reg_write_byte(const struct device *dev, uint8_t addr, uint8_t val)
int adxl345_reg_write_byte(const struct device *dev, uint8_t addr, uint8_t val)
{
return adxl345_reg_write(dev, addr, &val, 1);
}
static inline int adxl345_reg_read_byte(const struct device *dev, uint8_t addr, uint8_t *buf)
int adxl345_reg_read_byte(const struct device *dev, uint8_t addr, uint8_t *buf)
{
return adxl345_reg_read(dev, addr, buf, 1);
}
int adxl345_reg_write_mask(const struct device *dev,
uint8_t reg_addr,
uint8_t mask,
uint8_t data)
{
int ret;
uint8_t tmp;
ret = adxl345_reg_read_byte(dev, reg_addr, &tmp);
if (ret) {
return ret;
}
tmp &= ~mask;
tmp |= data;
return adxl345_reg_write_byte(dev, reg_addr, tmp);
}
static inline bool adxl345_bus_is_ready(const struct device *dev)
{
const struct adxl345_dev_config *cfg = dev->config;
@ -103,11 +125,168 @@ static inline bool adxl345_bus_is_ready(const struct device *dev)
return cfg->bus_is_ready(&cfg->bus);
}
static int adxl345_read_sample(const struct device *dev,
int adxl345_get_status(const struct device *dev,
uint8_t *status1,
uint16_t *fifo_entries)
{
uint8_t buf[2], length = 1U;
int ret;
ret = adxl345_reg_read(dev, ADXL345_INT_SOURCE, buf, length);
*status1 = buf[0];
ret = adxl345_reg_read(dev, ADXL345_FIFO_STATUS_REG, buf+1, length);
if (fifo_entries) {
*fifo_entries = buf[1] & 0x3F;
}
return ret;
}
/**
* Configure the operating parameters for the FIFO.
* @param dev - The device structure.
* @param mode - FIFO Mode. Specifies FIFO operating mode.
* Accepted values: ADXL345_FIFO_BYPASSED
* ADXL345_FIFO_STREAMED
* ADXL345_FIFO_TRIGGERED
* ADXL345_FIFO_OLD_SAVED
* @param trigger - FIFO trigger. Links trigger event to appropriate INT.
* Accepted values: ADXL345_INT1
* ADXL345_INT2
* @param fifo_samples - FIFO Samples. Watermark number of FIFO samples that
* triggers a FIFO_FULL condition when reached.
* Values range from 0 to 32.
* @return 0 in case of success, negative error code otherwise.
*/
int adxl345_configure_fifo(const struct device *dev,
enum adxl345_fifo_mode mode,
enum adxl345_fifo_trigger trigger,
uint16_t fifo_samples)
{
struct adxl345_dev_data *data = dev->data;
uint8_t fifo_config;
int ret;
if (fifo_samples > 32) {
return -EINVAL;
}
fifo_config = (ADXL345_FIFO_CTL_TRIGGER_MODE(trigger) |
ADXL345_FIFO_CTL_MODE_MODE(mode) |
ADXL345_FIFO_CTL_SAMPLES_MODE(fifo_samples));
ret = adxl345_reg_write_byte(dev, ADXL345_FIFO_CTL_REG, fifo_config);
if (ret) {
return ret;
}
data->fifo_config.fifo_trigger = trigger;
data->fifo_config.fifo_mode = mode;
data->fifo_config.fifo_samples = fifo_samples;
return 0;
}
/**
* Set the mode of operation.
* @param dev - The device structure.
* @param op_mode - Mode of operation.
* Accepted values: ADXL345_STANDBY
* ADXL345_MEASURE
* @return 0 in case of success, negative error code otherwise.
*/
int adxl345_set_op_mode(const struct device *dev, enum adxl345_op_mode op_mode)
{
return adxl345_reg_write_mask(dev, ADXL345_POWER_CTL_REG,
ADXL345_POWER_CTL_MEASURE_MSK,
ADXL345_POWER_CTL_MEASURE_MODE(op_mode));
}
/**
* Set Output data rate.
* @param dev - The device structure.
* @param odr - Output data rate.
* Accepted values: ADXL345_ODR_12HZ
* ADXL345_ODR_25HZ
* ADXL345_ODR_50HZ
* ADXL345_ODR_100HZ
* ADXL345_ODR_200HZ
* ADXL345_ODR_400HZ
* @return 0 in case of success, negative error code otherwise.
*/
static int adxl345_set_odr(const struct device *dev, enum adxl345_odr odr)
{
return adxl345_reg_write_mask(dev, ADXL345_RATE_REG,
ADXL345_ODR_MSK,
ADXL345_ODR_MODE(odr));
}
static int adxl345_attr_set_odr(const struct device *dev,
enum sensor_channel chan,
enum sensor_attribute attr,
const struct sensor_value *val)
{
enum adxl345_odr odr;
struct adxl345_dev_config *cfg = (struct adxl345_dev_config *)dev->config;
switch (val->val1) {
case 12:
odr = ADXL345_ODR_12HZ;
break;
case 25:
odr = ADXL345_ODR_25HZ;
break;
case 50:
odr = ADXL345_ODR_50HZ;
break;
case 100:
odr = ADXL345_ODR_100HZ;
break;
case 200:
odr = ADXL345_ODR_200HZ;
break;
case 400:
odr = ADXL345_ODR_400HZ;
break;
default:
return -EINVAL;
}
int ret = adxl345_set_odr(dev, odr);
if (ret == 0) {
cfg->odr = odr;
}
return ret;
}
static int adxl345_attr_set(const struct device *dev,
enum sensor_channel chan,
enum sensor_attribute attr,
const struct sensor_value *val)
{
switch (attr) {
case SENSOR_ATTR_SAMPLING_FREQUENCY:
return adxl345_attr_set_odr(dev, chan, attr, val);
default:
return -ENOTSUP;
}
}
int adxl345_read_sample(const struct device *dev,
struct adxl345_sample *sample)
{
int16_t raw_x, raw_y, raw_z;
uint8_t axis_data[6];
uint8_t axis_data[6], status1;
if (!IS_ENABLED(CONFIG_ADXL345_TRIGGER)) {
do {
adxl345_get_status(dev, &status1, NULL);
} while (!(ADXL345_STATUS_DATA_RDY(status1)));
}
int rc = adxl345_reg_read(dev, ADXL345_X_AXIS_DATA_0_REG, axis_data, 6);
@ -127,7 +306,7 @@ static int adxl345_read_sample(const struct device *dev,
return 0;
}
static void adxl345_accel_convert(struct sensor_value *val, int16_t sample)
void adxl345_accel_convert(struct sensor_value *val, int16_t sample)
{
if (sample & BIT(9)) {
sample |= ADXL345_COMPLEMENT;
@ -205,14 +384,60 @@ static int adxl345_channel_get(const struct device *dev,
}
static const struct sensor_driver_api adxl345_api_funcs = {
.attr_set = adxl345_attr_set,
.sample_fetch = adxl345_sample_fetch,
.channel_get = adxl345_channel_get,
#ifdef CONFIG_ADXL345_TRIGGER
.trigger_set = adxl345_trigger_set,
#endif
#ifdef CONFIG_SENSOR_ASYNC_API
.submit = adxl345_submit,
.get_decoder = adxl345_get_decoder,
#endif
};
#ifdef CONFIG_ADXL345_TRIGGER
/**
* Configure the INT1 and INT2 interrupt pins.
* @param dev - The device structure.
* @param int1 - INT1 interrupt pins.
* @return 0 in case of success, negative error code otherwise.
*/
static int adxl345_interrupt_config(const struct device *dev,
uint8_t int1)
{
int ret;
const struct adxl345_dev_config *cfg = dev->config;
ret = adxl345_reg_write_byte(dev, ADXL345_INT_MAP, int1);
if (ret) {
return ret;
}
ret = adxl345_reg_write_byte(dev, ADXL345_INT_ENABLE, int1);
if (ret) {
return ret;
}
uint8_t samples;
ret = adxl345_reg_read_byte(dev, ADXL345_INT_MAP, &samples);
ret = adxl345_reg_read_byte(dev, ADXL345_INT_ENABLE, &samples);
#ifdef CONFIG_ADXL345_TRIGGER
gpio_pin_interrupt_configure_dt(&cfg->interrupt,
GPIO_INT_EDGE_TO_ACTIVE);
#endif
return 0;
}
#endif
static int adxl345_init(const struct device *dev)
{
int rc;
struct adxl345_dev_data *data = dev->data;
#ifdef CONFIG_ADXL345_TRIGGER
const struct adxl345_dev_config *cfg = dev->config;
#endif
uint8_t dev_id;
data->sample_number = 0;
@ -246,15 +471,61 @@ static int adxl345_init(const struct device *dev)
return -EIO;
}
#ifdef CONFIG_ADXL345_TRIGGER
rc = adxl345_configure_fifo(dev, ADXL345_FIFO_STREAMED,
ADXL345_INT2,
SAMPLE_NUM);
if (rc) {
return rc;
}
#endif
rc = adxl345_reg_write_byte(dev, ADXL345_POWER_CTL_REG, ADXL345_ENABLE_MEASURE_BIT);
if (rc < 0) {
LOG_ERR("Enable measure bit failed\n");
return -EIO;
}
#ifdef CONFIG_ADXL345_TRIGGER
rc = adxl345_init_interrupt(dev);
if (rc < 0) {
LOG_ERR("Failed to initialize interrupt!");
return -EIO;
}
rc = adxl345_set_odr(dev, cfg->odr);
if (rc) {
return rc;
}
rc = adxl345_interrupt_config(dev, ADXL345_INT_MAP_WATERMARK_MSK);
if (rc) {
return rc;
}
#endif
return 0;
}
#ifdef CONFIG_ADXL345_TRIGGER
#define ADXL345_CFG_IRQ(inst) \
.interrupt = GPIO_DT_SPEC_INST_GET(inst, int2_gpios),
#else
#define ADXL345_CFG_IRQ(inst)
#endif /* CONFIG_ADXL345_TRIGGER */
#define ADXL345_RTIO_DEFINE(inst) \
SPI_DT_IODEV_DEFINE(adxl345_iodev_##inst, DT_DRV_INST(inst), \
SPI_WORD_SET(8) | SPI_TRANSFER_MSB | \
SPI_MODE_CPOL | SPI_MODE_CPHA, 0U); \
RTIO_DEFINE(adxl345_rtio_ctx_##inst, 64, 64);
#define ADXL345_CONFIG(inst) \
.odr = DT_INST_PROP(inst, odr), \
.fifo_config.fifo_mode = ADXL345_FIFO_STREAMED, \
.fifo_config.fifo_trigger = ADXL345_INT2, \
.fifo_config.fifo_samples = SAMPLE_NUM, \
.op_mode = TRUE, \
.odr = ADXL345_RATE_25HZ, \
#define ADXL345_CONFIG_SPI(inst) \
{ \
.bus = {.spi = SPI_DT_SPEC_INST_GET(inst, \
@ -265,6 +536,9 @@ static int adxl345_init(const struct device *dev)
0)}, \
.bus_is_ready = adxl345_bus_is_ready_spi, \
.reg_access = adxl345_reg_access_spi, \
ADXL345_CONFIG(inst) \
COND_CODE_1(DT_INST_NODE_HAS_PROP(inst, int2_gpios), \
(ADXL345_CFG_IRQ(inst)), ()) \
}
#define ADXL345_CONFIG_I2C(inst) \
@ -275,8 +549,11 @@ static int adxl345_init(const struct device *dev)
}
#define ADXL345_DEFINE(inst) \
static struct adxl345_dev_data adxl345_data_##inst; \
\
IF_ENABLED(CONFIG_ADXL345_STREAM, (ADXL345_RTIO_DEFINE(inst))); \
static struct adxl345_dev_data adxl345_data_##inst = { \
IF_ENABLED(CONFIG_ADXL345_STREAM, (.rtio_ctx = &adxl345_rtio_ctx_##inst, \
.iodev = &adxl345_iodev_##inst,)) \
}; \
static const struct adxl345_dev_config adxl345_config_##inst = \
COND_CODE_1(DT_INST_ON_BUS(inst, spi), (ADXL345_CONFIG_SPI(inst)), \
(ADXL345_CONFIG_I2C(inst))); \

View file

@ -7,9 +7,19 @@
#ifndef ZEPHYR_DRIVERS_SENSOR_ADX345_ADX345_H_
#define ZEPHYR_DRIVERS_SENSOR_ADX345_ADX345_H_
#include <zephyr/drivers/sensor.h>
#include <zephyr/types.h>
#include <zephyr/device.h>
#include <zephyr/drivers/gpio.h>
#include <zephyr/kernel.h>
#include <zephyr/sys/util.h>
#ifdef CONFIG_ADXL345_STREAM
#include <zephyr/rtio/rtio.h>
#endif /* CONFIG_ADXL345_STREAM */
#define DT_DRV_COMPAT adi_adxl345
#if DT_ANY_INST_ON_BUS_STATUS_OKAY(i2c)
#include <zephyr/drivers/i2c.h>
#endif
@ -23,6 +33,12 @@
#define ADXL345_READ_CMD 0x80
#define ADXL345_MULTIBYTE_FLAG 0x40
#define ADXL345_REG_READ(x) ((x & 0xFF) | ADXL345_READ_CMD)
#define SAMPLE_SIZE 6
#define SAMPLE_MASK 0x3F
#define SAMPLE_NUM 0x1F
/* Registers */
#define ADXL345_DEVICE_ID_REG 0x00
#define ADXL345_RATE_REG 0x2c
@ -46,15 +62,138 @@
#define ADXL345_MAX_FIFO_SIZE 32
#define ADXL345_INT_ENABLE 0x2Eu
#define ADXL345_INT_MAP 0x2Fu
#define ADXL345_INT_SOURCE 0x30u
/* ADXL345_STATUS_1 */
#define ADXL345_STATUS_DOUBLE_TAP(x) (((x) >> 5) & 0x1)
#define ADXL345_STATUS_SINGLE_TAP(x) (((x) >> 6) & 0x1)
#define ADXL345_STATUS_DATA_RDY(x) (((x) >> 7) & 0x1)
/* ADXL345_INT_MAP */
#define ADXL345_INT_MAP_OVERRUN_MSK BIT(0)
#define ADXL345_INT_MAP_OVERRUN_MODE(x) (((x) & 0x1) << 0)
#define ADXL345_INT_MAP_WATERMARK_MSK BIT(1)
#define ADXL345_INT_MAP_WATERMARK_MODE(x) (((x) & 0x1) << 1)
#define ADXL345_INT_MAP_FREE_FALL_MSK BIT(2)
#define ADXL345_INT_MAP_FREE_FALL_MODE(x) (((x) & 0x1) << 2)
#define ADXL345_INT_MAP_INACT_MSK BIT(3)
#define ADXL345_INT_MAP_INACT_MODE(x) (((x) & 0x1) << 3)
#define ADXL345_INT_MAP_ACT_MSK BIT(4)
#define ADXL345_INT_MAP_ACT_MODE(x) (((x) & 0x1) << 4)
#define ADXL345_INT_MAP_DOUBLE_TAP_MSK BIT(5)
#define ADXL345_INT_MAP_DOUBLE_TAP_MODE(x) (((x) & 0x1) << 5)
#define ADXL345_INT_MAP_SINGLE_TAP_MSK BIT(6)
#define ADXL345_INT_MAP_SINGLE_TAP_MODE(x) (((x) & 0x1) << 6)
#define ADXL345_INT_MAP_DATA_RDY_MSK BIT(7)
#define ADXL345_INT_MAP_DATA_RDY_MODE(x) (((x) & 0x1) << 7)
/* POWER_CTL */
#define ADXL345_POWER_CTL_WAKEUP_4HZ BIT(0)
#define ADXL345_POWER_CTL_WAKEUP_4HZ_MODE(x) (((x) & 0x1) << 0)
#define ADXL345_POWER_CTL_WAKEUP_2HZ BIT(1)
#define ADXL345_POWER_CTL_WAKEUP_2HZ_MODE(x) (((x) & 0x1) << 1)
#define ADXL345_POWER_CTL_SLEEP BIT(2)
#define ADXL345_POWER_CTL_SLEEP_MODE(x) (((x) & 0x1) << 2)
#define ADXL345_POWER_CTL_MEASURE_MSK GENMASK(3, 3)
#define ADXL345_POWER_CTL_MEASURE_MODE(x) (((x) & 0x1) << 3)
#define ADXL345_POWER_CTL_STANDBY_MODE(x) (((x) & 0x0) << 3)
/* ADXL345_FIFO_CTL */
#define ADXL345_FIFO_CTL_MODE_MSK GENMASK(7, 6)
#define ADXL345_FIFO_CTL_MODE_MODE(x) (((x) & 0x3) << 6)
#define ADXL345_FIFO_CTL_TRIGGER_MSK BIT(5)
#define ADXL345_FIFO_CTL_TRIGGER_MODE(x) (((x) & 0x1) << 5)
#define ADXL345_FIFO_CTL_SAMPLES_MSK BIT(0)
#define ADXL345_FIFO_CTL_SAMPLES_MODE(x) ((x) & 0x1F)
#define ADXL345_ODR_MSK GENMASK(3, 0)
#define ADXL345_ODR_MODE(x) ((x) & 0xF)
enum adxl345_odr {
ADXL345_ODR_12HZ = 0x7,
ADXL345_ODR_25HZ,
ADXL345_ODR_50HZ,
ADXL345_ODR_100HZ,
ADXL345_ODR_200HZ,
ADXL345_ODR_400HZ
};
enum adxl345_fifo_trigger {
ADXL345_INT1,
ADXL345_INT2
};
enum adxl345_fifo_mode {
ADXL345_FIFO_BYPASSED,
ADXL345_FIFO_OLD_SAVED,
ADXL345_FIFO_STREAMED,
ADXL345_FIFO_TRIGGERED
};
struct adxl345_fifo_config {
enum adxl345_fifo_mode fifo_mode;
enum adxl345_fifo_trigger fifo_trigger;
uint16_t fifo_samples;
};
enum adxl345_op_mode {
ADXL345_STANDBY,
ADXL345_MEASURE
};
struct adxl345_dev_data {
unsigned int sample_number;
int16_t bufx[ADXL345_MAX_FIFO_SIZE];
int16_t bufy[ADXL345_MAX_FIFO_SIZE];
int16_t bufz[ADXL345_MAX_FIFO_SIZE];
struct adxl345_fifo_config fifo_config;
#ifdef CONFIG_ADXL345_TRIGGER
struct gpio_callback gpio_cb;
sensor_trigger_handler_t th_handler;
const struct sensor_trigger *th_trigger;
sensor_trigger_handler_t drdy_handler;
const struct sensor_trigger *drdy_trigger;
const struct device *dev;
#if defined(CONFIG_ADXL345_TRIGGER_OWN_THREAD)
K_KERNEL_STACK_MEMBER(thread_stack, CONFIG_ADXL345_THREAD_STACK_SIZE);
struct k_sem gpio_sem;
struct k_thread thread;
#elif defined(CONFIG_ADXL345_TRIGGER_GLOBAL_THREAD)
struct k_work work;
#endif
#endif /* CONFIG_ADXL345_TRIGGER */
#ifdef CONFIG_ADXL345_STREAM
struct rtio_iodev_sqe *sqe;
struct rtio *rtio_ctx;
struct rtio_iodev *iodev;
uint8_t status1;
uint8_t fifo_ent[1];
uint64_t timestamp;
struct rtio *r_cb;
uint8_t fifo_watermark_irq;
uint8_t fifo_samples;
uint16_t fifo_total_bytes;
#endif /* CONFIG_ADXL345_STREAM */
};
struct adxl345_fifo_data {
uint8_t is_fifo: 1;
uint8_t sample_set_size: 4;
uint8_t int_status;
uint16_t accel_odr: 4;
uint16_t fifo_byte_count: 12;
uint64_t timestamp;
} __attribute__((__packed__));
struct adxl345_sample {
#ifdef CONFIG_ADXL345_STREAM
uint8_t is_fifo: 1;
uint8_t res: 7;
#endif /* CONFIG_ADXL345_STREAM */
int16_t x;
int16_t y;
int16_t z;
@ -77,6 +216,58 @@ struct adxl345_dev_config {
const union adxl345_bus bus;
adxl345_bus_is_ready_fn bus_is_ready;
adxl345_reg_access_fn reg_access;
enum adxl345_odr odr;
bool op_mode;
struct adxl345_fifo_config fifo_config;
#ifdef CONFIG_ADXL345_TRIGGER
struct gpio_dt_spec interrupt;
#endif
};
void adxl345_submit_stream(const struct device *dev, struct rtio_iodev_sqe *iodev_sqe);
void adxl345_stream_irq_handler(const struct device *dev);
#ifdef CONFIG_ADXL345_TRIGGER
int adxl345_get_status(const struct device *dev,
uint8_t *status, uint16_t *fifo_entries);
int adxl345_trigger_set(const struct device *dev,
const struct sensor_trigger *trig,
sensor_trigger_handler_t handler);
int adxl345_init_interrupt(const struct device *dev);
#endif /* CONFIG_ADXL345_TRIGGER */
int adxl345_reg_write_mask(const struct device *dev,
uint8_t reg_addr,
uint8_t mask,
uint8_t data);
int adxl345_reg_access(const struct device *dev, uint8_t cmd, uint8_t addr,
uint8_t *data, size_t len);
int adxl345_reg_write(const struct device *dev, uint8_t addr, uint8_t *data,
uint8_t len);
int adxl345_reg_read(const struct device *dev, uint8_t addr, uint8_t *data,
uint8_t len);
int adxl345_reg_write_byte(const struct device *dev, uint8_t addr, uint8_t val);
int adxl345_reg_read_byte(const struct device *dev, uint8_t addr, uint8_t *buf);
int adxl345_set_op_mode(const struct device *dev, enum adxl345_op_mode op_mode);
#ifdef CONFIG_SENSOR_ASYNC_API
int adxl345_read_sample(const struct device *dev, struct adxl345_sample *sample);
void adxl345_submit(const struct device *dev, struct rtio_iodev_sqe *iodev_sqe);
int adxl345_get_decoder(const struct device *dev, const struct sensor_decoder_api **decoder);
void adxl345_accel_convert(struct sensor_value *val, int16_t sample);
#endif /* CONFIG_SENSOR_ASYNC_API */
#ifdef CONFIG_ADXL345_STREAM
int adxl345_configure_fifo(const struct device *dev, enum adxl345_fifo_mode mode,
enum adxl345_fifo_trigger trigger, uint16_t fifo_samples);
size_t adxl345_get_packet_size(const struct adxl345_dev_config *cfg);
#endif /* CONFIG_ADXL345_STREAM */
#endif /* ZEPHYR_DRIVERS_SENSOR_ADX345_ADX345_H_ */

View file

@ -0,0 +1,212 @@
/*
* Copyright (c) 2024 Analog Devices Inc.
*
* SPDX-License-Identifier: Apache-2.0
*/
#include "adxl345.h"
#ifdef CONFIG_ADXL345_STREAM
#define SENSOR_SCALING_FACTOR (SENSOR_G / (16 * 1000 / 100))
static const uint32_t accel_period_ns[] = {
[ADXL345_ODR_12HZ] = UINT32_C(1000000000) / 12,
[ADXL345_ODR_25HZ] = UINT32_C(1000000000) / 25,
[ADXL345_ODR_50HZ] = UINT32_C(1000000000) / 50,
[ADXL345_ODR_100HZ] = UINT32_C(1000000000) / 100,
[ADXL345_ODR_200HZ] = UINT32_C(1000000000) / 200,
[ADXL345_ODR_400HZ] = UINT32_C(1000000000) / 400,
};
static inline void adxl345_accel_convert_q31(q31_t *out, uint16_t sample)
{
if (sample & BIT(9)) {
sample |= ADXL345_COMPLEMENT;
}
int32_t micro_ms2 = ((sample * SENSOR_G) / 32);
*out = CLAMP((((int64_t)micro_ms2) + (micro_ms2 % 1000000)), INT32_MIN, INT32_MAX);
}
static int adxl345_decode_stream(const uint8_t *buffer, struct sensor_chan_spec chan_spec,
uint32_t *fit, uint16_t max_count, void *data_out)
{
const struct adxl345_fifo_data *enc_data = (const struct adxl345_fifo_data *)buffer;
const uint8_t *buffer_end =
buffer + sizeof(struct adxl345_fifo_data) + enc_data->fifo_byte_count;
int count = 0;
uint8_t sample_num = 0;
if ((uintptr_t)buffer_end <= *fit || chan_spec.chan_idx != 0) {
return 0;
}
struct sensor_three_axis_data *data = (struct sensor_three_axis_data *)data_out;
memset(data, 0, sizeof(struct sensor_three_axis_data));
data->header.base_timestamp_ns = enc_data->timestamp;
data->header.reading_count = 1;
buffer += sizeof(struct adxl345_fifo_data);
uint8_t sample_set_size = enc_data->sample_set_size;
uint64_t period_ns = accel_period_ns[enc_data->accel_odr];
/* Calculate which sample is decoded. */
if ((uint8_t *)*fit >= buffer) {
sample_num = ((uint8_t *)*fit - buffer) / sample_set_size;
}
while (count < max_count && buffer < buffer_end) {
const uint8_t *sample_end = buffer;
sample_end += sample_set_size;
if ((uintptr_t)buffer < *fit) {
/* This frame was already decoded, move on to the next frame */
buffer = sample_end;
continue;
}
switch (chan_spec.chan_type) {
case SENSOR_CHAN_ACCEL_XYZ:
data->readings[count].timestamp_delta = sample_num * period_ns;
uint8_t buff_offset = 0;
adxl345_accel_convert_q31(&data->readings[count].x, *(int16_t *)buffer);
buff_offset = 2;
adxl345_accel_convert_q31(&data->readings[count].y,
*(int16_t *)(buffer + buff_offset));
buff_offset += 2;
adxl345_accel_convert_q31(&data->readings[count].z,
*(int16_t *)(buffer + buff_offset));
break;
default:
return -ENOTSUP;
}
buffer = sample_end;
*fit = (uintptr_t)sample_end;
count++;
}
return count;
}
#endif /* CONFIG_ADXL345_STREAM */
static int adxl345_decoder_get_frame_count(const uint8_t *buffer, struct sensor_chan_spec chan_spec,
uint16_t *frame_count)
{
int32_t ret = -ENOTSUP;
if (chan_spec.chan_idx != 0) {
return ret;
}
#ifdef CONFIG_ADXL345_STREAM
const struct adxl345_fifo_data *data = (const struct adxl345_fifo_data *)buffer;
if (!data->is_fifo) {
#endif /* CONFIG_ADXL345_STREAM */
switch (chan_spec.chan_type) {
case SENSOR_CHAN_ACCEL_X:
case SENSOR_CHAN_ACCEL_Y:
case SENSOR_CHAN_ACCEL_Z:
case SENSOR_CHAN_ACCEL_XYZ:
*frame_count = 1;
ret = 0;
break;
default:
break;
}
#ifdef CONFIG_ADXL345_STREAM
} else {
if (data->fifo_byte_count == 0) {
*frame_count = 0;
ret = 0;
} else {
switch (chan_spec.chan_type) {
case SENSOR_CHAN_ACCEL_XYZ:
*frame_count =
data->fifo_byte_count / data->sample_set_size;
ret = 0;
break;
default:
break;
}
}
}
#endif /* CONFIG_ADXL345_STREAM */
return ret;
}
static int adxl345_decode_sample(const struct adxl345_sample *data,
struct sensor_chan_spec chan_spec, uint32_t *fit,
uint16_t max_count, void *data_out)
{
struct sensor_value *out = (struct sensor_value *)data_out;
if (*fit > 0) {
return -ENOTSUP;
}
switch (chan_spec.chan_type) {
case SENSOR_CHAN_ACCEL_XYZ:
adxl345_accel_convert(out++, data->x);
adxl345_accel_convert(out++, data->y);
adxl345_accel_convert(out, data->z);
break;
default:
return -ENOTSUP;
}
*fit = 1;
return 0;
}
static int adxl345_decoder_decode(const uint8_t *buffer, struct sensor_chan_spec chan_spec,
uint32_t *fit, uint16_t max_count, void *data_out)
{
const struct adxl345_sample *data = (const struct adxl345_sample *)buffer;
#ifdef CONFIG_ADXL345_STREAM
if (data->is_fifo) {
return adxl345_decode_stream(buffer, chan_spec, fit, max_count, data_out);
}
#endif /* CONFIG_ADXL345_STREAM */
return adxl345_decode_sample(data, chan_spec, fit, max_count, data_out);
}
static bool adxl345_decoder_has_trigger(const uint8_t *buffer, enum sensor_trigger_type trigger)
{
const struct adxl345_fifo_data *data = (const struct adxl345_fifo_data *)buffer;
if (!data->is_fifo) {
return false;
}
switch (trigger) {
case SENSOR_TRIG_FIFO_WATERMARK:
return FIELD_GET(ADXL345_INT_MAP_WATERMARK_MSK, data->int_status);
default:
return false;
}
}
SENSOR_DECODER_API_DT_DEFINE() = {
.get_frame_count = adxl345_decoder_get_frame_count,
.decode = adxl345_decoder_decode,
.has_trigger = adxl345_decoder_has_trigger,
};
int adxl345_get_decoder(const struct device *dev, const struct sensor_decoder_api **decoder)
{
ARG_UNUSED(dev);
*decoder = &SENSOR_DECODER_NAME();
return 0;
}

View file

@ -0,0 +1,60 @@
/*
* Copyright (c) 2024 Analog Devices Inc.
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <zephyr/rtio/work.h>
#include <zephyr/logging/log.h>
#include <zephyr/drivers/sensor.h>
#include "adxl345.h"
LOG_MODULE_DECLARE(ADXL345, CONFIG_SENSOR_LOG_LEVEL);
static void adxl345_submit_fetch(struct rtio_iodev_sqe *iodev_sqe)
{
const struct sensor_read_config *cfg =
(const struct sensor_read_config *) iodev_sqe->sqe.iodev->data;
const struct device *dev = cfg->sensor;
int rc;
uint32_t min_buffer_len = sizeof(struct adxl345_dev_data);
uint8_t *buffer;
uint32_t buffer_len;
rc = rtio_sqe_rx_buf(iodev_sqe, min_buffer_len, min_buffer_len, &buffer, &buffer_len);
if (rc != 0) {
LOG_ERR("Failed to get a read buffer of size %u bytes", min_buffer_len);
rtio_iodev_sqe_err(iodev_sqe, rc);
return;
}
struct adxl345_sample *data = (struct adxl345_sample *)buffer;
rc = adxl345_read_sample(dev, data);
if (rc != 0) {
LOG_ERR("Failed to fetch samples");
rtio_iodev_sqe_err(iodev_sqe, rc);
return;
}
rtio_iodev_sqe_ok(iodev_sqe, 0);
}
void adxl345_submit(const struct device *dev, struct rtio_iodev_sqe *iodev_sqe)
{
const struct sensor_read_config *cfg =
(const struct sensor_read_config *) iodev_sqe->sqe.iodev->data;
if (!cfg->is_streaming) {
struct rtio_work_req *req = rtio_work_req_alloc();
__ASSERT_NO_MSG(req);
rtio_work_req_submit(req, iodev_sqe, adxl345_submit_fetch);
} else if (IS_ENABLED(CONFIG_ADXL345_STREAM)) {
adxl345_submit_stream(dev, iodev_sqe);
} else {
rtio_iodev_sqe_err(iodev_sqe, -ENOTSUP);
}
}

View file

@ -0,0 +1,369 @@
/*
* Copyright (c) 2024 Analog Devices Inc.
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <zephyr/logging/log.h>
#include <zephyr/drivers/sensor.h>
#include "adxl345.h"
LOG_MODULE_DECLARE(ADXL345, CONFIG_SENSOR_LOG_LEVEL);
void adxl345_submit_stream(const struct device *dev, struct rtio_iodev_sqe *iodev_sqe)
{
const struct sensor_read_config *cfg =
(const struct sensor_read_config *) iodev_sqe->sqe.iodev->data;
struct adxl345_dev_data *data = (struct adxl345_dev_data *)dev->data;
const struct adxl345_dev_config *cfg_345 = dev->config;
uint8_t int_value = (uint8_t)~ADXL345_INT_MAP_WATERMARK_MSK;
uint8_t fifo_watermark_irq = 0;
int rc = gpio_pin_interrupt_configure_dt(&cfg_345->interrupt,
GPIO_INT_DISABLE);
if (rc < 0) {
return;
}
for (size_t i = 0; i < cfg->count; i++) {
if (cfg->triggers[i].trigger == SENSOR_TRIG_FIFO_WATERMARK) {
int_value = ADXL345_INT_MAP_WATERMARK_MSK;
fifo_watermark_irq = 1;
}
}
uint8_t status;
if (fifo_watermark_irq != data->fifo_watermark_irq) {
data->fifo_watermark_irq = fifo_watermark_irq;
rc = adxl345_reg_write_mask(dev, ADXL345_INT_MAP, ADXL345_INT_MAP_WATERMARK_MSK,
int_value);
if (rc < 0) {
return;
}
/* Flush the FIFO by disabling it. Save current mode for after the reset. */
enum adxl345_fifo_mode current_fifo_mode = data->fifo_config.fifo_mode;
if (current_fifo_mode == ADXL345_FIFO_BYPASSED) {
current_fifo_mode = ADXL345_FIFO_STREAMED;
}
adxl345_configure_fifo(dev, ADXL345_FIFO_BYPASSED, data->fifo_config.fifo_trigger,
data->fifo_config.fifo_samples);
adxl345_configure_fifo(dev, current_fifo_mode, data->fifo_config.fifo_trigger,
data->fifo_config.fifo_samples);
rc = adxl345_reg_read_byte(dev, ADXL345_FIFO_STATUS_REG, &status);
}
rc = gpio_pin_interrupt_configure_dt(&cfg_345->interrupt,
GPIO_INT_EDGE_TO_ACTIVE);
if (rc < 0) {
return;
}
data->sqe = iodev_sqe;
}
static void adxl345_irq_en_cb(struct rtio *r, const struct rtio_sqe *sqr, void *arg)
{
const struct device *dev = (const struct device *)arg;
const struct adxl345_dev_config *cfg = dev->config;
gpio_pin_interrupt_configure_dt(&cfg->interrupt, GPIO_INT_EDGE_TO_ACTIVE);
}
static void adxl345_fifo_flush_rtio(const struct device *dev)
{
struct adxl345_dev_data *data = dev->data;
uint8_t fifo_config;
fifo_config = (ADXL345_FIFO_CTL_TRIGGER_MODE(data->fifo_config.fifo_trigger) |
ADXL345_FIFO_CTL_MODE_MODE(ADXL345_FIFO_BYPASSED) |
ADXL345_FIFO_CTL_SAMPLES_MODE(data->fifo_config.fifo_samples));
struct rtio_sqe *write_fifo_addr = rtio_sqe_acquire(data->rtio_ctx);
const uint8_t reg_addr_w2[2] = {ADXL345_FIFO_CTL_REG, fifo_config};
rtio_sqe_prep_tiny_write(write_fifo_addr, data->iodev, RTIO_PRIO_NORM, reg_addr_w2,
2, NULL);
fifo_config = (ADXL345_FIFO_CTL_TRIGGER_MODE(data->fifo_config.fifo_trigger) |
ADXL345_FIFO_CTL_MODE_MODE(data->fifo_config.fifo_mode) |
ADXL345_FIFO_CTL_SAMPLES_MODE(data->fifo_config.fifo_samples));
write_fifo_addr = rtio_sqe_acquire(data->rtio_ctx);
const uint8_t reg_addr_w3[2] = {ADXL345_FIFO_CTL_REG, fifo_config};
rtio_sqe_prep_tiny_write(write_fifo_addr, data->iodev, RTIO_PRIO_NORM, reg_addr_w3,
2, NULL);
write_fifo_addr->flags |= RTIO_SQE_CHAINED;
struct rtio_sqe *complete_op = rtio_sqe_acquire(data->rtio_ctx);
rtio_sqe_prep_callback(complete_op, adxl345_irq_en_cb, (void *)dev, NULL);
rtio_submit(data->rtio_ctx, 0);
}
static void adxl345_fifo_read_cb(struct rtio *rtio_ctx, const struct rtio_sqe *sqe, void *arg)
{
const struct device *dev = (const struct device *)arg;
struct adxl345_dev_data *data = (struct adxl345_dev_data *) dev->data;
const struct adxl345_dev_config *cfg = (const struct adxl345_dev_config *) dev->config;
struct rtio_iodev_sqe *iodev_sqe = sqe->userdata;
if (data->fifo_samples == 0) {
data->fifo_total_bytes = 0;
rtio_iodev_sqe_ok(iodev_sqe, 0);
gpio_pin_interrupt_configure_dt(&cfg->interrupt, GPIO_INT_EDGE_TO_ACTIVE);
}
}
static void adxl345_process_fifo_samples_cb(struct rtio *r, const struct rtio_sqe *sqr, void *arg)
{
const struct device *dev = (const struct device *)arg;
struct adxl345_dev_data *data = (struct adxl345_dev_data *) dev->data;
const struct adxl345_dev_config *cfg = (const struct adxl345_dev_config *) dev->config;
struct rtio_iodev_sqe *current_sqe = data->sqe;
uint16_t fifo_samples = (data->fifo_ent[0]) & SAMPLE_MASK;
size_t sample_set_size = SAMPLE_SIZE;
uint16_t fifo_bytes = fifo_samples * SAMPLE_SIZE;
data->sqe = NULL;
/* Not inherently an underrun/overrun as we may have a buffer to fill next time */
if (current_sqe == NULL) {
LOG_ERR("No pending SQE");
gpio_pin_interrupt_configure_dt(&cfg->interrupt, GPIO_INT_EDGE_TO_ACTIVE);
return;
}
const size_t min_read_size = sizeof(struct adxl345_fifo_data) + sample_set_size;
const size_t ideal_read_size = sizeof(struct adxl345_fifo_data) + fifo_bytes;
uint8_t *buf;
uint32_t buf_len;
if (rtio_sqe_rx_buf(current_sqe, min_read_size, ideal_read_size, &buf, &buf_len) != 0) {
LOG_ERR("Failed to get buffer");
rtio_iodev_sqe_err(current_sqe, -ENOMEM);
gpio_pin_interrupt_configure_dt(&cfg->interrupt, GPIO_INT_EDGE_TO_ACTIVE);
return;
}
LOG_DBG("Requesting buffer [%u, %u] got %u", (unsigned int)min_read_size,
(unsigned int)ideal_read_size, buf_len);
/* Read FIFO and call back to rtio with rtio_sqe completion */
struct adxl345_fifo_data *hdr = (struct adxl345_fifo_data *) buf;
hdr->is_fifo = 1;
hdr->timestamp = data->timestamp;
hdr->int_status = data->status1;
hdr->accel_odr = cfg->odr;
hdr->sample_set_size = sample_set_size;
uint32_t buf_avail = buf_len;
buf_avail -= sizeof(*hdr);
uint32_t read_len = MIN(fifo_bytes, buf_avail);
if (buf_avail < fifo_bytes) {
uint32_t pkts = read_len / sample_set_size;
read_len = pkts * sample_set_size;
}
((struct adxl345_fifo_data *)buf)->fifo_byte_count = read_len;
uint8_t *read_buf = buf + sizeof(*hdr);
/* Flush completions */
struct rtio_cqe *cqe;
int res = 0;
do {
cqe = rtio_cqe_consume(data->rtio_ctx);
if (cqe != NULL) {
if ((cqe->result < 0 && res == 0)) {
LOG_ERR("Bus error: %d", cqe->result);
res = cqe->result;
}
rtio_cqe_release(data->rtio_ctx, cqe);
}
} while (cqe != NULL);
/* Bail/cancel attempt to read sensor on any error */
if (res != 0) {
rtio_iodev_sqe_err(current_sqe, res);
return;
}
data->fifo_samples = fifo_samples;
for (size_t i = 0; i < fifo_samples; i++) {
struct rtio_sqe *write_fifo_addr = rtio_sqe_acquire(data->rtio_ctx);
struct rtio_sqe *read_fifo_data = rtio_sqe_acquire(data->rtio_ctx);
data->fifo_samples--;
const uint8_t reg_addr = ADXL345_REG_READ(ADXL345_X_AXIS_DATA_0_REG)
| ADXL345_MULTIBYTE_FLAG;
rtio_sqe_prep_tiny_write(write_fifo_addr, data->iodev, RTIO_PRIO_NORM, &reg_addr,
1, NULL);
write_fifo_addr->flags = RTIO_SQE_TRANSACTION;
rtio_sqe_prep_read(read_fifo_data, data->iodev, RTIO_PRIO_NORM,
read_buf + data->fifo_total_bytes,
SAMPLE_SIZE, current_sqe);
data->fifo_total_bytes += SAMPLE_SIZE;
if (i == fifo_samples-1) {
struct rtio_sqe *complete_op = rtio_sqe_acquire(data->rtio_ctx);
read_fifo_data->flags = RTIO_SQE_CHAINED;
rtio_sqe_prep_callback(complete_op, adxl345_fifo_read_cb, (void *)dev,
current_sqe);
}
rtio_submit(data->rtio_ctx, 0);
ARG_UNUSED(rtio_cqe_consume(data->rtio_ctx));
}
}
static void adxl345_process_status1_cb(struct rtio *r, const struct rtio_sqe *sqr, void *arg)
{
const struct device *dev = (const struct device *)arg;
struct adxl345_dev_data *data = (struct adxl345_dev_data *) dev->data;
const struct adxl345_dev_config *cfg = (const struct adxl345_dev_config *) dev->config;
struct rtio_iodev_sqe *current_sqe = data->sqe;
struct sensor_read_config *read_config;
uint8_t status1 = data->status1;
if (data->sqe == NULL) {
return;
}
read_config = (struct sensor_read_config *)data->sqe->sqe.iodev->data;
if (read_config == NULL) {
return;
}
if (read_config->is_streaming == false) {
return;
}
gpio_pin_interrupt_configure_dt(&cfg->interrupt, GPIO_INT_DISABLE);
struct sensor_stream_trigger *fifo_wmark_cfg = NULL;
for (int i = 0; i < read_config->count; ++i) {
if (read_config->triggers[i].trigger == SENSOR_TRIG_FIFO_WATERMARK) {
fifo_wmark_cfg = &read_config->triggers[i];
continue;
}
}
bool fifo_full_irq = false;
if ((fifo_wmark_cfg != NULL)
&& FIELD_GET(ADXL345_INT_MAP_WATERMARK_MSK, status1)) {
fifo_full_irq = true;
}
if (!fifo_full_irq) {
gpio_pin_interrupt_configure_dt(&cfg->interrupt, GPIO_INT_EDGE_TO_ACTIVE);
return;
}
/* Flush completions */
struct rtio_cqe *cqe;
int res = 0;
do {
cqe = rtio_cqe_consume(data->rtio_ctx);
if (cqe != NULL) {
if ((cqe->result < 0) && (res == 0)) {
LOG_ERR("Bus error: %d", cqe->result);
res = cqe->result;
}
rtio_cqe_release(data->rtio_ctx, cqe);
}
} while (cqe != NULL);
/* Bail/cancel attempt to read sensor on any error */
if (res != 0) {
rtio_iodev_sqe_err(current_sqe, res);
return;
}
enum sensor_stream_data_opt data_opt;
if (fifo_wmark_cfg != NULL) {
data_opt = fifo_wmark_cfg->opt;
}
if (data_opt == SENSOR_STREAM_DATA_NOP || data_opt == SENSOR_STREAM_DATA_DROP) {
uint8_t *buf;
uint32_t buf_len;
/* Clear streaming_sqe since we're done with the call */
data->sqe = NULL;
if (rtio_sqe_rx_buf(current_sqe, sizeof(struct adxl345_fifo_data),
sizeof(struct adxl345_fifo_data), &buf, &buf_len) != 0) {
rtio_iodev_sqe_err(current_sqe, -ENOMEM);
gpio_pin_interrupt_configure_dt(&cfg->interrupt, GPIO_INT_EDGE_TO_ACTIVE);
return;
}
struct adxl345_fifo_data *rx_data = (struct adxl345_fifo_data *)buf;
memset(buf, 0, buf_len);
rx_data->is_fifo = 1;
rx_data->timestamp = data->timestamp;
rx_data->int_status = status1;
rx_data->fifo_byte_count = 0;
rtio_iodev_sqe_ok(current_sqe, 0);
if (data_opt == SENSOR_STREAM_DATA_DROP) {
/* Flush the FIFO by disabling it. Save current mode for after the reset. */
adxl345_fifo_flush_rtio(dev);
}
gpio_pin_interrupt_configure_dt(&cfg->interrupt, GPIO_INT_EDGE_TO_ACTIVE);
return;
}
struct rtio_sqe *write_fifo_addr = rtio_sqe_acquire(data->rtio_ctx);
struct rtio_sqe *read_fifo_data = rtio_sqe_acquire(data->rtio_ctx);
struct rtio_sqe *complete_op = rtio_sqe_acquire(data->rtio_ctx);
const uint8_t reg_addr = ADXL345_REG_READ(ADXL345_FIFO_STATUS_REG);
rtio_sqe_prep_tiny_write(write_fifo_addr, data->iodev, RTIO_PRIO_NORM, &reg_addr, 1, NULL);
write_fifo_addr->flags = RTIO_SQE_TRANSACTION;
rtio_sqe_prep_read(read_fifo_data, data->iodev, RTIO_PRIO_NORM, data->fifo_ent, 1,
current_sqe);
read_fifo_data->flags = RTIO_SQE_CHAINED;
rtio_sqe_prep_callback(complete_op, adxl345_process_fifo_samples_cb, (void *)dev,
current_sqe);
rtio_submit(data->rtio_ctx, 0);
}
void adxl345_stream_irq_handler(const struct device *dev)
{
struct adxl345_dev_data *data = (struct adxl345_dev_data *) dev->data;
if (data->sqe == NULL) {
return;
}
data->timestamp = k_ticks_to_ns_floor64(k_uptime_ticks());
struct rtio_sqe *write_status_addr = rtio_sqe_acquire(data->rtio_ctx);
struct rtio_sqe *read_status_reg = rtio_sqe_acquire(data->rtio_ctx);
struct rtio_sqe *check_status_reg = rtio_sqe_acquire(data->rtio_ctx);
uint8_t reg = ADXL345_REG_READ(ADXL345_INT_SOURCE);
rtio_sqe_prep_tiny_write(write_status_addr, data->iodev, RTIO_PRIO_NORM, &reg, 1, NULL);
write_status_addr->flags = RTIO_SQE_TRANSACTION;
rtio_sqe_prep_read(read_status_reg, data->iodev, RTIO_PRIO_NORM, &data->status1, 1, NULL);
read_status_reg->flags = RTIO_SQE_CHAINED;
rtio_sqe_prep_callback(check_status_reg, adxl345_process_status1_cb, (void *)dev, NULL);
rtio_submit(data->rtio_ctx, 0);
}

View file

@ -0,0 +1,179 @@
/*
* Copyright (c) 2018 Analog Devices Inc.
*
* SPDX-License-Identifier: Apache-2.0
*/
#define DT_DRV_COMPAT adi_adxl345
#include <zephyr/device.h>
#include <zephyr/drivers/gpio.h>
#include <zephyr/sys/util.h>
#include <zephyr/kernel.h>
#include <zephyr/drivers/sensor.h>
#include "adxl345.h"
#include <zephyr/logging/log.h>
LOG_MODULE_DECLARE(ADXL345, CONFIG_SENSOR_LOG_LEVEL);
#if defined(CONFIG_ADXL345_TRIGGER_OWN_THREAD) || defined(CONFIG_ADXL345_TRIGGER_GLOBAL_THREAD)
static void adxl345_thread_cb(const struct device *dev)
{
const struct adxl345_dev_config *cfg = dev->config;
struct adxl345_dev_data *drv_data = dev->data;
uint8_t status1;
int ret;
/* Clear the status */
if (adxl345_get_status(dev, &status1, NULL) < 0) {
return;
}
if ((drv_data->drdy_handler != NULL) &&
ADXL345_STATUS_DATA_RDY(status1)) {
drv_data->drdy_handler(dev, drv_data->drdy_trigger);
}
ret = gpio_pin_interrupt_configure_dt(&cfg->interrupt,
GPIO_INT_EDGE_TO_ACTIVE);
__ASSERT(ret == 0, "Interrupt configuration failed");
}
#endif
static void adxl345_gpio_callback(const struct device *dev,
struct gpio_callback *cb, uint32_t pins)
{
struct adxl345_dev_data *drv_data =
CONTAINER_OF(cb, struct adxl345_dev_data, gpio_cb);
const struct adxl345_dev_config *cfg = drv_data->dev->config;
gpio_pin_interrupt_configure_dt(&cfg->interrupt, GPIO_INT_DISABLE);
if (IS_ENABLED(CONFIG_ADXL345_STREAM)) {
adxl345_stream_irq_handler(drv_data->dev);
}
#if defined(CONFIG_ADXL345_TRIGGER_OWN_THREAD)
k_sem_give(&drv_data->gpio_sem);
#elif defined(CONFIG_ADXL345_TRIGGER_GLOBAL_THREAD)
k_work_submit(&drv_data->work);
#endif
}
#if defined(CONFIG_ADXL345_TRIGGER_OWN_THREAD)
static void adxl345_thread(void *p1, void *p2, void *p3)
{
ARG_UNUSED(p2);
ARG_UNUSED(p3);
struct adxl345_dev_data *drv_data = p1;
while (true) {
k_sem_take(&drv_data->gpio_sem, K_FOREVER);
adxl345_thread_cb(drv_data->dev);
}
}
#elif defined(CONFIG_ADXL345_TRIGGER_GLOBAL_THREAD)
static void adxl345_work_cb(struct k_work *work)
{
struct adxl345_dev_data *drv_data =
CONTAINER_OF(work, struct adxl345_dev_data, work);
adxl345_thread_cb(drv_data->dev);
}
#endif
int adxl345_trigger_set(const struct device *dev,
const struct sensor_trigger *trig,
sensor_trigger_handler_t handler)
{
const struct adxl345_dev_config *cfg = dev->config;
struct adxl345_dev_data *drv_data = dev->data;
uint8_t int_mask, int_en, status1;
int ret;
ret = gpio_pin_interrupt_configure_dt(&cfg->interrupt,
GPIO_INT_DISABLE);
if (ret < 0) {
return ret;
}
switch (trig->type) {
case SENSOR_TRIG_DATA_READY:
drv_data->drdy_handler = handler;
drv_data->drdy_trigger = trig;
int_mask = ADXL345_INT_MAP_DATA_RDY_MSK;
break;
default:
LOG_ERR("Unsupported sensor trigger");
return -ENOTSUP;
}
if (handler) {
int_en = int_mask;
} else {
int_en = 0U;
}
ret = adxl345_reg_write_mask(dev, ADXL345_INT_MAP, int_mask, int_en);
if (ret < 0) {
return ret;
}
/* Clear status */
ret = adxl345_get_status(dev, &status1, NULL);
if (ret < 0) {
return ret;
}
ret = gpio_pin_interrupt_configure_dt(&cfg->interrupt,
GPIO_INT_EDGE_TO_ACTIVE);
if (ret < 0) {
return ret;
}
return 0;
}
int adxl345_init_interrupt(const struct device *dev)
{
const struct adxl345_dev_config *cfg = dev->config;
struct adxl345_dev_data *drv_data = dev->data;
int ret;
if (!gpio_is_ready_dt(&cfg->interrupt)) {
LOG_ERR("GPIO port %s not ready", cfg->interrupt.port->name);
return -EINVAL;
}
ret = gpio_pin_configure_dt(&cfg->interrupt, GPIO_INPUT);
if (ret < 0) {
return ret;
}
gpio_init_callback(&drv_data->gpio_cb,
adxl345_gpio_callback,
BIT(cfg->interrupt.pin));
ret = gpio_add_callback(cfg->interrupt.port, &drv_data->gpio_cb);
if (ret < 0) {
LOG_ERR("Failed to set gpio callback!");
return ret;
}
drv_data->dev = dev;
#if defined(CONFIG_ADXL345_TRIGGER_OWN_THREAD)
k_sem_init(&drv_data->gpio_sem, 0, K_SEM_MAX_LIMIT);
k_thread_create(&drv_data->thread, drv_data->thread_stack,
CONFIG_ADXL345_THREAD_STACK_SIZE,
adxl345_thread, drv_data,
NULL, NULL, K_PRIO_COOP(CONFIG_ADXL345_THREAD_PRIORITY),
0, K_NO_WAIT);
#elif defined(CONFIG_ADXL345_TRIGGER_GLOBAL_THREAD)
drv_data->work.handler = adxl345_work_cb;
#endif
return 0;
}

View file

@ -0,0 +1,31 @@
# Copyright (c) 2022 Analog Devices Inc.
# SPDX-License-Identifier: Apache-2.0
include: sensor-device.yaml
properties:
odr:
type: int
default: 0
description: |
Accelerometer sampling frequency (ODR). Default is power on reset value.
0 # 12.5Hz
1 # 25Hz
2 # 50Hz
3 # 100Hz
4 # 200Hz
5 # 400Hz
enum:
- 0
- 1
- 2
- 3
- 4
- 5
int2-gpios:
type: phandle-array
description: |
The INT2 signal defaults to active high as produced by the
sensor. The property value should ensure the flags properly
describe the signal that is presented to the driver.

View file

@ -5,4 +5,4 @@ description: ADXL345 3-axis accelerometer with SPI connection
compatible: "adi,adxl345"
include: [sensor-device.yaml, spi-device.yaml]
include: ["spi-device.yaml", "adi,adxl345-common.yaml"]