sensor: tdk 42688 driver

Adds a driver for TDK InvenSense 42688 six axis IMU. Verified using
the sensor shell sample app via:

- sensor info
- sensor get icm42688p@0

Signed-off-by: Tom Burdick <thomas.burdick@intel.com>
Signed-off-by: Yuval Peress <peress@google.com>
This commit is contained in:
Tom Burdick 2022-07-18 19:00:45 -05:00 committed by Maureen Helm
commit 15786ce648
12 changed files with 1321 additions and 0 deletions

View file

@ -83,7 +83,18 @@
pinctrl-names = "default";
dmas = <&xdmac 0 DMA_PERID_SPI0_TX>, <&xdmac 1 DMA_PERID_SPI0_RX>;
dma-names = "tx", "rx";
cs-gpios =<&pioa 31 GPIO_ACTIVE_LOW>;
status = "okay";
icm42688p@0 {
compatible = "invensense,icm42688";
reg = <0>;
spi-max-frequency = <24000000>;
accel-hz = <32000>;
accel-fs = <16>;
gyro-hz = <32000>;
gyro-fs = <2000>;
};
};
&spi1 {

View file

@ -36,6 +36,7 @@ add_subdirectory_ifdef(CONFIG_HTS221 hts221)
add_subdirectory_ifdef(CONFIG_I3G4250D i3g4250d)
add_subdirectory_ifdef(CONFIG_ICM42605 icm42605)
add_subdirectory_ifdef(CONFIG_ICM42670 icm42670)
add_subdirectory_ifdef(CONFIG_ICM42688 icm42688)
add_subdirectory_ifdef(CONFIG_ICP10125 icp10125)
add_subdirectory_ifdef(CONFIG_IIS2DH iis2dh)
add_subdirectory_ifdef(CONFIG_IIS2DLPC iis2dlpc)

View file

@ -113,6 +113,8 @@ source "drivers/sensor/icm42605/Kconfig"
source "drivers/sensor/icm42670/Kconfig"
source "drivers/sensor/icm42688/Kconfig"
source "drivers/sensor/icp10125/Kconfig"
source "drivers/sensor/iis2dh/Kconfig"

View file

@ -0,0 +1,9 @@
# SPDX-License-Identifier: Apache-2.0
zephyr_library()
zephyr_library_sources(
icm42688.c
icm42688_common.c
icm42688_spi.c
)

View file

@ -0,0 +1,13 @@
# ICM42688-P Six-Axis Motion Tracking device configuration options
#
# Copyright (c) 2022 Intel Corporation
#
# SPDX-License-Identifier: Apache-2.0
config ICM42688
bool "ICM42688 Six-Axis Motion Tracking Device"
default y
depends on DT_HAS_INVENSENSE_ICM42688_ENABLED
select SPI
help
Enable driver for ICM42688 SPI-based six-axis motion tracking device.

View file

@ -0,0 +1,192 @@
/*
* Copyright (c) 2022 Intel Corporation
* Copyright (c) 2022 Esco Medical ApS
* Copyright (c) 2020 TDK Invensense
*
* SPDX-License-Identifier: Apache-2.0
*/
#define DT_DRV_COMPAT invensense_icm42688
#include <zephyr/drivers/sensor.h>
#include <zephyr/drivers/spi.h>
#include <zephyr/sys/byteorder.h>
#include "icm42688.h"
#include "icm42688_reg.h"
#include "icm42688_spi.h"
#include <zephyr/logging/log.h>
LOG_MODULE_REGISTER(ICM42688, CONFIG_SENSOR_LOG_LEVEL);
struct icm42688_sensor_data {
struct icm42688_dev_data dev_data;
int16_t readings[7];
};
struct icm42688_sensor_config {
struct icm42688_dev_cfg dev_cfg;
};
static void icm42688_convert_accel(struct sensor_value *val, int16_t raw_val,
struct icm42688_cfg *cfg)
{
icm42688_accel_ms(cfg, (int32_t)raw_val, &val->val1, &val->val2);
}
static void icm42688_convert_gyro(struct sensor_value *val, int16_t raw_val,
struct icm42688_cfg *cfg)
{
icm42688_gyro_rads(cfg, (int32_t)raw_val, &val->val1, &val->val2);
}
static inline void icm42688_convert_temp(struct sensor_value *val, int16_t raw_val)
{
icm42688_temp_c((int32_t)raw_val, &val->val1, &val->val2);
}
static int icm42688_channel_get(const struct device *dev, enum sensor_channel chan,
struct sensor_value *val)
{
struct icm42688_sensor_data *data = dev->data;
switch (chan) {
case SENSOR_CHAN_ACCEL_XYZ:
icm42688_convert_accel(&val[0], data->readings[1], &data->dev_data.cfg);
icm42688_convert_accel(&val[1], data->readings[2], &data->dev_data.cfg);
icm42688_convert_accel(&val[2], data->readings[3], &data->dev_data.cfg);
break;
case SENSOR_CHAN_ACCEL_X:
icm42688_convert_accel(val, data->readings[1], &data->dev_data.cfg);
break;
case SENSOR_CHAN_ACCEL_Y:
icm42688_convert_accel(val, data->readings[2], &data->dev_data.cfg);
break;
case SENSOR_CHAN_ACCEL_Z:
icm42688_convert_accel(val, data->readings[3], &data->dev_data.cfg);
break;
case SENSOR_CHAN_GYRO_XYZ:
icm42688_convert_gyro(&val[0], data->readings[4], &data->dev_data.cfg);
icm42688_convert_gyro(&val[1], data->readings[5], &data->dev_data.cfg);
icm42688_convert_gyro(&val[2], data->readings[6], &data->dev_data.cfg);
break;
case SENSOR_CHAN_GYRO_X:
icm42688_convert_gyro(val, data->readings[4], &data->dev_data.cfg);
break;
case SENSOR_CHAN_GYRO_Y:
icm42688_convert_gyro(val, data->readings[5], &data->dev_data.cfg);
break;
case SENSOR_CHAN_GYRO_Z:
icm42688_convert_gyro(val, data->readings[6], &data->dev_data.cfg);
break;
case SENSOR_CHAN_DIE_TEMP:
icm42688_convert_temp(val, data->readings[0]);
break;
default:
return -ENOTSUP;
}
return 0;
}
static int icm42688_sample_fetch(const struct device *dev, enum sensor_channel chan)
{
uint8_t status;
struct icm42688_sensor_data *data = dev->data;
const struct icm42688_sensor_config *cfg = dev->config;
int res = icm42688_spi_read(&cfg->dev_cfg.spi, REG_INT_STATUS, &status, 1);
if (res) {
return res;
}
if (!FIELD_GET(BIT_INT_STATUS_DATA_RDY, status)) {
return -EBUSY;
}
uint8_t readings[14];
res = icm42688_read_all(dev, readings);
if (res) {
return res;
}
for (int i = 0; i < 7; i++) {
data->readings[i] =
sys_le16_to_cpu((readings[i * 2] << 8) | readings[i * 2 + 1]);
}
return 0;
}
static int icm42688_attr_set(const struct device *dev, enum sensor_channel chan,
enum sensor_attribute attr, const struct sensor_value *val)
{
return -ENOTSUP;
}
static int icm42688_attr_get(const struct device *dev, enum sensor_channel chan,
enum sensor_attribute attr, struct sensor_value *val)
{
return -ENOTSUP;
}
static const struct sensor_driver_api icm42688_driver_api = {
.sample_fetch = icm42688_sample_fetch,
.channel_get = icm42688_channel_get,
.attr_set = icm42688_attr_set,
.attr_get = icm42688_attr_get,
};
int icm42688_init(const struct device *dev)
{
struct icm42688_sensor_data *data = dev->data;
const struct icm42688_sensor_config *cfg = dev->config;
int res;
if (!spi_is_ready_dt(&cfg->dev_cfg.spi)) {
LOG_ERR("SPI bus is not ready");
return -ENODEV;
}
if (icm42688_reset(dev)) {
LOG_ERR("could not initialize sensor");
return -EIO;
}
data->dev_data.cfg.accel_mode = ICM42688_ACCEL_LN;
data->dev_data.cfg.gyro_mode = ICM42688_GYRO_LN;
data->dev_data.cfg.accel_fs = ICM42688_ACCEL_FS_2G;
data->dev_data.cfg.gyro_fs = ICM42688_GYRO_FS_125;
data->dev_data.cfg.accel_odr = ICM42688_ACCEL_ODR_1000;
data->dev_data.cfg.gyro_odr = ICM42688_GYRO_ODR_1000;
res = icm42688_configure(dev, &data->dev_data.cfg);
if (res != 0) {
LOG_ERR("Failed to configure");
}
return res;
}
/* device defaults to spi mode 0/3 support */
#define ICM42688_SPI_CFG \
SPI_OP_MODE_MASTER | SPI_MODE_CPOL | SPI_MODE_CPHA | SPI_WORD_SET(8) | SPI_TRANSFER_MSB
#define ICM42688_INIT(inst) \
static struct icm42688_sensor_data icm42688_driver_##inst = {}; \
\
static const struct icm42688_sensor_config icm42688_cfg_##inst = { \
.dev_cfg = \
{ \
.spi = SPI_DT_SPEC_INST_GET(inst, ICM42688_SPI_CFG, 0U), \
.gpio_int1 = GPIO_DT_SPEC_INST_GET_OR(inst, int_gpios, {0}), \
}, \
}; \
\
SENSOR_DEVICE_DT_INST_DEFINE(inst, icm42688_init, NULL, &icm42688_driver_##inst, \
&icm42688_cfg_##inst, POST_KERNEL, \
CONFIG_SENSOR_INIT_PRIORITY, &icm42688_driver_api);
DT_INST_FOREACH_STATUS_OKAY(ICM42688_INIT)

