drivers: sensor: Initial driver of Invensense ICM42605
Initial driver and sample application of TDK Invensense ICM42605 6-axis motion sensor. This driver provide DTS for nRF52 DK board DTS setting. Providing features are below. Sensor data streaming - Accel, gyro Tap, Double tap triggering. Set/Get FSR, ODR by set attr API Support multi instance feature. Signed-off-by: JuHyun Kim <jkim@invensense.com>
This commit is contained in:
parent
1badf77961
commit
cc56fb5247
13 changed files with 1986 additions and 0 deletions
|
@ -92,6 +92,8 @@ source "drivers/sensor/hp206c/Kconfig"
|
|||
|
||||
source "drivers/sensor/hts221/Kconfig"
|
||||
|
||||
source "drivers/sensor/icm42605/Kconfig"
|
||||
|
||||
source "drivers/sensor/iis2dh/Kconfig"
|
||||
|
||||
source "drivers/sensor/iis2dlpc/Kconfig"
|
||||
|
|
10
drivers/sensor/icm42605/CMakeLists.txt
Normal file
10
drivers/sensor/icm42605/CMakeLists.txt
Normal file
|
@ -0,0 +1,10 @@
|
|||
# SPDX-License-Identifier: Apache-2.0
|
||||
|
||||
zephyr_library()
|
||||
|
||||
if (CONFIG_ICM42605)
|
||||
zephyr_library_sources(icm42605.c)
|
||||
zephyr_library_sources(icm42605_setup.c)
|
||||
zephyr_library_sources_ifdef(CONFIG_SPI icm42605_spi.c)
|
||||
zephyr_library_sources_ifdef(CONFIG_ICM42605_TRIGGER icm42605_trigger.c)
|
||||
endif()
|
53
drivers/sensor/icm42605/Kconfig
Normal file
53
drivers/sensor/icm42605/Kconfig
Normal file
|
@ -0,0 +1,53 @@
|
|||
# ICM42605 Six-Axis Motion Tracking device configuration options
|
||||
|
||||
# Copyright (c) 2020 TDK Invensense
|
||||
# SPDX-License-Identifier: Apache-2.0
|
||||
|
||||
menuconfig ICM42605
|
||||
bool "ICM42605 Six-Axis Motion Tracking Device"
|
||||
depends on SPI
|
||||
help
|
||||
Enable driver for ICM42605 SPI-based six-axis motion tracking device.
|
||||
|
||||
if ICM42605
|
||||
|
||||
choice
|
||||
prompt "Trigger mode"
|
||||
default ICM42605_TRIGGER_GLOBAL_THREAD
|
||||
help
|
||||
Specify the type of triggering to be used by the driver.
|
||||
|
||||
config ICM42605_TRIGGER_NONE
|
||||
bool "No trigger"
|
||||
|
||||
config ICM42605_TRIGGER_GLOBAL_THREAD
|
||||
bool "Use global thread"
|
||||
depends on GPIO
|
||||
select ICM42605_TRIGGER
|
||||
|
||||
config ICM42605_TRIGGER_OWN_THREAD
|
||||
bool "Use own thread"
|
||||
depends on GPIO
|
||||
select ICM42605_TRIGGER
|
||||
|
||||
|
||||
endchoice
|
||||
|
||||
config ICM42605_TRIGGER
|
||||
bool
|
||||
|
||||
config ICM42605_THREAD_PRIORITY
|
||||
int "Thread priority"
|
||||
depends on ICM42605_TRIGGER_OWN_THREAD
|
||||
default 10
|
||||
help
|
||||
Priority of thread used by the driver to handle interrupts.
|
||||
|
||||
config ICM42605_THREAD_STACK_SIZE
|
||||
int "Thread stack size"
|
||||
depends on ICM42605_TRIGGER_OWN_THREAD
|
||||
default 1024
|
||||
help
|
||||
Stack size of thread used by the driver to handle interrupts.
|
||||
|
||||
endif # ICM42605
|
465
drivers/sensor/icm42605/icm42605.c
Normal file
465
drivers/sensor/icm42605/icm42605.c
Normal file
|
@ -0,0 +1,465 @@
|
|||
/*
|
||||
* Copyright (c) 2020 TDK Invensense
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
#define DT_DRV_COMPAT invensense_icm42605
|
||||
|
||||
#include <drivers/spi.h>
|
||||
#include <init.h>
|
||||
#include <sys/byteorder.h>
|
||||
#include <drivers/sensor.h>
|
||||
#include <logging/log.h>
|
||||
|
||||
#include "icm42605.h"
|
||||
#include "icm42605_reg.h"
|
||||
#include "icm42605_setup.h"
|
||||
#include "icm42605_spi.h"
|
||||
|
||||
LOG_MODULE_REGISTER(ICM42605, CONFIG_SENSOR_LOG_LEVEL);
|
||||
|
||||
static const uint16_t icm42605_gyro_sensitivity_x10[] = {
|
||||
1310, 655, 328, 164
|
||||
};
|
||||
|
||||
/* see "Accelerometer Measurements" section from register map description */
|
||||
static void icm42605_convert_accel(struct sensor_value *val,
|
||||
int16_t raw_val,
|
||||
uint16_t sensitivity_shift)
|
||||
{
|
||||
int64_t conv_val;
|
||||
|
||||
conv_val = ((int64_t)raw_val * SENSOR_G) >> sensitivity_shift;
|
||||
val->val1 = conv_val / 1000000;
|
||||
val->val2 = conv_val % 1000000;
|
||||
}
|
||||
|
||||
/* see "Gyroscope Measurements" section from register map description */
|
||||
static void icm42605_convert_gyro(struct sensor_value *val,
|
||||
int16_t raw_val,
|
||||
uint16_t sensitivity_x10)
|
||||
{
|
||||
int64_t conv_val;
|
||||
|
||||
conv_val = ((int64_t)raw_val * SENSOR_PI * 10) /
|
||||
(sensitivity_x10 * 180U);
|
||||
val->val1 = conv_val / 1000000;
|
||||
val->val2 = conv_val % 1000000;
|
||||
}
|
||||
|
||||
/* see "Temperature Measurement" section from register map description */
|
||||
static inline void icm42605_convert_temp(struct sensor_value *val,
|
||||
int16_t raw_val)
|
||||
{
|
||||
val->val1 = (((int64_t)raw_val * 100) / 207) + 25;
|
||||
val->val2 = ((((int64_t)raw_val * 100) % 207) * 1000000) / 207;
|
||||
|
||||
if (val->val2 < 0) {
|
||||
val->val1--;
|
||||
val->val2 += 1000000;
|
||||
} else if (val->val2 >= 1000000) {
|
||||
val->val1++;
|
||||
val->val2 -= 1000000;
|
||||
}
|
||||
}
|
||||
|
||||
static int icm42605_channel_get(const struct device *dev,
|
||||
enum sensor_channel chan,
|
||||
const struct sensor_value *val)
|
||||
{
|
||||
const struct icm42605_data *drv_data = dev->data;
|
||||
|
||||
switch (chan) {
|
||||
case SENSOR_CHAN_ACCEL_XYZ:
|
||||
icm42605_convert_accel(val, drv_data->accel_x,
|
||||
drv_data->accel_sensitivity_shift);
|
||||
icm42605_convert_accel(val + 1, drv_data->accel_y,
|
||||
drv_data->accel_sensitivity_shift);
|
||||
icm42605_convert_accel(val + 2, drv_data->accel_z,
|
||||
drv_data->accel_sensitivity_shift);
|
||||
break;
|
||||
case SENSOR_CHAN_ACCEL_X:
|
||||
icm42605_convert_accel(val, drv_data->accel_x,
|
||||
drv_data->accel_sensitivity_shift);
|
||||
break;
|
||||
case SENSOR_CHAN_ACCEL_Y:
|
||||
icm42605_convert_accel(val, drv_data->accel_y,
|
||||
drv_data->accel_sensitivity_shift);
|
||||
break;
|
||||
case SENSOR_CHAN_ACCEL_Z:
|
||||
icm42605_convert_accel(val, drv_data->accel_z,
|
||||
drv_data->accel_sensitivity_shift);
|
||||
break;
|
||||
case SENSOR_CHAN_GYRO_XYZ:
|
||||
icm42605_convert_gyro(val, drv_data->gyro_x,
|
||||
drv_data->gyro_sensitivity_x10);
|
||||
icm42605_convert_gyro(val + 1, drv_data->gyro_y,
|
||||
drv_data->gyro_sensitivity_x10);
|
||||
icm42605_convert_gyro(val + 2, drv_data->gyro_z,
|
||||
drv_data->gyro_sensitivity_x10);
|
||||
break;
|
||||
case SENSOR_CHAN_GYRO_X:
|
||||
icm42605_convert_gyro(val, drv_data->gyro_x,
|
||||
drv_data->gyro_sensitivity_x10);
|
||||
break;
|
||||
case SENSOR_CHAN_GYRO_Y:
|
||||
icm42605_convert_gyro(val, drv_data->gyro_y,
|
||||
drv_data->gyro_sensitivity_x10);
|
||||
break;
|
||||
case SENSOR_CHAN_GYRO_Z:
|
||||
icm42605_convert_gyro(val, drv_data->gyro_z,
|
||||
drv_data->gyro_sensitivity_x10);
|
||||
break;
|
||||
case SENSOR_CHAN_DIE_TEMP:
|
||||
icm42605_convert_temp(val, drv_data->temp);
|
||||
break;
|
||||
default:
|
||||
return -ENOTSUP;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int icm42605_tap_fetch(const struct device *dev)
|
||||
{
|
||||
int result = 0;
|
||||
const struct icm42605_data *drv_data = dev->data;
|
||||
|
||||
if (drv_data->tap_en &&
|
||||
(drv_data->tap_handler || drv_data->double_tap_handler)) {
|
||||
result = inv_spi_read(REG_INT_STATUS3, drv_data->fifo_data, 1);
|
||||
if (drv_data->fifo_data[0] & BIT_INT_STATUS_TAP_DET) {
|
||||
result = inv_spi_read(REG_APEX_DATA4,
|
||||
drv_data->fifo_data, 1);
|
||||
if (drv_data->fifo_data[0] & APEX_TAP) {
|
||||
if (drv_data->tap_trigger.type ==
|
||||
SENSOR_TRIG_TAP) {
|
||||
LOG_DBG("Single Tap detected");
|
||||
drv_data->tap_handler(dev
|
||||
, &drv_data->tap_trigger);
|
||||
} else {
|
||||
LOG_ERR("Trigger type is mismatched");
|
||||
}
|
||||
} else if (drv_data->fifo_data[0] & APEX_DOUBLE_TAP) {
|
||||
if (drv_data->double_tap_trigger.type ==
|
||||
SENSOR_TRIG_DOUBLE_TAP) {
|
||||
LOG_DBG("Double Tap detected");
|
||||
drv_data->double_tap_handler(dev
|
||||
, &drv_data->tap_trigger);
|
||||
} else {
|
||||
LOG_ERR("Trigger type is mismatched");
|
||||
}
|
||||
} else {
|
||||
LOG_DBG("Not supported tap event");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int icm42605_sample_fetch(const struct device *dev,
|
||||
enum sensor_channel chan)
|
||||
{
|
||||
int result = 0;
|
||||
uint16_t fifo_count = 0;
|
||||
struct icm42605_data *drv_data = dev->data;
|
||||
|
||||
/* Read INT_STATUS (0x45) and FIFO_COUNTH(0x46), FIFO_COUNTL(0x47) */
|
||||
result = inv_spi_read(REG_INT_STATUS, drv_data->fifo_data, 3);
|
||||
|
||||
if (drv_data->fifo_data[0] & BIT_INT_STATUS_DRDY) {
|
||||
fifo_count = (drv_data->fifo_data[1] << 8)
|
||||
+ (drv_data->fifo_data[2]);
|
||||
result = inv_spi_read(REG_FIFO_DATA, drv_data->fifo_data,
|
||||
fifo_count);
|
||||
|
||||
/* FIFO Data structure
|
||||
* Packet 1 : FIFO Header(1), AccelX(2), AccelY(2),
|
||||
* AccelZ(2), Temperature(1)
|
||||
* Packet 2 : FIFO Header(1), GyroX(2), GyroY(2),
|
||||
* GyroZ(2), Temperature(1)
|
||||
* Packet 3 : FIFO Header(1), AccelX(2), AccelY(2), AccelZ(2),
|
||||
* GyroX(2), GyroY(2), GyroZ(2), Temperature(1)
|
||||
*/
|
||||
if (drv_data->fifo_data[0] & BIT_FIFO_HEAD_ACCEL) {
|
||||
/* Check empty values */
|
||||
if (!(drv_data->fifo_data[1] == FIFO_ACCEL0_RESET_VALUE
|
||||
&& drv_data->fifo_data[2] ==
|
||||
FIFO_ACCEL1_RESET_VALUE)) {
|
||||
drv_data->accel_x =
|
||||
(drv_data->fifo_data[1] << 8)
|
||||
+ (drv_data->fifo_data[2]);
|
||||
drv_data->accel_y =
|
||||
(drv_data->fifo_data[3] << 8)
|
||||
+ (drv_data->fifo_data[4]);
|
||||
drv_data->accel_z =
|
||||
(drv_data->fifo_data[5] << 8)
|
||||
+ (drv_data->fifo_data[6]);
|
||||
}
|
||||
if (!(drv_data->fifo_data[0] & BIT_FIFO_HEAD_GYRO)) {
|
||||
drv_data->temp =
|
||||
(int16_t)(drv_data->fifo_data[7]);
|
||||
} else {
|
||||
if (!(drv_data->fifo_data[7] ==
|
||||
FIFO_GYRO0_RESET_VALUE &&
|
||||
drv_data->fifo_data[8] ==
|
||||
FIFO_GYRO1_RESET_VALUE)) {
|
||||
drv_data->gyro_x =
|
||||
(drv_data->fifo_data[7] << 8)
|
||||
+ (drv_data->fifo_data[8]);
|
||||
drv_data->gyro_y =
|
||||
(drv_data->fifo_data[9] << 8)
|
||||
+ (drv_data->fifo_data[10]);
|
||||
drv_data->gyro_z =
|
||||
(drv_data->fifo_data[11] << 8)
|
||||
+ (drv_data->fifo_data[12]);
|
||||
}
|
||||
drv_data->temp =
|
||||
(int16_t)(drv_data->fifo_data[13]);
|
||||
}
|
||||
} else {
|
||||
if (drv_data->fifo_data[0] & BIT_FIFO_HEAD_GYRO) {
|
||||
if (!(drv_data->fifo_data[1] ==
|
||||
FIFO_GYRO0_RESET_VALUE &&
|
||||
drv_data->fifo_data[2] ==
|
||||
FIFO_GYRO1_RESET_VALUE)) {
|
||||
drv_data->gyro_x =
|
||||
(drv_data->fifo_data[1] << 8)
|
||||
+ (drv_data->fifo_data[2]);
|
||||
drv_data->gyro_y =
|
||||
(drv_data->fifo_data[3] << 8)
|
||||
+ (drv_data->fifo_data[4]);
|
||||
drv_data->gyro_z =
|
||||
(drv_data->fifo_data[5] << 8)
|
||||
+ (drv_data->fifo_data[6]);
|
||||
}
|
||||
drv_data->temp =
|
||||
(int16_t)(drv_data->fifo_data[7]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int icm42605_attr_set(const struct device *dev,
|
||||
enum sensor_channel chan,
|
||||
enum sensor_attribute attr,
|
||||
const struct sensor_value *val)
|
||||
{
|
||||
struct icm42605_data *drv_data = dev->data;
|
||||
|
||||
__ASSERT_NO_MSG(val != NULL);
|
||||
|
||||
switch (chan) {
|
||||
case SENSOR_CHAN_ACCEL_X:
|
||||
case SENSOR_CHAN_ACCEL_Y:
|
||||
case SENSOR_CHAN_ACCEL_Z:
|
||||
case SENSOR_CHAN_ACCEL_XYZ:
|
||||
if (attr == SENSOR_ATTR_SAMPLING_FREQUENCY) {
|
||||
if (val->val1 > 8000 || val->val1 < 1) {
|
||||
LOG_ERR("Incorrect sampling value");
|
||||
return -EINVAL;
|
||||
} else {
|
||||
drv_data->accel_hz = val->val1;
|
||||
}
|
||||
} else if (attr == SENSOR_ATTR_FULL_SCALE) {
|
||||
if (val->val1 < ACCEL_FS_16G ||
|
||||
val->val1 > ACCEL_FS_2G) {
|
||||
LOG_ERR("Incorrect fullscale value");
|
||||
return -EINVAL;
|
||||
} else {
|
||||
drv_data->accel_sf = val->val1;
|
||||
}
|
||||
} else {
|
||||
LOG_ERR("Not supported ATTR");
|
||||
return -ENOTSUP;
|
||||
}
|
||||
|
||||
break;
|
||||
case SENSOR_CHAN_GYRO_X:
|
||||
case SENSOR_CHAN_GYRO_Y:
|
||||
case SENSOR_CHAN_GYRO_Z:
|
||||
case SENSOR_CHAN_GYRO_XYZ:
|
||||
if (attr == SENSOR_ATTR_SAMPLING_FREQUENCY) {
|
||||
if (val->val1 > 8000 || val->val1 < 12) {
|
||||
LOG_ERR("Incorrect sampling value");
|
||||
return -EINVAL;
|
||||
} else {
|
||||
drv_data->gyro_hz = val->val1;
|
||||
}
|
||||
} else if (attr == SENSOR_ATTR_FULL_SCALE) {
|
||||
if (val->val1 < GYRO_FS_2000DPS ||
|
||||
val->val1 > GYRO_FS_15DPS) {
|
||||
LOG_ERR("Incorrect fullscale value");
|
||||
return -EINVAL;
|
||||
} else {
|
||||
drv_data->gyro_sf = val->val1;
|
||||
}
|
||||
} else {
|
||||
LOG_ERR("Not supported ATTR");
|
||||
return -EINVAL;
|
||||
}
|
||||
break;
|
||||
default:
|
||||
LOG_ERR("Not support");
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int icm42605_attr_get(const struct device *dev,
|
||||
enum sensor_channel chan,
|
||||
enum sensor_attribute attr,
|
||||
struct sensor_value *val)
|
||||
{
|
||||
const struct icm42605_data *drv_data = dev->data;
|
||||
|
||||
__ASSERT_NO_MSG(val != NULL);
|
||||
|
||||
switch (chan) {
|
||||
case SENSOR_CHAN_ACCEL_X:
|
||||
case SENSOR_CHAN_ACCEL_Y:
|
||||
case SENSOR_CHAN_ACCEL_Z:
|
||||
case SENSOR_CHAN_ACCEL_XYZ:
|
||||
if (attr == SENSOR_ATTR_SAMPLING_FREQUENCY) {
|
||||
val->val1 = drv_data->accel_hz;
|
||||
} else if (attr == SENSOR_ATTR_FULL_SCALE) {
|
||||
val->val1 = drv_data->accel_sf;
|
||||
} else {
|
||||
LOG_ERR("Not supported ATTR");
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
break;
|
||||
case SENSOR_CHAN_GYRO_X:
|
||||
case SENSOR_CHAN_GYRO_Y:
|
||||
case SENSOR_CHAN_GYRO_Z:
|
||||
case SENSOR_CHAN_GYRO_XYZ:
|
||||
if (attr == SENSOR_ATTR_SAMPLING_FREQUENCY) {
|
||||
val->val1 = drv_data->gyro_hz;
|
||||
} else if (attr == SENSOR_ATTR_FULL_SCALE) {
|
||||
val->val1 = drv_data->gyro_sf;
|
||||
} else {
|
||||
LOG_ERR("Not supported ATTR");
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
break;
|
||||
|
||||
default:
|
||||
LOG_ERR("Not support");
|
||||
return -EINVAL;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static int icm42605_data_init(struct icm42605_data *data,
|
||||
const struct icm42605_config *cfg)
|
||||
{
|
||||
data->accel_x = 0;
|
||||
data->accel_y = 0;
|
||||
data->accel_z = 0;
|
||||
data->temp = 0;
|
||||
data->gyro_x = 0;
|
||||
data->gyro_y = 0;
|
||||
data->gyro_z = 0;
|
||||
data->accel_hz = cfg->accel_hz;
|
||||
data->gyro_hz = cfg->gyro_hz;
|
||||
|
||||
data->accel_sf = cfg->accel_fs;
|
||||
data->gyro_sf = cfg->gyro_fs;
|
||||
|
||||
data->tap_en = false;
|
||||
data->sensor_started = false;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
static int icm42605_init(const struct device *dev)
|
||||
{
|
||||
struct icm42605_data *drv_data = dev->data;
|
||||
const struct icm42605_config *cfg = dev->config;
|
||||
|
||||
drv_data->spi = device_get_binding(cfg->spi_label);
|
||||
if (!drv_data->spi) {
|
||||
LOG_ERR("SPI device not exist");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
drv_data->spi_cs.gpio_dev = device_get_binding(cfg->gpio_label);
|
||||
|
||||
if (!drv_data->spi_cs.gpio_dev) {
|
||||
LOG_ERR("GPIO device not exist");
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
drv_data->spi_cs.gpio_pin = cfg->gpio_pin;
|
||||
drv_data->spi_cs.gpio_dt_flags = cfg->gpio_dt_flags;
|
||||
drv_data->spi_cs.delay = 0U;
|
||||
|
||||
drv_data->spi_cfg.frequency = cfg->frequency;
|
||||
drv_data->spi_cfg.slave = cfg->slave;
|
||||
drv_data->spi_cfg.operation = (SPI_OP_MODE_MASTER | SPI_MODE_CPOL |
|
||||
SPI_MODE_CPHA | SPI_WORD_SET(8) | SPI_LINES_SINGLE |
|
||||
SPI_TRANSFER_MSB);
|
||||
drv_data->spi_cfg.cs = &drv_data->spi_cs;
|
||||
|
||||
icm42605_spi_init(drv_data->spi, &drv_data->spi_cfg);
|
||||
icm42605_data_init(drv_data, cfg);
|
||||
icm42605_sensor_init(dev);
|
||||
|
||||
drv_data->accel_sensitivity_shift = 14 - 3;
|
||||
drv_data->gyro_sensitivity_x10 = icm42605_gyro_sensitivity_x10[3];
|
||||
|
||||
if (icm42605_init_interrupt(dev) < 0) {
|
||||
LOG_ERR("Failed to initialize interrupts.");
|
||||
return -EIO;
|
||||
}
|
||||
|
||||
LOG_DBG("Initialize interrupt done");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static const struct sensor_driver_api icm42605_driver_api = {
|
||||
.trigger_set = icm42605_trigger_set,
|
||||
.sample_fetch = icm42605_sample_fetch,
|
||||
.channel_get = icm42605_channel_get,
|
||||
.attr_set = icm42605_attr_set,
|
||||
.attr_get = icm42605_attr_get,
|
||||
};
|
||||
|
||||
#define ICM42605_DEFINE_CONFIG(index) \
|
||||
static const struct icm42605_config icm42605_cfg_##index = { \
|
||||
.spi_label = DT_INST_BUS_LABEL(index), \
|
||||
.spi_addr = DT_INST_REG_ADDR(index), \
|
||||
.frequency = DT_INST_PROP(index, spi_max_frequency), \
|
||||
.slave = DT_INST_REG_ADDR(index), \
|
||||
.int_label = DT_INST_GPIO_LABEL(index, int_gpios), \
|
||||
.int_pin = DT_INST_GPIO_PIN(index, int_gpios), \
|
||||
.int_flags = DT_INST_GPIO_FLAGS(index, int_gpios), \
|
||||
.gpio_label = DT_INST_SPI_DEV_CS_GPIOS_LABEL(index), \
|
||||
.gpio_pin = DT_INST_SPI_DEV_CS_GPIOS_PIN(index), \
|
||||
.gpio_dt_flags = DT_INST_SPI_DEV_CS_GPIOS_FLAGS(index), \
|
||||
.accel_hz = DT_INST_PROP(index, accel_hz), \
|
||||
.gyro_hz = DT_INST_PROP(index, gyro_hz), \
|
||||
.accel_fs = DT_ENUM_IDX(DT_DRV_INST(index), accel_fs), \
|
||||
.gyro_fs = DT_ENUM_IDX(DT_DRV_INST(index), gyro_fs), \
|
||||
}
|
||||
|
||||
#define ICM42605_INIT(index) \
|
||||
ICM42605_DEFINE_CONFIG(index); \
|
||||
static struct icm42605_data icm42605_driver_##index; \
|
||||
DEVICE_AND_API_INIT(icm42605_##index, DT_INST_LABEL(index), \
|
||||
icm42605_init, &icm42605_driver_##index, \
|
||||
&icm42605_cfg_##index, POST_KERNEL, \
|
||||
CONFIG_SENSOR_INIT_PRIORITY, \
|
||||
&icm42605_driver_api);
|
||||
|
||||
DT_INST_FOREACH_STATUS_OKAY(ICM42605_INIT)
|
91
drivers/sensor/icm42605/icm42605.h
Normal file
91
drivers/sensor/icm42605/icm42605.h
Normal file
|
@ -0,0 +1,91 @@
|
|||
/*
|
||||
* Copyright (c) 2020 TDK Invensense
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
#ifndef ZEPHYR_DRIVERS_SENSOR_ICM42605_ICM42605_H_
|
||||
#define ZEPHYR_DRIVERS_SENSOR_ICM42605_ICM42605_H_
|
||||
|
||||
#include <device.h>
|
||||
#include <drivers/gpio.h>
|
||||
#include <drivers/spi.h>
|
||||
#include <sys/util.h>
|
||||
#include <zephyr/types.h>
|
||||
|
||||
#include "icm42605_reg.h"
|
||||
|
||||
typedef void (*tap_fetch_t)(const struct device *dev);
|
||||
|
||||
struct icm42605_data {
|
||||
struct device *spi;
|
||||
|
||||
uint8_t fifo_data[HARDWARE_FIFO_SIZE];
|
||||
|
||||
int16_t accel_x;
|
||||
int16_t accel_y;
|
||||
int16_t accel_z;
|
||||
uint16_t accel_sensitivity_shift;
|
||||
uint16_t accel_hz;
|
||||
uint16_t accel_sf;
|
||||
|
||||
int16_t temp;
|
||||
|
||||
int16_t gyro_x;
|
||||
int16_t gyro_y;
|
||||
int16_t gyro_z;
|
||||
uint16_t gyro_sensitivity_x10;
|
||||
uint16_t gyro_hz;
|
||||
uint16_t gyro_sf;
|
||||
|
||||
bool accel_en;
|
||||
bool gyro_en;
|
||||
bool tap_en;
|
||||
|
||||
bool sensor_started;
|
||||
|
||||
struct device *dev;
|
||||
struct device *gpio;
|
||||
struct gpio_callback gpio_cb;
|
||||
|
||||
struct sensor_trigger data_ready_trigger;
|
||||
sensor_trigger_handler_t data_ready_handler;
|
||||
|
||||
struct sensor_trigger tap_trigger;
|
||||
sensor_trigger_handler_t tap_handler;
|
||||
|
||||
struct sensor_trigger double_tap_trigger;
|
||||
sensor_trigger_handler_t double_tap_handler;
|
||||
|
||||
K_KERNEL_STACK_MEMBER(thread_stack, CONFIG_ICM42605_THREAD_STACK_SIZE);
|
||||
struct k_thread thread;
|
||||
struct k_sem gpio_sem;
|
||||
|
||||
struct spi_cs_control spi_cs;
|
||||
struct spi_config spi_cfg;
|
||||
};
|
||||
|
||||
struct icm42605_config {
|
||||
const char *spi_label;
|
||||
uint16_t spi_addr;
|
||||
uint32_t frequency;
|
||||
uint32_t slave;
|
||||
uint8_t int_pin;
|
||||
uint8_t int_flags;
|
||||
const char *int_label;
|
||||
const char *gpio_label;
|
||||
gpio_pin_t gpio_pin;
|
||||
gpio_dt_flags_t gpio_dt_flags;
|
||||
uint16_t accel_hz;
|
||||
uint16_t gyro_hz;
|
||||
uint16_t accel_fs;
|
||||
uint16_t gyro_fs;
|
||||
};
|
||||
|
||||
int icm42605_trigger_set(const struct device *dev,
|
||||
const struct sensor_trigger *trig,
|
||||
sensor_trigger_handler_t handler);
|
||||
|
||||
int icm42605_init_interrupt(const struct device *dev);
|
||||
|
||||
#endif /* __SENSOR_ICM42605__ */
|
545
drivers/sensor/icm42605/icm42605_reg.h
Normal file
545
drivers/sensor/icm42605/icm42605_reg.h
Normal file
|
@ -0,0 +1,545 @@
|
|||
/*
|
||||
* Copyright (c) 2020 TDK Invensense
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
#ifndef ZEPHYR_DRIVERS_SENSOR_ICM42605_ICM42605_REG_H_
|
||||
#define ZEPHYR_DRIVERS_SENSOR_ICM42605_ICM42605_REG_H_
|
||||
|
||||
/* BANK 0 */
|
||||
#define REG_DEVICE_CONFIG 0x11
|
||||
#define REG_DRIVE_CONFIG 0x13
|
||||
#define REG_INT_CONFIG 0x14
|
||||
#define REG_FIFO_CONFIG 0x16
|
||||
#define REG_TEMP_DATA1 0x1D
|
||||
#define REG_TEMP_DATA0 0x1E
|
||||
#define REG_ACCEL_DATA_X1 0x1F
|
||||
#define REG_ACCEL_DATA_X0 0x20
|
||||
#define REG_ACCEL_DATA_Y1 0x21
|
||||
#define REG_ACCEL_DATA_Y0 0x22
|
||||
#define REG_ACCEL_DATA_Z1 0x23
|
||||
#define REG_ACCEL_DATA_Z0 0x24
|
||||
#define REG_GYRO_DATA_X1 0x25
|
||||
#define REG_GYRO_DATA_X0 0x26
|
||||
#define REG_GYRO_DATA_Y1 0x27
|
||||
#define REG_GYRO_DATA_Y0 0x28
|
||||
#define REG_GYRO_DATA_Z1 0x29
|
||||
#define REG_GYRO_DATA_Z0 0x2A
|
||||
#define REG_TMST_FSYNCH 0x2B
|
||||
#define REG_TMST_FSYNCL 0x2C
|
||||
#define REG_INT_STATUS 0x2D
|
||||
#define REG_FIFO_COUNTH 0x2E
|
||||
#define REG_FIFO_COUNTL 0x2F
|
||||
#define REG_FIFO_DATA 0x30
|
||||
#define REG_APEX_DATA0 0x31
|
||||
#define REG_APEX_DATA1 0x32
|
||||
#define REG_APEX_DATA2 0x33
|
||||
#define REG_APEX_DATA3 0x34
|
||||
#define REG_APEX_DATA4 0x35
|
||||
#define REG_APEX_DATA5 0x36
|
||||
#define REG_INT_STATUS2 0x37
|
||||
#define REG_INT_STATUS3 0x38
|
||||
#define REG_SIGNAL_PATH_RESET 0x4B
|
||||
#define REG_INTF_CONFIG0 0x4C
|
||||
#define REG_INTF_CONFIG1 0x4D
|
||||
#define REG_PWR_MGMT0 0x4E
|
||||
#define REG_GYRO_CONFIG0 0x4F
|
||||
#define REG_ACCEL_CONFIG0 0x50
|
||||
#define REG_GYRO_CONFIG1 0x51
|
||||
#define REG_GYRO_ACCEL_CONFIG0 0x52
|
||||
#define REG_ACCEL_CONFIG1 0x53
|
||||
#define REG_TMST_CONFIG 0x54
|
||||
#define REG_APEX_CONFIG0 0x56
|
||||
#define REG_SMD_CONFIG 0x57
|
||||
#define REG_FIFO_CONFIG1 0x5F
|
||||
#define REG_FIFO_CONFIG2 0x60
|
||||
#define REG_FIFO_CONFIG4 0x61
|
||||
#define REG_FIFO_FSYNC_CONFIG 0x62
|
||||
#define REG_INT_CONFIG0 0x63
|
||||
#define REG_INT_CONFIG1 0x64
|
||||
#define REG_INT_SOURCE0 0x65
|
||||
#define REG_INT_SOURCE1 0x66
|
||||
#define REG_INT_SOURCE3 0x68
|
||||
#define REG_INT_SOURCE4 0x69
|
||||
#define REG_FIFO_LOST_PKT0 0x6C
|
||||
#define REG_FIFO_LOST_PKT1 0x6D
|
||||
#define REG_SELF_TEST_CONFIG 0x70
|
||||
#define REG_WHO_AM_I 0x75
|
||||
#define REG_BANK_SEL 0x76
|
||||
|
||||
/* BANK 1 */
|
||||
#define REG_SENSOR_CONFIG0 0x03
|
||||
#define REG_GYRO_CONFIG_STATIC2 0x0B
|
||||
#define REG_GYRO_CONFIG_STATIC3 0x0C
|
||||
#define REG_GYRO_CONFIG_STATIC4 0x0D
|
||||
#define REG_GYRO_CONFIG_STATIC5 0x0E
|
||||
#define REG_GYRO_CONFIG_STATIC6 0x0F
|
||||
#define REG_GYRO_CONFIG_STATIC7 0x10
|
||||
#define REG_GYRO_CONFIG_STATIC8 0x11
|
||||
#define REG_GYRO_CONFIG_STATIC9 0x12
|
||||
#define REG_GYRO_CONFIG_STATIC10 0x13
|
||||
#define REG_XG_ST_DATA 0x5F
|
||||
#define REG_YG_ST_DATA 0x60
|
||||
#define REG_ZG_ST_DATA 0x61
|
||||
#define REG_TMSTVAL0 0x62
|
||||
#define REG_TMSTVAL1 0x63
|
||||
#define REG_TMSTVAL2 0x64
|
||||
#define REG_INTF_CONFIG4 0x7A
|
||||
#define REG_INTF_CONFIG5 0x7B
|
||||
#define REG_INTF_CONFIG6 0x7C
|
||||
|
||||
/* BANK 2 */
|
||||
#define REG_ACCEL_CONFIG_STATIC2 0x03
|
||||
#define REG_ACCEL_CONFIG_STATIC3 0x04
|
||||
#define REG_ACCEL_CONFIG_STATIC4 0x05
|
||||
#define REG_XA_ST_DATA 0x3B
|
||||
#define REG_YA_ST_DATA 0x3C
|
||||
#define REG_ZA_ST_DATA 0x3D
|
||||
|
||||
/* BANK 4 */
|
||||
#define REG_GYRO_ON_OFF_CONFIG 0x0E
|
||||
#define REG_APEX_CONFIG1 0x40
|
||||
#define REG_APEX_CONFIG2 0x41
|
||||
#define REG_APEX_CONFIG3 0x42
|
||||
#define REG_APEX_CONFIG4 0x43
|
||||
#define REG_APEX_CONFIG5 0x44
|
||||
#define REG_APEX_CONFIG6 0x45
|
||||
#define REG_APEX_CONFIG7 0x46
|
||||
#define REG_APEX_CONFIG8 0x47
|
||||
#define REG_APEX_CONFIG9 0x48
|
||||
#define REG_ACCEL_WOM_X_THR 0x4A
|
||||
#define REG_ACCEL_WOM_Y_THR 0x4B
|
||||
#define REG_ACCEL_WOM_Z_THR 0x4C
|
||||
#define REG_INT_SOURCE6 0x4D
|
||||
#define REG_INT_SOURCE7 0x4E
|
||||
#define REG_INT_SOURCE8 0x4F
|
||||
#define REG_INT_SOURCE9 0x50
|
||||
#define REG_INT_SOURCE10 0x51
|
||||
#define REG_OFFSET_USER0 0x77
|
||||
#define REG_OFFSET_USER1 0x78
|
||||
#define REG_OFFSET_USER2 0x79
|
||||
#define REG_OFFSET_USER3 0x7A
|
||||
#define REG_OFFSET_USER4 0x7B
|
||||
#define REG_OFFSET_USER5 0x7C
|
||||
#define REG_OFFSET_USER6 0x7D
|
||||
#define REG_OFFSET_USER7 0x7E
|
||||
#define REG_OFFSET_USER8 0x7F
|
||||
|
||||
/* #define REG_#define REG_BANK_SEL */
|
||||
#define BIT_BANK_SEL_0 0x00
|
||||
#define BIT_BANK_SEL_1 0x01
|
||||
#define BIT_BANK_SEL_2 0x02
|
||||
#define BIT_BANK_SEL_3 0x03
|
||||
#define BIT_BANK_SEL_4 0x04
|
||||
|
||||
#define WHO_AM_I_ICM42605 0x42
|
||||
|
||||
/* Bank0 #define REG_DEVICE_CONFIG_REG */
|
||||
#define BIT_SOFT_RESET 0x01
|
||||
|
||||
/* Bank0 #define REG_GYRO_CONFIG0, REG_ACCEL_CONFIG0 */
|
||||
#define SHIFT_GYRO_FS_SEL 5
|
||||
#define SHIFT_ACCEL_FS_SEL 5
|
||||
#define SHIFT_ODR_CONF 0
|
||||
|
||||
/* Bank0 #define REG_GYRO_CONFIG1 */
|
||||
#define BIT_TEMP_FILT_BW_BYPASS 0x00
|
||||
#define BIT_TEMP_FILT_BW_170 0x20
|
||||
#define BIT_TEMP_FILT_BW_82 0x40
|
||||
#define BIT_TEMP_FILT_BW_40 0x60
|
||||
#define BIT_TEMP_FILT_BW_20 0x80
|
||||
#define BIT_TEMP_FILT_BW_10 0x90
|
||||
#define BIT_TEMP_FILT_BW_5 0xC0
|
||||
#define BIT_GYR_AVG_FLT_RATE_8KHZ 0x10
|
||||
#define BIT_GYR_AVG_FLT_RATE_1KHZ 0x00
|
||||
#define BIT_GYR_UI_FILT_ORD_IND_1 0x00
|
||||
#define BIT_GYR_UI_FILT_ORD_IND_2 0x04
|
||||
#define BIT_GYR_UI_FILT_ORD_IND_3 0x08
|
||||
#define BIT_GYR_DEC2_M2_ORD_1 0x00
|
||||
#define BIT_GYR_DEC2_M2_ORD_2 0x01
|
||||
#define BIT_GYR_DEC2_M2_ORD_3 0x02
|
||||
|
||||
/* Bank0 REG_ACCEL_CONFIG1 */
|
||||
#define BIT_ACC_UI_FILT_ODR_IND_1 0x00
|
||||
#define BIT_ACC_UI_FILT_ODR_IND_2 0x08
|
||||
#define BIT_ACC_UI_FILT_ODR_IND_3 0x10
|
||||
#define BIT_ACC_DEC2_M2_ORD_1 0x00
|
||||
#define BIT_ACC_DEC2_M2_ORD_2 0x02
|
||||
#define BIT_ACC_DEC2_M2_ORD_3 0x04
|
||||
#define BIT_ACC_AVG_FLT_RATE_8KHZ 0x01
|
||||
#define BIT_ACC_AVG_FLT_RATE_1KHZ 0x00
|
||||
|
||||
/* Bank0 REG_INT_CONFIG_REG */
|
||||
#define SHIFT_INT1_POLARITY 0
|
||||
#define SHIFT_INT1_DRIVE_CIRCUIT 1
|
||||
#define SHIFT_INT1_MODE 2
|
||||
|
||||
/* Bank0 REG_PWR_MGMT_0 */
|
||||
#define BIT_TEMP_DIS 0x20
|
||||
#define BIT_IDLE 0x10
|
||||
#define BIT_GYRO_MODE_OFF 0x00
|
||||
#define BIT_GYRO_MODE_STBY 0x04
|
||||
#define BIT_GYRO_MODE_LPM 0x08
|
||||
#define BIT_GYRO_MODE_LNM 0x0C
|
||||
#define BIT_ACCEL_MODE_OFF 0x00
|
||||
#define BIT_ACCEL_MODE_LPM 0x02
|
||||
#define BIT_ACCEL_MODE_LNM 0x03
|
||||
|
||||
/* Bank0 REG_SIGNAL_PATH_RESET */
|
||||
#define BIT_TEMP_RST 0x01
|
||||
#define BIT_FIFO_FLUSH 0x02
|
||||
#define BIT_TMST_STROBE 0x04
|
||||
#define BIT_ABORT_AND_RESET 0x08
|
||||
#define BIT_S4S_RESTART 0x10
|
||||
#define BIT_DMP_MEM_RESET_EN 0x20
|
||||
#define BIT_DMP_INIT_EN 0x40
|
||||
|
||||
/* Bank0 REG_INTF_CONFIG0 */
|
||||
#define BIT_FIFO_COUNT_REC 0x40
|
||||
#define BIT_COUNT_BIG_ENDIAN 0x20
|
||||
#define BIT_SENS_DATA_BIG_ENDIAN 0x10
|
||||
#define BIT_UI_SIFS_DISABLE_SPI 0x02
|
||||
#define BIT_UI_SIFS_DISABLE_I2C 0x03
|
||||
|
||||
/* Bank0 REG_INTF_CONFIG1 */
|
||||
#define BIT_GYRO_AFSR_MODE_LFS 0x00
|
||||
#define BIT_GYRO_AFSR_MODE_HFS 0x40
|
||||
#define BIT_GYRO_AFSR_MODE_DYN 0xC0
|
||||
#define BIT_ACCEL_AFSR_MODE_LFS 0x00
|
||||
#define BIT_ACCEL_AFSR_MODE_HFS 0x10
|
||||
#define BIT_ACCEL_AFSR_MODE_DYN 0x30
|
||||
#define BIT_ACCEL_LP_CLK_SEL 0x08
|
||||
#define BIT_RTC_MODE 0x04
|
||||
#define BIT_CLK_SEL_RC 0x00
|
||||
#define BIT_CLK_SEL_PLL 0x01
|
||||
#define BIT_CLK_SEL_DIS 0x03
|
||||
|
||||
/* Bank0 REG_FIFO_CONFIG1 */
|
||||
#define BIT_FIFO_ACCEL_EN 0x01
|
||||
#define BIT_FIFO_GYRO_EN 0x02
|
||||
#define BIT_FIFO_TEMP_EN 0x04
|
||||
#define BIT_FIFO_TMST_FSYNC_EN 0x08
|
||||
#define BIT_FIFO_HIRES_EN 0x10
|
||||
#define BIT_FIFO_WM_TH 0x20
|
||||
#define BIT_FIFO_RESUME_PART_RD 0x40
|
||||
|
||||
/* Bank0 REG_INT_CONFIG1 */
|
||||
#define BIT_INT_ASY_RST_DISABLE 0x10
|
||||
|
||||
/* Bank0 REG_INT_SOURCE0 */
|
||||
#define BIT_INT_UI_AGC_RDY_INT1_EN 0x01
|
||||
#define BIT_INT_FIFO_FULL_INT1_EN 0x02
|
||||
#define BIT_INT_FIFO_THS_INT1_EN 0x04
|
||||
#define BIT_INT_UI_DRDY_INT1_EN 0x08
|
||||
#define BIT_INT_RESET_DONE_INT1_EN 0x10
|
||||
#define BIT_INT_PLL_RDY_INT1_EN 0x20
|
||||
#define BIT_INT_UI_FSYNC_INT1_EN 0x40
|
||||
|
||||
/* Bank0 REG_INT_SOURCE1 */
|
||||
#define BIT_INT_WOM_X_INT1_EN 0x01
|
||||
#define BIT_INT_WOM_Y_INT1_EN 0x02
|
||||
#define BIT_INT_WOM_Z_INT1_EN 0x04
|
||||
#define BIT_INT_SMD_INT1_EN 0x08
|
||||
#define BIT_INT_WOM_XYZ_INT1_EN \
|
||||
(BIT_INT_WOM_X_INT1_EN | BIT_INT_WOM_Y_INT1_EN | BIT_INT_WOM_Z_INT1_EN)
|
||||
|
||||
/* Bank0 REG_SENSOR_SELFTEST_REG1 */
|
||||
#define BIT_ACCEL_SELF_TEST_PASS 0x08
|
||||
#define BIT_GYRO_SELF_TEST_PASS 0x04
|
||||
#define BIT_ACCEL_SELF_TEST_DONE 0x02
|
||||
#define BIT_GYRO_SELF_TEST_DONE 0x01
|
||||
|
||||
/* Bank0 REG_SELF_TEST_CONFIG */
|
||||
#define BIT_SELF_TEST_REGULATOR_EN 0x40
|
||||
#define BIT_TEST_AZ_EN 0x20
|
||||
#define BIT_TEST_AY_EN 0x10
|
||||
#define BIT_TEST_AX_EN 0x08
|
||||
#define BIT_TEST_GZ_EN 0x04
|
||||
#define BIT_TEST_GY_EN 0x02
|
||||
#define BIT_TEST_GX_EN 0x01
|
||||
|
||||
/* Bank0 REG_INT_STATUS */
|
||||
#define BIT_INT_STATUS_AGC_RDY 0x01
|
||||
#define BIT_INT_STATUS_FIFO_FULL 0x02
|
||||
#define BIT_INT_STATUS_FIFO_THS 0x04
|
||||
#define BIT_INT_STATUS_DRDY 0x08
|
||||
#define BIT_INT_STATUS_RESET_DONE 0x10
|
||||
#define BIT_INT_STATUS_PLL_DRY 0x20
|
||||
#define BIT_INT_STATUS_UI_FSYNC 0x40
|
||||
|
||||
/* Bank0 REG_INT_STATUS2 */
|
||||
#define BIT_INT_STATUS_WOM_X 0x01
|
||||
#define BIT_INT_STATUS_WOM_Y 0x02
|
||||
#define BIT_INT_STATUS_WOM_Z 0x04
|
||||
#define BIT_INT_STATUS_SMD 0x08
|
||||
#define BIT_INT_STATUS_WOM_XYZ \
|
||||
(BIT_INT_STATUS_WOM_X | BIT_INT_STATUS_WOM_Y | BIT_INT_STATUS_WOM_Z)
|
||||
|
||||
/* Bank0 REG_INT_STATUS3 */
|
||||
#define BIT_INT_STATUS_TAP_DET 0x01
|
||||
#define BIT_INT_STATUS_SLEEP_DET 0x02
|
||||
#define BIT_INT_STATUS_RAISE_DET 0x04
|
||||
#define BIT_INT_STATUS_TILT_DET 0x08
|
||||
#define BIT_INT_STATUS_STEP_CNT_OVFL 0x10
|
||||
#define BIT_INT_STATUS_STEP_DET 0x20
|
||||
#define BIT_INT_STATUS_DMP_POWER_SAVE 0x40
|
||||
|
||||
/* Bank0 REG_FIFO_CONFIG_REG */
|
||||
#define BIT_FIFO_MODE_BYPASS 0x00
|
||||
#define BIT_FIFO_MODE_STREAM 0x40
|
||||
#define BIT_FIFO_MODE_STOP_FULL 0x80
|
||||
|
||||
/* Bank0 REG_GYRO_ACCEL_CONFIG0 */
|
||||
#define BIT_ACCEL_UI_LNM_BW_2_FIR 0x00
|
||||
#define BIT_ACCEL_UI_LNM_BW_4_IIR 0x10
|
||||
#define BIT_ACCEL_UI_LNM_BW_5_IIR 0x20
|
||||
#define BIT_ACCEL_UI_LNM_BW_8_IIR 0x30
|
||||
#define BIT_ACCEL_UI_LNM_BW_10_IIR 0x40
|
||||
#define BIT_ACCEL_UI_LNM_BW_16_IIR 0x50
|
||||
#define BIT_ACCEL_UI_LNM_BW_20_IIR 0x60
|
||||
#define BIT_ACCEL_UI_LNM_BW_40_IIR 0x70
|
||||
#define BIT_ACCEL_UI_LNM_AVG_1 0xF0
|
||||
#define BIT_ACCEL_UI_LPM_BW_2_FIR 0x00
|
||||
#define BIT_ACCEL_UI_LPM_AVG_1 0x10
|
||||
#define BIT_ACCEL_UI_LPM_AVG_2 0x20
|
||||
#define BIT_ACCEL_UI_LPM_AVG_3 0x30
|
||||
#define BIT_ACCEL_UI_LPM_AVG_4 0x40
|
||||
#define BIT_ACCEL_UI_LPM_AVG_8 0x50
|
||||
#define BIT_ACCEL_UI_LPM_AVG_16 0x60
|
||||
#define BIT_ACCEL_UI_LPM_AVG_32 0x70
|
||||
#define BIT_ACCEL_UI_LPM_AVG_64 0x80
|
||||
#define BIT_ACCEL_UI_LPM_AVG_128 0x90
|
||||
#define BIT_GYRO_UI_LNM_BW_2_FIR 0x00
|
||||
#define BIT_GYRO_UI_LNM_BW_4_IIR 0x01
|
||||
#define BIT_GYRO_UI_LNM_BW_5_IIR 0x02
|
||||
#define BIT_GYRO_UI_LNM_BW_8_IIR 0x03
|
||||
#define BIT_GYRO_UI_LNM_BW_10_IIR 0x04
|
||||
#define BIT_GYRO_UI_LNM_BW_16_IIR 0x05
|
||||
#define BIT_GYRO_UI_LNM_BW_20_IIR 0x06
|
||||
#define BIT_GYRO_UI_LNM_BW_40_IIR 0x07
|
||||
#define BIT_GYRO_UI_LNM_AVG_1 0xF0
|
||||
#define BIT_GYRO_UI_LPM_BW_2_FIR 0x00
|
||||
#define BIT_GYRO_UI_LPM_AVG_1 0x01
|
||||
#define BIT_GYRO_UI_LPM_AVG_2 0x02
|
||||
#define BIT_GYRO_UI_LPM_AVG_3 0x03
|
||||
#define BIT_GYRO_UI_LPM_AVG_4 0x04
|
||||
#define BIT_GYRO_UI_LPM_AVG_8 0x05
|
||||
#define BIT_GYRO_UI_LPM_AVG_16 0x06
|
||||
#define BIT_GYRO_UI_LPM_AVG_32 0x07
|
||||
#define BIT_GYRO_UI_LPM_AVG_64 0x08
|
||||
#define BIT_GYRO_UI_LPM_AVG_128 0x09
|
||||
|
||||
/* Bank0 REG_SMD_CONFIG */
|
||||
#define BIT_WOM_INT_MODE_OR 0x00
|
||||
#define BIT_WOM_INT_MODE_AND 0x08
|
||||
#define BIT_WOM_MODE_INITIAL 0x00
|
||||
#define BIT_WOM_MODE_PREV 0x04
|
||||
#define BIT_SMD_MODE_OFF 0x00
|
||||
#define BIT_SMD_MODE_OLD 0x01
|
||||
#define BIT_SMD_MODE_SHORT 0x02
|
||||
#define BIT_SMD_MODE_LONG 0x03
|
||||
|
||||
/* Bank0 REG_TMST_CONFIG */
|
||||
#define BIT_FIFO_RAM_ISO_ENA 0x40
|
||||
#define BIT_EN_DREG_FIFO_D2A 0x20
|
||||
#define BIT_TMST_TO_REGS_EN 0x10
|
||||
#define BIT_TMST_RESOL 0x08
|
||||
#define BIT_TMST_DELTA_EN 0x04
|
||||
#define BIT_TMST_FSYNC_EN 0x02
|
||||
#define BIT_TMST_EN 0x01
|
||||
|
||||
/* Bank0 REG_APEX_CONFIG0 */
|
||||
#define BIT_DMP_ODR_25HZ 0x00
|
||||
#define BIT_DMP_ODR_50HZ 0x02
|
||||
#define BIT_DMP_ODR_100HZ 0x03
|
||||
#define BIT_RAISE_ENABLE 0x08
|
||||
#define BIT_TILT_ENABLE 0x10
|
||||
#define BIT_PEDO_ENABLE 0x20
|
||||
#define BIT_TAP_ENABLE 0x40
|
||||
#define BIT_DMP_POWER_SAVE_EN 0x80
|
||||
|
||||
/* Bank0 REG_ACCEL_CONFIG0 */
|
||||
#define BIT_ACCEL_FSR 0xE0
|
||||
#define BIT_ACCEL_ODR 0x0F
|
||||
|
||||
#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_500 0x0F
|
||||
#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 0x0B
|
||||
#define BIT_ACCEL_ODR_6 0x0C
|
||||
#define BIT_ACCEL_ODR_3 0x0D
|
||||
#define BIT_ACCEL_ODR_1 0x0E
|
||||
|
||||
/* Bank0 REG_GYRO_CONFIG0 */
|
||||
#define BIT_GYRO_FSR 0xE0
|
||||
#define BIT_GYRO_ODR 0x0F
|
||||
#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_500 0x0F
|
||||
#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 0x0B
|
||||
|
||||
/* Bank1 REG_INTF_CONFIG5 */
|
||||
#define BIT_PIN9_FUNC_INT2 0x00
|
||||
#define BIT_PIN9_FUNC_FSYNC 0x02
|
||||
#define BIT_PIN9_FUNC_CLKIN 0x04
|
||||
#define BIT_PIN9_FUNC_RSV 0x06
|
||||
|
||||
/* Bank4 REG_DRV_GYR_CFG0_REG */
|
||||
#define GYRO_DRV_TEST_FSMFORCE_D2A_LINEAR_START_MODE 0x0D
|
||||
#define GYRO_DRV_TEST_FSMFORCE_D2A_STEADY_STATE_AGC_REG_MODE 0x2A
|
||||
|
||||
/* Bank4 REG_DRV_GYR_CFG2_REG */
|
||||
#define GYRO_DRV_SPARE2_D2A_EN 0x01
|
||||
|
||||
/* Bank4 REG_INT_SOURCE6 */
|
||||
#define BIT_INT_TAP_DET_INT1_EN 0x01
|
||||
#define BIT_INT_SLEEP_DET_INT1_EN 0x02
|
||||
#define BIT_INT_RAISE_DET_INT1_EN 0x04
|
||||
#define BIT_INT_TILT_DET_INT1_EN 0x08
|
||||
#define BIT_INT_STEP_CNT_OVFL_INT1_EN 0x10
|
||||
#define BIT_INT_STEP_DET_INT1_EN 0x20
|
||||
#define BIT_INT_DMP_POWER_SAVE_INT1_EN 0x40
|
||||
|
||||
/* Bank4 REG_INT_SOURCE7 */
|
||||
#define BIT_INT_TAP_DET_INT2_EN 0x01
|
||||
#define BIT_INT_HIGHG_DET_INT2_EN 0x02
|
||||
#define BIT_INT_LOWG_DET_INT2_EN 0x04
|
||||
#define BIT_INT_TILT_DET_INT2_EN 0x80
|
||||
#define BIT_INT_STEP_CNT_OVFL_INT2_EN 0x10
|
||||
#define BIT_INT_STEP_DET_INT2_EN 0x20
|
||||
#define BIT_INT_DMP_POWER_SAVE_INT2_EN 0x40
|
||||
|
||||
/* Bank4 REG_INT_SOURCE8 */
|
||||
#define BIT_INT_AGC_RDY_IBI_EN 0x01
|
||||
#define BIT_INT_FIFO_FULL_IBI_EN 0x02
|
||||
#define BIT_INT_FIFO_THS_IBI_EN 0x04
|
||||
#define BIT_INT_UI_DRDY_IBI_EN 0x08
|
||||
#define BIT_INT_PLL_RDY_IBI_EN 0x10
|
||||
#define BIT_INT_FSYNC_IBI_EN 0x20
|
||||
#define BIT_INT_OIS1_DRDY_IBI_EN 0x40
|
||||
|
||||
/* Bank4 REG_INT_SOURCE9 */
|
||||
#define BIT_INT_DMP_POWER_SAVE_IBI_EN 0x01
|
||||
#define BIT_INT_WOM_X_IBI_EN 0x02
|
||||
#define BIT_INT_WOM_Y_IBI_EN 0x04
|
||||
#define BIT_INT_WOM_Z_IBI_EN 0x08
|
||||
#define BIT_INT_SMD_IBI_EN 0x10
|
||||
|
||||
/* Bank4 REG_INT_SOURCE10 */
|
||||
#define BIT_INT_TAP_DET_IBI_EN 0x01
|
||||
#define BIT_INT_HIGHG_DET_IBI_EN 0x02
|
||||
#define BIT_INT_LOWG_DET_IBI_EN 0x04
|
||||
#define BIT_INT_TILT_DET_IBI_EN 0x08
|
||||
#define BIT_INT_STEP_CNT_OVFL_IBI_EN 0x10
|
||||
#define BIT_INT_STEP_DET_IBI_EN 0x20
|
||||
|
||||
/* fifo data packet header */
|
||||
#define BIT_FIFO_HEAD_MSG 0x80
|
||||
#define BIT_FIFO_HEAD_ACCEL 0x40
|
||||
#define BIT_FIFO_HEAD_GYRO 0x20
|
||||
#define BIT_FIFO_HEAD_20 0x10
|
||||
#define BIT_FIFO_HEAD_TMSP_ODR 0x08
|
||||
#define BIT_FIFO_HEAD_TMSP_NO_ODR 0x04
|
||||
#define BIT_FIFO_HEAD_TMSP_FSYNC 0x0C
|
||||
#define BIT_FIFO_HEAD_ODR_ACCEL 0x02
|
||||
#define BIT_FIFO_HEAD_ODR_GYRO 0x01
|
||||
|
||||
/* data definitions */
|
||||
#define FIFO_PACKET_BYTE_SINGLE 8
|
||||
#define FIFO_PACKET_BYTE_6X 16
|
||||
#define FIFO_PACKET_BYTE_HIRES 20
|
||||
#define FIFO_COUNT_BYTE 2
|
||||
|
||||
/* sensor startup time */
|
||||
#define INV_ICM42600_GYRO_START_TIME 100
|
||||
#define INV_ICM42600_ACCEL_START_TIME 50
|
||||
|
||||
/* temperature sensor */
|
||||
/* scale by 100, 1LSB=1degC, 9447 */
|
||||
#define TEMP_SCALE 100
|
||||
/* 25 degC */
|
||||
#define TEMP_OFFSET (25 * TEMP_SCALE)
|
||||
|
||||
#ifdef SUPPORT_RTC_MODE
|
||||
#define BASE_SAMPLE_RATE (RTC_FREQ_HZ / 32)
|
||||
#else
|
||||
#define BASE_SAMPLE_RATE 1000
|
||||
#endif
|
||||
#define GESTURE_ACCEL_RATE 50
|
||||
#define ESI_GYRO_RATE 1000
|
||||
#define MPU_INIT_SENSOR_RATE_LNM 12 /* min Hz in LNM */
|
||||
#define MPU_INIT_SENSOR_RATE_LPM 3 /* min Hz in LPM */
|
||||
#define MAX_FIFO_PACKET_READ 16
|
||||
#define HARDWARE_FIFO_SIZE 2048
|
||||
#define FIFO_SIZE (HARDWARE_FIFO_SIZE * 7 / 8)
|
||||
#define LEFT_OVER_BYTES 128
|
||||
#define POWER_UP_TIME 100
|
||||
#define REG_UP_TIME_USEC 100
|
||||
#define IIO_BUFFER_BYTES 8
|
||||
#define BYTES_PER_SENSOR 6
|
||||
#define BYTES_FOR_TEMP 1
|
||||
#define MAX_BATCH_FIFO_SIZE FIFO_SIZE
|
||||
#define FIRST_DROP_SAMPLES_ACC_500HZ 20
|
||||
#define FIRST_DROP_SAMPLES_ACC_200HZ 10
|
||||
#define FIRST_DROP_SAMPLES_GYR_500HZ 20
|
||||
#define FIRST_DROP_SAMPLES_GYR_200HZ 10
|
||||
#define WOM_THRESHOLD 13 /* 1000 / 256 * 13 = 50.7mg */
|
||||
|
||||
#define BIT_GYRO_FSR 0xE0
|
||||
#define BIT_GYRO_ODR 0x0F
|
||||
#define BIT_ACCEL_FSR 0xE0
|
||||
#define BIT_ACCEL_ODR 0x0F
|
||||
|
||||
#define FIFO_ACCEL0_RESET_VALUE 0x80
|
||||
#define FIFO_ACCEL1_RESET_VALUE 0x00
|
||||
#define FIFO_GYRO0_RESET_VALUE 0x80
|
||||
#define FIFO_GYRO1_RESET_VALUE 0x00
|
||||
|
||||
#define APEX_TAP 0x08
|
||||
#define APEX_DOUBLE_TAP 0x10
|
||||
|
||||
/*
|
||||
* INT configurations
|
||||
* Polarity: 0 -> Active Low, 1 -> Active High
|
||||
* Drive circuit: 0 -> Open Drain, 1 -> Push-Pull
|
||||
* Mode: 0 -> Pulse, 1 -> Latch
|
||||
*/
|
||||
#define INT_POLARITY 1
|
||||
#define INT_DRIVE_CIRCUIT 1
|
||||
#define INT_MODE 0
|
||||
|
||||
#define ACC_LPM_MAX_RATE 500
|
||||
#define GYR_LPM_MAX_RATE 200
|
||||
|
||||
enum {
|
||||
GYRO_FS_2000DPS = 0,
|
||||
GYRO_FS_1000DPS,
|
||||
GYRO_FS_500DPS,
|
||||
GYRO_FS_250DPS,
|
||||
GYRO_FS_125DPS,
|
||||
GYRO_FS_62DPS,
|
||||
GYRO_FS_32DPS,
|
||||
GYRO_FS_15DPS,
|
||||
};
|
||||
|
||||
enum {
|
||||
ACCEL_FS_16G = 0,
|
||||
ACCEL_FS_8G,
|
||||
ACCEL_FS_4G,
|
||||
ACCEL_FS_2G,
|
||||
};
|
||||
|
||||
#endif /* __SENSOR_ICM42605_ICM42605_REG__ */
|
447
drivers/sensor/icm42605/icm42605_setup.c
Normal file
447
drivers/sensor/icm42605/icm42605_setup.c
Normal file
|
@ -0,0 +1,447 @@
|
|||
/*
|
||||
* Copyright (c) 2020 TDK Invensense
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
#include <sys/byteorder.h>
|
||||
#include <drivers/sensor.h>
|
||||
#include <logging/log.h>
|
||||
|
||||
#include "icm42605.h"
|
||||
#include "icm42605_reg.h"
|
||||
#include "icm42605_spi.h"
|
||||
|
||||
LOG_MODULE_REGISTER(ICM42605, CONFIG_SENSOR_LOG_LEVEL);
|
||||
|
||||
int icm42605_set_fs(const struct device *dev, uint16_t a_sf, uint16_t g_sf)
|
||||
{
|
||||
uint8_t databuf;
|
||||
int result;
|
||||
|
||||
result = inv_spi_read(REG_ACCEL_CONFIG0, &databuf, 1);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
databuf &= ~BIT_ACCEL_FSR;
|
||||
|
||||
databuf |= a_sf;
|
||||
|
||||
result = inv_spi_single_write(REG_ACCEL_CONFIG0, &databuf);
|
||||
|
||||
result = inv_spi_read(REG_GYRO_CONFIG0, &databuf, 1);
|
||||
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
databuf &= ~BIT_GYRO_FSR;
|
||||
databuf |= g_sf;
|
||||
|
||||
result = inv_spi_single_write(REG_GYRO_CONFIG0, &databuf);
|
||||
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int icm42605_set_odr(const struct device *dev, uint16_t a_rate, uint16_t g_rate)
|
||||
{
|
||||
uint8_t databuf;
|
||||
int result;
|
||||
|
||||
if (a_rate > 8000 || g_rate > 8000 ||
|
||||
a_rate < 1 || g_rate < 12) {
|
||||
LOG_ERR("Not supported frequency");
|
||||
return -ENOTSUP;
|
||||
}
|
||||
|
||||
result = inv_spi_read(REG_ACCEL_CONFIG0, &databuf, 1);
|
||||
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
databuf &= ~BIT_ACCEL_ODR;
|
||||
|
||||
if (a_rate > 4000) {
|
||||
databuf |= BIT_ACCEL_ODR_8000;
|
||||
} else if (a_rate > 2000) {
|
||||
databuf |= BIT_ACCEL_ODR_4000;
|
||||
} else if (a_rate > 1000) {
|
||||
databuf |= BIT_ACCEL_ODR_2000;
|
||||
} else if (a_rate > 500) {
|
||||
databuf |= BIT_ACCEL_ODR_1000;
|
||||
} else if (a_rate > 200) {
|
||||
databuf |= BIT_ACCEL_ODR_500;
|
||||
} else if (a_rate > 100) {
|
||||
databuf |= BIT_ACCEL_ODR_200;
|
||||
} else if (a_rate > 50) {
|
||||
databuf |= BIT_ACCEL_ODR_100;
|
||||
} else if (a_rate > 25) {
|
||||
databuf |= BIT_ACCEL_ODR_50;
|
||||
} else if (a_rate > 12) {
|
||||
databuf |= BIT_ACCEL_ODR_25;
|
||||
} else if (a_rate > 6) {
|
||||
databuf |= BIT_ACCEL_ODR_12;
|
||||
} else if (a_rate > 3) {
|
||||
databuf |= BIT_ACCEL_ODR_6;
|
||||
} else if (a_rate > 1) {
|
||||
databuf |= BIT_ACCEL_ODR_3;
|
||||
} else {
|
||||
databuf |= BIT_ACCEL_ODR_1;
|
||||
}
|
||||
|
||||
result = inv_spi_single_write(REG_ACCEL_CONFIG0, &databuf);
|
||||
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
LOG_DBG("Write Accel ODR 0x%X", databuf);
|
||||
|
||||
result = inv_spi_read(REG_GYRO_CONFIG0, &databuf, 1);
|
||||
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
databuf &= ~BIT_GYRO_ODR;
|
||||
|
||||
if (g_rate > 4000) {
|
||||
databuf |= BIT_GYRO_ODR_8000;
|
||||
} else if (g_rate > 2000) {
|
||||
databuf |= BIT_GYRO_ODR_4000;
|
||||
} else if (g_rate > 1000) {
|
||||
databuf |= BIT_GYRO_ODR_2000;
|
||||
} else if (g_rate > 500) {
|
||||
databuf |= BIT_GYRO_ODR_1000;
|
||||
} else if (g_rate > 200) {
|
||||
databuf |= BIT_GYRO_ODR_500;
|
||||
} else if (g_rate > 100) {
|
||||
databuf |= BIT_GYRO_ODR_200;
|
||||
} else if (g_rate > 50) {
|
||||
databuf |= BIT_GYRO_ODR_100;
|
||||
} else if (g_rate > 25) {
|
||||
databuf |= BIT_GYRO_ODR_50;
|
||||
} else if (g_rate > 12) {
|
||||
databuf |= BIT_GYRO_ODR_25;
|
||||
} else {
|
||||
databuf |= BIT_GYRO_ODR_12;
|
||||
}
|
||||
|
||||
LOG_DBG("Write GYRO ODR 0x%X", databuf);
|
||||
|
||||
result = inv_spi_single_write(REG_GYRO_CONFIG0, &databuf);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
int icm42605_sensor_init(const struct device *dev)
|
||||
{
|
||||
int result = 0;
|
||||
uint8_t v;
|
||||
|
||||
result = inv_spi_read(REG_WHO_AM_I, &v, 1);
|
||||
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
LOG_DBG("WHO AM I : 0x%X", v);
|
||||
|
||||
result = inv_spi_read(REG_DEVICE_CONFIG, &v, 1);
|
||||
|
||||
if (result) {
|
||||
LOG_DBG("read REG_DEVICE_CONFIG_REG failed");
|
||||
return result;
|
||||
}
|
||||
|
||||
v |= BIT_SOFT_RESET;
|
||||
|
||||
result = inv_spi_single_write(REG_DEVICE_CONFIG, &v);
|
||||
|
||||
if (result) {
|
||||
LOG_ERR("write REG_DEVICE_CONFIG failed");
|
||||
return result;
|
||||
}
|
||||
|
||||
/* Need at least 10ms after soft reset */
|
||||
k_msleep(10);
|
||||
|
||||
v = BIT_GYRO_AFSR_MODE_HFS | BIT_ACCEL_AFSR_MODE_HFS | BIT_CLK_SEL_PLL;
|
||||
|
||||
result = inv_spi_single_write(REG_INTF_CONFIG1, &v);
|
||||
|
||||
if (result) {
|
||||
LOG_ERR("write REG_INTF_CONFIG1 failed");
|
||||
return result;
|
||||
}
|
||||
|
||||
v = BIT_EN_DREG_FIFO_D2A |
|
||||
BIT_TMST_TO_REGS_EN |
|
||||
BIT_TMST_EN;
|
||||
|
||||
result = inv_spi_single_write(REG_TMST_CONFIG, &v);
|
||||
|
||||
if (result) {
|
||||
LOG_ERR("Write REG_TMST_CONFIG failed");
|
||||
return result;
|
||||
}
|
||||
|
||||
result = inv_spi_read(REG_INTF_CONFIG0, &v, 1);
|
||||
|
||||
if (result) {
|
||||
LOG_ERR("Read REG_INTF_CONFIG0 failed");
|
||||
return result;
|
||||
}
|
||||
|
||||
LOG_DBG("Read REG_INTF_CONFIG0 0x%X", v);
|
||||
|
||||
v |= BIT_UI_SIFS_DISABLE_I2C;
|
||||
|
||||
result = inv_spi_single_write(REG_INTF_CONFIG0, &v);
|
||||
|
||||
if (result) {
|
||||
LOG_ERR("Write REG_INTF_CONFIG failed");
|
||||
return result;
|
||||
}
|
||||
|
||||
v = 0;
|
||||
result = inv_spi_single_write(REG_INT_CONFIG1, &v);
|
||||
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
result = inv_spi_single_write(REG_PWR_MGMT0, &v);
|
||||
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int icm42605_turn_on_fifo(const struct device *dev)
|
||||
{
|
||||
const struct icm42605_data *drv_data = dev->data;
|
||||
|
||||
uint8_t int0_en, fifo_en;
|
||||
uint8_t burst_read[3];
|
||||
int result;
|
||||
uint8_t v = 0;
|
||||
|
||||
v = BIT_FIFO_MODE_BYPASS;
|
||||
result = inv_spi_single_write(REG_FIFO_CONFIG, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
v = 0;
|
||||
result = inv_spi_single_write(REG_FIFO_CONFIG1, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
result = inv_spi_read(REG_FIFO_COUNTH, burst_read, 2);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
result = inv_spi_read(REG_FIFO_DATA, burst_read, 3);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
v = BIT_FIFO_MODE_STREAM;
|
||||
result = inv_spi_single_write(REG_FIFO_CONFIG, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
fifo_en |= (BIT_FIFO_ACCEL_EN | BIT_FIFO_GYRO_EN | BIT_FIFO_WM_TH);
|
||||
|
||||
result = inv_spi_single_write(REG_FIFO_CONFIG1, &fifo_en);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
int0_en = BIT_INT_UI_DRDY_INT1_EN;
|
||||
result = inv_spi_single_write(REG_INT_SOURCE0, &int0_en);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
if (drv_data->tap_en) {
|
||||
v = BIT_TAP_ENABLE;
|
||||
result = inv_spi_single_write(REG_APEX_CONFIG0, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
v = BIT_DMP_INIT_EN;
|
||||
result = inv_spi_single_write(REG_SIGNAL_PATH_RESET, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
v = BIT_BANK_SEL_4;
|
||||
result = inv_spi_single_write(REG_BANK_SEL, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
v = BIT_INT_STATUS_TAP_DET;
|
||||
result = inv_spi_single_write(REG_INT_SOURCE6, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
v = BIT_BANK_SEL_0;
|
||||
result = inv_spi_single_write(REG_BANK_SEL, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
}
|
||||
|
||||
LOG_DBG("turn on fifo done");
|
||||
return 0;
|
||||
}
|
||||
|
||||
int icm42605_turn_off_fifo(const struct device *dev)
|
||||
{
|
||||
const struct icm42605_data *drv_data = dev->data;
|
||||
|
||||
uint8_t int0_en = 0;
|
||||
uint8_t burst_read[3];
|
||||
int result;
|
||||
uint8_t v = 0;
|
||||
|
||||
v = BIT_FIFO_MODE_BYPASS;
|
||||
result = inv_spi_single_write(REG_FIFO_CONFIG, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
v = 0;
|
||||
result = inv_spi_single_write(REG_FIFO_CONFIG1, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
result = inv_spi_read(REG_FIFO_COUNTH, burst_read, 2);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
result = inv_spi_read(REG_FIFO_DATA, burst_read, 3);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
result = inv_spi_single_write(REG_INT_SOURCE0, &int0_en);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
if (drv_data->tap_en) {
|
||||
v = 0;
|
||||
result = inv_spi_single_write(REG_APEX_CONFIG0, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
result = inv_spi_single_write(REG_SIGNAL_PATH_RESET, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
v = BIT_BANK_SEL_4;
|
||||
result = inv_spi_single_write(REG_BANK_SEL, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
v = 0;
|
||||
result = inv_spi_single_write(REG_INT_SOURCE6, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
v = BIT_BANK_SEL_0;
|
||||
result = inv_spi_single_write(REG_BANK_SEL, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int icm42605_turn_on_sensor(const struct device *dev)
|
||||
{
|
||||
struct icm42605_data *drv_data = dev->data;
|
||||
|
||||
uint8_t v = 0;
|
||||
int result = 0;
|
||||
|
||||
|
||||
if (drv_data->sensor_started) {
|
||||
LOG_ERR("Sensor already started");
|
||||
return -EALREADY;
|
||||
}
|
||||
|
||||
icm42605_set_fs(dev, drv_data->accel_sf, drv_data->gyro_sf);
|
||||
|
||||
icm42605_set_odr(dev, drv_data->accel_hz, drv_data->gyro_hz);
|
||||
|
||||
v |= BIT_ACCEL_MODE_LNM;
|
||||
v |= BIT_GYRO_MODE_LNM;
|
||||
|
||||
result = inv_spi_single_write(REG_PWR_MGMT0, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
/* Accelerometer sensor need at least 10ms startup time
|
||||
* Gyroscope sensor need at least 30ms startup time
|
||||
*/
|
||||
k_msleep(100);
|
||||
|
||||
icm42605_turn_on_fifo(dev);
|
||||
|
||||
drv_data->sensor_started = true;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int icm42605_turn_off_sensor(const struct device *dev)
|
||||
{
|
||||
uint8_t v = 0;
|
||||
int result = 0;
|
||||
|
||||
result = inv_spi_read(REG_PWR_MGMT0, &v, 1);
|
||||
|
||||
v ^= BIT_ACCEL_MODE_LNM;
|
||||
v ^= BIT_GYRO_MODE_LNM;
|
||||
|
||||
result = inv_spi_single_write(REG_PWR_MGMT0, &v);
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
/* Accelerometer sensor need at least 10ms startup time
|
||||
* Gyroscope sensor need at least 30ms startup time
|
||||
*/
|
||||
k_msleep(100);
|
||||
|
||||
icm42605_turn_off_fifo(dev);
|
||||
|
||||
return 0;
|
||||
}
|
18
drivers/sensor/icm42605/icm42605_setup.h
Normal file
18
drivers/sensor/icm42605/icm42605_setup.h
Normal file
|
@ -0,0 +1,18 @@
|
|||
/*
|
||||
* Copyright (c) 2020 TDK Invensense
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
#ifdef ZEPHYR_DRIVERS_SENSOR_ICM42605_ICM42605_SETUP_H_
|
||||
#define ZEPHYR_DRIVERS_SENSOR_ICM42605_ICM42605_SETUP_H_
|
||||
|
||||
#include <device.h>
|
||||
|
||||
int icm42605_sensor_init(const struct device *dev);
|
||||
int icm42605_turn_on_fifo(const struct device *dev);
|
||||
int icm42605_turn_off_fifo(const struct device *dev);
|
||||
int icm42605_turn_off_sensor(const struct device *dev);
|
||||
int icm42605_set_odr(const struct device *dev, int a_rate, int g_rate);
|
||||
|
||||
#endif /* __SENSOR_ICM42605_ICM42605_SETUP__ */
|
96
drivers/sensor/icm42605/icm42605_spi.c
Normal file
96
drivers/sensor/icm42605/icm42605_spi.c
Normal file
|
@ -0,0 +1,96 @@
|
|||
/*
|
||||
* Copyright (c) 2020 TDK Invensense
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
#include <device.h>
|
||||
#include <drivers/spi.h>
|
||||
#include <logging/log.h>
|
||||
#include <sys/__assert.h>
|
||||
|
||||
LOG_MODULE_REGISTER(ICM42605, CONFIG_SENSOR_LOG_LEVEL);
|
||||
|
||||
struct device *spi_dev;
|
||||
static struct spi_config *spi_cfg;
|
||||
|
||||
int inv_spi_single_write(uint8_t reg, const uint8_t *data)
|
||||
{
|
||||
int result;
|
||||
|
||||
const struct spi_buf buf[2] = {
|
||||
{
|
||||
.buf = ®,
|
||||
.len = 1,
|
||||
},
|
||||
{
|
||||
.buf = data,
|
||||
.len = 1,
|
||||
}
|
||||
};
|
||||
const struct spi_buf_set tx = {
|
||||
.buffers = buf,
|
||||
.count = 2,
|
||||
};
|
||||
|
||||
result = spi_write(spi_dev, spi_cfg, &tx);
|
||||
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int inv_spi_read(uint8_t reg, uint8_t *data, size_t len)
|
||||
{
|
||||
int result;
|
||||
unsigned char tx_buffer[2] = { 0, };
|
||||
|
||||
tx_buffer[0] = 0x80 | 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 = tx_buffer,
|
||||
.len = 1,
|
||||
},
|
||||
{
|
||||
.buf = data,
|
||||
.len = len,
|
||||
}
|
||||
};
|
||||
|
||||
const struct spi_buf_set rx = {
|
||||
.buffers = rx_buf,
|
||||
.count = 2,
|
||||
};
|
||||
|
||||
result = spi_transceive(spi_dev, spi_cfg, &tx, &rx);
|
||||
|
||||
if (result) {
|
||||
return result;
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
int icm42605_spi_init(const struct device *spi_device,
|
||||
const struct spi_config *spi_config)
|
||||
{
|
||||
__ASSERT_NO_MSG(spi_device);
|
||||
__ASSERT_NO_MSG(spi_config);
|
||||
|
||||
spi_dev = spi_device;
|
||||
spi_cfg = spi_config;
|
||||
|
||||
return 0;
|
||||
}
|
17
drivers/sensor/icm42605/icm42605_spi.h
Normal file
17
drivers/sensor/icm42605/icm42605_spi.h
Normal file
|
@ -0,0 +1,17 @@
|
|||
/*
|
||||
* Copyright (c) 2020 TDK Invensense
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
#ifdef ZEPHYR_DRIVERS_SENSOR_ICM42605_ICM42605_SPI_H_
|
||||
#define ZEPHYR_DRIVERS_SENSOR_ICM42605_ICM42605_SPI_H_
|
||||
|
||||
#include <device.h>
|
||||
|
||||
int inv_spi_single_write(uint8_t reg, uint8_t *data);
|
||||
int inv_spi_read(uint8_t reg, uint8_t *data, size_t len);
|
||||
int icm42605_spi_init(const struct device *spi_device,
|
||||
const struct spi_config *spi_config);
|
||||
|
||||
#endif /* __SENSOR_ICM42605_ICM42605_SPI__ */
|
151
drivers/sensor/icm42605/icm42605_trigger.c
Normal file
151
drivers/sensor/icm42605/icm42605_trigger.c
Normal file
|
@ -0,0 +1,151 @@
|
|||
/*
|
||||
* Copyright (c) 2016 TDK Invensense
|
||||
*
|
||||
* SPDX-License-Identifier: Apache-2.0
|
||||
*/
|
||||
|
||||
#include <device.h>
|
||||
#include <drivers/i2c.h>
|
||||
#include <sys/util.h>
|
||||
#include <kernel.h>
|
||||
#include <drivers/sensor.h>
|
||||
#include <logging/log.h>
|
||||
#include "icm42605.h"
|
||||
#include "icm42605_setup.h"
|
||||
|
||||
LOG_MODULE_DECLARE(ICM42605, CONFIG_SENSOR_LOG_LEVEL);
|
||||
|
||||
int icm42605_trigger_set(const struct device *dev,
|
||||
const struct sensor_trigger *trig,
|
||||
sensor_trigger_handler_t handler)
|
||||
{
|
||||
struct icm42605_data *drv_data = dev->data;
|
||||
const struct icm42605_config *cfg = dev->config;
|
||||
|
||||
if (trig->type != SENSOR_TRIG_DATA_READY
|
||||
&& trig->type != SENSOR_TRIG_TAP
|
||||
&& trig->type != SENSOR_TRIG_DOUBLE_TAP) {
|
||||
return -ENOTSUP;
|
||||
}
|
||||
|
||||
gpio_pin_interrupt_configure(drv_data->gpio, cfg->int_pin,
|
||||
GPIO_INT_DISABLE);
|
||||
|
||||
if (handler == NULL) {
|
||||
icm42605_turn_off_sensor(dev);
|
||||
return 0;
|
||||
}
|
||||
|
||||
if (trig->type == SENSOR_TRIG_DATA_READY) {
|
||||
drv_data->data_ready_handler = handler;
|
||||
drv_data->data_ready_trigger = *trig;
|
||||
} else if (trig->type == SENSOR_TRIG_TAP) {
|
||||
drv_data->tap_handler = handler;
|
||||
drv_data->tap_trigger = *trig;
|
||||
drv_data->tap_en = true;
|
||||
} else if (trig->type == SENSOR_TRIG_DOUBLE_TAP) {
|
||||
drv_data->double_tap_handler = handler;
|
||||
drv_data->double_tap_trigger = *trig;
|
||||
drv_data->tap_en = true;
|
||||
} else {
|
||||
return -ENOTSUP;
|
||||
}
|
||||
|
||||
gpio_pin_interrupt_configure(drv_data->gpio, cfg->int_pin,
|
||||
GPIO_INT_EDGE_TO_ACTIVE);
|
||||
|
||||
icm42605_turn_on_sensor(dev);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
static void icm42605_gpio_callback(const struct device *dev,
|
||||
struct gpio_callback *cb, uint32_t pins)
|
||||
{
|
||||
struct icm42605_data *drv_data =
|
||||
CONTAINER_OF(cb, struct icm42605_data, gpio_cb);
|
||||
const struct icm42605_config *cfg = drv_data->dev->config;
|
||||
|
||||
ARG_UNUSED(pins);
|
||||
|
||||
gpio_pin_interrupt_configure(drv_data->gpio, cfg->int_pin,
|
||||
GPIO_INT_DISABLE);
|
||||
|
||||
k_sem_give(&drv_data->gpio_sem);
|
||||
}
|
||||
|
||||
static void icm42605_thread_cb(void *arg)
|
||||
{
|
||||
const struct device *dev = arg;
|
||||
const struct icm42605_data *drv_data = dev->data;
|
||||
const struct icm42605_config *cfg = dev->config;
|
||||
|
||||
if (drv_data->data_ready_handler != NULL) {
|
||||
drv_data->data_ready_handler(dev,
|
||||
&drv_data->data_ready_trigger);
|
||||
}
|
||||
|
||||
if (drv_data->tap_handler != NULL ||
|
||||
drv_data->double_tap_handler != NULL) {
|
||||
icm42605_tap_fetch(dev);
|
||||
}
|
||||
|
||||
gpio_pin_interrupt_configure(drv_data->gpio, cfg->int_pin,
|
||||
GPIO_INT_EDGE_TO_ACTIVE);
|
||||
}
|
||||
|
||||
static void icm42605_thread(int dev_ptr, int unused)
|
||||
{
|
||||
const struct device *dev = INT_TO_POINTER(dev_ptr);
|
||||
const struct icm42605_data *drv_data = dev->data;
|
||||
|
||||
ARG_UNUSED(unused);
|
||||
|
||||
while (1) {
|
||||
k_sem_take(&drv_data->gpio_sem, K_FOREVER);
|
||||
icm42605_thread_cb(dev);
|
||||
}
|
||||
}
|
||||
|
||||
int icm42605_init_interrupt(const struct device *dev)
|
||||
{
|
||||
struct icm42605_data *drv_data = dev->data;
|
||||
const struct icm42605_config *cfg = dev->config;
|
||||
int result = 0;
|
||||
|
||||
/* setup data ready gpio interrupt */
|
||||
drv_data->gpio = device_get_binding(cfg->int_label);
|
||||
if (drv_data->gpio == NULL) {
|
||||
LOG_ERR("Failed to get pointer to %s device",
|
||||
cfg->int_label);
|
||||
return -ENODEV;
|
||||
}
|
||||
|
||||
drv_data->dev = dev;
|
||||
|
||||
gpio_pin_configure(drv_data->gpio, cfg->int_pin,
|
||||
GPIO_INPUT | cfg->int_flags);
|
||||
|
||||
gpio_init_callback(&drv_data->gpio_cb,
|
||||
icm42605_gpio_callback,
|
||||
BIT(cfg->int_pin));
|
||||
|
||||
result = gpio_add_callback(drv_data->gpio, &drv_data->gpio_cb);
|
||||
if (result < 0) {
|
||||
LOG_ERR("Failed to set gpio callback");
|
||||
return result;
|
||||
}
|
||||
|
||||
k_sem_init(&drv_data->gpio_sem, 0, UINT_MAX);
|
||||
|
||||
k_thread_create(&drv_data->thread, drv_data->thread_stack,
|
||||
CONFIG_ICM42605_THREAD_STACK_SIZE,
|
||||
(k_thread_entry_t)icm42605_thread, dev,
|
||||
0, NULL, K_PRIO_COOP(CONFIG_ICM42605_THREAD_PRIORITY),
|
||||
0, K_NO_WAIT);
|
||||
|
||||
gpio_pin_interrupt_configure(drv_data->gpio, cfg->int_pin,
|
||||
GPIO_INT_EDGE_TO_INACTIVE);
|
||||
|
||||
return 0;
|
||||
}
|
89
dts/bindings/sensor/invensense,icm42605.yaml
Normal file
89
dts/bindings/sensor/invensense,icm42605.yaml
Normal file
|
@ -0,0 +1,89 @@
|
|||
# Copyright (c) 2020 TDK Invensense
|
||||
# SPDX-License-Identifier: Apache-2.0
|
||||
|
||||
description: ICM-42605 motion tracking device
|
||||
|
||||
# ICM-42605 is SPI.
|
||||
compatible: "invensense,icm42605"
|
||||
|
||||
include: spi-device.yaml
|
||||
|
||||
properties:
|
||||
int-gpios:
|
||||
type: phandle-array
|
||||
required: true
|
||||
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
|
||||
required: false
|
||||
default: 12
|
||||
description: |
|
||||
Default frequency of accelerometer. (Unit - Hz)
|
||||
Maps to ACCEL_ODR field in ACCEL_CONFIG0 setting
|
||||
enum:
|
||||
- 1
|
||||
- 3
|
||||
- 6
|
||||
- 12
|
||||
- 25
|
||||
- 50
|
||||
- 100
|
||||
- 200
|
||||
- 500
|
||||
- 1000
|
||||
- 2000
|
||||
- 4000
|
||||
- 8000
|
||||
|
||||
gyro-hz:
|
||||
type: int
|
||||
required: false
|
||||
default: 12
|
||||
description: |
|
||||
Default frequency of gyroscope. (Unit - Hz)
|
||||
Maps to GYRO_ODR field in GYRO_CONFIG0 setting
|
||||
enum:
|
||||
- 12
|
||||
- 25
|
||||
- 50
|
||||
- 100
|
||||
- 200
|
||||
- 500
|
||||
- 1000
|
||||
- 2000
|
||||
- 4000
|
||||
- 8000
|
||||
|
||||
accel-fs:
|
||||
type: int
|
||||
required: false
|
||||
default: 16
|
||||
description: |
|
||||
Default full scale of accelerometer. (Unit - g)
|
||||
Maps to ACCEL_FS_SEL field in ACCEL_CONFIG0 setting
|
||||
enum:
|
||||
- 16
|
||||
- 8
|
||||
- 4
|
||||
- 2
|
||||
|
||||
gyro-fs:
|
||||
type: int
|
||||
required: false
|
||||
default: 2000
|
||||
description: |
|
||||
Default full scale of gyroscope. (Unit - DPS)
|
||||
Maps to GYRO_FS_SEL field in GYRO_CONFIG0 setting
|
||||
enum:
|
||||
- 2000
|
||||
- 1000
|
||||
- 500
|
||||
- 250
|
||||
- 125
|
||||
- 62.5
|
||||
- 31.25
|
||||
- 15.625
|
|
@ -6,6 +6,8 @@ CONFIG_SENSOR=y
|
|||
CONFIG_SPI=y
|
||||
CONFIG_LOG=y
|
||||
CONFIG_SENSOR_LOG_LEVEL_DBG=y
|
||||
CONFIG_ICM42605=y
|
||||
CONFIG_ICM42605_TRIGGER_OWN_THREAD=y
|
||||
CONFIG_IIS3DHHC=y
|
||||
CONFIG_ISL29035=y
|
||||
CONFIG_LIS2DH=y
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue