drivers: sensor: icm42670: Add I2C bus support

Add bus interface so the driver can support both
SPI and I2C bus.

Signed-off-by: Lucas Tamborrino <lucas.tamborrino@espressif.com>
This commit is contained in:
Lucas Tamborrino 2024-06-17 08:57:15 -03:00 committed by Anas Nashif
commit ca31dbc0bc
12 changed files with 270 additions and 108 deletions

View file

@ -5,6 +5,7 @@ zephyr_library()
zephyr_library_sources(
icm42670.c
icm42670_spi.c
icm42670_i2c.c
)
zephyr_library_sources_ifdef(CONFIG_ICM42670_TRIGGER icm42670_trigger.c)

View file

@ -9,7 +9,8 @@ menuconfig ICM42670
bool "ICM42670 Six-Axis Motion Tracking Device"
default y
depends on DT_HAS_INVENSENSE_ICM42670_ENABLED
select SPI
select SPI if $(dt_compat_on_bus,$(DT_COMPAT_INVENSENSE_ICM42670),spi)
select I2C if $(dt_compat_on_bus,$(DT_COMPAT_INVENSENSE_ICM42670),i2c)
help
Enable driver for ICM42670 SPI-based six-axis motion tracking device.

View file

@ -12,7 +12,6 @@
#include <zephyr/sys/byteorder.h>
#include "icm42670.h"
#include "icm42670_reg.h"
#include "icm42670_spi.h"
#include "icm42670_trigger.h"
#include <zephyr/logging/log.h>
@ -52,7 +51,7 @@ static int icm42670_set_accel_fs(const struct device *dev, uint16_t fs)
data->accel_sensitivity_shift = MIN_ACCEL_SENS_SHIFT + temp;
return icm42670_spi_update_register(&cfg->spi, REG_ACCEL_CONFIG0,
return cfg->bus_io->update(&cfg->bus, REG_ACCEL_CONFIG0,
(uint8_t)MASK_ACCEL_UI_FS_SEL, temp);
}
@ -79,7 +78,7 @@ static int icm42670_set_gyro_fs(const struct device *dev, uint16_t fs)
data->gyro_sensitivity_x10 = icm42670_gyro_sensitivity_x10[temp];
return icm42670_spi_update_register(&cfg->spi, REG_GYRO_CONFIG0,
return cfg->bus_io->update(&cfg->bus, REG_GYRO_CONFIG0,
(uint8_t)MASK_GYRO_UI_FS_SEL, temp);
}
@ -117,7 +116,7 @@ static int icm42670_set_accel_odr(const struct device *dev, uint16_t rate)
temp = BIT_ACCEL_ODR_1;
}
return icm42670_spi_update_register(&cfg->spi, REG_ACCEL_CONFIG0, (uint8_t)MASK_ACCEL_ODR,
return cfg->bus_io->update(&cfg->bus, REG_ACCEL_CONFIG0, (uint8_t)MASK_ACCEL_ODR,
temp);
}
@ -149,7 +148,7 @@ static int icm42670_set_gyro_odr(const struct device *dev, uint16_t rate)
temp = BIT_GYRO_ODR_12;
}
return icm42670_spi_update_register(&cfg->spi, REG_GYRO_CONFIG0, (uint8_t)MASK_GYRO_ODR,
return cfg->bus_io->update(&cfg->bus, REG_GYRO_CONFIG0, (uint8_t)MASK_GYRO_ODR,
temp);
}
@ -158,7 +157,7 @@ static int icm42670_enable_mclk(const struct device *dev)
const struct icm42670_config *cfg = dev->config;
/* switch on MCLK by setting the IDLE bit */
int res = icm42670_spi_single_write(&cfg->spi, REG_PWR_MGMT0, BIT_IDLE);
int res = cfg->bus_io->write(&cfg->bus, REG_PWR_MGMT0, BIT_IDLE);
if (res) {
return res;
@ -169,7 +168,7 @@ static int icm42670_enable_mclk(const struct device *dev)
uint8_t value = 0;
k_usleep(MCLK_POLL_INTERVAL_US);
res = icm42670_spi_read(&cfg->spi, REG_MCLK_RDY, &value, 1);
res = cfg->bus_io->read(&cfg->bus, REG_MCLK_RDY, &value, 1);
if (res) {
return res;
@ -193,7 +192,7 @@ static int icm42670_sensor_init(const struct device *dev)
k_msleep(3);
/* perform a soft reset to ensure a clean slate, reset bit will auto-clear */
res = icm42670_spi_single_write(&cfg->spi, REG_SIGNAL_PATH_RESET, BIT_SOFT_RESET);
res = cfg->bus_io->write(&cfg->bus, REG_SIGNAL_PATH_RESET, BIT_SOFT_RESET);
if (res) {
LOG_ERR("write REG_SIGNAL_PATH_RESET failed");
@ -204,14 +203,14 @@ static int icm42670_sensor_init(const struct device *dev)
k_msleep(SOFT_RESET_TIME_MS);
/* force SPI-4w hardware configuration (so that next read is correct) */
res = icm42670_spi_single_write(&cfg->spi, REG_DEVICE_CONFIG, BIT_SPI_AP_4WIRE);
res = cfg->bus_io->write(&cfg->bus, REG_DEVICE_CONFIG, BIT_SPI_AP_4WIRE);
if (res) {
return res;
}
/* always use internal RC oscillator */
res = icm42670_spi_single_write(&cfg->spi, REG_INTF_CONFIG1,
res = cfg->bus_io->write(&cfg->bus, REG_INTF_CONFIG1,
(uint8_t)FIELD_PREP(MASK_CLKSEL, BIT_CLKSEL_INT_RC));
if (res) {
@ -219,7 +218,7 @@ static int icm42670_sensor_init(const struct device *dev)
}
/* clear reset done int flag */
res = icm42670_spi_read(&cfg->spi, REG_INT_STATUS, &value, 1);
res = cfg->bus_io->read(&cfg->bus, REG_INT_STATUS, &value, 1);
if (res) {
return res;
@ -237,7 +236,7 @@ static int icm42670_sensor_init(const struct device *dev)
return res;
}
res = icm42670_spi_read(&cfg->spi, REG_WHO_AM_I, &value, 1);
res = cfg->bus_io->read(&cfg->bus, REG_WHO_AM_I, &value, 1);
if (res) {
return res;
@ -263,7 +262,7 @@ static int icm42670_turn_on_sensor(const struct device *dev)
value = FIELD_PREP(MASK_ACCEL_MODE, BIT_ACCEL_MODE_LNM) |
FIELD_PREP(MASK_GYRO_MODE, BIT_GYRO_MODE_LNM);
res = icm42670_spi_update_register(&cfg->spi, REG_PWR_MGMT0,
res = cfg->bus_io->update(&cfg->bus, REG_PWR_MGMT0,
(uint8_t)(MASK_ACCEL_MODE | MASK_GYRO_MODE), value);
if (res) {
@ -394,7 +393,7 @@ static int icm42670_sample_fetch_accel(const struct device *dev)
struct icm42670_data *data = dev->data;
uint8_t buffer[ACCEL_DATA_SIZE];
int res = icm42670_spi_read(&cfg->spi, REG_ACCEL_DATA_X1, buffer, ACCEL_DATA_SIZE);
int res = cfg->bus_io->read(&cfg->bus, REG_ACCEL_DATA_X1, buffer, ACCEL_DATA_SIZE);
if (res) {
return res;
@ -413,7 +412,7 @@ static int icm42670_sample_fetch_gyro(const struct device *dev)
struct icm42670_data *data = dev->data;
uint8_t buffer[GYRO_DATA_SIZE];
int res = icm42670_spi_read(&cfg->spi, REG_GYRO_DATA_X1, buffer, GYRO_DATA_SIZE);
int res = cfg->bus_io->read(&cfg->bus, REG_GYRO_DATA_X1, buffer, GYRO_DATA_SIZE);
if (res) {
return res;
@ -432,7 +431,7 @@ static int icm42670_sample_fetch_temp(const struct device *dev)
struct icm42670_data *data = dev->data;
uint8_t buffer[TEMP_DATA_SIZE];
int res = icm42670_spi_read(&cfg->spi, REG_TEMP_DATA1, buffer, TEMP_DATA_SIZE);
int res = cfg->bus_io->read(&cfg->bus, REG_TEMP_DATA1, buffer, TEMP_DATA_SIZE);
if (res) {
return res;
@ -450,7 +449,7 @@ static int icm42670_sample_fetch(const struct device *dev, enum sensor_channel c
icm42670_lock(dev);
int res = icm42670_spi_read(&cfg->spi, REG_INT_STATUS_DRDY, &status, 1);
int res = cfg->bus_io->read(&cfg->bus, REG_INT_STATUS_DRDY, &status, 1);
if (res) {
goto cleanup;
@ -616,12 +615,18 @@ static int icm42670_attr_get(const struct device *dev, enum sensor_channel chan,
return res;
}
static inline int icm42670_bus_check(const struct device *dev)
{
const struct icm42670_config *cfg = dev->config;
return cfg->bus_io->check(&cfg->bus);
}
static int icm42670_init(const struct device *dev)
{
struct icm42670_data *data = dev->data;
const struct icm42670_config *cfg = dev->config;
if (!spi_is_ready_dt(&cfg->spi)) {
if (icm42670_bus_check(dev) < 0) {
LOG_ERR("SPI bus is not ready");
return -ENODEV;
}
@ -686,6 +691,16 @@ static const struct sensor_driver_api icm42670_driver_api = {
#define ICM42670_SPI_CFG \
SPI_OP_MODE_MASTER | SPI_MODE_CPOL | SPI_MODE_CPHA | SPI_WORD_SET(8) | SPI_TRANSFER_MSB
/* Initializes the bus members for an instance on a SPI bus. */
#define ICM42670_CONFIG_SPI(inst) \
.bus.spi = SPI_DT_SPEC_INST_GET(inst, ICM42670_SPI_CFG, 0), \
.bus_io = &icm42670_bus_io_spi,
/* Initializes the bus members for an instance on an I2C bus. */
#define ICM42670_CONFIG_I2C(inst) \
.bus.i2c = I2C_DT_SPEC_INST_GET(inst), \
.bus_io = &icm42670_bus_io_i2c,
#define ICM42670_INIT(inst) \
static struct icm42670_data icm42670_driver_##inst = { \
.accel_hz = DT_INST_PROP(inst, accel_hz), \
@ -695,8 +710,10 @@ static const struct sensor_driver_api icm42670_driver_api = {
}; \
\
static const struct icm42670_config icm42670_cfg_##inst = { \
.spi = SPI_DT_SPEC_INST_GET(inst, ICM42670_SPI_CFG, 0U), \
.gpio_int = GPIO_DT_SPEC_INST_GET_OR(inst, int_gpios, { 0 }), \
COND_CODE_1(DT_INST_ON_BUS(inst, spi), \
(ICM42670_CONFIG_SPI(inst)), \
(ICM42670_CONFIG_I2C(inst))) \
.gpio_int = GPIO_DT_SPEC_INST_GET_OR(inst, int_gpios, {0}), \
}; \
\
SENSOR_DEVICE_DT_INST_DEFINE(inst, icm42670_init, NULL, &icm42670_driver_##inst, \

View file

@ -11,8 +11,45 @@
#include <zephyr/drivers/gpio.h>
#include <zephyr/drivers/sensor.h>
#include <zephyr/drivers/spi.h>
#include <zephyr/drivers/i2c.h>
#include <zephyr/kernel.h>
#define ICM42670_BUS_SPI DT_HAS_COMPAT_ON_BUS_STATUS_OKAY(invensense_icm42670, spi)
#define ICM42670_BUS_I2C DT_HAS_COMPAT_ON_BUS_STATUS_OKAY(invensense_icm42670, i2c)
union icm42670_bus {
#if ICM42670_BUS_SPI
struct spi_dt_spec spi;
#endif
#if ICM42670_BUS_I2C
struct i2c_dt_spec i2c;
#endif
};
typedef int (*icm42670_bus_check_fn)(const union icm42670_bus *bus);
typedef int (*icm42670_reg_read_fn)(const union icm42670_bus *bus,
uint16_t reg, uint8_t *data, size_t size);
typedef int (*icm42670_reg_write_fn)(const union icm42670_bus *bus,
uint16_t reg, uint8_t data);
typedef int (*icm42670_reg_update_fn)(const union icm42670_bus *bus,
uint16_t reg, uint8_t mask, uint8_t data);
struct icm42670_bus_io {
icm42670_bus_check_fn check;
icm42670_reg_read_fn read;
icm42670_reg_write_fn write;
icm42670_reg_update_fn update;
};
#if ICM42670_BUS_SPI
extern const struct icm42670_bus_io icm42670_bus_io_spi;
#endif
#if ICM42670_BUS_I2C
extern const struct icm42670_bus_io icm42670_bus_io_i2c;
#endif
struct icm42670_data {
int16_t accel_x;
int16_t accel_y;
@ -45,7 +82,8 @@ struct icm42670_data {
};
struct icm42670_config {
struct spi_dt_spec spi;
union icm42670_bus bus;
const struct icm42670_bus_io *bus_io;
struct gpio_dt_spec gpio_int;
};

View file

@ -0,0 +1,122 @@
/*
* Copyright (c) 2024 Espressif Systems (Shanghai) Co., Ltd.
*
* SPDX-License-Identifier: Apache-2.0
*/
/*
* Bus-specific functionality for ICM42670 accessed via I2C.
*/
#include "icm42670.h"
#include "icm42670_reg.h"
#if ICM42670_BUS_I2C
static int icm42670_bus_check_i2c(const union icm42670_bus *bus)
{
return i2c_is_ready_dt(&bus->i2c) ? 0 : -ENODEV;
}
static int i2c_read_mreg(const union icm42670_bus *bus, uint8_t reg, uint8_t bank,
uint8_t *buf, size_t len)
{
int res = i2c_reg_write_byte_dt(&bus->i2c, REG_BLK_SEL_R, bank);
if (res) {
return res;
}
/* reads from MREG registers must be done byte-by-byte */
for (size_t i = 0; i < len; i++) {
uint8_t addr = reg + i;
res = i2c_reg_write_byte_dt(&bus->i2c, REG_MADDR_R, addr);
if (res) {
return res;
}
k_usleep(MREG_R_W_WAIT_US);
res = i2c_reg_read_byte_dt(&bus->i2c, REG_M_R, &buf[i]);
if (res) {
return res;
}
k_usleep(MREG_R_W_WAIT_US);
}
return 0;
}
static int icm42670_reg_read_i2c(const union icm42670_bus *bus, uint16_t reg, uint8_t *data,
size_t len)
{
int res = 0;
uint8_t bank = FIELD_GET(REG_BANK_MASK, reg);
uint8_t address = FIELD_GET(REG_ADDRESS_MASK, reg);
if (bank) {
res = i2c_read_mreg(bus, address, bank, data, len);
} else {
res = i2c_burst_read_dt(&bus->i2c, address, data, len);
}
return res;
}
static int i2c_write_mreg(const union icm42670_bus *bus, uint16_t reg, uint8_t bank,
uint8_t buf)
{
int res = i2c_reg_write_byte_dt(&bus->i2c, REG_BLK_SEL_W, bank);
if (res) {
return res;
}
res = i2c_reg_write_byte_dt(&bus->i2c, REG_MADDR_W, reg);
if (res) {
return res;
}
res = i2c_reg_write_byte_dt(&bus->i2c, REG_M_W, buf);
if (res) {
return res;
}
k_usleep(MREG_R_W_WAIT_US);
return 0;
}
static int icm42670_reg_write_i2c(const union icm42670_bus *bus,
uint16_t reg, uint8_t data)
{
int res = 0;
uint8_t bank = FIELD_GET(REG_BANK_MASK, reg);
uint8_t address = FIELD_GET(REG_ADDRESS_MASK, reg);
if (bank) {
res = i2c_write_mreg(bus, address, bank, data);
} else {
res = i2c_reg_write_byte_dt(&bus->i2c, address, data);
}
return res;
}
static int icm42670_reg_update_i2c(const union icm42670_bus *bus, uint16_t reg, uint8_t mask,
uint8_t val)
{
return i2c_reg_update_byte_dt(&bus->i2c, reg, mask, val);
}
const struct icm42670_bus_io icm42670_bus_io_i2c = {
.check = icm42670_bus_check_i2c,
.read = icm42670_reg_read_i2c,
.write = icm42670_reg_write_i2c,
.update = icm42670_reg_update_i2c,
};
#endif /* ICM42670_BUS_I2C */

View file

@ -7,10 +7,11 @@
#include <zephyr/kernel.h>
#include <zephyr/sys/util.h>
#include "icm42670_spi.h"
#include "icm42670.h"
#include "icm42670_reg.h"
static inline int spi_write_register(const struct spi_dt_spec *bus, uint8_t reg, uint8_t data)
#if ICM42670_BUS_SPI
static inline int spi_write_register(const union icm42670_bus *bus, uint8_t reg, uint8_t data)
{
const struct spi_buf buf[2] = {
{
@ -28,10 +29,10 @@ static inline int spi_write_register(const struct spi_dt_spec *bus, uint8_t reg,
.count = 2,
};
return spi_write_dt(bus, &tx);
return spi_write_dt(&bus->spi, &tx);
}
static inline int spi_read_register(const struct spi_dt_spec *bus, uint8_t reg, uint8_t *data,
static inline int spi_read_register(const union icm42670_bus *bus, uint8_t reg, uint8_t *data,
size_t len)
{
uint8_t tx_buffer = REG_SPI_READ_BIT | reg;
@ -62,10 +63,10 @@ static inline int spi_read_register(const struct spi_dt_spec *bus, uint8_t reg,
.count = 2,
};
return spi_transceive_dt(bus, &tx, &rx);
return spi_transceive_dt(&bus->spi, &tx, &rx);
}
static inline int spi_read_mreg(const struct spi_dt_spec *bus, uint8_t reg, uint8_t bank,
static inline int spi_read_mreg(const union icm42670_bus *bus, uint8_t reg, uint8_t bank,
uint8_t *buf, size_t len)
{
int res = spi_write_register(bus, REG_BLK_SEL_R, bank);
@ -97,7 +98,7 @@ static inline int spi_read_mreg(const struct spi_dt_spec *bus, uint8_t reg, uint
return 0;
}
static inline int spi_write_mreg(const struct spi_dt_spec *bus, uint8_t reg, uint8_t bank,
static inline int spi_write_mreg(const union icm42670_bus *bus, uint8_t reg, uint8_t bank,
uint8_t buf)
{
int res = spi_write_register(bus, REG_BLK_SEL_W, bank);
@ -123,7 +124,7 @@ static inline int spi_write_mreg(const struct spi_dt_spec *bus, uint8_t reg, uin
return 0;
}
int icm42670_spi_read(const struct spi_dt_spec *bus, uint16_t reg, uint8_t *data, size_t len)
int icm42670_spi_read(const union icm42670_bus *bus, uint16_t reg, uint8_t *data, size_t len)
{
int res = 0;
uint8_t bank = FIELD_GET(REG_BANK_MASK, reg);
@ -138,7 +139,22 @@ int icm42670_spi_read(const struct spi_dt_spec *bus, uint16_t reg, uint8_t *data
return res;
}
int icm42670_spi_update_register(const struct spi_dt_spec *bus, uint16_t reg, uint8_t mask,
int icm42670_spi_single_write(const union icm42670_bus *bus, uint16_t reg, uint8_t data)
{
int res = 0;
uint8_t bank = FIELD_GET(REG_BANK_MASK, reg);
uint8_t address = FIELD_GET(REG_ADDRESS_MASK, reg);
if (bank) {
res = spi_write_mreg(bus, address, bank, data);
} else {
res = spi_write_register(bus, address, data);
}
return res;
}
int icm42670_spi_update_register(const union icm42670_bus *bus, uint16_t reg, uint8_t mask,
uint8_t data)
{
uint8_t temp = 0;
@ -154,17 +170,16 @@ int icm42670_spi_update_register(const struct spi_dt_spec *bus, uint16_t reg, ui
return icm42670_spi_single_write(bus, reg, temp);
}
int icm42670_spi_single_write(const struct spi_dt_spec *bus, uint16_t reg, uint8_t data)
static int icm42670_bus_check_spi(const union icm42670_bus *bus)
{
int res = 0;
uint8_t bank = FIELD_GET(REG_BANK_MASK, reg);
uint8_t address = FIELD_GET(REG_ADDRESS_MASK, reg);
if (bank) {
res = spi_write_mreg(bus, address, bank, data);
} else {
res = spi_write_register(bus, address, data);
}
return res;
return spi_is_ready_dt(&bus->spi) ? 0 : -ENODEV;
}
const struct icm42670_bus_io icm42670_bus_io_spi = {
.check = icm42670_bus_check_spi,
.read = icm42670_spi_read,
.write = icm42670_spi_single_write,
.update = icm42670_spi_update_register,
};
#endif /* ICM42670_BUS_SPI */

View file

@ -1,56 +0,0 @@
/*
* Copyright (c) 2022 Esco Medical ApS
* Copyright (c) 2020 TDK Invensense
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_DRIVERS_SENSOR_ICM42670_SPI_H_
#define ZEPHYR_DRIVERS_SENSOR_ICM42670_SPI_H_
#include <zephyr/device.h>
#include <zephyr/drivers/spi.h>
/**
* @brief perform a single SPI write to a ICM42670 register
*
* this functions wraps all logic necessary to write to any of the ICM42670 registers, regardless
* of which memory bank the register belongs to.
*
* @param bus SPI bus pointer
* @param reg address of ICM42670 register to write to
* @param data data byte to write to register
* @return int 0 on success, negative error code otherwise
*/
int icm42670_spi_single_write(const struct spi_dt_spec *bus, uint16_t reg, uint8_t data);
/**
* @brief update a single ICM42670 register value
*
* this functions wraps all logic necessary to update any of the ICM42670 registers, regardless
* of which memory bank the register belongs to.
*
* @param bus SPI bus pointer
* @param reg address of ICM42670 register to update
* @param mask bitmask defining which bits of the register to update
* @param data new value to update register with, respecting the bitmask
* @return int 0 on success, negative error code otherwise
*/
int icm42670_spi_update_register(const struct spi_dt_spec *bus, uint16_t reg, uint8_t mask,
uint8_t data);
/**
* @brief read from one or more ICM42670 registers
*
* this functions wraps all logic necessary to read from any of the ICM42670 registers, regardless
* of which memory bank the register belongs to.
*
* @param bus SPI bus pointer
* @param reg start address of ICM42670 register(s) to read from
* @param data pointer to byte array to read register values to
* @param len number of bytes to read from the device
* @return int 0 on success, negative error code otherwise
*/
int icm42670_spi_read(const struct spi_dt_spec *bus, uint16_t reg, uint8_t *data, size_t len);
#endif /* ZEPHYR_DRIVERS_SENSOR_ICM42670_SPI_H_ */

View file

@ -10,7 +10,6 @@
#include <zephyr/sys/util.h>
#include "icm42670.h"
#include "icm42670_reg.h"
#include "icm42670_spi.h"
#include "icm42670_trigger.h"
#include <zephyr/logging/log.h>
@ -149,7 +148,7 @@ int icm42670_trigger_enable_interrupt(const struct device *dev)
const struct icm42670_config *cfg = dev->config;
/* pulse-mode (auto clearing), push-pull and active-high */
res = icm42670_spi_single_write(&cfg->spi, REG_INT_CONFIG,
res = cfg->bus_io->write(&cfg->bus, REG_INT_CONFIG,
BIT_INT1_DRIVE_CIRCUIT | BIT_INT1_POLARITY);
if (res) {
@ -157,7 +156,7 @@ int icm42670_trigger_enable_interrupt(const struct device *dev)
}
/* enable data ready interrupt on INT1 pin */
return icm42670_spi_single_write(&cfg->spi, REG_INT_SOURCE0, BIT_INT_DRDY_INT1_EN);
return cfg->bus_io->write(&cfg->bus, REG_INT_SOURCE0, BIT_INT_DRDY_INT1_EN);
}
void icm42670_lock(const struct device *dev)

View file

@ -0,0 +1,8 @@
# Copyright (c) 2024 Espressif Systems (Shanghai) Co., Ltd.
# SPDX-License-Identifier: Apache-2.0
description: ICM-42670 motion tracking device
compatible: "invensense,icm42670"
include: [i2c-device.yaml, "invensense,icm42670.yaml"]

View file

@ -0,0 +1,9 @@
# Copyright (c) 2022 Esco Medical ApS
# Copyright (c) 2020 TDK Invensense
# SPDX-License-Identifier: Apache-2.0
description: ICM-42670 motion tracking device
compatible: "invensense,icm42670"
include: [spi-device.yaml, "invensense,icm42670.yaml"]

View file

@ -4,9 +4,7 @@
description: ICM-42670 motion tracking device
compatible: "invensense,icm42670"
include: [sensor-device.yaml, spi-device.yaml]
include: [sensor-device.yaml]
properties:
int-gpios:

View file

@ -1072,3 +1072,13 @@ test_i2c_lsm9ds1: lsm9ds1@91 {
compatible = "st,lsm9ds1";
reg = <0x8e>;
};
test_i2c_icm42670: icm42670@92 {
compatible = "invensense,icm42670";
reg = <0x92>;
int-gpios = <&test_gpio 0 0>;
accel-hz = <800>;
accel-fs = <16>;
gyro-hz = <800>;
gyro-fs = <2000>;
};