sensor: dts: Add SPI capability to bmi270 driver

Added SPI bus support for BMI270 gyroscope driver.

Signed-off-by: Dominik Chat <dominik.chat@nordicsemi.no>
This commit is contained in:
Dominik Chat 2022-08-18 14:22:10 +02:00 committed by Carles Cufí
parent f0a85f69ad
commit 6cbb84c3ee
9 changed files with 336 additions and 72 deletions

View file

@ -1,5 +1,6 @@
#
# Copyright (c) 2021 Bosch Sensortec GmbH
# Copyright (c) 2022 Nordic Semiconductor ASA
#
# SPDX-License-Identifier: Apache-2.0
#
@ -7,3 +8,5 @@
zephyr_library()
zephyr_library_sources(bmi270.c)
zephyr_library_sources_ifdef(CONFIG_BMI270_BUS_I2C bmi270_i2c.c)
zephyr_library_sources_ifdef(CONFIG_BMI270_BUS_SPI bmi270_spi.c)

View file

@ -1,12 +1,28 @@
# BMI270 6 Axis IMU configuration
# Copyright (c) 2021 Bosch Sensortec GmbH
# Copyright (c) 2022 Nordic Semiconductor ASA
# SPDX-License-Identifier: Apache-2.0
config BMI270
menuconfig BMI270
bool "BMI270 Inertial measurement unit"
default y
depends on DT_HAS_BOSCH_BMI270_ENABLED
select I2C
select I2C if $(dt_compat_on_bus,$(DT_COMPAT_BOSCH_BMI270),i2c)
select SPI if $(dt_compat_on_bus,$(DT_COMPAT_BOSCH_BMI270),spi)
help
Enable driver for BMI270 I2C-based imu sensor
if BMI270
config BMI270_BUS_I2C
bool
default y
depends on $(dt_compat_on_bus,$(DT_COMPAT_BOSCH_BMI270),i2c)
config BMI270_BUS_SPI
bool
default y
depends on $(dt_compat_on_bus,$(DT_COMPAT_BOSCH_BMI270),spi)
endif # BMI270

View file

