ardupilot/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h
Andrew Tridgell d9c8db7024 AP_InertialSensor: implement a new strategy for fast sampling
this moves to using a 1p filter on the high rate data, followed by
averaging down to 1kHz then a 2p filter to apply configured cutoff
frequency.

It also fixes the FIFO reset to not cause data corruption. We need to
disable all FIFO channels before doing the reset, and wait for the
FIFO to stop in the sensor.

Finally it moves sampling of the MPU6000 and MPU9250 into the main
thread. That significantly improves scheduling performance as we no
longer get long FIFO SPI transfers happening during other tasks. All
transfers happen at the start of the fast loop. That makes timing much
more predictable.

Thanks to Leonard and Paul for help with this design!
2016-11-25 17:49:57 +11:00

174 lines
4.8 KiB
C++

#pragma once
#include <stdint.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/SPIDevice.h>
#include <AP_HAL/utility/OwnPtr.h>
#include <AP_Math/AP_Math.h>
#include <Filter/Filter.h>
#include <Filter/LowPassFilter.h>
#include <Filter/LowPassFilter2p.h>
#include "AP_InertialSensor.h"
#include "AP_InertialSensor_Backend.h"
#include "AuxiliaryBus.h"
class AP_MPU6000_AuxiliaryBus;
class AP_MPU6000_AuxiliaryBusSlave;
class AP_InertialSensor_MPU6000 : public AP_InertialSensor_Backend
{
friend AP_MPU6000_AuxiliaryBus;
friend AP_MPU6000_AuxiliaryBusSlave;
public:
virtual ~AP_InertialSensor_MPU6000();
static AP_InertialSensor_MPU6000 &from(AP_InertialSensor_Backend &backend) {
return static_cast<AP_InertialSensor_MPU6000&>(backend);
}
static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev,
enum Rotation rotation = ROTATION_NONE);
static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev,
enum Rotation rotation = ROTATION_NONE);
/* update accel and gyro state */
bool update() override;
void accumulate() override;
/*
* Return an AuxiliaryBus if the bus driver allows it
*/
AuxiliaryBus *get_auxiliary_bus() override;
void start() override;
private:
AP_InertialSensor_MPU6000(AP_InertialSensor &imu,
AP_HAL::OwnPtr<AP_HAL::Device> dev,
enum Rotation rotation);
/* Initialize sensor*/
bool _init();
bool _hardware_init();
bool _check_whoami();
void _set_filter_register(void);
void _fifo_reset();
void _fifo_enable();
bool _has_auxiliary_bus();
/* Read samples from FIFO (FIFO enabled) */
void _read_fifo();
/* Check if there's data available by either reading DRDY pin or register */
bool _data_ready();
/* Poll for new data (non-blocking) */
bool _poll_data();
/* Read and write functions taking the differences between buses into
* account */
bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size);
uint8_t _register_read(uint8_t reg);
void _register_write(uint8_t reg, uint8_t val, bool checked=false);
bool _accumulate(uint8_t *samples, uint8_t n_samples, int16_t raw_temp);
bool _accumulate_fast_sampling(uint8_t *samples, uint8_t n_samples, int16_t raw_temp);
// instance numbers of accel and gyro data
uint8_t _gyro_instance;
uint8_t _accel_instance;
uint16_t _error_count;
float _temp_filtered;
float _accel_scale;
LowPassFilter2pFloat _temp_filter;
enum Rotation _rotation;
AP_HAL::DigitalSource *_drdy_pin;
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
AP_MPU6000_AuxiliaryBus *_auxiliary_bus;
// is this an ICM-20608?
bool _is_icm_device;
// are we doing more than 1kHz sampling?
bool _fast_sampling;
// are we using accumulate for sensor reading or a bus callback?
bool _use_accumulate;
// has master i2c been enabled?
bool _master_i2c_enable;
// buffer for fifo read
uint8_t *_fifo_buffer;
uint8_t _reg_check_counter;
/*
accumulators for fast sampling
See description in _accumulate_fast_sampling()
*/
struct {
Vector3f accel;
Vector3f gyro;
uint8_t count;
LowPassFilterVector3f accel_filter{4000, 188};
LowPassFilterVector3f gyro_filter{8000, 188};
} _accum;
};
class AP_MPU6000_AuxiliaryBusSlave : public AuxiliaryBusSlave
{
friend class AP_MPU6000_AuxiliaryBus;
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:
AP_MPU6000_AuxiliaryBusSlave(AuxiliaryBus &bus, uint8_t addr, uint8_t instance);
int _set_passthrough(uint8_t reg, uint8_t size, uint8_t *out = nullptr);
private:
const uint8_t _mpu6000_addr;
const uint8_t _mpu6000_reg;
const uint8_t _mpu6000_ctrl;
const uint8_t _mpu6000_do;
uint8_t _ext_sens_data = 0;
};
class AP_MPU6000_AuxiliaryBus : public AuxiliaryBus
{
friend class AP_InertialSensor_MPU6000;
public:
AP_HAL::Semaphore *get_semaphore() override;
protected:
AP_MPU6000_AuxiliaryBus(AP_InertialSensor_MPU6000 &backend, uint32_t devid);
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;
};