2016-01-12 14:22:11 -04:00
|
|
|
#pragma once
|
2016-12-13 21:47:22 -04:00
|
|
|
/*
|
|
|
|
driver for the invensense range of IMUs, including:
|
|
|
|
|
|
|
|
MPU6000
|
|
|
|
MPU9250
|
|
|
|
ICM-20608
|
|
|
|
*/
|
2011-11-12 23:20:25 -04:00
|
|
|
|
|
|
|
#include <stdint.h>
|
2015-10-14 10:54:59 -03:00
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2016-01-12 14:22:11 -04:00
|
|
|
#include <AP_HAL/I2CDevice.h>
|
|
|
|
#include <AP_HAL/SPIDevice.h>
|
|
|
|
#include <AP_HAL/utility/OwnPtr.h>
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
2015-10-14 10:54:59 -03:00
|
|
|
#include <Filter/Filter.h>
|
|
|
|
#include <Filter/LowPassFilter.h>
|
2016-01-12 14:22:11 -04:00
|
|
|
#include <Filter/LowPassFilter2p.h>
|
2015-08-16 16:23:24 -03:00
|
|
|
|
2011-11-12 23:20:25 -04:00
|
|
|
#include "AP_InertialSensor.h"
|
2016-01-19 21:26:31 -04:00
|
|
|
#include "AP_InertialSensor_Backend.h"
|
2015-08-16 16:23:24 -03:00
|
|
|
#include "AuxiliaryBus.h"
|
2011-11-12 23:20:25 -04:00
|
|
|
|
2016-12-13 21:47:22 -04:00
|
|
|
class AP_Invensense_AuxiliaryBus;
|
|
|
|
class AP_Invensense_AuxiliaryBusSlave;
|
2015-08-16 16:23:24 -03:00
|
|
|
|
2016-12-13 21:47:22 -04:00
|
|
|
class AP_InertialSensor_Invensense : public AP_InertialSensor_Backend
|
2011-11-12 23:20:25 -04:00
|
|
|
{
|
2016-12-13 21:47:22 -04:00
|
|
|
friend AP_Invensense_AuxiliaryBus;
|
|
|
|
friend AP_Invensense_AuxiliaryBusSlave;
|
2015-08-16 16:23:24 -03:00
|
|
|
|
2012-08-17 03:19:57 -03:00
|
|
|
public:
|
2016-12-13 21:47:22 -04:00
|
|
|
virtual ~AP_InertialSensor_Invensense();
|
|
|
|
static AP_InertialSensor_Invensense &from(AP_InertialSensor_Backend &backend) {
|
|
|
|
return static_cast<AP_InertialSensor_Invensense&>(backend);
|
2015-09-13 15:28:02 -03:00
|
|
|
}
|
2011-11-12 23:20:25 -04:00
|
|
|
|
2016-01-12 14:22:11 -04:00
|
|
|
static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
|
2016-11-03 06:19:04 -03:00
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
|
2019-08-27 06:28:37 -03:00
|
|
|
enum Rotation rotation);
|
2016-01-12 14:22:11 -04:00
|
|
|
|
|
|
|
static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
|
2016-11-03 06:19:04 -03:00
|
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev,
|
2019-08-27 06:28:37 -03:00
|
|
|
enum Rotation rotation);
|
2016-01-12 14:22:11 -04:00
|
|
|
|
2014-10-14 01:48:33 -03:00
|
|
|
/* update accel and gyro state */
|
2022-04-01 16:59:10 -03:00
|
|
|
bool update() override __RAMFUNC__; /* front end */
|
2021-09-14 17:28:20 -03:00
|
|
|
void accumulate() override; /* front end */
|
2011-11-12 23:20:25 -04:00
|
|
|
|
2015-08-16 16:23:24 -03:00
|
|
|
/*
|
|
|
|
* Return an AuxiliaryBus if the bus driver allows it
|
|
|
|
*/
|
2015-10-02 15:02:16 -03:00
|
|
|
AuxiliaryBus *get_auxiliary_bus() override;
|
2015-08-16 16:23:24 -03:00
|
|
|
|
2015-08-05 13:29:35 -03:00
|
|
|
void start() override;
|
|
|
|
|
2020-05-21 15:29:28 -03:00
|
|
|
// get a startup banner to output to the GCS
|
|
|
|
bool get_output_banner(char* banner, uint8_t banner_len) override;
|
|
|
|
|
2016-12-13 21:47:22 -04:00
|
|
|
enum Invensense_Type {
|
|
|
|
Invensense_MPU6000=0,
|
2017-02-06 19:47:39 -04:00
|
|
|
Invensense_MPU6500,
|
2016-12-13 21:47:22 -04:00
|
|
|
Invensense_MPU9250,
|
|
|
|
Invensense_ICM20608,
|
2017-03-01 20:52:03 -04:00
|
|
|
Invensense_ICM20602,
|
2019-03-25 15:25:33 -03:00
|
|
|
Invensense_ICM20601,
|
2017-03-09 19:43:54 -04:00
|
|
|
Invensense_ICM20789,
|
2018-04-10 08:08:52 -03:00
|
|
|
Invensense_ICM20689,
|
2016-12-13 21:47:22 -04:00
|
|
|
};
|
2018-03-18 20:28:33 -03:00
|
|
|
|
|
|
|
// acclerometers on Invensense sensors will return values up to
|
|
|
|
// 24G, but they are not guaranteed to be remotely linear past
|
|
|
|
// 16G
|
|
|
|
const uint16_t multiplier_accel = INT16_MAX/(26*GRAVITY_MSS);
|
|
|
|
|
2014-10-14 01:48:33 -03:00
|
|
|
private:
|
2016-12-13 21:47:22 -04:00
|
|
|
AP_InertialSensor_Invensense(AP_InertialSensor &imu,
|
2016-01-12 14:22:11 -04:00
|
|
|
AP_HAL::OwnPtr<AP_HAL::Device> dev,
|
2016-11-03 06:19:04 -03:00
|
|
|
enum Rotation rotation);
|
2015-07-28 13:43:27 -03:00
|
|
|
|
2016-01-12 14:22:11 -04:00
|
|
|
/* Initialize sensor*/
|
|
|
|
bool _init();
|
|
|
|
bool _hardware_init();
|
2016-11-05 06:43:28 -03:00
|
|
|
bool _check_whoami();
|
2012-11-07 02:20:22 -04:00
|
|
|
|
2016-11-08 23:07:31 -04:00
|
|
|
void _set_filter_register(void);
|
2021-09-14 17:28:20 -03:00
|
|
|
void _fifo_reset(bool log_error) __RAMFUNC__;
|
2022-10-22 01:48:46 -03:00
|
|
|
void _fast_fifo_reset() __RAMFUNC__;
|
|
|
|
|
2016-01-12 14:22:11 -04:00
|
|
|
bool _has_auxiliary_bus();
|
2011-11-12 23:20:25 -04:00
|
|
|
|
2016-01-12 14:22:11 -04:00
|
|
|
/* Read samples from FIFO (FIFO enabled) */
|
2021-09-14 17:28:20 -03:00
|
|
|
void _read_fifo() __RAMFUNC__;
|
2012-10-11 21:27:19 -03:00
|
|
|
|
2016-01-12 14:22:11 -04:00
|
|
|
/* Check if there's data available by either reading DRDY pin or register */
|
2021-09-14 17:28:20 -03:00
|
|
|
bool _data_ready() __RAMFUNC__;
|
2011-11-12 23:20:25 -04:00
|
|
|
|
2016-01-12 14:22:11 -04:00
|
|
|
/* Poll for new data (non-blocking) */
|
2021-09-14 17:28:20 -03:00
|
|
|
void _poll_data() __RAMFUNC__;
|
2013-02-06 19:23:08 -04:00
|
|
|
|
2021-02-23 19:46:23 -04:00
|
|
|
// debug function to watch for register changes
|
2021-09-14 17:28:20 -03:00
|
|
|
void _check_register_change(void) __RAMFUNC__;
|
2021-02-23 19:46:23 -04:00
|
|
|
|
2016-01-12 14:22:11 -04:00
|
|
|
/* Read and write functions taking the differences between buses into
|
|
|
|
* account */
|
2021-09-14 17:28:20 -03:00
|
|
|
bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size) __RAMFUNC__;
|
|
|
|
uint8_t _register_read(uint8_t reg) __RAMFUNC__;
|
|
|
|
void _register_write(uint8_t reg, uint8_t val, bool checked=false) __RAMFUNC__;
|
2014-10-16 19:24:08 -03:00
|
|
|
|
2021-09-14 17:28:20 -03:00
|
|
|
bool _accumulate(uint8_t *samples, uint8_t n_samples) __RAMFUNC__;
|
|
|
|
bool _accumulate_sensor_rate_sampling(uint8_t *samples, uint8_t n_samples) __RAMFUNC__;
|
2015-09-25 11:04:49 -03:00
|
|
|
|
2021-09-14 17:28:20 -03:00
|
|
|
bool _check_raw_temp(int16_t t2) __RAMFUNC__;
|
2016-11-26 04:02:22 -04:00
|
|
|
|
|
|
|
int16_t _raw_temp;
|
|
|
|
|
2016-01-12 14:22:11 -04:00
|
|
|
// instance numbers of accel and gyro data
|
|
|
|
uint8_t _gyro_instance;
|
|
|
|
uint8_t _accel_instance;
|
2011-11-12 23:20:25 -04:00
|
|
|
|
2019-04-04 19:07:44 -03:00
|
|
|
float temp_sensitivity = 1.0f/340; // degC/LSB
|
|
|
|
float temp_zero = 36.53f; // degC
|
2017-03-29 08:09:16 -03:00
|
|
|
|
2016-01-12 14:22:11 -04:00
|
|
|
float _temp_filtered;
|
2016-08-08 12:38:11 -03:00
|
|
|
float _accel_scale;
|
2019-03-25 15:25:33 -03:00
|
|
|
float _gyro_scale;
|
2018-04-09 23:16:45 -03:00
|
|
|
|
|
|
|
float _fifo_accel_scale;
|
|
|
|
float _fifo_gyro_scale;
|
2016-01-12 14:22:11 -04:00
|
|
|
LowPassFilter2pFloat _temp_filter;
|
2020-09-01 02:42:43 -03:00
|
|
|
uint32_t last_reset_ms;
|
|
|
|
uint8_t reset_count;
|
2022-10-22 01:48:46 -03:00
|
|
|
uint8_t fast_reset_count;
|
|
|
|
uint8_t last_fast_reset_count;
|
|
|
|
uint32_t last_fast_reset_count_report_ms;
|
2015-07-25 14:29:13 -03:00
|
|
|
|
2016-11-03 06:19:04 -03:00
|
|
|
enum Rotation _rotation;
|
|
|
|
|
2021-02-23 19:46:23 -04:00
|
|
|
// enable checking of unexpected resets of offsets
|
|
|
|
bool _enable_offset_checking;
|
|
|
|
|
2022-10-22 01:48:46 -03:00
|
|
|
// enable fast fifo reset instead of full fifo reset
|
|
|
|
bool _enable_fast_fifo_reset;
|
|
|
|
|
2021-02-23 19:46:23 -04:00
|
|
|
// ICM-20602 y offset register. See usage for explanation
|
|
|
|
uint8_t _saved_y_ofs_high;
|
|
|
|
|
2016-01-12 14:22:11 -04:00
|
|
|
AP_HAL::DigitalSource *_drdy_pin;
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
|
2016-12-13 21:47:22 -04:00
|
|
|
AP_Invensense_AuxiliaryBus *_auxiliary_bus;
|
2016-11-05 06:43:28 -03:00
|
|
|
|
2016-12-13 21:47:22 -04:00
|
|
|
// which sensor type this is
|
|
|
|
enum Invensense_Type _mpu_type;
|
2016-11-08 20:33:05 -04:00
|
|
|
|
|
|
|
// are we doing more than 1kHz sampling?
|
2016-11-08 21:16:54 -04:00
|
|
|
bool _fast_sampling;
|
2016-11-08 20:33:05 -04:00
|
|
|
|
2020-05-21 15:29:28 -03:00
|
|
|
// what downsampling rate are we using from the FIFO for gyros?
|
|
|
|
uint8_t _gyro_fifo_downsample_rate;
|
2018-01-17 03:17:33 -04:00
|
|
|
|
2020-05-21 15:29:28 -03:00
|
|
|
// what downsampling rate are we using from the FIFO for accels?
|
|
|
|
uint8_t _accel_fifo_downsample_rate;
|
|
|
|
|
|
|
|
// ratio of raw gyro to accel sample rate
|
|
|
|
uint8_t _gyro_to_accel_sample_ratio;
|
|
|
|
|
|
|
|
// what rate are we generating samples into the backend for gyros?
|
|
|
|
uint16_t _gyro_backend_rate_hz;
|
|
|
|
|
|
|
|
// what rate are we generating samples into the backend for accels?
|
|
|
|
uint16_t _accel_backend_rate_hz;
|
2018-01-17 03:17:33 -04:00
|
|
|
|
2016-11-23 02:02:39 -04:00
|
|
|
// Last status from register user control
|
|
|
|
uint8_t _last_stat_user_ctrl;
|
|
|
|
|
2016-11-08 20:33:05 -04:00
|
|
|
// buffer for fifo read
|
|
|
|
uint8_t *_fifo_buffer;
|
2016-11-10 02:27:22 -04:00
|
|
|
|
2016-11-21 01:49:16 -04:00
|
|
|
/*
|
2018-03-18 20:28:33 -03:00
|
|
|
accumulators for sensor_rate sampling
|
|
|
|
See description in _accumulate_sensor_rate_sampling()
|
2016-11-21 01:49:16 -04:00
|
|
|
*/
|
2016-11-15 01:51:18 -04:00
|
|
|
struct {
|
2016-11-21 01:49:16 -04:00
|
|
|
Vector3f accel;
|
|
|
|
Vector3f gyro;
|
2020-05-21 15:29:28 -03:00
|
|
|
uint8_t accel_count;
|
|
|
|
uint8_t gyro_count;
|
2016-11-21 01:49:16 -04:00
|
|
|
LowPassFilterVector3f accel_filter{4000, 188};
|
2016-11-15 01:51:18 -04:00
|
|
|
} _accum;
|
2015-06-05 04:47:31 -03:00
|
|
|
};
|
|
|
|
|
2016-12-13 21:47:22 -04:00
|
|
|
class AP_Invensense_AuxiliaryBusSlave : public AuxiliaryBusSlave
|
2015-08-16 16:23:24 -03:00
|
|
|
{
|
2016-12-13 21:47:22 -04:00
|
|
|
friend class AP_Invensense_AuxiliaryBus;
|
2015-08-16 16:23:24 -03:00
|
|
|
|
|
|
|
public:
|
|
|
|
int passthrough_read(uint8_t reg, uint8_t *buf, uint8_t size) override;
|
|
|
|
int passthrough_write(uint8_t reg, uint8_t val) override;
|
|
|
|
|
|
|
|
int read(uint8_t *buf) override;
|
|
|
|
|
|
|
|
protected:
|
2016-12-13 21:47:22 -04:00
|
|
|
AP_Invensense_AuxiliaryBusSlave(AuxiliaryBus &bus, uint8_t addr, uint8_t instance);
|
2015-08-16 16:23:24 -03:00
|
|
|
int _set_passthrough(uint8_t reg, uint8_t size, uint8_t *out = nullptr);
|
|
|
|
|
|
|
|
private:
|
2016-12-13 21:47:22 -04:00
|
|
|
const uint8_t _mpu_addr;
|
|
|
|
const uint8_t _mpu_reg;
|
|
|
|
const uint8_t _mpu_ctrl;
|
|
|
|
const uint8_t _mpu_do;
|
2015-08-16 16:23:24 -03:00
|
|
|
|
|
|
|
uint8_t _ext_sens_data = 0;
|
|
|
|
};
|
|
|
|
|
2016-12-13 21:47:22 -04:00
|
|
|
class AP_Invensense_AuxiliaryBus : public AuxiliaryBus
|
2015-08-16 16:23:24 -03:00
|
|
|
{
|
2016-12-13 21:47:22 -04:00
|
|
|
friend class AP_InertialSensor_Invensense;
|
2015-08-16 16:23:24 -03:00
|
|
|
|
|
|
|
public:
|
|
|
|
AP_HAL::Semaphore *get_semaphore() override;
|
2017-08-02 13:08:09 -03:00
|
|
|
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb) override;
|
2015-08-16 16:23:24 -03:00
|
|
|
|
|
|
|
protected:
|
2016-12-13 21:47:22 -04:00
|
|
|
AP_Invensense_AuxiliaryBus(AP_InertialSensor_Invensense &backend, uint32_t devid);
|
2015-08-16 16:23:24 -03:00
|
|
|
|
|
|
|
AuxiliaryBusSlave *_instantiate_slave(uint8_t addr, uint8_t instance) override;
|
|
|
|
int _configure_periodic_read(AuxiliaryBusSlave *slave, uint8_t reg,
|
|
|
|
uint8_t size) override;
|
|
|
|
|
|
|
|
private:
|
|
|
|
void _configure_slaves();
|
|
|
|
|
|
|
|
static const uint8_t MAX_EXT_SENS_DATA = 24;
|
|
|
|
uint8_t _ext_sens_data = 0;
|
|
|
|
};
|
2017-03-09 19:43:54 -04:00
|
|
|
|
|
|
|
#ifndef INS_INVENSENSE_20789_I2C_ADDR
|
|
|
|
#define INS_INVENSENSE_20789_I2C_ADDR 0x68
|
|
|
|
#endif
|