View file

@ -0,0 +1,373 @@
/*
* Copyright (c) 2022 Intel Corporation
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_DRIVERS_SENSOR_ICM42688_H_
#define ZEPHYR_DRIVERS_SENSOR_ICM42688_H_
#include <zephyr/drivers/gpio.h>
#include <zephyr/drivers/sensor.h>
#include <zephyr/drivers/spi.h>
#include <zephyr/logging/log.h>
#include <zephyr/sys/byteorder.h>
#include <stdlib.h>
/**
* @brief Accelerometer power modes
*/
enum icm42688_accel_mode {
ICM42688_ACCEL_OFF,
ICM42688_ACCEL_LP = 2,
ICM42688_ACCEL_LN = 3,
};
/**
* @brief Gyroscope power modes
*/
enum icm42688_gyro_mode {
ICM42688_GYRO_OFF,
ICM42688_GYRO_STANDBY,
ICM42688_GYRO_LN = 3,
};
/**
* @brief Accelerometer scale options
*/
enum icm42688_accel_fs {
ICM42688_ACCEL_FS_16G,
ICM42688_ACCEL_FS_8G,
ICM42688_ACCEL_FS_4G,
ICM42688_ACCEL_FS_2G,
};
/**
* @brief Gyroscope scale options
*/
enum icm42688_gyro_fs {
ICM42688_GYRO_FS_2000,
ICM42688_GYRO_FS_1000,
ICM42688_GYRO_FS_500,
ICM42688_GYRO_FS_250,
ICM42688_GYRO_FS_125,
ICM42688_GYRO_FS_62_5,
ICM42688_GYRO_FS_31_25,
ICM42688_GYRO_FS_15_625,
};
/**
* @brief Accelerometer data rate options
*/
enum icm42688_accel_odr {
ICM42688_ACCEL_ODR_32000 = 1,
ICM42688_ACCEL_ODR_16000,
ICM42688_ACCEL_ODR_8000,
ICM42688_ACCEL_ODR_4000,
ICM42688_ACCEL_ODR_2000,
ICM42688_ACCEL_ODR_1000,
ICM42688_ACCEL_ODR_200,
ICM42688_ACCEL_ODR_100,
ICM42688_ACCEL_ODR_50,
ICM42688_ACCEL_ODR_25,
ICM42688_ACCEL_ODR_12_5,
ICM42688_ACCEL_ODR_6_25,
ICM42688_ACCEL_ODR_3_125,
ICM42688_ACCEL_ODR_1_5625,
ICM42688_ACCEL_ODR_500,
};
/**
* @brief Gyroscope data rate options
*/
enum icm42688_gyro_odr {
ICM42688_GYRO_ODR_32000 = 1,
ICM42688_GYRO_ODR_16000,
ICM42688_GYRO_ODR_8000,
ICM42688_GYRO_ODR_4000,
ICM42688_GYRO_ODR_2000,
ICM42688_GYRO_ODR_1000,
ICM42688_GYRO_ODR_200,
ICM42688_GYRO_ODR_100,
ICM42688_GYRO_ODR_50,
ICM42688_GYRO_ODR_25,
ICM42688_GYRO_ODR_12_5,
ICM42688_GYRO_ODR_500 = 0xF
};
/**
* @brief All sensor configuration options
*/
struct icm42688_cfg {
enum icm42688_accel_mode accel_mode;
enum icm42688_accel_fs accel_fs;
enum icm42688_accel_odr accel_odr;
/* TODO accel signal processing options */
enum icm42688_gyro_mode gyro_mode;
enum icm42688_gyro_fs gyro_fs;
enum icm42688_gyro_odr gyro_odr;
/* TODO gyro signal processing options */
bool temp_dis;
/* TODO temp signal processing options */
/* TODO timestamp options */
bool fifo_en;
uint16_t fifo_wm;
bool fifo_hires;
/* TODO additional FIFO options */
/* TODO interrupt options */
};
/**
* @brief Device data (struct device)
*/
struct icm42688_dev_data {
struct icm42688_cfg cfg;
};
/**
* @brief Device config (struct device)
*/
struct icm42688_dev_cfg {
struct spi_dt_spec spi;
struct gpio_dt_spec gpio_int1;
struct gpio_dt_spec gpio_int2;
};
/**
* @brief Reset the sensor
*
* @param dev icm42688 device pointer
*
* @retval 0 success
* @retval -EINVAL Reset status or whoami register returned unexpected value.
*/
int icm42688_reset(const struct device *dev);
/**
* @brief (Re)Configure the sensor with the given configuration
*
* @param dev icm42688 device pointer
* @param cfg icm42688_cfg pointer
*
* @retval 0 success
* @retval -errno Error
*/
int icm42688_configure(const struct device *dev, struct icm42688_cfg *cfg);
/**
* @brief Reads all channels
*
* Regardless of what is enabled/disabled this reads all data registers
* as the time to read the 14 bytes at 1MHz is going to be 112 us which
* is less time than a SPI transaction takes to setup typically.
*
* @param dev icm42688 device pointer
* @param buf 14 byte buffer to store data values (7 channels, 2 bytes each)
*
* @retval 0 success
* @retval -errno Error
*/
int icm42688_read_all(const struct device *dev, uint8_t data[14]);
/**
* @brief Convert icm42688 accelerometer value to useful g values
*
* @param cfg icm42688_cfg current device configuration
* @param in raw data value in int32_t format
* @param out_g whole G's output in int32_t
* @param out_ug micro (1/1000000) of a G output as uint32_t
*/
static inline void icm42688_accel_g(struct icm42688_cfg *cfg, int32_t in, int32_t *out_g,
uint32_t *out_ug)
{
int32_t sensitivity = 0; /* value equivalent for 1g */
switch (cfg->accel_fs) {
case ICM42688_ACCEL_FS_2G:
sensitivity = 16384;
break;
case ICM42688_ACCEL_FS_4G:
sensitivity = 8192;
break;
case ICM42688_ACCEL_FS_8G:
sensitivity = 4096;
break;
case ICM42688_ACCEL_FS_16G:
sensitivity = 2048;
break;
}
/* Whole g's */
*out_g = in / sensitivity;
/* Micro g's */
*out_ug = ((abs(in) - (abs((*out_g)) * sensitivity)) * 1000000) / sensitivity;
}
/**
* @brief Convert icm42688 gyroscope value to useful deg/s values
*
* @param cfg icm42688_cfg current device configuration
* @param in raw data value in int32_t format
* @param out_dps whole deg/s output in int32_t
* @param out_udps micro (1/1000000) deg/s as uint32_t
*/
static inline void icm42688_gyro_dps(struct icm42688_cfg *cfg, int32_t in, int32_t *out_dps,
uint32_t *out_udps)
{
int64_t sensitivity = 0; /* value equivalent for 10x gyro reading deg/s */
switch (cfg->gyro_fs) {
case ICM42688_GYRO_FS_2000:
sensitivity = 164;
break;
case ICM42688_GYRO_FS_1000:
sensitivity = 328;
break;
case ICM42688_GYRO_FS_500:
sensitivity = 655;
break;
case ICM42688_GYRO_FS_250:
sensitivity = 1310;
break;
case ICM42688_GYRO_FS_125:
sensitivity = 2620;
break;
case ICM42688_GYRO_FS_62_5:
sensitivity = 5243;
break;
case ICM42688_GYRO_FS_31_25:
sensitivity = 10486;
break;
case ICM42688_GYRO_FS_15_625:
sensitivity = 20972;
break;
}
int32_t in10 = in * 10;
/* Whole deg/s */
*out_dps = in10 / sensitivity;
/* Micro deg/s */
*out_udps = ((int64_t)(llabs(in10) - (llabs((*out_dps)) * sensitivity)) * 1000000LL) /
sensitivity;
}
/**
* @brief Convert icm42688 accelerometer value to useful m/s^2 values
*
* @param cfg icm42688_cfg current device configuration
* @param in raw data value in int32_t format
* @param out_ms meters/s^2 (whole) output in int32_t
* @param out_ums micrometers/s^2 output as uint32_t
*/
static inline void icm42688_accel_ms(struct icm42688_cfg *cfg, int32_t in, int32_t *out_ms,
uint32_t *out_ums)
{
int64_t sensitivity = 0; /* value equivalent for 1g */
switch (cfg->accel_fs) {
case ICM42688_ACCEL_FS_2G:
sensitivity = 16384;
break;
case ICM42688_ACCEL_FS_4G:
sensitivity = 8192;
break;
case ICM42688_ACCEL_FS_8G:
sensitivity = 4096;
break;
case ICM42688_ACCEL_FS_16G:
sensitivity = 2048;
break;
}
/* Convert to micrometers/s^2 */
int64_t in_ms = in * SENSOR_G;
/* meters/s^2 whole values */
*out_ms = in_ms / (sensitivity * 1000000LL);
/* micrometers/s^2 */
*out_ums = ((llabs(in_ms) - (llabs(*out_ms) * sensitivity * 1000000LL)) / sensitivity);
}
/**
* @brief Convert icm42688 gyroscope value to useful rad/s values
*
* @param cfg icm42688_cfg current device configuration
* @param in raw data value in int32_t format
* @param out_rads whole rad/s output in int32_t
* @param out_urads microrad/s as uint32_t
*/
static inline void icm42688_gyro_rads(struct icm42688_cfg *cfg, int32_t in, int32_t *out_rads,
uint32_t *out_urads)
{
int64_t sensitivity = 0; /* value equivalent for 10x gyro reading deg/s */
switch (cfg->gyro_fs) {
case ICM42688_GYRO_FS_2000:
sensitivity = 164;
break;
case ICM42688_GYRO_FS_1000:
sensitivity = 328;
break;
case ICM42688_GYRO_FS_500:
sensitivity = 655;
break;
case ICM42688_GYRO_FS_250:
sensitivity = 1310;
break;
case ICM42688_GYRO_FS_125:
sensitivity = 2620;
break;
case ICM42688_GYRO_FS_62_5:
sensitivity = 5243;
break;
case ICM42688_GYRO_FS_31_25:
sensitivity = 10486;
break;
case ICM42688_GYRO_FS_15_625:
sensitivity = 20972;
break;
}
int64_t in10_rads = (int64_t)in * SENSOR_PI * 10LL;
/* Whole rad/s */
*out_rads = in10_rads / (sensitivity * 180LL * 1000000LL);
/* microrad/s */
*out_urads = ((llabs(in10_rads) - (llabs((*out_rads)) * sensitivity * 180LL * 1000000LL))) /
(sensitivity * 180LL);
}
/**
* @brief Convert icm42688 temp value to useful celsius values
*
* @param cfg icm42688_cfg current device configuration
* @param in raw data value in int32_t format
* @param out_c whole celsius output in int32_t
* @param out_uc micro (1/1000000) celsius as uint32_t
*/
static inline void icm42688_temp_c(int32_t in, int32_t *out_c, uint32_t *out_uc)
{
int64_t sensitivity = 13248; /* value equivalent for x100 1c */
int64_t in100 = in * 100;
/* Whole celsius */
*out_c = in100 / sensitivity;
/* Micro celsius */
*out_uc = ((llabs(in100) - (llabs(*out_c)) * sensitivity) * 1000000LL) / sensitivity;
/* Shift whole celsius 25 degress */
*out_c = *out_c + 25;
}
#endif /* ZEPHYR_DRIVERS_SENSOR_ICM42688_H_ */

