APM:Libraries
AP_InertialSensor_Revo.h
Go to the documentation of this file.
1 #pragma once
2 /*
3  copied from AP_InertialSensor_Invensense
4 
5  driver for the invensense range of IMUs, including:
6 
7  MPU6000
8  MPU9250
9  ICM-20608
10  */
11 
12 #include <stdint.h>
13 
14 #include <AP_HAL/AP_HAL.h>
15 #include <AP_HAL/I2CDevice.h>
16 #include <AP_HAL/SPIDevice.h>
17 #include <AP_HAL/utility/OwnPtr.h>
18 #include <AP_Math/AP_Math.h>
19 #include <Filter/Filter.h>
20 #include <Filter/LowPassFilter.h>
21 #include <Filter/LowPassFilter2p.h>
22 
23 #include "AP_InertialSensor.h"
25 #include "AuxiliaryBus.h"
26 
27 typedef struct MPU_Item {
28  uint64_t time;
29  uint16_t ax;
30  uint16_t ay;
31  uint16_t az;
32  uint16_t temp;
33  uint16_t gx;
34  uint16_t gy;
35  uint16_t gz;
36 } mpu_item;
37 
38 
39 typedef struct {
40  uint32_t t;
41  uint16_t read_ptr;
42  uint16_t write_ptr;
43 } mpu_log_item;
44 
46 
48 {
50 
51 public:
52  virtual ~AP_InertialSensor_Revo();
53 
55  return static_cast<AP_InertialSensor_Revo&>(backend);
56  }
57 
60  enum Rotation rotation = ROTATION_NONE);
61 
64  enum Rotation rotation = ROTATION_NONE);
65 
66  /* update accel and gyro state */
67  bool update() override;
68  void accumulate() override;
69 
70  void start() override;
71 
72  void _isr();
73  void _ioc();
74 
76  Invensense_MPU6000=0,
81  };
82 
83 private:
86  enum Rotation rotation);
87 
88  /* Initialize sensor*/
89  bool _init();
90  bool _hardware_init();
91  bool _check_whoami();
92  void _start(); // used for start and restart
93 
94  void _set_filter_register(void);
95 
96  /* Read samples from FIFO in RAM */
97  void _read_fifo();
98 
99  /* Check if there's data available by either reading DRDY pin or register */
100  bool _data_ready();
101 
102  /* Poll for new data (non-blocking) */
103  void _poll_data();
104 
105  /* Read and write functions taking the differences between buses into
106  * account */
107  bool _block_read(uint8_t reg, uint8_t *buf, uint32_t size);
108  uint8_t _register_read(uint8_t reg);
109  void _register_write(uint8_t reg, uint8_t val, bool checked=false);
110 
111  bool _accumulate(uint8_t *samples, uint8_t n_samples);
112  bool _accumulate_sensor_rate_sampling(uint8_t *samples, uint8_t n_samples);
113 
114  bool _check_raw_temp(int16_t t2);
115 
116  int16_t _raw_temp;
117 
118  // instance numbers of accel and gyro data
119  uint8_t _gyro_instance;
121 
122  uint16_t _error_count;
123 
124  float temp_sensitivity = 1.0/340; // degC/LSB
125  float temp_zero = 36.53; // degC
126 
130 
131  enum Rotation _rotation;
132 
135 
136  // which sensor type this is
137  enum Invensense_Type _mpu_type;
138  uint8_t product_id;
139 
140  // are we doing more than 1kHz sampling?
142 
143  // Last status from register user control
145 
146  // buffer for fifo read
147  uint8_t *_fifo_buffer;
148 
149 
150  /*
151  accumulators for fast sampling
152  See description in _accumulate_sensor_rate_sampling()
153  */
154  struct {
157  uint8_t count;
158  LowPassFilterVector3f accel_filter{4000, 188};
159  LowPassFilterVector3f gyro_filter{8000, 188};
160  } _accum;
161 
162  uint16_t read_ptr;
163  volatile uint16_t write_ptr; // changed in interrupt
164  uint16_t nodata_count;
165  void * task_handle;
166  float accel_len;
167  uint32_t last_sample;
168 
170 
171 
172 //#define MPU_DEBUG_LOG
173 
174 #ifdef MPU_DEBUG_LOG
175 #define MPU_LOG_SIZE 512
176  static mpu_log_item mpu_log[MPU_LOG_SIZE];
177  static uint16_t mpu_log_ptr;
178 #endif
179 };
180 
t2
Definition: calcH_MAG.c:1
AP_HAL::DigitalSource * _drdy_pin
Rotation
Definition: rotations.h:27
AP_HAL::OwnPtr< AP_HAL::Device > _dev
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
LowPassFilter2pFloat _temp_filter
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 MPU_Item mpu_item
static AP_InertialSensor_Revo & from(AP_InertialSensor_Backend &backend)