sensor: bmp388: Add I2C-base or SPI-base interface in build time

move DT_DRV_COMPAT to bmp388.h. so that can be decide which
interface to use.

define struct bmp388_bus_io interface bmp388_i2c.c and bmp388_spi.c.

redefined bus operation interface in bmp388.c, this allow the driver
to decide which interface to use during construction

Signed-off-by: Weiwei Guo <guoweiwei@syriusrobotics.com>
This commit is contained in:
Weiwei Guo 2022-11-02 13:48:10 +08:00 committed by Carles Cufí
commit 88f0793025
6 changed files with 230 additions and 221 deletions

View file

@ -5,5 +5,5 @@
#
zephyr_library()
zephyr_library_sources(bmp388.c)
zephyr_library_sources(bmp388.c bmp388_i2c.c bmp388_spi.c)
zephyr_library_sources_ifdef(CONFIG_BMP388_TRIGGER bmp388_trigger.c)

View file

@ -8,12 +8,8 @@
* https://www.bosch-sensortec.com/media/boschsensortec/downloads/datasheets/bst-bmp388-ds001.pdf
*/
#define DT_DRV_COMPAT bosch_bmp388
#include <zephyr/logging/log.h>
#include <zephyr/sys/byteorder.h>
#include <zephyr/drivers/i2c.h>
#include <zephyr/drivers/sensor.h>
#include <zephyr/pm/device.h>
#include "bmp388.h"
@ -45,156 +41,27 @@ static const struct {
};
#endif
#if DT_ANY_INST_ON_BUS_STATUS_OKAY(spi)
static int bmp388_transceive(const struct device *dev,
void *data, size_t length)
{
const struct bmp388_config *cfg = dev->config;
const struct spi_buf buf = { .buf = data, .len = length };
const struct spi_buf_set s = { .buffers = &buf, .count = 1 };
return spi_transceive_dt(&cfg->spi, &s, &s);
}
static int bmp388_read_spi(const struct device *dev,
uint8_t reg,
void *data,
size_t length)
static inline int bmp388_bus_check(const struct device *dev)
{
const struct bmp388_config *cfg = dev->config;
/* Reads must clock out a dummy byte after sending the address. */
uint8_t reg_buf[2] = { reg | BIT(7), 0 };
const struct spi_buf buf[2] = {
{ .buf = reg_buf, .len = 2 },
{ .buf = data, .len = length }
};
const struct spi_buf_set tx = { .buffers = buf, .count = 1 };
const struct spi_buf_set rx = { .buffers = buf, .count = 2 };
return spi_transceive_dt(&cfg->spi, &tx, &rx);
return cfg->bus_io->check(&cfg->bus);
}
static int bmp388_byte_read_spi(const struct device *dev,
uint8_t reg,
uint8_t *byte)
{
/* Reads must clock out a dummy byte after sending the address. */
uint8_t data[] = { reg | BIT(7), 0, 0 };
int ret;
ret = bmp388_transceive(dev, data, sizeof(data));
*byte = data[2];
return ret;
}
static int bmp388_byte_write_spi(const struct device *dev,
uint8_t reg,
uint8_t byte)
{
uint8_t data[] = { reg, byte };
return bmp388_transceive(dev, data, sizeof(data));
}
int bmp388_reg_field_update_spi(const struct device *dev,
uint8_t reg,
uint8_t mask,
uint8_t val)
{
uint8_t old_val;
if (bmp388_byte_read_spi(dev, reg, &old_val) < 0) {
return -EIO;
}
return bmp388_byte_write_spi(dev, reg, (old_val & ~mask) | (val & mask));
}
static const struct bmp388_io_ops bmp388_spi_ops = {
.read = bmp388_read_spi,
.byte_read = bmp388_byte_read_spi,
.byte_write = bmp388_byte_write_spi,
.reg_field_update = bmp388_reg_field_update_spi,
};
#endif /* DT_ANY_INST_ON_BUS_STATUS_OKAY(spi) */
#if DT_ANY_INST_ON_BUS_STATUS_OKAY(i2c)
static int bmp388_read_i2c(const struct device *dev,
uint8_t reg,
void *data,
size_t length)
static inline int bmp388_reg_read(const struct device *dev,
uint8_t start, uint8_t *buf, int size)
{
const struct bmp388_config *cfg = dev->config;
return i2c_burst_read_dt(&cfg->i2c, reg, data, length);
return cfg->bus_io->read(&cfg->bus, start, buf, size);
}
static int bmp388_byte_read_i2c(const struct device *dev,
uint8_t reg,
uint8_t *byte)
static inline int bmp388_reg_write(const struct device *dev, uint8_t reg,
uint8_t val)
{
const struct bmp388_config *cfg = dev->config;
return i2c_reg_read_byte_dt(&cfg->i2c, reg, byte);
}
static int bmp388_byte_write_i2c(const struct device *dev,
uint8_t reg,
uint8_t byte)
{
const struct bmp388_config *cfg = dev->config;
return i2c_reg_write_byte_dt(&cfg->i2c, reg, byte);
}
int bmp388_reg_field_update_i2c(const struct device *dev,
uint8_t reg,
uint8_t mask,
uint8_t val)
{
const struct bmp388_config *cfg = dev->config;
return i2c_reg_update_byte_dt(&cfg->i2c, reg, mask, val);
}
static const struct bmp388_io_ops bmp388_i2c_ops = {
.read = bmp388_read_i2c,
.byte_read = bmp388_byte_read_i2c,
.byte_write = bmp388_byte_write_i2c,
.reg_field_update = bmp388_reg_field_update_i2c,
};
#endif /* DT_ANY_INST_ON_BUS_STATUS_OKAY(i2c) */
static int bmp388_read(const struct device *dev,
uint8_t reg,
void *data,
size_t length)
{
const struct bmp388_config *cfg = dev->config;
return cfg->ops->read(dev, reg, data, length);
}
static int bmp388_byte_read(const struct device *dev,
uint8_t reg,
uint8_t *byte)
{
const struct bmp388_config *cfg = dev->config;
return cfg->ops->byte_read(dev, reg, byte);
}
static int bmp388_byte_write(const struct device *dev,
uint8_t reg,
uint8_t byte)
{
const struct bmp388_config *cfg = dev->config;
return cfg->ops->byte_write(dev, reg, byte);
return cfg->bus_io->write(&cfg->bus, reg, val);
}
int bmp388_reg_field_update(const struct device *dev,
@ -202,9 +69,21 @@ int bmp388_reg_field_update(const struct device *dev,
uint8_t mask,
uint8_t val)
{
int rc = 0;
uint8_t old_value, new_value;
const struct bmp388_config *cfg = dev->config;
return cfg->ops->reg_field_update(dev, reg, mask, val);
rc = cfg->bus_io->read(&cfg->bus, reg, &old_value, 1);
if (rc != 0) {
return rc;
}
new_value = (old_value & ~mask) | (val & mask);
if (new_value == old_value) {
return 0;
}
return cfg->bus_io->write(&cfg->bus, reg, new_value);
}
#ifdef CONFIG_BMP388_ODR_RUNTIME
@ -363,13 +242,13 @@ static int bmp388_sample_fetch(const struct device *dev,
/* Wait for status to indicate that data is ready. */
raw[0] = 0U;
while ((raw[0] & BMP388_STATUS_DRDY_PRESS) == 0U) {
ret = bmp388_byte_read(dev, BMP388_REG_STATUS, raw);
ret = bmp388_reg_read(dev, BMP388_REG_STATUS, raw, 1);
if (ret < 0) {
goto error;
}
}
ret = bmp388_read(dev,
ret = bmp388_reg_read(dev,
BMP388_REG_DATA0,
raw,
BMP388_SAMPLE_BUFFER_SIZE);
@ -534,7 +413,7 @@ static int bmp388_get_calibration_data(const struct device *dev)
struct bmp388_data *data = dev->data;
struct bmp388_cal_data *cal = &data->cal;
if (bmp388_read(dev, BMP388_REG_CALIB0, cal, sizeof(*cal)) < 0) {
if (bmp388_reg_read(dev, BMP388_REG_CALIB0, (uint8_t *)cal, sizeof(*cal)) < 0) {
return -EIO;
}
@ -593,45 +472,20 @@ static int bmp388_init(const struct device *dev)
const struct bmp388_config *cfg = dev->config;
uint8_t val = 0U;
#if DT_ANY_INST_ON_BUS_STATUS_OKAY(spi)
bool is_spi = (cfg->ops == &bmp388_spi_ops);
#endif
if (!device_is_ready(cfg->i2c.bus)) {
LOG_ERR("I2C bus device is not ready");
return -EINVAL;
if (bmp388_bus_check(dev) < 0) {
LOG_DBG("bus check failed");
return -ENODEV;
}
#if DT_ANY_INST_ON_BUS_STATUS_OKAY(spi)
/* Verify the SPI bus */
if (is_spi) {
if (!spi_is_ready_dt(&cfg->spi)) {
LOG_ERR("SPI bus is not ready");
return -ENODEV;
}
}
#endif /* DT_ANY_INST_ON_BUS_STATUS_OKAY(spi) */
/* reboot the chip */
if (bmp388_byte_write(dev, BMP388_REG_CMD, BMP388_CMD_SOFT_RESET) < 0) {
if (bmp388_reg_write(dev, BMP388_REG_CMD, BMP388_CMD_SOFT_RESET) < 0) {
LOG_ERR("Cannot reboot chip.");
return -EIO;
}
k_busy_wait(2000);
#if DT_ANY_INST_ON_BUS_STATUS_OKAY(spi)
if (is_spi) {
/* do a dummy read from 0x7F to activate SPI */
if (bmp388_byte_read(dev, 0x7F, &val) < 0) {
return -EIO;
}
k_busy_wait(100);
}
#endif
if (bmp388_byte_read(dev, BMP388_REG_CHIPID, &val) < 0) {
if (bmp388_reg_read(dev, BMP388_REG_CHIPID, &val, 1) < 0) {
LOG_ERR("Failed to read chip id.");
return -EIO;
}
@ -659,26 +513,38 @@ static int bmp388_init(const struct device *dev)
/* Set OSR */
val = (bmp388->osr_pressure << BMP388_OSR_PRESSURE_POS);
val |= (bmp388->osr_temp << BMP388_OSR_TEMP_POS);
if (bmp388_byte_write(dev, BMP388_REG_OSR, val) < 0) {
if (bmp388_reg_write(dev, BMP388_REG_OSR, val) < 0) {
LOG_ERR("Failed to set OSR.");
return -EIO;
}
/* Set IIR filter coefficient */
val = (cfg->iir_filter << BMP388_IIR_FILTER_POS) & BMP388_IIR_FILTER_MASK;
if (bmp388_byte_write(dev, BMP388_REG_CONFIG, val) < 0) {
if (bmp388_reg_write(dev, BMP388_REG_CONFIG, val) < 0) {
LOG_ERR("Failed to set IIR coefficient.");
return -EIO;
}
/* Enable sensors and normal mode*/
if (bmp388_byte_write(dev,
BMP388_REG_PWR_CTRL,
BMP388_PWR_CTRL_ON) < 0) {
if (bmp388_reg_write(dev,
BMP388_REG_PWR_CTRL,
BMP388_PWR_CTRL_ON) < 0) {
LOG_ERR("Failed to enable sensors.");
return -EIO;
}
/* Read error register */
if (bmp388_reg_read(dev, BMP388_REG_ERR_REG, &val, 1) < 0) {
LOG_ERR("Failed get sensors error register.");
return -EIO;
}
/* OSR and ODR config not proper */
if (val & BMP388_STATUS_CONF_ERR) {
LOG_ERR("OSR and ODR configuration is not proper");
return -EINVAL;
}
#ifdef CONFIG_BMP388_TRIGGER
if (bmp388_trigger_mode_init(dev) < 0) {
LOG_ERR("Cannot set up trigger mode.");
@ -689,18 +555,20 @@ static int bmp388_init(const struct device *dev)
return 0;
}
#define BMP388_BUS_CFG_I2C(inst) \
.ops = &bmp388_i2c_ops, \
.i2c = I2C_DT_SPEC_INST_GET(inst)
/* Initializes a struct bmp388_config for an instance on a SPI bus. */
#define BMP388_CONFIG_SPI(inst) \
.bus.spi = SPI_DT_SPEC_INST_GET(inst, BMP388_SPI_OPERATION, 0), \
.bus_io = &bmp388_bus_io_spi,
#define BMP388_BUS_CFG_SPI(inst) \
.ops = &bmp388_spi_ops, \
.spi = SPI_DT_SPEC_INST_GET(inst, SPI_OP_MODE_MASTER | SPI_WORD_SET(8), 0)
/* Initializes a struct bmp388_config for an instance on an I2C bus. */
#define BMP388_CONFIG_I2C(inst) \
.bus.i2c = I2C_DT_SPEC_INST_GET(inst), \
.bus_io = &bmp388_bus_io_i2c,
#define BMP388_BUS_CFG(inst) \
COND_CODE_1(DT_INST_ON_BUS(inst, i2c), \
(BMP388_BUS_CFG_I2C(inst)), \
(BMP388_BUS_CFG_SPI(inst)))
(BMP388_CONFIG_I2C(inst)), \
(BMP388_CONFIG_SPI(inst)))
#if defined(CONFIG_BMP388_TRIGGER)
#define BMP388_INT_CFG(inst) \
@ -716,7 +584,7 @@ static int bmp388_init(const struct device *dev)
.osr_temp = DT_INST_ENUM_IDX(inst, osr_temp), \
}; \
static const struct bmp388_config bmp388_config_##inst = { \
BMP388_BUS_CFG(inst), \
BMP388_BUS_CFG(inst) \
BMP388_INT_CFG(inst) \
.iir_filter = DT_INST_ENUM_IDX(inst, iir_filter), \
}; \

View file

@ -11,11 +11,50 @@
#ifndef __BMP388_H
#define __BMP388_H
#include <zephyr/drivers/gpio.h>
#include <zephyr/device.h>
#include <zephyr/devicetree.h>
#include <zephyr/drivers/spi.h>
#include <zephyr/drivers/i2c.h>
#include <zephyr/drivers/gpio.h>
#include <zephyr/drivers/sensor.h>
#include <zephyr/sys/util.h>
#define DT_DRV_COMPAT bosch_bmp388
#define BMP388_BUS_SPI DT_ANY_INST_ON_BUS_STATUS_OKAY(spi)
#define BMP388_BUS_I2C DT_ANY_INST_ON_BUS_STATUS_OKAY(i2c)
union bmp388_bus {
#if BMP388_BUS_SPI
struct spi_dt_spec spi;
#endif
#if BMP388_BUS_I2C
struct i2c_dt_spec i2c;
#endif
};
typedef int (*bmp388_bus_check_fn)(const union bmp388_bus *bus);
typedef int (*bmp388_reg_read_fn)(const union bmp388_bus *bus,
uint8_t start, uint8_t *buf, int size);
typedef int (*bmp388_reg_write_fn)(const union bmp388_bus *bus,
uint8_t reg, uint8_t val);
struct bmp388_bus_io {
bmp388_bus_check_fn check;
bmp388_reg_read_fn read;
bmp388_reg_write_fn write;
};
#if BMP388_BUS_SPI
#define BMP388_SPI_OPERATION (SPI_WORD_SET(8) | SPI_TRANSFER_MSB | \
SPI_MODE_CPOL | SPI_MODE_CPHA)
extern const struct bmp388_bus_io bmp388_bus_io_spi;
#endif
#if BMP388_BUS_I2C
extern const struct bmp388_bus_io bmp388_bus_io_i2c;
#endif
/* registers */
#define BMP388_REG_CHIPID 0x00
#define BMP388_REG_ERR_REG 0x02
@ -122,33 +161,9 @@ struct bmp388_sample {
int64_t comp_temp;
};
struct bmp388_io_ops {
int (*read)(const struct device *dev,
uint8_t reg,
void *data,
size_t length);
int (*byte_read)(const struct device *dev,
uint8_t reg,
uint8_t *byte);
int (*byte_write)(const struct device *dev,
uint8_t reg,
uint8_t byte);
int (*reg_field_update)(const struct device *dev,
uint8_t reg,
uint8_t mask,
uint8_t val);
};
struct bmp388_config {
const struct bmp388_io_ops *ops;
union {
#if DT_ANY_INST_ON_BUS_STATUS_OKAY(spi)
struct spi_dt_spec spi;
#endif
#if DT_ANY_INST_ON_BUS_STATUS_OKAY(i2c)
struct i2c_dt_spec i2c;
#endif
};
union bmp388_bus bus;
const struct bmp388_bus_io *bus_io;
#ifdef CONFIG_BMP388_TRIGGER
struct gpio_dt_spec gpio_int;

View file

@ -0,0 +1,38 @@
/*
* Copyright (c) 2016, 2017 Intel Corporation
* Copyright (c) 2017 IpTronix S.r.l.
* Copyright (c) 2021 Nordic Semiconductor ASA
*
* SPDX-License-Identifier: Apache-2.0
*/
/*
* Bus-specific functionality for BMP388s accessed via I2C.
*/
#include "bmp388.h"
#if BMP388_BUS_I2C
static int bmp388_bus_check_i2c(const union bmp388_bus *bus)
{
return i2c_is_ready_dt(&bus->i2c) ? 0 : -ENODEV;
}
static int bmp388_reg_read_i2c(const union bmp388_bus *bus,
uint8_t start, uint8_t *buf, int size)
{
return i2c_burst_read_dt(&bus->i2c, start, buf, size);
}
static int bmp388_reg_write_i2c(const union bmp388_bus *bus,
uint8_t reg, uint8_t val)
{
return i2c_reg_write_byte_dt(&bus->i2c, reg, val);
}
const struct bmp388_bus_io bmp388_bus_io_i2c = {
.check = bmp388_bus_check_i2c,
.read = bmp388_reg_read_i2c,
.write = bmp388_reg_write_i2c,
};
#endif /* BMP388_BUS_I2C */

View file

@ -0,0 +1,92 @@
/*
* Copyright (c) 2016, 2017 Intel Corporation
* Copyright (c) 2017 IpTronix S.r.l.
* Copyright (c) 2021 Nordic Semiconductor ASA
*
* SPDX-License-Identifier: Apache-2.0
*/
/*
* Bus-specific functionality for BMP388s accessed via SPI.
*/
#include <zephyr/logging/log.h>
#include "bmp388.h"
#if BMP388_BUS_SPI
LOG_MODULE_DECLARE(BMP388, CONFIG_SENSOR_LOG_LEVEL);
static int bmp388_bus_check_spi(const union bmp388_bus *bus)
{
return spi_is_ready_dt(&bus->spi) ? 0 : -ENODEV;
}
static int bmp388_reg_read_spi(const union bmp388_bus *bus,
uint8_t start, uint8_t *buf, int size)
{
uint8_t addr;
const struct spi_buf tx_buf = {
.buf = &addr,
.len = 1
};
const struct spi_buf_set tx = {
.buffers = &tx_buf,
.count = 1
};
struct spi_buf rx_buf[2];
const struct spi_buf_set rx = {
.buffers = rx_buf,
.count = ARRAY_SIZE(rx_buf)
};
int i;
rx_buf[0].buf = NULL;
rx_buf[0].len = 1;
rx_buf[1].len = 1;
for (i = 0; i < size; i++) {
int ret;
addr = (start + i) | 0x80;
rx_buf[1].buf = &buf[i];
ret = spi_transceive_dt(&bus->spi, &tx, &rx);
if (ret) {
LOG_DBG("spi_transceive FAIL %d\n", ret);
return ret;
}
}
return 0;
}
static int bmp388_reg_write_spi(const union bmp388_bus *bus,
uint8_t reg, uint8_t val)
{
uint8_t cmd[] = { reg & 0x7F, val };
const struct spi_buf tx_buf = {
.buf = cmd,
.len = sizeof(cmd)
};
const struct spi_buf_set tx = {
.buffers = &tx_buf,
.count = 1
};
int ret;
ret = spi_write_dt(&bus->spi, &tx);
if (ret) {
LOG_DBG("spi_write FAIL %d\n", ret);
return ret;
}
return 0;
}
const struct bmp388_bus_io bmp388_bus_io_spi = {
.check = bmp388_bus_check_spi,
.read = bmp388_reg_read_spi,
.write = bmp388_reg_write_spi,
};
#endif /* BMP388_BUS_SPI */

View file

@ -8,11 +8,7 @@
* https://www.bosch-sensortec.com/media/boschsensortec/downloads/datasheets/bst-bmp388-ds001.pdf
*/
#define DT_DRV_COMPAT bosch_bmp388
#include <zephyr/kernel.h>
#include <zephyr/drivers/sensor.h>
#include <zephyr/drivers/gpio.h>
#include <zephyr/pm/device.h>
#include <zephyr/logging/log.h>