View file

@ -0,0 +1,196 @@
/*
* Copyright (c) 2022 Intel Corporation
* Copyright (c) 2022 Esco Medical ApS
* Copyright (c) 2020 TDK Invensense
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <zephyr/drivers/sensor.h>
#include <zephyr/drivers/spi.h>
#include <zephyr/sys/byteorder.h>
#include "icm42688.h"
#include "icm42688_reg.h"
#include "icm42688_spi.h"
#include <zephyr/logging/log.h>
LOG_MODULE_REGISTER(ICM42688_LL, CONFIG_SENSOR_LOG_LEVEL);
int icm42688_reset(const struct device *dev)
{
int res;
uint8_t value;
const struct icm42688_dev_cfg *dev_cfg = dev->config;
/* start up time for register read/write after POR is 1ms and supply ramp time is 3ms */
k_msleep(3);
/* perform a soft reset to ensure a clean slate, reset bit will auto-clear */
res = icm42688_spi_single_write(&dev_cfg->spi, REG_DEVICE_CONFIG, BIT_SOFT_RESET);
if (res) {
LOG_ERR("write REG_SIGNAL_PATH_RESET failed");
return res;
}
/* wait for soft reset to take effect */
k_msleep(SOFT_RESET_TIME_MS);
/* clear reset done int flag */
res = icm42688_spi_read(&dev_cfg->spi, REG_INT_STATUS, &value, 1);
if (res) {
return res;
}
if (FIELD_GET(BIT_INT_STATUS_RESET_DONE, value) != 1) {
LOG_ERR("unexpected RESET_DONE value, %i", value);
return -EINVAL;
}
res = icm42688_spi_read(&dev_cfg->spi, REG_WHO_AM_I, &value, 1);
if (res) {
return res;
}
if (value != WHO_AM_I_ICM42688) {
LOG_ERR("invalid WHO_AM_I value, was %i but expected %i", value, WHO_AM_I_ICM42688);
return -EINVAL;
}
LOG_DBG("device id: 0x%02X", value);
return res;
}
int icm42688_configure(const struct device *dev, struct icm42688_cfg *cfg)
{
struct icm42688_dev_data *dev_data = dev->data;
const struct icm42688_dev_cfg *dev_cfg = dev->config;
int res;
/* if fifo is enabled right now, disable and flush */
if (dev_data->cfg.fifo_en) {
res = icm42688_spi_single_write(&dev_cfg->spi, REG_FIFO_CONFIG,
FIELD_PREP(MASK_FIFO_MODE, BIT_FIFO_MODE_BYPASS));
if (res != 0) {
LOG_ERR("Error writing FIFO_CONFIG");
return -EINVAL;
}
/* TODO ideally this might read out the FIFO one last time and call
* out to the application with the data there prior to reconfiguring?
*/
res = icm42688_spi_single_write(&dev_cfg->spi, REG_SIGNAL_PATH_RESET,
FIELD_PREP(BIT_FIFO_FLUSH, 1));
if (res != 0) {
LOG_ERR("Error flushing fifo");
return -EINVAL;
}
}
/* TODO maybe do the next few steps intelligently by checking current config */
/* Power management to set gyro/accel modes */
res = icm42688_spi_single_write(&dev_cfg->spi, REG_PWR_MGMT0,
FIELD_PREP(MASK_GYRO_MODE, cfg->gyro_mode) |
FIELD_PREP(MASK_ACCEL_MODE, cfg->accel_mode) |
FIELD_PREP(BIT_TEMP_DIS, cfg->temp_dis));
if (res != 0) {
LOG_ERR("Error writing PWR_MGMT0");
return -EINVAL;
}
/* Need to wait at least 200us before updating more registers
* see datasheet 14.36
*/
k_busy_wait(250);
res = icm42688_spi_single_write(&dev_cfg->spi, REG_ACCEL_CONFIG0,
FIELD_PREP(MASK_ACCEL_ODR, cfg->accel_odr) |
FIELD_PREP(MASK_ACCEL_UI_FS_SEL, cfg->accel_fs));
if (res != 0) {
LOG_ERR("Error writing ACCEL_CONFIG0");
return -EINVAL;
}
res = icm42688_spi_single_write(&dev_cfg->spi, REG_GYRO_CONFIG0,
FIELD_PREP(MASK_GYRO_ODR, cfg->gyro_odr) |
FIELD_PREP(MASK_GYRO_UI_FS_SEL, cfg->gyro_fs));
if (res != 0) {
LOG_ERR("Error writing GYRO_CONFIG0");
return -EINVAL;
}
/*
* Accelerometer sensor need at least 10ms startup time
* Gyroscope sensor need at least 30ms startup time
*/
k_msleep(50);
/* fifo configuration steps if desired */
if (cfg->fifo_en) {
/* Set watermark and interrupt handling first */
res = icm42688_spi_single_write(&dev_cfg->spi, REG_FIFO_CONFIG2,
cfg->fifo_wm & 0xFF);
if (res != 0) {
LOG_ERR("Error writing FIFO_CONFIG2");
return -EINVAL;
}
res = icm42688_spi_single_write(&dev_cfg->spi, REG_FIFO_CONFIG3,
(cfg->fifo_wm >> 8) & 0x0F);
if (res != 0) {
LOG_ERR("Error writing FIFO_CONFIG3");
return -EINVAL;
}
/* TODO we have two interrupt lines, either can be used for watermark, choose 1 for
* now...
*/
res = icm42688_spi_single_write(&dev_cfg->spi, REG_INT_SOURCE0,
FIELD_PREP(BIT_FIFO_THS_INT1_EN, 1));
if (res != 0) {
LOG_ERR("Error writing INT0_SOURCE");
return -EINVAL;
}
/* Setup desired FIFO packet fields, maybe should base this on the other
* temp/accel/gyro en fields in cfg
*/
res = icm42688_spi_single_write(
&dev_cfg->spi, REG_FIFO_CONFIG1,
FIELD_PREP(BIT_FIFO_HIRES_EN, cfg->fifo_hires ? 1 : 0) |
FIELD_PREP(BIT_FIFO_TEMP_EN, 1) | FIELD_PREP(BIT_FIFO_GYRO_EN, 1) |
FIELD_PREP(BIT_FIFO_ACCEL_EN, 1));
if (res != 0) {
LOG_ERR("Error writing FIFO_CONFIG1");
return -EINVAL;
}
/* Begin streaming */
res = icm42688_spi_single_write(&dev_cfg->spi, REG_FIFO_CONFIG,
FIELD_PREP(MASK_FIFO_MODE, BIT_FIFO_MODE_STREAM));
}
return res;
}
int icm42688_read_all(const struct device *dev, uint8_t data[14])
{
const struct icm42688_dev_cfg *dev_cfg = dev->config;
int res;
res = icm42688_spi_read(&dev_cfg->spi, REG_TEMP_DATA1, data, 14);
return res;
}

