driver: sensor: Add support for BMP388 pressure sensor
Adds support for Bosch's BMP388 pressure sensors connected either by a I2C or SPI bus. Signed-off-by: Corey Wharton <coreyw7@fb.com>
This commit is contained in:
parent
8cae466100
commit
e3c94d381a
13 changed files with 1351 additions and 0 deletions
|
@ -16,6 +16,7 @@ add_subdirectory_ifdef(CONFIG_BMG160 bmg160)
|
|||
add_subdirectory_ifdef(CONFIG_BMI160 bmi160)
|
||||
add_subdirectory_ifdef(CONFIG_BMI270 bmi270)
|
||||
add_subdirectory_ifdef(CONFIG_BMM150 bmm150)
|
||||
add_subdirectory_ifdef(CONFIG_BMP388 bmp388)
|
||||
add_subdirectory_ifdef(CONFIG_BQ274XX bq274xx)
|
||||
add_subdirectory_ifdef(CONFIG_CCS811 ccs811)
|
||||
add_subdirectory_ifdef(CONFIG_DHT dht)
|
||||
|
|
|
@ -70,6 +70,8 @@ source "drivers/sensor/bmi270/Kconfig"
|
|||
|
||||
source "drivers/sensor/bmm150/Kconfig"
|
||||
|
||||
source "drivers/sensor/bmp388/Kconfig"
|
||||
|
||||
source "drivers/sensor/bq274xx/Kconfig"
|
||||
|
||||
source "drivers/sensor/ccs811/Kconfig"
|
||||
|
|
9
drivers/sensor/bmp388/CMakeLists.txt
Normal file
9
drivers/sensor/bmp388/CMakeLists.txt
Normal file
|
@ -0,0 +1,9 @@
|
|||
#
|
||||
# Copyright (c) 2020 Facebook, Inc. and its affiliates
|
||||
#
|
||||
# SPDX-License-Identifier: Apache-2.0
|
||||
#
|
||||
|
||||
zephyr_library()
|
||||
zephyr_library_sources(bmp388.c)
|
||||
zephyr_library_sources_ifdef(CONFIG_BMP388_TRIGGER bmp388_trigger.c)
|
59
drivers/sensor/bmp388/Kconfig
Normal file
59
drivers/sensor/bmp388/Kconfig
Normal file
|
@ -0,0 +1,59 @@
|
|||
# Copyright (c) 2020 Facebook, Inc. and its affiliates
|
||||
# SPDX-License-Identifier: Apache-2.0
|
||||
|
||||
menuconfig BMP388
|
||||
bool "Bosch BMP388 pressure sensor"
|
||||
depends on SPI || I2C
|
||||
help
|
||||
Enable driver for the Bosch BMP388 pressure sensor
|
||||
|
||||
if BMP388
|
||||
|
||||
choice BMP388_TRIGGER_MODE
|
||||
prompt "Trigger mode"
|
||||
default BMP388_TRIGGER_GLOBAL_THREAD
|
||||
help
|
||||
Specify the type of triggering to be used by the driver.
|
||||
|
||||
config BMP388_TRIGGER_NONE
|
||||
bool "No trigger"
|
||||
|
||||
config BMP388_TRIGGER_GLOBAL_THREAD
|
||||
bool "Use global thread"
|
||||
select BMP388_TRIGGER
|
||||
|
||||
config BMP388_TRIGGER_OWN_THREAD
|
||||
bool "Use own thread"
|
||||
select BMP388_TRIGGER
|
||||
|
||||
config BMP388_TRIGGER_DIRECT
|
||||
bool "Use IRQ handler"
|
||||
select BMP388_TRIGGER
|
||||
endchoice
|
||||
|
||||
config BMP388_TRIGGER
|
||||
bool
|
||||
|
||||
config BMP388_THREAD_PRIORITY
|
||||
int "Own thread priority"
|
||||
depends on BMP388_TRIGGER_OWN_THREAD
|
||||
default 10
|
||||
help
|
||||
Priority of the thread used by the driver to handle interrupts.
|
||||
|
||||
config BMP388_THREAD_STACK_SIZE
|
||||
int "Own thread stack size"
|
||||
depends on BMP388_TRIGGER_OWN_THREAD
|
||||
default 1024
|
||||
help
|
||||
Stack size of thread used by the driver to handle interrupts.
|
||||
|
||||
config BMP388_ODR_RUNTIME
|
||||
bool "Change ODR at runtime."
|
||||
default y
|
||||
|
||||
config BMP388_OSR_RUNTIME
|
||||
bool "Change OSR at runtime."
|
||||
default y
|
||||
|
||||
endif # BMP388
|
768
drivers/sensor/bmp388/bmp388.c
Normal file
768
drivers/sensor/bmp388/bmp388.c
Normal file
|
@ -0,0 +1,768 @@
|
|||
/* Bosch BMP388 pressure sensor
|
||||
*
|
||||
* Copyright (c) 2020 Facebook, Inc. and its affiliates
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* Datasheet:
|
||||
* https://www.bosch-sensortec.com/media/boschsensortec/downloads/datasheets/bst-bmp388-ds001.pdf
|
||||
*/
|
||||
|
||||
#define DT_DRV_COMPAT bosch_bmp388
|
||||
|
||||
#include <logging/log.h>
|
||||
#include <sys/byteorder.h>
|
||||
#include <drivers/i2c.h>
|
||||
#include <drivers/sensor.h>
|
||||
|
||||
#include "bmp388.h"
|
||||
|
||||
LOG_MODULE_REGISTER(BMP388, CONFIG_SENSOR_LOG_LEVEL);
|
||||
|
||||
#if defined(CONFIG_BMP388_ODR_RUNTIME)
|
||||
static const struct {
|
||||
uint16_t freq_int;
|
||||
uint16_t freq_milli;
|
||||
} bmp388_odr_map[] = {
|
||||
{ 0, 3 }, /* 25/8192 - 327.68s */
|
||||
{ 0, 6 }, /* 25/4096 - 163.84s */
|
||||
{ 0, 12 }, /* 25/2048 - 81.92s */
|
||||
{ 0, 24 }, /* 25/1024 - 40.96s */
|
||||
{ 0, 49 }, /* 25/512 - 20.48s */
|
||||
{ 0, 98 }, /* 25/256 - 10.24s */
|
||||
{ 0, 195 }, /* 25/128 - 5.12s */
|
||||
{ 0, 391 }, /* 25/64 - 2.56s */
|
||||
{ 0, 781 }, /* 25/32 - 1.28s */
|
||||
{ 1, 563 }, /* 25/16 - 640ms */
|
||||
{ 3, 125 }, /* 25/8 - 320ms */
|
||||
{ 6, 250 }, /* 25/4 - 160ms */
|
||||
{ 12, 500 }, /* 25/2 - 80ms */
|
||||
{ 25, 0 }, /* 25 - 40ms */
|
||||
{ 50, 0 }, /* 50 - 20ms */
|
||||
{ 100, 0 }, /* 100 - 10ms */
|
||||
{ 200, 0 }, /* 200 - 5ms */
|
||||
};
|
||||
#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_CFG(dev);
|
||||
const struct spi_buf buf = { .buf = data, .len = length };
|
||||
const struct spi_buf_set s = { .buffers = &buf, .count = 1 };
|
||||
|
||||
return spi_transceive(cfg->bus, &cfg->spi_cfg, &s, &s);
|
||||
}
|
||||
|
||||
static int bmp388_read_spi(const struct device *dev,
|
||||
uint8_t reg,
|
||||
void *data,
|
||||
size_t length)
|
||||
{
|
||||
const struct bmp388_config *cfg = DEV_CFG(dev);
|
||||
|
||||
/* 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(cfg->bus, &cfg->spi_cfg, &tx, &rx);
|
||||
}
|
||||
|
||||
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)
|
||||
{
|
||||
const struct bmp388_config *cfg = DEV_CFG(dev);
|
||||
|
||||
return i2c_burst_read(cfg->bus, cfg->bus_addr, reg, data, length);
|
||||
}
|
||||
|
||||
static int bmp388_byte_read_i2c(const struct device *dev,
|
||||
uint8_t reg,
|
||||
uint8_t *byte)
|
||||
{
|
||||
const struct bmp388_config *cfg = DEV_CFG(dev);
|
||||
|
||||
return i2c_reg_read_byte(cfg->bus, cfg->bus_addr, reg, byte);
|
||||
}
|
||||
|
||||
static int bmp388_byte_write_i2c(const struct device *dev,
|
||||
uint8_t reg,
|
||||
uint8_t byte)
|
||||
{
|
||||
const struct bmp388_config *cfg = DEV_CFG(dev);
|
||||
|
||||
return i2c_reg_write_byte(cfg->bus, cfg->bus_addr, 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_CFG(dev);
|
||||
|
||||
return i2c_reg_update_byte(cfg->bus, cfg->bus_addr, 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_CFG(dev);
|
||||
|
||||
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_CFG(dev);
|
||||
|
||||
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_CFG(dev);
|
||||
|
||||
return cfg->ops->byte_write(dev, reg, byte);
|
||||
}
|
||||
|
||||
int bmp388_reg_field_update(const struct device *dev,
|
||||
uint8_t reg,
|
||||
uint8_t mask,
|
||||
uint8_t val)
|
||||
{
|
||||
const struct bmp388_config *cfg = DEV_CFG(dev);
|
||||
|
||||
return cfg->ops->reg_field_update(dev, reg, mask, val);
|
||||
}
|
||||
|
||||
#ifdef CONFIG_BMP388_ODR_RUNTIME
|
||||
static int bmp388_freq_to_odr_val(uint16_t freq_int, uint16_t freq_milli)
|
||||
{
|
||||
size_t i;
|
||||
|
||||
/* An ODR of 0 Hz is not allowed */
|
||||
if (freq_int == 0U && freq_milli == 0U) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
for (i = 0; i < ARRAY_SIZE(bmp388_odr_map); i++) {
|
||||
if (freq_int < bmp388_odr_map[i].freq_int ||
|
||||
(freq_int == bmp388_odr_map[i].freq_int &&
|
||||
freq_milli <= bmp388_odr_map[i].freq_milli)) {
|
||||
return (ARRAY_SIZE(bmp388_odr_map) - 1) - i;
|
||||
}
|
||||
}
|
||||
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
static int bmp388_attr_set_odr(const struct device *dev,
|
||||
uint16_t freq_int,
|
||||
uint16_t freq_milli)
|
||||
{
|
||||
int err;
|
||||
struct bmp388_data *data = DEV_DATA(dev);
|
||||
int odr = bmp388_freq_to_odr_val(freq_int, freq_milli);
|
||||
|
||||
if (odr < 0) {
|
||||
return odr;
|
||||
}
|
||||
|
||||
err = bmp388_reg_field_update(dev,
|
||||
BMP388_REG_ODR,
|
||||
BMP388_ODR_MASK,
|
||||
(uint8_t)odr);
|
||||
if (err == 0) {
|
||||
data->odr = odr;
|
||||
}
|
||||
|
||||
return err;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_BMP388_OSR_RUNTIME
|
||||
static int bmp388_attr_set_oversampling(const struct device *dev,
|
||||
enum sensor_channel chan,
|
||||
uint16_t val)
|
||||
{
|
||||
uint8_t reg_val = 0;
|
||||
uint32_t pos, mask;
|
||||
int err;
|
||||
|
||||
struct bmp388_data *data = DEV_DATA(dev);
|
||||
|
||||
/* Value must be a positive power of 2 <= 32. */
|
||||
if ((val <= 0) || (val > 32) || ((val & (val - 1)) != 0)) {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
if (chan == SENSOR_CHAN_PRESS) {
|
||||
pos = BMP388_OSR_PRESSURE_POS;
|
||||
mask = BMP388_OSR_PRESSURE_MASK;
|
||||
} else if ((chan == SENSOR_CHAN_AMBIENT_TEMP) ||
|
||||
(chan == SENSOR_CHAN_DIE_TEMP)) {
|
||||
pos = BMP388_OSR_TEMP_POS;
|
||||
mask = BMP388_OSR_TEMP_MASK;
|
||||
} else {
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
/* Determine exponent: this corresponds to register setting. */
|
||||
while ((val % 2) == 0) {
|
||||
val >>= 1;
|
||||
++reg_val;
|
||||
}
|
||||
|
||||
err = bmp388_reg_field_update(dev,
|
||||
BMP388_REG_OSR,
|
||||
mask,
|
||||
reg_val << pos);
|
||||
if (err < 0) {
|
||||
return err;
|
||||
}
|
||||
|
||||
/* Store for future use in converting RAW values. */
|
||||
if (chan == SENSOR_CHAN_PRESS) {
|
||||
data->osr_pressure = reg_val;
|
||||
} else {
|
||||
data->osr_temp = reg_val;
|
||||
}
|
||||
|
||||
return err;
|
||||
}
|
||||
#endif
|
||||
|
||||
static int bmp388_attr_set(const struct device *dev,
|
||||
enum sensor_channel chan,
|
||||
enum sensor_attribute attr,
|
||||
const struct sensor_value *val)
|
||||
{
|
||||
int ret;
|
||||
|
||||
#ifdef CONFIG_DEVICE_POWER_MANAGEMENT
|
||||
struct bmp388_data *data = DEV_DATA(dev);
|
||||
|
||||
if (data->device_power_state != DEVICE_PM_ACTIVE_STATE) {
|
||||
return -EBUSY;
|
||||
}
|
||||
#endif
|
||||
|
||||
switch (attr) {
|
||||
#ifdef CONFIG_BMP388_ODR_RUNTIME
|
||||
case SENSOR_ATTR_SAMPLING_FREQUENCY:
|
||||
ret = bmp388_attr_set_odr(dev, val->val1, val->val2 / 1000);
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_BMP388_OSR_RUNTIME
|
||||
case SENSOR_ATTR_OVERSAMPLING:
|
||||
ret = bmp388_attr_set_oversampling(dev, chan, val->val1);
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
ret = -EINVAL;
|
||||
}
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
static int bmp388_sample_fetch(const struct device *dev,
|
||||
enum sensor_channel chan)
|
||||
{
|
||||
struct bmp388_data *bmp388 = DEV_DATA(dev);
|
||||
uint8_t raw[BMP388_SAMPLE_BUFFER_SIZE];
|
||||
int ret = 0;
|
||||
|
||||
__ASSERT_NO_MSG(chan == SENSOR_CHAN_ALL);
|
||||
|
||||
#ifdef CONFIG_DEVICE_POWER_MANAGEMENT
|
||||
if (bmp388->device_power_state != DEVICE_PM_ACTIVE_STATE) {
|
||||
return -EBUSY;
|
||||
}
|
||||
#endif
|
||||
|
||||
device_busy_set(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);
|
||||
if (ret < 0) {
|
||||
goto error;
|
||||
}
|
||||
}
|
||||
|
||||
ret = bmp388_read(dev,
|
||||
BMP388_REG_DATA0,
|
||||
raw,
|
||||
BMP388_SAMPLE_BUFFER_SIZE);
|
||||
if (ret < 0) {
|
||||
goto error;
|
||||
}
|
||||
|
||||
/* convert samples to 32bit values */
|
||||
bmp388->sample.press = (uint32_t)raw[0] |
|
||||
((uint32_t)raw[1] << 8) |
|
||||
((uint32_t)raw[2] << 16);
|
||||
bmp388->sample.raw_temp = (uint32_t)raw[3] |
|
||||
((uint32_t)raw[4] << 8) |
|
||||
((uint32_t)raw[5] << 16);
|
||||
bmp388->sample.comp_temp = 0;
|
||||
|
||||
error:
|
||||
device_busy_clear(dev);
|
||||
return ret;
|
||||
}
|
||||
|
||||
static void bmp388_compensate_temp(struct bmp388_data *data)
|
||||
{
|
||||
/* Adapted from:
|
||||
* https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c
|
||||
*/
|
||||
|
||||
int64_t partial_data1;
|
||||
int64_t partial_data2;
|
||||
int64_t partial_data3;
|
||||
int64_t partial_data4;
|
||||
int64_t partial_data5;
|
||||
|
||||
struct bmp388_cal_data *cal = &data->cal;
|
||||
|
||||
partial_data1 = ((int64_t)data->sample.raw_temp - (256 * cal->t1));
|
||||
partial_data2 = cal->t2 * partial_data1;
|
||||
partial_data3 = (partial_data1 * partial_data1);
|
||||
partial_data4 = (int64_t)partial_data3 * cal->t3;
|
||||
partial_data5 = ((int64_t)(partial_data2 * 262144) + partial_data4);
|
||||
|
||||
/* Store for pressure calculation */
|
||||
data->sample.comp_temp = partial_data5 / 4294967296;
|
||||
}
|
||||
|
||||
static int bmp388_temp_channel_get(const struct device *dev,
|
||||
struct sensor_value *val)
|
||||
{
|
||||
struct bmp388_data *data = DEV_DATA(dev);
|
||||
|
||||
if (data->sample.comp_temp == 0) {
|
||||
bmp388_compensate_temp(data);
|
||||
}
|
||||
|
||||
int64_t tmp = (data->sample.comp_temp * 250000) / 16384;
|
||||
|
||||
val->val1 = tmp / 1000000;
|
||||
val->val2 = tmp % 1000000;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static uint64_t bmp388_compensate_press(struct bmp388_data *data)
|
||||
{
|
||||
/* Adapted from:
|
||||
* https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3.c
|
||||
*/
|
||||
|
||||
int64_t partial_data1;
|
||||
int64_t partial_data2;
|
||||
int64_t partial_data3;
|
||||
int64_t partial_data4;
|
||||
int64_t partial_data5;
|
||||
int64_t partial_data6;
|
||||
int64_t offset;
|
||||
int64_t sensitivity;
|
||||
uint64_t comp_press;
|
||||
|
||||
struct bmp388_cal_data *cal = &data->cal;
|
||||
|
||||
int64_t t_lin = data->sample.comp_temp;
|
||||
uint32_t raw_pressure = data->sample.press;
|
||||
|
||||
partial_data1 = t_lin * t_lin;
|
||||
partial_data2 = partial_data1 / 64;
|
||||
partial_data3 = (partial_data2 * t_lin) / 256;
|
||||
partial_data4 = (cal->p8 * partial_data3) / 32;
|
||||
partial_data5 = (cal->p7 * partial_data1) * 16;
|
||||
partial_data6 = (cal->p6 * t_lin) * 4194304;
|
||||
offset = (cal->p5 * 140737488355328) + partial_data4 + partial_data5 +
|
||||
partial_data6;
|
||||
partial_data2 = (cal->p4 * partial_data3) / 32;
|
||||
partial_data4 = (cal->p3 * partial_data1) * 4;
|
||||
partial_data5 = (cal->p2 - 16384) * t_lin * 2097152;
|
||||
sensitivity = ((cal->p1 - 16384) * 70368744177664) + partial_data2 +
|
||||
partial_data4 + partial_data5;
|
||||
partial_data1 = (sensitivity / 16777216) * raw_pressure;
|
||||
partial_data2 = cal->p10 * t_lin;
|
||||
partial_data3 = partial_data2 + (65536 * cal->p9);
|
||||
partial_data4 = (partial_data3 * raw_pressure) / 8192;
|
||||
/* Dividing by 10 followed by multiplying by 10 to avoid overflow caused
|
||||
* (raw_pressure * partial_data4)
|
||||
*/
|
||||
partial_data5 = (raw_pressure * (partial_data4 / 10)) / 512;
|
||||
partial_data5 = partial_data5 * 10;
|
||||
partial_data6 = ((int64_t)raw_pressure * (int64_t)raw_pressure);
|
||||
partial_data2 = (cal->p11 * partial_data6) / 65536;
|
||||
partial_data3 = (partial_data2 * raw_pressure) / 128;
|
||||
partial_data4 = (offset / 4) + partial_data1 + partial_data5 +
|
||||
partial_data3;
|
||||
|
||||
comp_press = (((uint64_t)partial_data4 * 25) / (uint64_t)1099511627776);
|
||||
|
||||
/* returned value is in hundreths of Pa. */
|
||||
return comp_press;
|
||||
}
|
||||
|
||||
static int bmp388_press_channel_get(const struct device *dev,
|
||||
struct sensor_value *val)
|
||||
{
|
||||
struct bmp388_data *data = DEV_DATA(dev);
|
||||
|
||||
if (data->sample.comp_temp == 0) {
|
||||
bmp388_compensate_temp(data);
|
||||
}
|
||||
|
||||
uint64_t tmp = bmp388_compensate_press(data);
|
||||
|
||||
/* tmp is in hundreths of Pa. Convert to kPa as specified in sensor
|
||||
* interface.
|
||||
*/
|
||||
val->val1 = tmp / 100000;
|
||||
val->val2 = (tmp % 100000) * 10;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int bmp388_channel_get(const struct device *dev,
|
||||
enum sensor_channel chan,
|
||||
struct sensor_value *val)
|
||||
{
|
||||
switch (chan) {
|
||||
case SENSOR_CHAN_PRESS:
|
||||
bmp388_press_channel_get(dev, val);
|
||||
break;
|
||||
|
||||
case SENSOR_CHAN_DIE_TEMP:
|
||||
case SENSOR_CHAN_AMBIENT_TEMP:
|
||||
bmp388_temp_channel_get(dev, val);
|
||||
break;
|
||||
|
||||
default:
|
||||
LOG_DBG("Channel not supported.");
|
||||
return -ENOTSUP;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int bmp388_get_calibration_data(const struct device *dev)
|
||||
{
|
||||
struct bmp388_data *data = DEV_DATA(dev);
|
||||
struct bmp388_cal_data *cal = &data->cal;
|
||||
|
||||
if (bmp388_read(dev, BMP388_REG_CALIB0, cal, sizeof(*cal)) < 0) {
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
cal->t1 = sys_le16_to_cpu(cal->t1);
|
||||
cal->t2 = sys_le16_to_cpu(cal->t2);
|
||||
cal->p1 = sys_le16_to_cpu(cal->p1);
|
||||
cal->p2 = sys_le16_to_cpu(cal->p2);
|
||||
cal->p5 = sys_le16_to_cpu(cal->p5);
|
||||
cal->p6 = sys_le16_to_cpu(cal->p6);
|
||||
cal->p9 = sys_le16_to_cpu(cal->p9);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_DEVICE_POWER_MANAGEMENT
|
||||
static int bmp388_set_power_state(const struct device *dev,
|
||||
uint32_t power_state)
|
||||
{
|
||||
uint8_t reg_val;
|
||||
|
||||
struct bmp388_data *data = DEV_DATA(dev);
|
||||
|
||||
if (data->device_power_state == power_state) {
|
||||
/* We are already in the desired state. */
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (power_state == DEVICE_PM_ACTIVE_STATE) {
|
||||
reg_val = BMP388_PWR_CTRL_MODE_NORMAL;
|
||||
} else if ((power_state == DEVICE_PM_SUSPEND_STATE) ||
|
||||
(power_state == DEVICE_PM_OFF_STATE)) {
|
||||
reg_val = BMP388_PWR_CTRL_MODE_SLEEP;
|
||||
} else {
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (bmp388_reg_field_update(dev,
|
||||
BMP388_REG_PWR_CTRL,
|
||||
BMP388_PWR_CTRL_MODE_MASK,
|
||||
reg_val) < 0) {
|
||||
LOG_DBG("Failed to set power mode.");
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
data->device_power_state = power_state;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static uint32_t bmp388_get_power_state(const struct device *dev)
|
||||
{
|
||||
struct bmp388_data *ctx = DEV_DATA(dev);
|
||||
|
||||
return ctx->device_power_state;
|
||||
}
|
||||
|
||||
static int bmp388_device_ctrl(
|
||||
const struct device *dev,
|
||||
uint32_t ctrl_command,
|
||||
void *context,
|
||||
device_pm_cb cb,
|
||||
void *arg)
|
||||
{
|
||||
int ret = 0;
|
||||
|
||||
if (ctrl_command == DEVICE_PM_SET_POWER_STATE) {
|
||||
ret = bmp388_set_power_state(dev, *((uint32_t *)context));
|
||||
} else if (ctrl_command == DEVICE_PM_GET_POWER_STATE) {
|
||||
*((uint32_t *)context) = bmp388_get_power_state(dev);
|
||||
}
|
||||
|
||||
if (cb) {
|
||||
cb(dev, ret, context, arg);
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
#endif /* CONFIG_DEVICE_POWER_MANAGEMENT */
|
||||
|
||||
static const struct sensor_driver_api bmp388_api = {
|
||||
.attr_set = bmp388_attr_set,
|
||||
#ifdef CONFIG_BMP388_TRIGGER
|
||||
.trigger_set = bmp388_trigger_set,
|
||||
#endif
|
||||
.sample_fetch = bmp388_sample_fetch,
|
||||
.channel_get = bmp388_channel_get,
|
||||
};
|
||||
|
||||
static int bmp388_init(const struct device *dev)
|
||||
{
|
||||
struct bmp388_data *bmp388 = DEV_DATA(dev);
|
||||
const struct bmp388_config *cfg = DEV_CFG(dev);
|
||||
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->bus)) {
|
||||
LOG_ERR("Bus device is not ready");
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
#if DT_ANY_INST_ON_BUS_STATUS_OKAY(spi)
|
||||
/* Verify that the CS device is ready if it is set in the DT. */
|
||||
if (is_spi && (cfg->spi_cfg.cs != NULL)) {
|
||||
if (!device_is_ready(cfg->spi_cfg.cs->gpio_dev)) {
|
||||
LOG_ERR("SPI CS device 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) {
|
||||
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) {
|
||||
LOG_ERR("Failed to read chip id.");
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
if (val != BMP388_CHIP_ID) {
|
||||
LOG_ERR("Unsupported chip detected (0x%x)!", val);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_DEVICE_POWER_MANAGEMENT
|
||||
bmp388->device_power_state = DEVICE_PM_ACTIVE_STATE;
|
||||
#endif
|
||||
|
||||
/* Read calibration data */
|
||||
if (bmp388_get_calibration_data(dev) < 0) {
|
||||
LOG_ERR("Failed to read calibration data.");
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
/* Set ODR */
|
||||
if (bmp388_reg_field_update(dev,
|
||||
BMP388_REG_ODR,
|
||||
BMP388_ODR_MASK,
|
||||
bmp388->odr) < 0) {
|
||||
LOG_ERR("Failed to set ODR.");
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
/* 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) {
|
||||
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) {
|
||||
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) {
|
||||
LOG_ERR("Failed to enable sensors.");
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
#ifdef CONFIG_BMP388_TRIGGER
|
||||
if (bmp388_trigger_mode_init(dev) < 0) {
|
||||
LOG_ERR("Cannot set up trigger mode.");
|
||||
return -EINVAL;
|
||||
}
|
||||
#endif
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#define BMP388_BUS_CFG_I2C(inst) \
|
||||
.ops = &bmp388_i2c_ops, \
|
||||
.bus_addr = DT_INST_REG_ADDR(inst)
|
||||
|
||||
#define BMP388_BUS_CFG_SPI(inst) \
|
||||
.ops = &bmp388_spi_ops, \
|
||||
.spi_cfg = SPI_CONFIG_DT_INST(inst, SPI_OP_MODE_MASTER | SPI_WORD_SET(8), 0)
|
||||
|
||||
#define BMP388_BUS_CFG(inst) \
|
||||
COND_CODE_1(DT_INST_ON_BUS(inst, i2c), \
|
||||
(BMP388_BUS_CFG_I2C(inst)), \
|
||||
(BMP388_BUS_CFG_SPI(inst)))
|
||||
|
||||
#if defined(CONFIG_BMP388_TRIGGER)
|
||||
#define BMP388_INT_CFG(inst) \
|
||||
.gpio_int = GPIO_DT_SPEC_GET(DT_DRV_INST(inst), int_gpios),
|
||||
#else
|
||||
#define BMP388_INT_CFG(inst)
|
||||
#endif
|
||||
|
||||
#define BMP388_INST(inst) \
|
||||
static struct bmp388_data bmp388_data_##inst = { \
|
||||
.odr = DT_ENUM_IDX(DT_DRV_INST(inst), odr), \
|
||||
.osr_pressure = DT_ENUM_IDX(DT_DRV_INST(inst), osr_press), \
|
||||
.osr_temp = DT_ENUM_IDX(DT_DRV_INST(inst), osr_temp), \
|
||||
}; \
|
||||
static const struct bmp388_config bmp388_config_##inst = { \
|
||||
.bus = DEVICE_DT_GET(DT_INST_BUS(inst)), \
|
||||
BMP388_BUS_CFG(inst), \
|
||||
BMP388_INT_CFG(inst) \
|
||||
.iir_filter = DT_ENUM_IDX(DT_DRV_INST(inst), iir_filter), \
|
||||
}; \
|
||||
DEVICE_DT_INST_DEFINE( \
|
||||
inst, \
|
||||
bmp388_init, \
|
||||
bmp388_device_ctrl, \
|
||||
&bmp388_data_##inst, \
|
||||
&bmp388_config_##inst, \
|
||||
POST_KERNEL, \
|
||||
CONFIG_SENSOR_INIT_PRIORITY, \
|
||||
&bmp388_api);
|
||||
|
||||
DT_INST_FOREACH_STATUS_OKAY(BMP388_INST)
|
206
drivers/sensor/bmp388/bmp388.h
Normal file
206
drivers/sensor/bmp388/bmp388.h
Normal file
|
@ -0,0 +1,206 @@
|
|||
/* Bosch BMP388 pressure sensor
|
||||
*
|
||||
* Copyright (c) 2020 Facebook, Inc. and its affiliates
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* Datasheet:
|
||||
* https://www.bosch-sensortec.com/media/boschsensortec/downloads/datasheets/bst-bmp388-ds001.pdf
|
||||
*/
|
||||
|
||||
#ifndef __BMP388_H
|
||||
#define __BMP388_H
|
||||
|
||||
#include <drivers/gpio.h>
|
||||
#include <drivers/spi.h>
|
||||
#include <sys/util.h>
|
||||
|
||||
/* registers */
|
||||
#define BMP388_REG_CHIPID 0x00
|
||||
#define BMP388_REG_ERR_REG 0x02
|
||||
#define BMP388_REG_STATUS 0x03
|
||||
#define BMP388_REG_DATA0 0x04
|
||||
#define BMP388_REG_DATA1 0x05
|
||||
#define BMP388_REG_DATA2 0x06
|
||||
#define BMP388_REG_DATA3 0x07
|
||||
#define BMP388_REG_DATA4 0x08
|
||||
#define BMP388_REG_DATA5 0x09
|
||||
#define BMP388_REG_SENSORTIME0 0x0C
|
||||
#define BMP388_REG_SENSORTIME1 0x0D
|
||||
#define BMP388_REG_SENSORTIME2 0x0E
|
||||
#define BMP388_REG_SENSORTIME3 0x0F
|
||||
#define BMP388_REG_EVENT 0x10
|
||||
#define BMP388_REG_INT_STATUS 0x11
|
||||
#define BMP388_REG_FIFO_LENGTH0 0x12
|
||||
#define BMP388_REG_FIFO_LENGTH1 0x13
|
||||
#define BMP388_REG_FIFO_DATA 0x14
|
||||
#define BMP388_REG_FIFO_WTM0 0x15
|
||||
#define BMP388_REG_FIFO_WTM1 0x16
|
||||
#define BMP388_REG_FIFO_CONFIG1 0x17
|
||||
#define BMP388_REG_FIFO_CONFIG2 0x18
|
||||
#define BMP388_REG_INT_CTRL 0x19
|
||||
#define BMP388_REG_IF_CONF 0x1A
|
||||
#define BMP388_REG_PWR_CTRL 0x1B
|
||||
#define BMP388_REG_OSR 0x1C
|
||||
#define BMP388_REG_ODR 0x1D
|
||||
#define BMP388_REG_CONFIG 0x1F
|
||||
#define BMP388_REG_CALIB0 0x31
|
||||
#define BMP388_REG_CMD 0x7E
|
||||
|
||||
/* BMP388_REG_CHIPID */
|
||||
#define BMP388_CHIP_ID 0x50
|
||||
|
||||
/* BMP388_REG_STATUS */
|
||||
#define BMP388_STATUS_FATAL_ERR BIT(0)
|
||||
#define BMP388_STATUS_CMD_ERR BIT(1)
|
||||
#define BMP388_STATUS_CONF_ERR BIT(2)
|
||||
#define BMP388_STATUS_CMD_RDY BIT(4)
|
||||
#define BMP388_STATUS_DRDY_PRESS BIT(5)
|
||||
#define BMP388_STATUS_DRDY_TEMP BIT(6)
|
||||
|
||||
/* BMP388_REG_INT_CTRL */
|
||||
#define BMP388_INT_CTRL_DRDY_EN_POS 6
|
||||
#define BMP388_INT_CTRL_DRDY_EN_MASK BIT(6)
|
||||
|
||||
/* BMP388_REG_PWR_CTRL */
|
||||
#define BMP388_PWR_CTRL_PRESS_EN BIT(0)
|
||||
#define BMP388_PWR_CTRL_TEMP_EN BIT(1)
|
||||
#define BMP388_PWR_CTRL_MODE_POS 4
|
||||
#define BMP388_PWR_CTRL_MODE_MASK (0x03 << BMP388_PWR_CTRL_MODE_POS)
|
||||
#define BMP388_PWR_CTRL_MODE_SLEEP (0x00 << BMP388_PWR_CTRL_MODE_POS)
|
||||
#define BMP388_PWR_CTRL_MODE_FORCED (0x01 << BMP388_PWR_CTRL_MODE_POS)
|
||||
#define BMP388_PWR_CTRL_MODE_NORMAL (0x03 << BMP388_PWR_CTRL_MODE_POS)
|
||||
|
||||
/* BMP388_REG_OSR */
|
||||
#define BMP388_ODR_POS 0
|
||||
#define BMP388_ODR_MASK 0x1F
|
||||
|
||||
/* BMP388_REG_ODR */
|
||||
#define BMP388_OSR_PRESSURE_POS 0
|
||||
#define BMP388_OSR_PRESSURE_MASK (0x07 << BMP388_OSR_PRESSURE_POS)
|
||||
#define BMP388_OSR_TEMP_POS 3
|
||||
#define BMP388_OSR_TEMP_MASK (0x07 << BMP388_OSR_TEMP_POS)
|
||||
|
||||
/* BMP388_REG_CONFIG */
|
||||
#define BMP388_IIR_FILTER_POS 1
|
||||
#define BMP388_IIR_FILTER_MASK (0x7 << BMP388_IIR_FILTER_POS)
|
||||
|
||||
/* BMP388_REG_CMD */
|
||||
#define BMP388_CMD_FIFO_FLUSH 0xB0
|
||||
#define BMP388_CMD_SOFT_RESET 0xB6
|
||||
|
||||
/* default PWR_CTRL settings */
|
||||
#define BMP388_PWR_CTRL_ON \
|
||||
(BMP388_PWR_CTRL_PRESS_EN | \
|
||||
BMP388_PWR_CTRL_TEMP_EN | \
|
||||
BMP388_PWR_CTRL_MODE_NORMAL)
|
||||
#define BMP388_PWR_CTRL_OFF 0
|
||||
|
||||
#define BMP388_SAMPLE_BUFFER_SIZE (6)
|
||||
|
||||
struct bmp388_cal_data {
|
||||
uint16_t t1;
|
||||
uint16_t t2;
|
||||
int8_t t3;
|
||||
int16_t p1;
|
||||
int16_t p2;
|
||||
int8_t p3;
|
||||
int8_t p4;
|
||||
uint16_t p5;
|
||||
uint16_t p6;
|
||||
int8_t p7;
|
||||
int8_t p8;
|
||||
int16_t p9;
|
||||
int8_t p10;
|
||||
int8_t p11;
|
||||
} __packed;
|
||||
|
||||
struct bmp388_sample {
|
||||
uint32_t press;
|
||||
uint32_t raw_temp;
|
||||
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 device *bus;
|
||||
const struct bmp388_io_ops *ops;
|
||||
union {
|
||||
#if DT_ANY_INST_ON_BUS_STATUS_OKAY(spi)
|
||||
struct spi_config spi_cfg;
|
||||
#endif
|
||||
#if DT_ANY_INST_ON_BUS_STATUS_OKAY(i2c)
|
||||
uint16_t bus_addr;
|
||||
#endif
|
||||
};
|
||||
|
||||
#ifdef CONFIG_BMP388_TRIGGER
|
||||
struct gpio_dt_spec gpio_int;
|
||||
#endif
|
||||
|
||||
uint8_t iir_filter;
|
||||
};
|
||||
|
||||
struct bmp388_data {
|
||||
uint8_t odr;
|
||||
uint8_t osr_pressure;
|
||||
uint8_t osr_temp;
|
||||
struct bmp388_cal_data cal;
|
||||
|
||||
#ifdef CONFIG_DEVICE_POWER_MANAGEMENT
|
||||
uint32_t device_power_state;
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_BMP388_TRIGGER)
|
||||
struct gpio_callback gpio_cb;
|
||||
#endif
|
||||
|
||||
struct bmp388_sample sample;
|
||||
|
||||
#ifdef CONFIG_BMP388_TRIGGER_OWN_THREAD
|
||||
struct k_sem sem;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_BMP388_TRIGGER_GLOBAL_THREAD
|
||||
struct k_work work;
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_BMP388_TRIGGER_GLOBAL_THREAD) || \
|
||||
defined(CONFIG_BMP388_TRIGGER_DIRECT)
|
||||
const struct device *dev;
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_BMP388_TRIGGER
|
||||
sensor_trigger_handler_t handler_drdy;
|
||||
#endif /* CONFIG_BMP388_TRIGGER */
|
||||
};
|
||||
|
||||
#define DEV_DATA(dev) ((struct bmp388_data *)dev->data)
|
||||
#define DEV_CFG(dev) ((const struct bmp388_config *)dev->config)
|
||||
|
||||
int bmp388_trigger_mode_init(const struct device *dev);
|
||||
int bmp388_trigger_set(const struct device *dev,
|
||||
const struct sensor_trigger *trig,
|
||||
sensor_trigger_handler_t handler);
|
||||
int bmp388_reg_field_update(const struct device *dev,
|
||||
uint8_t reg,
|
||||
uint8_t mask,
|
||||
uint8_t val);
|
||||
|
||||
#endif /* __BMP388_H */
|
163
drivers/sensor/bmp388/bmp388_trigger.c
Normal file
163
drivers/sensor/bmp388/bmp388_trigger.c
Normal file
|
@ -0,0 +1,163 @@
|
|||
/* Bosch BMP388 pressure sensor
|
||||
*
|
||||
* Copyright (c) 2020 Facebook, Inc. and its affiliates
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*
|
||||
* Datasheet:
|
||||
* https://www.bosch-sensortec.com/media/boschsensortec/downloads/datasheets/bst-bmp388-ds001.pdf
|
||||
*/
|
||||
|
||||
#define DT_DRV_COMPAT bosch_bmp388
|
||||
|
||||
#include <kernel.h>
|
||||
#include <drivers/sensor.h>
|
||||
#include <drivers/gpio.h>
|
||||
#include <logging/log.h>
|
||||
|
||||
#include "bmp388.h"
|
||||
|
||||
LOG_MODULE_DECLARE(BMP388, CONFIG_SENSOR_LOG_LEVEL);
|
||||
|
||||
static void bmp388_handle_interrupts(const void *arg)
|
||||
{
|
||||
const struct device *dev = (const struct device *)arg;
|
||||
struct bmp388_data *data = DEV_DATA(dev);
|
||||
|
||||
struct sensor_trigger drdy_trigger = {
|
||||
.type = SENSOR_TRIG_DATA_READY,
|
||||
.chan = SENSOR_CHAN_PRESS,
|
||||
};
|
||||
|
||||
if (data->handler_drdy) {
|
||||
data->handler_drdy(dev, &drdy_trigger);
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef CONFIG_BMP388_TRIGGER_OWN_THREAD
|
||||
static K_THREAD_STACK_DEFINE(bmp388_thread_stack,
|
||||
CONFIG_BMP388_THREAD_STACK_SIZE);
|
||||
static struct k_thread bmp388_thread;
|
||||
|
||||
static void bmp388_thread_main(void *arg1, void *unused1, void *unused2)
|
||||
{
|
||||
ARG_UNUSED(unused1);
|
||||
ARG_UNUSED(unused2);
|
||||
const struct device *dev = (const struct device *)arg1;
|
||||
struct bmp388_data *data = DEV_DATA(dev);
|
||||
|
||||
while (1) {
|
||||
k_sem_take(&data->sem, K_FOREVER);
|
||||
bmp388_handle_interrupts(dev);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_BMP388_TRIGGER_GLOBAL_THREAD
|
||||
static void bmp388_work_handler(struct k_work *work)
|
||||
{
|
||||
struct bmp388_data *data = CONTAINER_OF(work,
|
||||
struct bmp388_data,
|
||||
work);
|
||||
|
||||
bmp388_handle_interrupts(data->dev);
|
||||
}
|
||||
#endif
|
||||
|
||||
static void bmp388_gpio_callback(const struct device *port,
|
||||
struct gpio_callback *cb,
|
||||
uint32_t pin)
|
||||
{
|
||||
struct bmp388_data *data = CONTAINER_OF(cb,
|
||||
struct bmp388_data,
|
||||
gpio_cb);
|
||||
|
||||
ARG_UNUSED(port);
|
||||
ARG_UNUSED(pin);
|
||||
|
||||
#if defined(CONFIG_BMP388_TRIGGER_OWN_THREAD)
|
||||
k_sem_give(&data->sem);
|
||||
#elif defined(CONFIG_BMP388_TRIGGER_GLOBAL_THREAD)
|
||||
k_work_submit(&data->work);
|
||||
#elif defined(CONFIG_BMP388_TRIGGER_DIRECT)
|
||||
bmp388_handle_interrupts(data->dev);
|
||||
#endif
|
||||
}
|
||||
|
||||
int bmp388_trigger_set(
|
||||
const struct device *dev,
|
||||
const struct sensor_trigger *trig,
|
||||
sensor_trigger_handler_t handler)
|
||||
{
|
||||
struct bmp388_data *data = DEV_DATA(dev);
|
||||
|
||||
#ifdef CONFIG_DEVICE_POWER_MANAGEMENT
|
||||
if (data->device_power_state != DEVICE_PM_ACTIVE_STATE) {
|
||||
return -EBUSY;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (trig->type != SENSOR_TRIG_DATA_READY) {
|
||||
return -ENOTSUP;
|
||||
}
|
||||
|
||||
if (bmp388_reg_field_update(
|
||||
dev,
|
||||
BMP388_REG_INT_CTRL,
|
||||
BMP388_INT_CTRL_DRDY_EN_MASK,
|
||||
(handler != NULL) << BMP388_INT_CTRL_DRDY_EN_POS) < 0) {
|
||||
LOG_ERR("Failed to enable DRDY interrupt");
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
data->handler_drdy = handler;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int bmp388_trigger_mode_init(const struct device *dev)
|
||||
{
|
||||
struct bmp388_data *data = DEV_DATA(dev);
|
||||
const struct bmp388_config *cfg = DEV_CFG(dev);
|
||||
|
||||
if (!device_is_ready(cfg->gpio_int.port)) {
|
||||
LOG_ERR("INT device is not ready");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
#if defined(CONFIG_BMP388_TRIGGER_OWN_THREAD)
|
||||
k_sem_init(&data->sem, 0, 1);
|
||||
k_thread_create(
|
||||
&bmp388_thread,
|
||||
bmp388_thread_stack,
|
||||
CONFIG_BMP388_THREAD_STACK_SIZE,
|
||||
bmp388_thread_main,
|
||||
(void *)dev,
|
||||
NULL,
|
||||
NULL,
|
||||
K_PRIO_COOP(CONFIG_BMP388_THREAD_PRIORITY),
|
||||
0,
|
||||
K_NO_WAIT);
|
||||
#elif defined(CONFIG_BMP388_TRIGGER_GLOBAL_THREAD)
|
||||
data->work.handler = bmp388_work_handler;
|
||||
#endif
|
||||
|
||||
#if defined(CONFIG_BMP388_TRIGGER_GLOBAL_THREAD) || \
|
||||
defined(CONFIG_BMP388_TRIGGER_DIRECT)
|
||||
data->dev = dev;
|
||||
#endif
|
||||
|
||||
gpio_pin_configure(cfg->gpio_int.port,
|
||||
cfg->gpio_int.pin,
|
||||
GPIO_INPUT | cfg->gpio_int.dt_flags);
|
||||
|
||||
gpio_init_callback(&data->gpio_cb,
|
||||
bmp388_gpio_callback,
|
||||
BIT(cfg->gpio_int.pin));
|
||||
gpio_add_callback(cfg->gpio_int.port, &data->gpio_cb);
|
||||
gpio_pin_interrupt_configure(cfg->gpio_int.port,
|
||||
cfg->gpio_int.pin,
|
||||
GPIO_INT_EDGE_TO_ACTIVE);
|
||||
|
||||
return 0;
|
||||
}
|
9
dts/bindings/sensor/bosch,bmp388-i2c.yaml
Normal file
9
dts/bindings/sensor/bosch,bmp388-i2c.yaml
Normal file
|
@ -0,0 +1,9 @@
|
|||
# Copyright (c) 2020 Facebook, Inc. and its affiliates
|
||||
# SPDX-License-Identifier: Apache-2.0
|
||||
|
||||
description: |
|
||||
Bosch BMP388 pressure sensor accessed through I2C bus
|
||||
|
||||
compatible: "bosch,bmp388"
|
||||
|
||||
include: [i2c-device.yaml, "bosch,bmp388.yaml"]
|
9
dts/bindings/sensor/bosch,bmp388-spi.yaml
Normal file
9
dts/bindings/sensor/bosch,bmp388-spi.yaml
Normal file
|
@ -0,0 +1,9 @@
|
|||
# Copyright (c) 2020 Facebook, Inc. and its affiliates
|
||||
# SPDX-License-Identifier: Apache-2.0
|
||||
|
||||
description: |
|
||||
Bosch BMP388 pressure sensor accessed through SPI bus
|
||||
|
||||
compatible: "bosch,bmp388"
|
||||
|
||||
include: [spi-device.yaml, "bosch,bmp388.yaml"]
|
109
dts/bindings/sensor/bosch,bmp388.yaml
Normal file
109
dts/bindings/sensor/bosch,bmp388.yaml
Normal file
|
@ -0,0 +1,109 @@
|
|||
# Copyright (c) 2020 Facebook, Inc. and its affiliates
|
||||
# SPDX-License-Identifier: Apache-2.0
|
||||
|
||||
# Common fields for BMP388
|
||||
|
||||
properties:
|
||||
int-gpios:
|
||||
type: phandle-array
|
||||
required: false
|
||||
|
||||
odr:
|
||||
type: string
|
||||
required: false
|
||||
description: |
|
||||
Default output data rate in Hz. Only the following values are allowed:
|
||||
200 - 200 - 5ms (default; chip reset value)
|
||||
100 - 100 - 10ms
|
||||
50 - 50 - 20ms
|
||||
25 - 25 - 40ms
|
||||
12.5 - 25/2 - 80ms
|
||||
6.25 - 25/4 - 160ms
|
||||
3.125 - 25/8 - 320ms
|
||||
1.563 - 25/16 - 640ms
|
||||
.781 - 25/32 - 1.28s
|
||||
.391 - 25/64 - 2.56s
|
||||
.195 - 25/128 - 5.12s
|
||||
.098 - 25/256 - 10.24s
|
||||
.049 - 25/512 - 20.48s
|
||||
.024 - 25/1024 - 40.96s
|
||||
.012 - 25/2048 - 81.92s
|
||||
.006 - 25/4096 - 163.84s
|
||||
.003 - 25/8192 - 327.68s
|
||||
default: "200"
|
||||
enum:
|
||||
- "200"
|
||||
- "100"
|
||||
- "50"
|
||||
- "25"
|
||||
- "12.5"
|
||||
- "6.25"
|
||||
- "3.125"
|
||||
- "1.563"
|
||||
- ".781"
|
||||
- ".391"
|
||||
- ".195"
|
||||
- ".098"
|
||||
- ".049"
|
||||
- ".024"
|
||||
- ".012"
|
||||
- ".006"
|
||||
- ".003"
|
||||
|
||||
osr-press:
|
||||
type: int
|
||||
required: false
|
||||
description: |
|
||||
Default pressure oversampling rate. Only the following values are
|
||||
allowed:
|
||||
1 sample, 16-bit, 2.64 Pa
|
||||
2 samples, 17-bit, 1.32 Pa
|
||||
4 samples, 18-bit, 0.66 Pa (default; chip reset value)
|
||||
8 samples, 19-bit, 0.33 Pa
|
||||
16 samples, 20-bit, 0.17 Pa
|
||||
32 Samples, 21-bit, 0.085 Pa
|
||||
default: 4
|
||||
enum:
|
||||
- 1
|
||||
- 2
|
||||
- 4
|
||||
- 8
|
||||
- 16
|
||||
- 32
|
||||
|
||||
osr-temp:
|
||||
type: int
|
||||
required: false
|
||||
description: |
|
||||
Default temperature oversampling rate. Only the following values are
|
||||
allowed:
|
||||
1 sample, 16-bit, .0050 C (default; chip reset value)
|
||||
2 samples, 17-bit, .0025 C
|
||||
4 samples, 18-bit, .0012 C
|
||||
8 samples, 19-bit, .0006 C
|
||||
16 samples, 20-bit, .0003 C
|
||||
32 Samples, 21-bit, .00015 C
|
||||
default: 1
|
||||
enum:
|
||||
- 1
|
||||
- 2
|
||||
- 4
|
||||
- 8
|
||||
- 16
|
||||
- 32
|
||||
|
||||
iir-filter:
|
||||
type: int
|
||||
required: false
|
||||
description: |
|
||||
Default IIR filter coefficient. The default 0 is the chip reset value.
|
||||
default: 0
|
||||
enum:
|
||||
- 0
|
||||
- 1
|
||||
- 3
|
||||
- 7
|
||||
- 15
|
||||
- 31
|
||||
- 63
|
||||
- 127
|
|
@ -610,3 +610,10 @@ test_i2c_fdc2x1x: fdc2x1x@2a {
|
|||
inductance = <18>;
|
||||
};
|
||||
};
|
||||
|
||||
test_i2c_bmp388: bmp388@4c {
|
||||
compatible = "bosch,bmp388";
|
||||
label = "BMP388";
|
||||
reg = <0x4c>;
|
||||
int-gpios = <&test_gpio 0 0>;
|
||||
};
|
||||
|
|
|
@ -21,6 +21,7 @@ CONFIG_BMG160=y
|
|||
CONFIG_BMI160=y
|
||||
CONFIG_BMI270=y
|
||||
CONFIG_BMM150=y
|
||||
CONFIG_BMP388=y
|
||||
CONFIG_BQ274XX=y
|
||||
CONFIG_CCS811=y
|
||||
CONFIG_DHT=y
|
||||
|
|
|
@ -581,3 +581,11 @@ test_spi_bmi270: bmi270@39 {
|
|||
reg = <0x39>;
|
||||
spi-max-frequency = <0>;
|
||||
};
|
||||
|
||||
test_spi_bmp388: bmp388@3a {
|
||||
compatible = "bosch,bmp388";
|
||||
label = "BMP388";
|
||||
reg = <0x3a>;
|
||||
spi-max-frequency = <0>;
|
||||
int-gpios = <&test_gpio 0 0>;
|
||||
};
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue