36#include "mcu_periph/gpio_arch.h"
52 {4.36332, 4.36332, 4.36332},
53 {2.18166, 2.18166, 2.18166},
54 {1.09083, 1.09083, 1.09083},
55 {0.545415, 0.545415, 0.545415},
56 {0.272707, 0.272707, 0.272707},
57 {0.136353, 0.136353, 0.136353},
58 {0.0681769, 0.0681769, 0.0681769},
59 {0.0340884, 0.0340884, 0.0340884},
65 {4.905, 4.905, 4.905},
66 {2.4525, 2.4525, 2.4525},
67 {1.22583, 1.22583, 1.22583},
68 {0.61312, 0.61312, 0.61312},
215 inv->register_bank = 0xFF;
227 inv->spi.trans.slave_idx =
inv->spi.slave_idx;
228 inv->spi.trans.output_length = 0;
229 inv->spi.trans.input_length = 0;
230 inv->spi.trans.before_cb =
NULL;
231 inv->spi.trans.after_cb =
NULL;
232 inv->spi.trans.input_buf =
inv->spi.rx_buf;
233 inv->spi.trans.output_buf =
inv->spi.tx_buf;
236 inv->rx_buffer =
inv->spi.rx_buf;
237 inv->tx_buffer =
inv->spi.tx_buf;
238 inv->rx_length = &
inv->spi.trans.input_length;
242 inv->i2c.trans.slave_addr =
inv->i2c.slave_addr;
247 inv->rx_length = &
inv->i2c.trans.len_r;
269 switch(
inv->status) {
284 switch (
inv->parser) {
323 inv->register_bank =
inv->tx_buffer[1];
332 switch(
inv->status) {
364 switch (
inv->parser) {
388 if(*
inv->rx_length > 3) {
419 switch(
inv->status) {
453 uint8_t accel_samplerate = 17 -
inv->accel_odr;
456 if (accel_samplerate > gyro_samplerate)
467 if ((data[0] & 0xFC) != 0x68) {
606 switch(
inv->gyro_odr) {
608 inv->gyro_samplerate = 32000;
611 inv->gyro_samplerate = 16000;
614 inv->gyro_samplerate = 8000;
617 inv->gyro_samplerate = 4000;
620 inv->gyro_samplerate = 2000;
623 inv->gyro_samplerate = 1000;
626 inv->gyro_samplerate = 200;
629 inv->gyro_samplerate = 100;
632 inv->gyro_samplerate = 50;
635 inv->gyro_samplerate = 25;
638 inv->gyro_samplerate = 12.5;
641 inv->gyro_samplerate = 6.25;
644 inv->gyro_samplerate = 3.125;
647 inv->gyro_samplerate = 1.5625;
650 inv->gyro_samplerate = 500;
653 switch(
inv->accel_odr) {
655 inv->accel_samplerate = 32000;
658 inv->accel_samplerate = 16000;
661 inv->accel_samplerate = 8000;
664 inv->accel_samplerate = 4000;
667 inv->accel_samplerate = 2000;
670 inv->accel_samplerate = 1000;
673 inv->accel_samplerate = 200;
676 inv->accel_samplerate = 100;
679 inv->accel_samplerate = 50;
682 inv->accel_samplerate = 25;
685 inv->accel_samplerate = 12.5;
688 inv->accel_samplerate = 6.25;
691 inv->accel_samplerate = 3.125;
694 inv->accel_samplerate = 1.5625;
697 inv->accel_samplerate = 500;
725 inv->tx_buffer[0] = reg;
726 inv->tx_buffer[1] = value;
730 inv->spi.trans.output_length = 2;
731 inv->spi.trans.input_length = 0;
764 inv->spi.trans.output_length = 2;
765 inv->spi.trans.input_length = 1 + size;
766 inv->tx_buffer[1] = 0;
794 inv->spi.trans.output_length = 2;
795 inv->spi.trans.input_length = 0;
826 switch(
inv->config_idx) {
937 switch(
inv->parser) {
Main include for ABI (AirBorneInterface).
uint32_t get_sys_time_usec(void)
Get the time in microseconds since startup.
bool i2c_transmit(struct i2c_periph *p, struct i2c_transaction *t, uint8_t s_addr, uint8_t len)
Submit a write only transaction.
bool i2c_transceive(struct i2c_periph *p, struct i2c_transaction *t, uint8_t s_addr, uint8_t len_w, uint16_t len_r)
Submit a write/read transaction.
@ I2CTransSuccess
transaction successfully finished by I2C driver
@ I2CTransFailed
transaction failed
@ I2CTransDone
transaction set to done by user level
#define RMAT_COPY(_o, _i)
int32_t p
in rad/s with INT32_RATE_FRAC
int32_t r
in rad/s with INT32_RATE_FRAC
int32_t q
in rad/s with INT32_RATE_FRAC
bool spi_submit(struct spi_periph *p, struct spi_transaction *t)
Submit SPI transaction.
@ SPICpolIdleHigh
CPOL = 1.
@ SPISelectUnselect
slave is selected before transaction and unselected after
void imu_set_defaults_gyro(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Rates *neutral, const struct FloatRates *scale_f)
Set the defaults for a gyro sensor WARNING: Should be called before sensor is publishing messages to ...
void imu_set_defaults_accel(uint8_t abi_id, const struct Int32RMat *imu_to_sensor, const struct Int32Vect3 *neutral, const struct FloatVect3 *scale_f)
Set the defaults for a accel sensor WARNING: Should be called before sensor is publishing messages to...
Inertial Measurement Unit interface.
#define GYRO_FS_SEL_SHIFT
#define ACCEL_FS_SEL_SHIFT
static const uint16_t invensense3_aaf4x605[][4]
void invensense3_periodic(struct invensense3_t *inv)
Should be called periodically to request sensor readings.
static const struct FloatRates invensense3_gyro_scale_f[8]
static void invensense3_parse_fifo_data(struct invensense3_t *inv, uint8_t *data, uint16_t samples)
Parse the FIFO buffer data.
static int samples_from_odr(int odr)
static const uint8_t invensense3_fifo_sample_size[4]
static const uint16_t invensense3_aaf[][4]
static void invensense3_parse_reg_data(struct invensense3_t *inv, uint8_t *data)
Parse data from registers.
static bool invensense3_reset_fifo(struct invensense3_t *inv)
Reset FIFO (can be useful in some situations)
static bool invensense3_select_bank(struct invensense3_t *inv, uint8_t bank)
Select the correct register bank.
void invensense3_event(struct invensense3_t *inv)
Should be called in the event thread.
static bool invensense3_config(struct invensense3_t *inv)
Configure the Invensense 3 device register by register.
static void invensense3_fix_config(struct invensense3_t *inv)
This fixes the configuration errors and sets the correct scalings.
static const struct FloatVect3 invensense3_accel_scale_f[5]
static bool invensense3_register_read(struct invensense3_t *inv, uint16_t bank_reg, uint16_t size)
Read a register based on a combined bank/regsiter value.
static bool invensense3_register_write(struct invensense3_t *inv, uint16_t bank_reg, uint8_t value)
Write a register based on a combined bank/regsiter value.
void invensense3_init(struct invensense3_t *inv)
Initialize the invensense v3 sensor instance.
Driver for the Invensense V3 IMUs ICM40605, ICM40609, ICM42605, IIM42652 and ICM42688.
@ INVENSENSE3_ACCEL_RANGE_16G
@ INVENSENSE3_ACCEL_RANGE_4G
@ INVENSENSE3_GYRO_ODR_4KHZ
@ INVENSENSE3_GYRO_ODR_25HZ
@ INVENSENSE3_GYRO_ODR_500HZ
@ INVENSENSE3_GYRO_ODR_8KHZ
@ INVENSENSE3_GYRO_ODR_1_5625HZ
@ INVENSENSE3_GYRO_ODR_100HZ
@ INVENSENSE3_GYRO_ODR_2KHZ
@ INVENSENSE3_GYRO_ODR_50HZ
@ INVENSENSE3_GYRO_ODR_1KHZ
@ INVENSENSE3_GYRO_ODR_16KHZ
Not possible for ICM40605 and ICM42605.
@ INVENSENSE3_GYRO_ODR_32KHZ
Not possible for ICM40605 and ICM42605.
@ INVENSENSE3_GYRO_ODR_3_125HZ
@ INVENSENSE3_GYRO_ODR_6_25HZ
@ INVENSENSE3_GYRO_ODR_200HZ
@ INVENSENSE3_GYRO_ODR_12_5HZ
@ INVENSENSE3_PARSER_FIFO
@ INVENSENSE3_PARSER_REGISTERS
@ INVENSENSE3_ACCEL_ODR_4KHZ
@ INVENSENSE3_ACCEL_ODR_16KHZ
Not possible for ICM40605 and ICM42605.
@ INVENSENSE3_ACCEL_ODR_50HZ
@ INVENSENSE3_ACCEL_ODR_32KHZ
Not possible for ICM40605 and ICM42605.
@ INVENSENSE3_ACCEL_ODR_2KHZ
@ INVENSENSE3_ACCEL_ODR_25HZ
@ INVENSENSE3_ACCEL_ODR_1_5625HZ
@ INVENSENSE3_ACCEL_ODR_8KHZ
@ INVENSENSE3_ACCEL_ODR_6_25HZ
@ INVENSENSE3_ACCEL_ODR_200HZ
@ INVENSENSE3_ACCEL_ODR_100HZ
@ INVENSENSE3_ACCEL_ODR_1KHZ
@ INVENSENSE3_ACCEL_ODR_500HZ
@ INVENSENSE3_ACCEL_ODR_12_5HZ
@ INVENSENSE3_ACCEL_ODR_3_125HZ
@ INVENSENSE3_SAMPLE_SIZE_PK3
#define INVENSENSE3_FIFO_BUFFER_LEN
Register and address definitions for the Invensense V3 from ardupilot.
#define INV3REG_INTF_CONFIG1
#define FIFO_CONFIG_MODE_SHIFT
#define INV3REG_FIFO_CONFIG
#define FIFO_CONFIG_MODE_STOP_ON_FULL
#define INV3REG_GYRO_CONFIG_STATIC2
#define INV3REG_ACCEL_CONFIG_STATIC2
#define BIT_FIFO_CONFIG1_ACCEL_EN
#define INV3_WHOAMI_ICM42605
#define BIT_FIFO_CONFIG1_GYRO_EN
#define INV3REG_FIFO_CONFIG3
#define ACCEL_AAF_BITSHIFT_SHIFT
#define INV3REG_PWR_MGMT0
#define INV3REG_INT_CONFIG1
#define BIT_SIGNAL_PATH_RESET_FIFO_FLUSH
#define INV3REG_FIFO_CONFIG1
#define BIT_FIFO_FULL_INT_EN
#define ACCEL_AAF_DELT_SHIFT
#define BIT_FIFO_CONFIG1_TEMP_EN
#define INV3REG_INTF_CONFIG0
#define INV3REG_INT_SOURCE0
#define INV3_WHOAMI_ICM42688
#define GYRO_AAF_BITSHIFT_SHIFT
#define INV3REG_TEMP_DATA1
#define INV3_WHOAMI_ICM40605
#define BIT_INT_ASYNC_RESET
#define INV3REG_DEVICE_CONFIG
#define INV3REG_GYRO_CONFIG_STATIC3
#define BIT_FIFO_THS_INT_EN
#define INV3REG_ACCEL_CONFIG_STATIC4
#define INV3REG_GYRO_CONFIG_STATIC5
#define INV3REG_GYRO_CONFIG_STATIC4
#define BIT_UI_DRDY_INT_EN
#define INV3_WHOAMI_IIM42652
#define INV3REG_ACCEL_CONFIG_STATIC3
#define INV3REG_ACCEL_CONFIG0
#define BIT_DEVICE_CONFIG_SOFT_RESET_CONFIG
#define INV3REG_FIFO_CONFIG2
#define INV3REG_FIFO_COUNTH
#define INV3_WHOAMI_ICM40609
#define INV3REG_SIGNAL_PATH_RESET
#define INV3REG_GYRO_CONFIG0
Paparazzi floating point algebra.
Paparazzi fixed point algebra.
Paparazzi atmospheric pressure conversion utilities.
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
int int32_t
Typedef defining 32 bit int type.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
short int16_t
Typedef defining 16 bit short type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
signed char int8_t
Typedef defining 8 bit char type.