View file

@ -0,0 +1,273 @@
/*
* Copyright (c) 2022 Intel Corporation
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_DRIVERS_SENSOR_ICM42688_REG_H_
#define ZEPHYR_DRIVERS_SENSOR_ICM42688_REG_H_
#include <zephyr/sys/util.h>
/* Address value has a read bit */
#define REG_SPI_READ_BIT BIT(7)
/* Common bank select register and values */
#define REG_BANK_SEL 0x76
#define MASK_BANK_SEL GENMASK(2, 0)
#define BIT_BANK0 0x000
#define BIT_BANK1 0x001
#define BIT_BANK2 0x010
#define BIT_BANK3 0x011
#define BIT_BANK4 0x100
/* Helper macros for addressing registers in the 4 register banks
* registers are defined as 16 bit values with the bank in the high
* byte and the register address in the low byte
*/
#define REG_ADDRESS_MASK GENMASK(7, 0)
#define REG_BANK_MASK GENMASK(15, 8)
#define REG_BANK_OFFSET(bank) (bank << 8)
#define REG_BANK0_OFFSET REG_BANK_OFFSET(BIT_BANK0)
#define REG_BANK1_OFFSET REG_BANK_OFFSET(BIT_BANK1)
#define REG_BANK2_OFFSET REG_BANK_OFFSET(BIT_BANK2)
#define REG_BANK3_OFFSET REG_BANK_OFFSET(BIT_BANK3)
#define REG_BANK4_OFFSET REG_BANK_OFFSET(BIT_BANK4)
/* Bank 0 */
#define REG_DEVICE_CONFIG (REG_BANK0_OFFSET | 0x11)
#define REG_DRIVE_CONFIG (REG_BANK0_OFFSET | 0x13)
#define REG_INT_CONFIG (REG_BANK0_OFFSET | 0x13)
#define REG_FIFO_CONFIG (REG_BANK0_OFFSET | 0x14)
#define REG_TEMP_DATA1 (REG_BANK0_OFFSET | 0x1D)
#define REG_TEMP_DATA0 (REG_BANK0_OFFSET | 0x1E)
#define REG_ACCEL_DATA_X1 (REG_BANK0_OFFSET | 0x1F)
#define REG_ACCEL_DATA_X0 (REG_BANK0_OFFSET | 0x20)
#define REG_ACCEL_DATA_Y1 (REG_BANK0_OFFSET | 0x21)
#define REG_ACCEL_DATA_Y0 (REG_BANK0_OFFSET | 0x22)
#define REG_ACCEL_DATA_Z1 (REG_BANK0_OFFSET | 0x23)
#define REG_ACCEL_DATA_Z0 (REG_BANK0_OFFSET | 0x24)
#define REG_GYRO_DATA_X1 (REG_BANK0_OFFSET | 0x25)
#define REG_GYRO_DATA_X0 (REG_BANK0_OFFSET | 0x26)
#define REG_GYRO_DATA_Y1 (REG_BANK0_OFFSET | 0x27)
#define REG_GYRO_DATA_Y0 (REG_BANK0_OFFSET | 0x28)
#define REG_GYRO_DATA_Z1 (REG_BANK0_OFFSET | 0x29)
#define REG_GYRO_DATA_Z0 (REG_BANK0_OFFSET | 0x2A)
#define REG_TMST_FSYNCH (REG_BANK0_OFFSET | 0x2B)
#define REG_TMST_FSYNCL (REG_BANK0_OFFSET | 0x2C)
#define REG_INT_STATUS (REG_BANK0_OFFSET | 0x2D)
#define REG_FIFO_COUNTH (REG_BANK0_OFFSET | 0x2E)
#define REG_FIFO_COUNTL (REG_BANK0_OFFSET | 0x2F)
#define REG_FIFO_DATA (REG_BANK0_OFFSET | 0x30)
#define REG_APEX_DATA0 (REG_BANK0_OFFSET | 0x31)
#define REG_APEX_DATA1 (REG_BANK0_OFFSET | 0x32)
#define REG_APEX_DATA2 (REG_BANK0_OFFSET | 0x33)
#define REG_APEX_DATA3 (REG_BANK0_OFFSET | 0x34)
#define REG_APEX_DATA4 (REG_BANK0_OFFSET | 0x35)
#define REG_APEX_DATA5 (REG_BANK0_OFFSET | 0x36)
#define REG_INT_STATUS2 (REG_BANK0_OFFSET | 0x37)
#define REG_INT_STATUS3 (REG_BANK0_OFFSET | 0x38)
#define REG_SIGNAL_PATH_RESET (REG_BANK0_OFFSET | 0x4B)
#define REG_INTF_CONFIG0 (REG_BANK0_OFFSET | 0x4C)
#define REG_INTF_CONFIG1 (REG_BANK0_OFFSET | 0x4D)
#define REG_PWR_MGMT0 (REG_BANK0_OFFSET | 0x4E)
#define REG_GYRO_CONFIG0 (REG_BANK0_OFFSET | 0x4F)
#define REG_ACCEL_CONFIG0 (REG_BANK0_OFFSET | 0x50)
#define REG_GYRO_CONFIG1 (REG_BANK0_OFFSET | 0x51)
#define REG_GYRO_ACCEL_CONFIG0 (REG_BANK0_OFFSET | 0x52)
#define REG_ACCEL_CONFIG1 (REG_BANK0_OFFSET | 0x53)
#define REG_TMST_CONFIG (REG_BANK0_OFFSET | 0x54)
#define REG_APEX_CONFIG0 (REG_BANK0_OFFSET | 0x56)
#define REG_SMD_CONFIG (REG_BANK0_OFFSET | 0x57)
#define REG_FIFO_CONFIG1 (REG_BANK0_OFFSET | 0x5F)
#define REG_FIFO_CONFIG2 (REG_BANK0_OFFSET | 0x60)
#define REG_FIFO_CONFIG3 (REG_BANK0_OFFSET | 0x61)
#define REG_FSYNC_CONFIG (REG_BANK0_OFFSET | 0x62)
#define REG_INT_CONFIG0 (REG_BANK0_OFFSET | 0x63)
#define REG_INT_CONFIG1 (REG_BANK0_OFFSET | 0x64)
#define REG_INT_SOURCE0 (REG_BANK0_OFFSET | 0x65)
#define REG_INT_SOURCE1 (REG_BANK0_OFFSET | 0x66)
#define REG_INT_SOURCE3 (REG_BANK0_OFFSET | 0x68)
#define REG_INT_SOURCE4 (REG_BANK0_OFFSET | 0x69)
#define REG_FIFO_LOST_PKT0 (REG_BANK0_OFFSET | 0x6C)
#define REG_FIFO_LOST_PKT1 (REG_BANK0_OFFSET | 0x6D)
#define REG_SELF_TEST_CONFIG (REG_BANK0_OFFSET | 0x70)
#define REG_WHO_AM_I (REG_BANK0_OFFSET | 0x75)
/* Bank 1 */
#define SENSOR_CONFIG0 (REG_BANK1_OFFSET | 0x03)
#define GYRO_CONFIG_STATIC2 (REG_BANK1_OFFSET | 0x0B)
#define GYRO_CONFIG_STATIC3 (REG_BANK1_OFFSET | 0x0C)
#define GYRO_CONFIG_STATIC4 (REG_BANK1_OFFSET | 0x0D)
#define GYRO_CONFIG_STATIC5 (REG_BANK1_OFFSET | 0x0E)
#define GYRO_CONFIG_STATIC6 (REG_BANK1_OFFSET | 0x0F)
#define GYRO_CONFIG_STATIC7 (REG_BANK1_OFFSET | 0x10)
#define GYRO_CONFIG_STATIC8 (REG_BANK1_OFFSET | 0x11)
#define GYRO_CONFIG_STATIC9 (REG_BANK1_OFFSET | 0x12)
#define GYRO_CONFIG_STATIC10 (REG_BANK1_OFFSET | 0x13)
#define REG_XG_ST_DATA (REG_BANK1_OFFSET | 0x5F)
#define REG_YG_ST_DATA (REG_BANK1_OFFSET | 0x60)
#define REG_ZG_ST_DATA (REG_BANK1_OFFSET | 0x61)
#define REG_TMSTVAL0 (REG_BANK1_OFFSET | 0x62)
#define REG_TMSTVAL1 (REG_BANK1_OFFSET | 0x63)
#define REG_TMSTVAL2 (REG_BANK1_OFFSET | 0x64)
#define REG_INTF_CONFIG4 (REG_BANK1_OFFSET | 0x7A)
#define REG_INTF_CONFIG5 (REG_BANK1_OFFSET | 0x7B)
#define REG_INTF_CONFIG6 (REG_BANK1_OFFSET | 0x7C)
/* Bank 2 */
/* Bank0 REG_DEVICE_CONFIG */
#define BIT_SOFT_RESET BIT(0)
#define BIT_SPI_MODE BIT(4)
/* Bank0 REG_DRIVE_CONFIG */
/* Not used! */
/* Bank0 REG_INT_CONFIG */
#define BIT_INT1_POLARITY BIT(0)
#define BIT_INT1_DRIVE_CIRCUIT BIT(1)
#define BIT_INT1_MODE BIT(2)
#define BIT_INT2_POLARITY BIT(3)
#define BIT_INT2_DRIVE_CIRCUIT BIT(4)
#define BIT_INT2_MODE BIT(5)
/* Bank0 REG_FIFO_CONFIG */
#define MASK_FIFO_MODE GENMASK(7, 6)
#define BIT_FIFO_MODE_BYPASS 0x00
#define BIT_FIFO_MODE_STREAM 0x01
#define BIT_FIFO_MODE_STOP_ON_FULL 0x10
/* Bank0 REG_INT_STATUS */
#define BIT_INT_STATUS_AGC_RDY BIT(0)
#define BIT_INT_STATUS_FIFO_FULL BIT(1)
#define BIT_INT_STATUS_FIFO_THS BIT(2)
#define BIT_INT_STATUS_DATA_RDY BIT(3)
#define BIT_INT_STATUS_RESET_DONE BIT(4)
#define BIT_INT_STATUS_PLL_RDY BIT(5)
#define BIT_INT_STATUS_FSYNC BIT(6)
/* Bank0 REG_INT_STATUS2 */
#define BIT_INT_STATUS_WOM_Z BIT(0)
#define BIT_INT_STATUS_WOM_Y BIT(1)
#define BIT_INT_STATUS_WOM_X BIT(2)
#define BIT_INT_STATUS_SMD BIT(3)
/* Bank0 REG_INT_STATUS3 */
#define BIT_INT_STATUS_LOWG_DET BIT(1)
#define BIT_INT_STATUS_FF_DET BIT(2)
#define BIT_INT_STATUS_TILT_DET BIT(3)
#define BIT_INT_STATUS_STEP_CNT_OVFL BIT(4)
#define BIT_INT_STATUS_STEP_DET BIT(5)
/* Bank0 REG_SIGNAL_PATH_RESET */
#define BIT_FIFO_FLUSH BIT(1)
#define BIT_TMST_STROBE BIT(2)
#define BIT_ABORT_AND_RESET BIT(3)
#define BIT_DMP_MEM_RESET_EN BIT(5)
#define BIT_DMP_INIT_EN BIT(6)
/* Bank0 REG_INTF_CONFIG0 */
#define MASK_UI_SIFS_CFG GENMASK(1, 0)
#define BIT_UI_SIFS_CFG_DISABLE_SPI 0x10
#define BIT_UI_SIFS_CFG_DISABLE_I2C 0x11
#define BIT_SENSOR_DATA_ENDIAN BIT(4)
#define BIT_FIFO_COUNT_ENDIAN BIT(5)
#define BIT_FIFO_COUNT_REC BIT(6)
#define BIT_FIFO_HOLD_LAST_DATA_EN BIT(7)
/* Bank0 REG_INTF_CONFIG1 */
#define MASK_CLKSEL GENMASK(1, 0)
#define BIT_CLKSEL_INT_RC 0x00
#define BIT_CLKSEL_PLL_OR_RC 0x01
#define BIT_CLKSEL_DISABLE 0x11
#define BIT_RTC_MODE BIT(2)
#define BIT_ACCEL_LP_CLK_SEL BIT(3)
/* Bank0 REG_PWR_MGMT_0 */
#define MASK_ACCEL_MODE GENMASK(1, 0)
#define BIT_ACCEL_MODE_OFF 0x00
#define BIT_ACCEL_MODE_LPM 0x02
#define BIT_ACCEL_MODE_LNM 0x03
#define MASK_GYRO_MODE GENMASK(3, 2)
#define BIT_GYRO_MODE_OFF 0x00
#define BIT_GYRO_MODE_STBY 0x01
#define BIT_GYRO_MODE_LNM 0x03
#define BIT_IDLE BIT(4)
#define BIT_TEMP_DIS BIT(5)
/* Bank0 REG_GYRO_CONFIG0 */
#define MASK_GYRO_UI_FS_SEL GENMASK(7, 5)
#define BIT_GYRO_UI_FS_2000 0x00
#define BIT_GYRO_UI_FS_1000 0x01
#define BIT_GYRO_UI_FS_500 0x02
#define BIT_GYRO_UI_FS_250 0x03
#define BIT_GYRO_UI_FS_125 0x04
#define BIT_GYRO_UI_FS_62_5 0x05
#define BIT_GYRO_UI_FS_31_25 0x06
#define BIT_GYRO_UI_FS_15_625 0x07
#define MASK_GYRO_ODR GENMASK(3, 0)
#define BIT_GYRO_ODR_32000 0x01
#define BIT_GYRO_ODR_16000 0x02
#define BIT_GYRO_ODR_8000 0x03
#define BIT_GYRO_ODR_4000 0x04
#define BIT_GYRO_ODR_2000 0x05
#define BIT_GYRO_ODR_1000 0x06
#define BIT_GYRO_ODR_200 0x07
#define BIT_GYRO_ODR_100 0x08
#define BIT_GYRO_ODR_50 0x09
#define BIT_GYRO_ODR_25 0x0A
#define BIT_GYRO_ODR_12_5 0x0B
#define BIT_GYRO_ODR_500 0x0F
/* Bank0 REG_ACCEL_CONFIG0 */
#define MASK_ACCEL_UI_FS_SEL GENMASK(7, 5)
#define BIT_ACCEL_UI_FS_16 0x00
#define BIT_ACCEL_UI_FS_8 0x01
#define BIT_ACCEL_UI_FS_4 0x02
#define BIT_ACCEL_UI_FS_2 0x03
#define MASK_ACCEL_ODR GENMASK(3, 0)
#define BIT_ACCEL_ODR_32000 0x01
#define BIT_ACCEL_ODR_16000 0x02
#define BIT_ACCEL_ODR_8000 0x03
#define BIT_ACCEL_ODR_4000 0x04
#define BIT_ACCEL_ODR_2000 0x05
#define BIT_ACCEL_ODR_1000 0x06
#define BIT_ACCEL_ODR_200 0x07
#define BIT_ACCEL_ODR_100 0x08
#define BIT_ACCEL_ODR_50 0x09
#define BIT_ACCEL_ODR_25 0x0A
#define BIT_ACCEL_ODR_12_5 0x0B
#define BIT_ACCEL_ODR_6_25 0x0C
#define BIT_ACCEL_ODR_3_12 0x0D
#define BIT_ACCEL_ODR_1_5625 0x0E
#define BIT_ACCEL_ODR_500 0x0F
/* Bank0 FIFO_CONFIG1 */
#define BIT_FIFO_HIRES_EN BIT(4)
#define BIT_FIFO_TMST_FSYNC_EN BIT(3)
#define BIT_FIFO_GYRO_EN BIT(2)
#define BIT_FIFO_ACCEL_EN BIT(1)
#define BIT_FIFO_TEMP_EN BIT(0)
/* Bank0 INT_SOURCE0 */
#define BIT_UI_FSYNC_INT1_EN BIT(6)
#define BIT_PLL_RDY_INT1_EN BIT(5)
#define BIT_RESET_DONE_INT1_EN BIT(4)
#define BIT_UI_DRDY_INT1_EN BIT(3)
#define BIT_FIFO_THS_INT1_EN BIT(2)
#define BIT_FIFO_FULL_INT1_EN BIT(1)
#define BIT_FIFO_UI_AGC_RDY_INT1_EN BIT(0)
/* misc. defines */
#define WHO_AM_I_ICM42688 0x47
#define MIN_ACCEL_SENS_SHIFT 11
#define ACCEL_DATA_SIZE 6
#define GYRO_DATA_SIZE 6
#define TEMP_DATA_SIZE 2
#define MCLK_POLL_INTERVAL_US 250
#define MCLK_POLL_ATTEMPTS 100
#define SOFT_RESET_TIME_MS 2 /* 1ms + elbow room */
#endif /* ZEPHYR_DRIVERS_SENSOR_ICM42688_REG_H_ */

View file

@ -0,0 +1,100 @@
/*
* Copyright (c) 2022 Intel Corporation
*
* SPDX-License-Identifier: Apache-2.0
*/
#include <zephyr/sys/util.h>
#include "icm42688_spi.h"
#include "icm42688_reg.h"
static inline int spi_write_register(const struct spi_dt_spec *bus, uint8_t reg, uint8_t data)
{
const struct spi_buf buf[2] = {
{
.buf = &reg,
.len = 1,
},
{
.buf = &data,
.len = 1,
}
};
const struct spi_buf_set tx = {
.buffers = buf,
.count = 2,
};
return spi_write_dt(bus, &tx);
}
static inline int spi_read_register(const struct spi_dt_spec *bus, uint8_t reg, uint8_t *data,
size_t len)
{
uint8_t tx_buffer = REG_SPI_READ_BIT | reg;
const struct spi_buf tx_buf = {
.buf = &tx_buffer,
.len = 1,
};
const struct spi_buf_set tx = {
.buffers = &tx_buf,
.count = 1,
};
struct spi_buf rx_buf[2] = {
{
.buf = NULL,
.len = 1,
},
{
.buf = data,
.len = len,
}
};
const struct spi_buf_set rx = {
.buffers = rx_buf,
.count = 2,
};
return spi_transceive_dt(bus, &tx, &rx);
}
int icm42688_spi_read(const struct spi_dt_spec *bus, uint16_t reg, uint8_t *data, size_t len)
{
int res = 0;
uint8_t address = FIELD_GET(REG_ADDRESS_MASK, reg);
res = spi_read_register(bus, address, data, len);
return res;
}
int icm42688_spi_update_register(const struct spi_dt_spec *bus, uint16_t reg, uint8_t mask,
uint8_t data)
{
uint8_t temp = 0;
int res = icm42688_spi_read(bus, reg, &temp, 1);
if (res) {
return res;
}
temp &= ~mask;
temp |= FIELD_PREP(mask, data);
return icm42688_spi_single_write(bus, reg, temp);
}
int icm42688_spi_single_write(const struct spi_dt_spec *bus, uint16_t reg, uint8_t data)
{
int res = 0;
uint8_t address = FIELD_GET(REG_ADDRESS_MASK, reg);
res = spi_write_register(bus, address, data);
return res;
}

View file

@ -0,0 +1,55 @@
/*
* Copyright (c) 2022 Intel Corporation
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_DRIVERS_SENSOR_ICM42688_SPI_H_
#define ZEPHYR_DRIVERS_SENSOR_ICM42688_SPI_H_
#include <zephyr/device.h>
#include <zephyr/drivers/spi.h>
/**
* @brief perform a single SPI write to a ICM42688 register
*
* this functions wraps all logic necessary to write to any of the ICM42688 registers, regardless
* of which memory bank the register belongs to.
*
* @param bus SPI bus pointer
* @param reg address of ICM42688 register to write to
* @param data data byte to write to register
* @return int 0 on success, negative error code otherwise
*/
int icm42688_spi_single_write(const struct spi_dt_spec *bus, uint16_t reg, uint8_t data);
/**
* @brief update a single ICM42688 register value
*
* this functions wraps all logic necessary to update any of the ICM42688 registers, regardless
* of which memory bank the register belongs to.
*
* @param bus SPI bus pointer
* @param reg address of ICM42688 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 icm42688_spi_update_register(const struct spi_dt_spec *bus, uint16_t reg, uint8_t mask,
uint8_t data);
/**
* @brief read from one or more ICM42688 registers
*
* this functions wraps all logic necessary to read from any of the ICM42688 registers, regardless
* of which memory bank the register belongs to.
*
* @param bus SPI bus pointer
* @param reg start address of ICM42688 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 icm42688_spi_read(const struct spi_dt_spec *bus, uint16_t reg, uint8_t *data, size_t len);
#endif /* ZEPHYR_DRIVERS_SENSOR_ICM42688_SPI_H_ */

View file

@ -0,0 +1,96 @@
# Copyright (c) 2022 Intel Corporation
# Copyright (c) 2022 Esco Medical ApS
# Copyright (c) 2020 TDK Invensense
# SPDX-License-Identifier: Apache-2.0
description: ICM-42688 motion tracking device
compatible: "invensense,icm42688"
include: [sensor-device.yaml, spi-device.yaml]
properties:
int-gpios:
type: phandle-array
description: |
The INT signal default configuration is active-high. The
property value should ensure the flags properly describe the
signal that is presented to the driver.
accel-hz:
type: int
description: |
Default frequency of accelerometer. (Unit - Hz)
Maps to ACCEL_ODR field in ACCEL_CONFIG0 setting
Power-on reset value is 1000.
default: 1000
enum:
- 1
- 3
- 6
- 12
- 25
- 50
- 100
- 200
- 500
- 1000
- 2000
- 4000
- 8000
- 16000
- 32000
gyro-hz:
type: int
description: |
Default frequency of gyroscope. (Unit - Hz)
Maps to GYRO_ODR field in GYRO_CONFIG0 setting
Power-on reset value is 1000.
default: 1000
enum:
- 1
- 3
- 6
- 12
- 25
- 50
- 100
- 200
- 500
- 1000
- 2000
- 4000
- 8000
- 16000
- 32000
accel-fs:
type: int
description: |
Default full scale of accelerometer. (Unit - g)
Maps to ACCEL_FS_SEL field in ACCEL_CONFIG0 setting
Power-on reset value is 16
default: 16
enum:
- 16
- 8
- 4
- 2
gyro-fs:
type: int
description: |
Default full scale of gyroscope. (Unit - DPS)
Maps to GYRO_FS_SEL field in GYRO_CONFIG0 setting
Power-on reset value is 2000
default: 2000
enum:
- 2000
- 1000
- 500
- 250
- 125
- 63
- 31
- 16