@ -1,12 +1,12 @@
/*
* Copyright (c) 2021 Bosch Sensortec GmbH
* Copyright (c) 2022 Nordic Semiconductor ASA
*
* SPDX-License-Identifier: Apache-2.0
*/
#define DT_DRV_COMPAT bosch_bmi270
#include <zephyr/drivers/i2c.h>
#include <zephyr/drivers/sensor.h>
#include <zephyr/init.h>
#include <zephyr/sys/__assert.h>
@ -23,26 +23,49 @@ LOG_MODULE_REGISTER(bmi270, CONFIG_SENSOR_LOG_LEVEL);
#define BMI270_CONFIG_FILE_POLL_PERIOD_US 10000
#define BMI270_INTER_WRITE_DELAY_US 1000
static int reg_read(const struct device *dev, uint8_t reg, uint8_t *data, uint16_t length)
{
const struct bmi270_dev_config *cfg = dev->config;
struct bmi270_config {
union bmi270_bus bus;
const struct bmi270_bus_io *bus_io;
};
return i2c_burst_read_dt(&cfg->i2c, reg, data, length);
static inline int bmi270_bus_check(const struct device *dev)
{
const struct bmi270_config *cfg = dev->config;
return cfg->bus_io->check(&cfg->bus);
}
static int reg_write(const struct device *dev, uint8_t reg, const uint8_t *data, uint16_t length)
static inline int bmi270_bus_init(const struct device *dev)
{
const struct bmi270_dev_config *cfg = dev->config;
const struct bmi270_config *cfg = dev->config;
return i2c_burst_write_dt(&cfg->i2c, reg, data, length);
return cfg->bus_io->init(&cfg->bus);
}
static int reg_write_with_delay(const struct device *dev, uint8_t reg, const uint8_t *data,
uint16_t length, uint32_t delay_us)
static int bmi270_reg_read(const struct device *dev, uint8_t reg, uint8_t *data, uint16_t length)
{
const struct bmi270_config *cfg = dev->config;
return cfg->bus_io->read(&cfg->bus, reg, data, length);
}
static int bmi270_reg_write(const struct device *dev, uint8_t reg,
const uint8_t *data, uint16_t length)
{
const struct bmi270_config *cfg = dev->config;
return cfg->bus_io->write(&cfg->bus, reg, data, length);
}
static int bmi270_reg_write_with_delay(const struct device *dev,
uint8_t reg,
const uint8_t *data,
uint16_t length,
uint32_t delay_us)
{
int ret = 0;
ret = reg_write(dev, reg, data, length);
ret = bmi270_reg_write(dev, reg, data, length);
if (ret == 0) {
k_usleep(delay_us);
}
@ -125,12 +148,12 @@ static int set_accel_odr_osr(const struct device *dev, const struct sensor_value
int ret = 0;
if (odr || osr) {
ret = reg_read(dev, BMI270_REG_ACC_CONF, &acc_conf, 1);
ret = bmi270_reg_read(dev, BMI270_REG_ACC_CONF, &acc_conf, 1);
if (ret != 0) {
return ret;
}
ret = reg_read(dev, BMI270_REG_PWR_CTRL, &pwr_ctrl, 1);
ret = bmi270_reg_read(dev, BMI270_REG_PWR_CTRL, &pwr_ctrl, 1);
if (ret != 0) {
return ret;
}
@ -221,7 +244,7 @@ static int set_accel_odr_osr(const struct device *dev, const struct sensor_value
}
if (odr || osr) {
ret = reg_write(dev, BMI270_REG_ACC_CONF, &acc_conf, 1);
ret = bmi270_reg_write(dev, BMI270_REG_ACC_CONF, &acc_conf, 1);
if (ret != 0) {
return ret;
}
@ -230,8 +253,9 @@ static int set_accel_odr_osr(const struct device *dev, const struct sensor_value
k_usleep(BMI270_TRANSC_DELAY_SUSPEND);
pwr_ctrl &= BMI270_PWR_CTRL_MSK;
ret = reg_write_with_delay(dev, BMI270_REG_PWR_CTRL, &pwr_ctrl, 1,
BMI270_INTER_WRITE_DELAY_US);
ret = bmi270_reg_write_with_delay(dev, BMI270_REG_PWR_CTRL,
&pwr_ctrl, 1,
BMI270_INTER_WRITE_DELAY_US);
}
return ret;
@ -243,7 +267,7 @@ static int set_accel_range(const struct device *dev, const struct sensor_value *
int ret = 0;
uint8_t acc_range, reg;
ret = reg_read(dev, BMI270_REG_ACC_RANGE, &acc_range, 1);
ret = bmi270_reg_read(dev, BMI270_REG_ACC_RANGE, &acc_range, 1);
if (ret != 0) {
return ret;
}
@ -272,8 +296,8 @@ static int set_accel_range(const struct device *dev, const struct sensor_value *
acc_range = BMI270_SET_BITS_POS_0(acc_range, BMI270_ACC_RANGE,
reg);
ret = reg_write_with_delay(dev, BMI270_REG_ACC_RANGE, &acc_range, 1,
BMI270_INTER_WRITE_DELAY_US);
ret = bmi270_reg_write_with_delay(dev, BMI270_REG_ACC_RANGE, &acc_range,
1, BMI270_INTER_WRITE_DELAY_US);
return ret;
}
@ -312,12 +336,12 @@ static int set_gyro_odr_osr(const struct device *dev, const struct sensor_value
int ret = 0;
if (odr || osr) {
ret = reg_read(dev, BMI270_REG_GYR_CONF, &gyr_conf, 1);
ret = bmi270_reg_read(dev, BMI270_REG_GYR_CONF, &gyr_conf, 1);
if (ret != 0) {
return ret;
}
ret = reg_read(dev, BMI270_REG_PWR_CTRL, &pwr_ctrl, 1);
ret = bmi270_reg_read(dev, BMI270_REG_PWR_CTRL, &pwr_ctrl, 1);
if (ret != 0) {
return ret;
}
@ -379,7 +403,7 @@ static int set_gyro_odr_osr(const struct device *dev, const struct sensor_value
}
if (odr || osr) {
ret = reg_write(dev, BMI270_REG_GYR_CONF, &gyr_conf, 1);
ret = bmi270_reg_write(dev, BMI270_REG_GYR_CONF, &gyr_conf, 1);
if (ret != 0) {
return ret;
}
@ -388,8 +412,9 @@ static int set_gyro_odr_osr(const struct device *dev, const struct sensor_value
k_usleep(BMI270_TRANSC_DELAY_SUSPEND);
pwr_ctrl &= BMI270_PWR_CTRL_MSK;
ret = reg_write_with_delay(dev, BMI270_REG_PWR_CTRL, &pwr_ctrl, 1,
BMI270_INTER_WRITE_DELAY_US);
ret = bmi270_reg_write_with_delay(dev, BMI270_REG_PWR_CTRL,
&pwr_ctrl, 1,
BMI270_INTER_WRITE_DELAY_US);
}
return ret;
@ -401,7 +426,7 @@ static int set_gyro_range(const struct device *dev, const struct sensor_value *r
int ret = 0;
uint8_t gyr_range, reg;
ret = reg_read(dev, BMI270_REG_GYR_RANGE, &gyr_range, 1);
ret = bmi270_reg_read(dev, BMI270_REG_GYR_RANGE, &gyr_range, 1);
if (ret != 0) {
return ret;
}
@ -433,8 +458,8 @@ static int set_gyro_range(const struct device *dev, const struct sensor_value *r
}
gyr_range = BMI270_SET_BITS_POS_0(gyr_range, BMI270_GYR_RANGE, reg);
ret = reg_write_with_delay(dev, BMI270_REG_GYR_RANGE, &gyr_range, 1,
BMI270_INTER_WRITE_DELAY_US);
ret = bmi270_reg_write_with_delay(dev, BMI270_REG_GYR_RANGE, &gyr_range,
1, BMI270_INTER_WRITE_DELAY_US);
return ret;
}
@ -454,13 +479,16 @@ static int8_t write_config_file(const struct device *dev)
/* Store 4 to 11 bits of address in the second byte */
addr_array[1] = (uint8_t)((index / 2) >> 4);
ret = reg_write_with_delay(dev, BMI270_REG_INIT_ADDR_0, addr_array, 2,
BMI270_INTER_WRITE_DELAY_US);
ret = bmi270_reg_write_with_delay(dev, BMI270_REG_INIT_ADDR_0,
addr_array, 2,
BMI270_INTER_WRITE_DELAY_US);
if (ret == 0) {
ret = reg_write_with_delay(dev, BMI270_REG_INIT_DATA,
(bmi270_config_file + index),
BMI270_WR_LEN, BMI270_INTER_WRITE_DELAY_US);
ret = bmi270_reg_write_with_delay(dev,
BMI270_REG_INIT_DATA,
(bmi270_config_file + index),
BMI270_WR_LEN,
BMI270_INTER_WRITE_DELAY_US);
}
}
@ -477,7 +505,7 @@ static int bmi270_sample_fetch(const struct device *dev, enum sensor_channel cha
return -ENOTSUP;
}
ret = reg_read(dev, BMI270_REG_ACC_X_LSB, data, 12);
ret = bmi270_reg_read(dev, BMI270_REG_ACC_X_LSB, data, 12);
if (ret == 0) {
drv_dev->ax = (int16_t)sys_get_le16(&data[0]);
drv_dev->ay = (int16_t)sys_get_le16(&data[2]);
@ -584,7 +612,6 @@ static int bmi270_init(const struct device *dev)
{
int ret;
struct bmi270_data *drv_dev = dev->data;
const struct bmi270_dev_config *cfg = dev->config;
uint8_t chip_id;
uint8_t soft_reset_cmd;
uint8_t init_ctrl;
@ -592,9 +619,10 @@ static int bmi270_init(const struct device *dev)
uint8_t tries;
uint8_t adv_pwr_save;
if (!device_is_ready(cfg->i2c.bus)) {
LOG_ERR("I2C bus device not ready");
return -ENODEV;
ret = bmi270_bus_check(dev);
if (ret < 0) {
LOG_ERR("Could not initialize bus");
return ret;
}
drv_dev->acc_odr = BMI270_ACC_ODR_100_HZ;
@ -604,7 +632,13 @@ static int bmi270_init(const struct device *dev)
k_usleep(BMI270_POWER_ON_TIME);
ret = reg_read(dev, BMI270_REG_CHIP_ID, &chip_id, 1);
ret = bmi270_bus_init(dev);
if (ret != 0) {
LOG_ERR("Could not initiate bus communication");
return ret;
}
ret = bmi270_reg_read(dev, BMI270_REG_CHIP_ID, &chip_id, 1);
if (ret != 0) {
return ret;
}
@ -616,14 +650,14 @@ static int bmi270_init(const struct device *dev)
}
soft_reset_cmd = BMI270_CMD_SOFT_RESET;
ret = reg_write(dev, BMI270_REG_CMD, &soft_reset_cmd, 1);
ret = bmi270_reg_write(dev, BMI270_REG_CMD, &soft_reset_cmd, 1);
if (ret != 0) {
return ret;
}
k_usleep(BMI270_SOFT_RESET_TIME);
ret = reg_read(dev, BMI270_REG_PWR_CONF, &adv_pwr_save, 1);
ret = bmi270_reg_read(dev, BMI270_REG_PWR_CONF, &adv_pwr_save, 1);
if (ret != 0) {
return ret;
}
@ -631,14 +665,15 @@ static int bmi270_init(const struct device *dev)
adv_pwr_save = BMI270_SET_BITS_POS_0(adv_pwr_save,
BMI270_PWR_CONF_ADV_PWR_SAVE,
BMI270_PWR_CONF_ADV_PWR_SAVE_DIS);
ret = reg_write_with_delay(dev, BMI270_REG_PWR_CONF, &adv_pwr_save, 1,
BMI270_INTER_WRITE_DELAY_US);
ret = bmi270_reg_write_with_delay(dev, BMI270_REG_PWR_CONF,
&adv_pwr_save, 1,
BMI270_INTER_WRITE_DELAY_US);
if (ret != 0) {
return ret;
}
init_ctrl = BMI270_PREPARE_CONFIG_LOAD;
ret = reg_write(dev, BMI270_REG_INIT_CTRL, &init_ctrl, 1);
ret = bmi270_reg_write(dev, BMI270_REG_INIT_CTRL, &init_ctrl, 1);
if (ret != 0) {
return ret;
}
@ -650,18 +685,18 @@ static int bmi270_init(const struct device *dev)
}
init_ctrl = BMI270_COMPLETE_CONFIG_LOAD;
ret = reg_write(dev, BMI270_REG_INIT_CTRL, &init_ctrl, 1);
ret = bmi270_reg_write(dev, BMI270_REG_INIT_CTRL, &init_ctrl, 1);
if (ret != 0) {
return ret;
}
/* Timeout after BMI270_CONFIG_FILE_RETRIES x
* BMI270_CONFIG_FILE_POLL_PERIOD_US microseconds.
* If tries is 0 by the end of the loop,
* If tries is BMI270_CONFIG_FILE_RETRIES by the end of the loop,
* report an error
*/
for (tries = 0; tries <= BMI270_CONFIG_FILE_RETRIES; tries++) {
ret = reg_read(dev, BMI270_REG_INTERNAL_STATUS, &msg, 1);
ret = bmi270_reg_read(dev, BMI270_REG_INTERNAL_STATUS, &msg, 1);
if (ret != 0) {
return ret;
}
@ -674,15 +709,16 @@ static int bmi270_init(const struct device *dev)
k_usleep(BMI270_CONFIG_FILE_POLL_PERIOD_US);
}
if (tries == 0) {
if (tries == BMI270_CONFIG_FILE_RETRIES) {
return -EIO;
}
adv_pwr_save = BMI270_SET_BITS_POS_0(adv_pwr_save,
BMI270_PWR_CONF_ADV_PWR_SAVE,
BMI270_PWR_CONF_ADV_PWR_SAVE_EN);
ret = reg_write_with_delay(dev, BMI270_REG_PWR_CONF, &adv_pwr_save, 1,
BMI270_INTER_WRITE_DELAY_US);
ret = bmi270_reg_write_with_delay(dev, BMI270_REG_PWR_CONF,
&adv_pwr_save, 1,
BMI270_INTER_WRITE_DELAY_US);
return ret;
}
@ -693,21 +729,38 @@ static const struct sensor_driver_api bmi270_driver_api = {
.attr_set = bmi270_attr_set
};
#define BMI270_CREATE_INST(inst) \
\
static struct bmi270_data bmi270_drv_##inst; \
\
static const struct bmi270_dev_config bmi270_config_##inst = { \
.i2c = I2C_DT_SPEC_INST_GET(inst), \
}; \
\
DEVICE_DT_INST_DEFINE(inst, \
bmi270_init, \
NULL, \
&bmi270_drv_##inst, \
&bmi270_config_##inst, \
POST_KERNEL, \
CONFIG_SENSOR_INIT_PRIORITY, \
/* Initializes a struct bmi270_config for an instance on a SPI bus. */
#define BMI270_CONFIG_SPI(inst) \
{ \
.bus.spi = SPI_DT_SPEC_INST_GET( \
inst, BMI270_SPI_OPERATION, 0), \
.bus_io = &bmi270_bus_io_spi, \
}
/* Initializes a struct bmi270_config for an instance on an I2C bus. */
#define BMI270_CONFIG_I2C(inst) \
{ \
.bus.i2c = I2C_DT_SPEC_INST_GET(inst), \
.bus_io = &bmi270_bus_io_i2c, \
}
#define BMI270_CREATE_INST(inst) \
\
static struct bmi270_data bmi270_drv_##inst; \
\
static const struct bmi270_config bmi270_config_##inst = \
COND_CODE_1(DT_INST_ON_BUS(inst, spi), \
(BMI270_CONFIG_SPI(inst)), \
(BMI270_CONFIG_I2C(inst))); \
\
DEVICE_DT_INST_DEFINE(inst, \
bmi270_init, \
NULL, \
&bmi270_drv_##inst, \
&bmi270_config_##inst, \
POST_KERNEL, \
CONFIG_SENSOR_INIT_PRIORITY, \
&bmi270_driver_api);
DT_INST_FOREACH_STATUS_OKAY(BMI270_CREATE_INST)

View file

@ -1,5 +1,6 @@
/*
* Copyright (c) 2021 Bosch Sensortec GmbH
* Copyright (c) 2022 Nordic Semiconductor ASA
*
* SPDX-License-Identifier: Apache-2.0
*/
@ -11,7 +12,9 @@
#include <zephyr/sys/util.h>
#include <zephyr/types.h>
#include <zephyr/drivers/sensor.h>
#include <zephyr/drivers/spi.h>
#include <zephyr/drivers/i2c.h>
#include <zephyr/devicetree.h>
#define BMI270_REG_CHIP_ID 0x00
#define BMI270_REG_ERROR 0x02
@ -67,6 +70,7 @@
#define BMI270_REG_PWR_CONF 0x7C
#define BMI270_REG_PWR_CTRL 0x7D
#define BMI270_REG_CMD 0x7E
#define BMI270_REG_MASK GENMASK(6, 0)
#define BMI270_CHIP_ID 0x24
@ -206,8 +210,41 @@ struct bmi270_data {
uint16_t gyr_range;
};
struct bmi270_dev_config {
union bmi270_bus {
#if CONFIG_BMI270_BUS_SPI
struct spi_dt_spec spi;
#endif
#if CONFIG_BMI270_BUS_I2C
struct i2c_dt_spec i2c;
#endif
};
typedef int (*bmi270_bus_check_fn)(const union bmi270_bus *bus);
typedef int (*bmi270_bus_init_fn)(const union bmi270_bus *bus);
typedef int (*bmi270_reg_read_fn)(const union bmi270_bus *bus,
uint8_t start,
uint8_t *data,
uint16_t len);
typedef int (*bmi270_reg_write_fn)(const union bmi270_bus *bus,
uint8_t start,
const uint8_t *data,
uint16_t len);
struct bmi270_bus_io {
bmi270_bus_check_fn check;
bmi270_reg_read_fn read;
bmi270_reg_write_fn write;
bmi270_bus_init_fn init;
};
#if CONFIG_BMI270_BUS_SPI
#define BMI270_SPI_OPERATION (SPI_WORD_SET(8) | SPI_TRANSFER_MSB)
#define BMI270_SPI_ACC_DELAY_US 2
extern const struct bmi270_bus_io bmi270_bus_io_spi;
#endif
#if CONFIG_BMI270_BUS_I2C
extern const struct bmi270_bus_io bmi270_bus_io_i2c;
#endif
#endif /* ZEPHYR_DRIVERS_SENSOR_BMI270_BMI270_H_ */

View file

@ -0,0 +1,42 @@
/*
* Copyright (c) 2022 Nordic Semiconductor ASA
*
* SPDX-License-Identifier: Apache-2.0
*/
/*
* Bus-specific functionality for BMI270s accessed via I2C.
*/
#include "bmi270.h"
static int bmi270_bus_check_i2c(const union bmi270_bus *bus)
{
return device_is_ready(bus->i2c.bus) ? 0 : -ENODEV;
}
static int bmi270_reg_read_i2c(const union bmi270_bus *bus,
uint8_t start, uint8_t *data, uint16_t len)
{
return i2c_burst_read_dt(&bus->i2c, start, data, len);
}
static int bmi270_reg_write_i2c(const union bmi270_bus *bus, uint8_t start,
const uint8_t *data, uint16_t len)
{
return i2c_burst_write_dt(&bus->i2c, start, data, len);
}
static int bmi270_bus_init_i2c(const union bmi270_bus *bus)
{
/* I2C is used by default
*/
return 0;
}
const struct bmi270_bus_io bmi270_bus_io_i2c = {
.check = bmi270_bus_check_i2c,
.read = bmi270_reg_read_i2c,
.write = bmi270_reg_write_i2c,
.init = bmi270_bus_init_i2c,
};

View file

@ -0,0 +1,101 @@
/*
* Copyright (c) 2022 Nordic Semiconductor ASA
*
* SPDX-License-Identifier: Apache-2.0
*/
/*
* Bus-specific functionality for BMI270s accessed via SPI.
*/
#include <zephyr/logging/log.h>
#include "bmi270.h"
LOG_MODULE_DECLARE(bmi270, CONFIG_SENSOR_LOG_LEVEL);
static int bmi270_bus_check_spi(const union bmi270_bus *bus)
{
return spi_is_ready(&bus->spi) ? 0 : -ENODEV;
}
static int bmi270_reg_read_spi(const union bmi270_bus *bus,
uint8_t start, uint8_t *data, uint16_t len)
{
int ret;
uint8_t addr;
uint8_t tmp[2];
int i;
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)
};
rx_buf[0].buf = &tmp[0];
rx_buf[0].len = 2;
rx_buf[1].len = 1;
for (i = 0; i < len; i++) {
addr = (start + i) | 0x80;
rx_buf[1].buf = &data[i];
ret = spi_transceive_dt(&bus->spi, &tx, &rx);
if (ret < 0) {
LOG_DBG("spi_transceive failed %i", ret);
return ret;
}
}
k_usleep(BMI270_SPI_ACC_DELAY_US);
return 0;
}
static int bmi270_reg_write_spi(const union bmi270_bus *bus, uint8_t start,
const uint8_t *data, uint16_t len)
{
int ret;
uint8_t addr;
const struct spi_buf tx_buf[2] = {
{.buf = &addr, .len = sizeof(addr)},
{.buf = (uint8_t *)data, .len = len}
};
const struct spi_buf_set tx = {
.buffers = tx_buf,
.count = ARRAY_SIZE(tx_buf)
};
addr = start & BMI270_REG_MASK;
ret = spi_write_dt(&bus->spi, &tx);
if (ret < 0) {
LOG_ERR("spi_write_dt failed %i", ret);
return ret;
}
k_usleep(BMI270_SPI_ACC_DELAY_US);
return 0;
}
static int bmi270_bus_init_spi(const union bmi270_bus *bus)
{
uint8_t tmp;
/* Single read of SPI initializes the chip to SPI mode
*/
return bmi270_reg_read_spi(bus, BMI270_REG_CHIP_ID, &tmp, 1);
}
const struct bmi270_bus_io bmi270_bus_io_spi = {
.check = bmi270_bus_check_spi,
.read = bmi270_reg_read_spi,
.write = bmi270_reg_write_spi,
.init = bmi270_bus_init_spi,
};

View file

@ -1,10 +1,7 @@
# Copyright (c) 2021, Bosch Sensortec GmbH
# Copyright (c) 2022, Nordic Semiconductor ASA
# SPDX-License-Identifier: Apache-2.0
description: |
The BMI270 is an inertial measurment unit. See more info at:
https://www.bosch-sensortec.com/products/motion-sensors/imus/bmi270.html
compatible: "bosch,bmi270"
include: i2c-device.yaml
include: [i2c-device.yaml, "bosch,bmi270.yaml"]

View file

@ -0,0 +1,6 @@
# Copyright (c) 2022, Nordic Semiconductor ASA
# SPDX-License-Identifier: Apache-2.0
compatible: "bosch,bmi270"
include: ["spi-device.yaml", "bosch,bmi270.yaml"]

View file

@ -0,0 +1,9 @@
# Copyright (c) 2021, Bosch Sensortec GmbH
# Copyright (c) 2022, Nordic Semiconductor ASA
# SPDX-License-Identifier: Apache-2.0
description: |
The BMI270 is an inertial measurement unit. See more info at:
https://www.bosch-sensortec.com/products/motion-sensors/imus/bmi270.html
compatible: "bosch,bmi270"