APM:Libraries
AP_InertialSensor_Invensense.h
Go to the documentation of this file.
1 #pragma once
2 /*
3  driver for the invensense range of IMUs, including:
4 
5  MPU6000
6  MPU9250
7  ICM-20608
8  */
9 
10 #include <stdint.h>
11 
12 #include <AP_HAL/AP_HAL.h>
13 #include <AP_HAL/I2CDevice.h>
14 #include <AP_HAL/SPIDevice.h>
15 #include <AP_HAL/utility/OwnPtr.h>
16 #include <AP_Math/AP_Math.h>
17 #include <Filter/Filter.h>
18 #include <Filter/LowPassFilter.h>
19 #include <Filter/LowPassFilter2p.h>
20 
21 #include "AP_InertialSensor.h"
23 #include "AuxiliaryBus.h"
24 
27 
29 {
32 
33 public:
35 
37  return static_cast<AP_InertialSensor_Invensense&>(backend);
38  }
39 
42  enum Rotation rotation = ROTATION_NONE);
43 
46  enum Rotation rotation = ROTATION_NONE);
47 
48  /* update accel and gyro state */
49  bool update() override;
50  void accumulate() override;
51 
52  /*
53  * Return an AuxiliaryBus if the bus driver allows it
54  */
55  AuxiliaryBus *get_auxiliary_bus() override;
56 
57  void start() override;
58 
67  };
68 
69  // acclerometers on Invensense sensors will return values up to
70  // 24G, but they are not guaranteed to be remotely linear past
71  // 16G
72  const uint16_t multiplier_accel = INT16_MAX/(26*GRAVITY_MSS);
73 
74 private:
77  enum Rotation rotation);
78 
79  /* Initialize sensor*/
80  bool _init();
81  bool _hardware_init();
82  bool _check_whoami();
83 
84  void _set_filter_register(void);
85  void _fifo_reset();
86  bool _has_auxiliary_bus();
87 
88  /* Read samples from FIFO (FIFO enabled) */
89  void _read_fifo();
90 
91  /* Check if there's data available by either reading DRDY pin or register */
92  bool _data_ready();
93 
94  /* Poll for new data (non-blocking) */
95  void _poll_data();
96 
97  /* Read and write functions taking the differences between buses into
98  * account */
99  bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size);
100  uint8_t _register_read(uint8_t reg);
101  void _register_write(uint8_t reg, uint8_t val, bool checked=false);
102 
103  bool _accumulate(uint8_t *samples, uint8_t n_samples);
104  bool _accumulate_sensor_rate_sampling(uint8_t *samples, uint8_t n_samples);
105 
106  bool _check_raw_temp(int16_t t2);
107 
108  int16_t _raw_temp;
109 
110  // instance numbers of accel and gyro data
111  uint8_t _gyro_instance;
113 
114  float temp_sensitivity = 1.0/340; // degC/LSB
115  float temp_zero = 36.53; // degC
116 
119 
123 
125 
129 
130  // which sensor type this is
132 
133  // are we doing more than 1kHz sampling?
135 
136  // what downsampling rate are we using from the FIFO?
138 
139  // what rate are we generating samples into the backend?
141 
142  // Last status from register user control
144 
145  // buffer for fifo read
146  uint8_t *_fifo_buffer;
147 
148  /*
149  accumulators for sensor_rate sampling
150  See description in _accumulate_sensor_rate_sampling()
151  */
152  struct {
155  uint8_t count;
158  } _accum;
159 };
160 
162 {
164 
165 public:
166  int passthrough_read(uint8_t reg, uint8_t *buf, uint8_t size) override;
167  int passthrough_write(uint8_t reg, uint8_t val) override;
168 
169  int read(uint8_t *buf) override;
170 
171 protected:
172  AP_Invensense_AuxiliaryBusSlave(AuxiliaryBus &bus, uint8_t addr, uint8_t instance);
173  int _set_passthrough(uint8_t reg, uint8_t size, uint8_t *out = nullptr);
174 
175 private:
176  const uint8_t _mpu_addr;
177  const uint8_t _mpu_reg;
178  const uint8_t _mpu_ctrl;
179  const uint8_t _mpu_do;
180 
181  uint8_t _ext_sens_data = 0;
182 };
183 
185 {
187 
188 public:
189  AP_HAL::Semaphore *get_semaphore() override;
190  AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb) override;
191 
192 protected:
194 
195  AuxiliaryBusSlave *_instantiate_slave(uint8_t addr, uint8_t instance) override;
196  int _configure_periodic_read(AuxiliaryBusSlave *slave, uint8_t reg,
197  uint8_t size) override;
198 
199 private:
200  void _configure_slaves();
201 
202  static const uint8_t MAX_EXT_SENS_DATA = 24;
203  uint8_t _ext_sens_data = 0;
204 };
205 
206 #ifndef INS_INVENSENSE_20789_I2C_ADDR
207 #define INS_INVENSENSE_20789_I2C_ADDR 0x68
208 #endif
t2
Definition: calcH_MAG.c:1
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size)
bool _accumulate(uint8_t *samples, uint8_t n_samples)
AP_Invensense_AuxiliaryBus * _auxiliary_bus
Rotation
Definition: rotations.h:27
AP_HAL::OwnPtr< AP_HAL::Device > _dev
bool _accumulate_sensor_rate_sampling(uint8_t *samples, uint8_t n_samples)
AP_InertialSensor_Invensense(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::Device > dev, enum Rotation rotation)
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
#define GRAVITY_MSS
Definition: definitions.h:47
void * PeriodicHandle
Definition: Device.h:42
static AP_InertialSensor_Invensense & from(AP_InertialSensor_Backend &backend)
A class to implement a second order low pass filter.
A class to implement a low pass filter without losing precision even for int types the downside being...
struct AP_InertialSensor_Invensense::@122 _accum
void _register_write(uint8_t reg, uint8_t val, bool checked=false)