APM:Libraries
AP_InertialSensor_Backend.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  IMU driver backend class. Each supported gyro/accel sensor type
18  needs to have an object derived from this class.
19 
20  Note that drivers can implement just gyros or just accels, and can
21  also provide multiple gyro/accel instances.
22  */
23 #pragma once
24 
25 #include <inttypes.h>
26 
27 #include <AP_Math/AP_Math.h>
28 
29 #include "AP_InertialSensor.h"
30 
31 #if CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
33 #include <AP_HAL_F4Light/GPIO.h>
35 using namespace F4Light;
36 #endif
37 
38 class AuxiliaryBus;
39 class DataFlash_Class;
40 
42 {
43 public:
46 
47  // we declare a virtual destructor so that drivers can
48  // override with a custom destructor if need be.
49  virtual ~AP_InertialSensor_Backend(void) {}
50 
51  /*
52  * Update the sensor data. Called by the frontend to transfer
53  * accumulated sensor readings to the frontend structure via the
54  * _publish_gyro() and _publish_accel() functions
55  */
56  virtual bool update() = 0;
57 
58  /*
59  * optional function to accumulate more samples. This is needed for drivers that don't use a timer to gather samples
60  */
61  virtual void accumulate() {}
62 
63  /*
64  * Configure and start all sensors. The empty implementation allows
65  * subclasses to already start the sensors when it's detected
66  */
67  virtual void start() { }
68 
69  /*
70  * Return an AuxiliaryBus if backend has another bus it is able to export
71  */
72  virtual AuxiliaryBus *get_auxiliary_bus() { return nullptr; }
73 
74  /*
75  * Return the unique identifier for this backend: it's the same for
76  * several sensors if the backend registers more gyros/accels
77  */
78  int16_t get_id() const { return _id; }
79 
80  // notify of a fifo reset
81  void notify_fifo_reset(void);
82 
83  /*
84  device driver IDs. These are used to fill in the devtype field
85  of the device ID, which shows up as INS*ID* parameters to
86  users. The values are chosen for compatibility with existing PX4
87  drivers.
88  If a change is made to a driver that would make existing
89  calibration values invalid then this number must be changed.
90  */
91  enum DevTypes {
92  DEVTYPE_BMI160 = 0x09,
93  DEVTYPE_L3G4200D = 0x10,
94  DEVTYPE_ACC_LSM303D = 0x11,
95  DEVTYPE_ACC_BMA180 = 0x12,
96  DEVTYPE_ACC_MPU6000 = 0x13,
97  DEVTYPE_ACC_MPU9250 = 0x16,
98  DEVTYPE_ACC_IIS328DQ = 0x17,
99  DEVTYPE_ACC_LSM9DS1 = 0x18,
100  DEVTYPE_GYR_MPU6000 = 0x21,
101  DEVTYPE_GYR_L3GD20 = 0x22,
102  DEVTYPE_GYR_MPU9250 = 0x24,
103  DEVTYPE_GYR_I3G4250D = 0x25,
104  DEVTYPE_GYR_LSM9DS1 = 0x26,
105  DEVTYPE_INS_ICM20789 = 0x27,
106  DEVTYPE_INS_ICM20689 = 0x28,
107  };
108 
109 protected:
110  // access to frontend
112 
113  // semaphore for access to shared frontend data
115 
116  void _rotate_and_correct_accel(uint8_t instance, Vector3f &accel);
117  void _rotate_and_correct_gyro(uint8_t instance, Vector3f &gyro);
118 
119  // rotate gyro vector, offset and publish
120  void _publish_gyro(uint8_t instance, const Vector3f &gyro);
121 
122  // this should be called every time a new gyro raw sample is
123  // available - be it published or not the sample is raw in the
124  // sense that it's not filtered yet, but it must be rotated and
125  // corrected (_rotate_and_correct_gyro)
126  // The sample_us value must be provided for non-FIFO based
127  // sensors, and should be set to zero for FIFO based sensors
128  void _notify_new_gyro_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0);
129 
130  // rotate accel vector, scale, offset and publish
131  void _publish_accel(uint8_t instance, const Vector3f &accel);
132 
133  // this should be called every time a new accel raw sample is available -
134  // be it published or not
135  // the sample is raw in the sense that it's not filtered yet, but it must
136  // be rotated and corrected (_rotate_and_correct_accel)
137  // The sample_us value must be provided for non-FIFO based
138  // sensors, and should be set to zero for FIFO based sensors
139  void _notify_new_accel_raw_sample(uint8_t instance, const Vector3f &accel, uint64_t sample_us=0, bool fsync_set=false);
140 
141  // set the amount of oversamping a accel is doing
142  void _set_accel_oversampling(uint8_t instance, uint8_t n);
143 
144  // set the amount of oversamping a gyro is doing
145  void _set_gyro_oversampling(uint8_t instance, uint8_t n);
146 
147  // indicate the backend is doing sensor-rate sampling for this accel
148  void _set_accel_sensor_rate_sampling_enabled(uint8_t instance, bool value) {
149  const uint8_t bit = (1<<instance);
150  if (value) {
152  } else {
154  }
155  }
156 
157  void _set_gyro_sensor_rate_sampling_enabled(uint8_t instance, bool value) {
158  const uint8_t bit = (1<<instance);
159  if (value) {
161  } else {
163  }
164  }
165 
166  void _set_raw_sample_accel_multiplier(uint8_t instance, uint16_t mul) {
167  _imu._accel_raw_sampling_multiplier[instance] = mul;
168  }
169  void _set_raw_sampl_gyro_multiplier(uint8_t instance, uint16_t mul) {
170  _imu._gyro_raw_sampling_multiplier[instance] = mul;
171  }
172 
173  // update the sensor rate for FIFO sensors
174  void _update_sensor_rate(uint16_t &count, uint32_t &start_us, float &rate_hz) const;
175 
176  // set accelerometer max absolute offset for calibration
177  void _set_accel_max_abs_offset(uint8_t instance, float offset);
178 
179  // get accelerometer raw sample rate
180  uint32_t _accel_raw_sample_rate(uint8_t instance) const {
181  return _imu._accel_raw_sample_rates[instance];
182  }
183 
184  // set accelerometer raw sample rate
185  void _set_accel_raw_sample_rate(uint8_t instance, uint16_t rate_hz) {
186  _imu._accel_raw_sample_rates[instance] = rate_hz;
187  }
188 
189  // get gyroscope raw sample rate
190  uint32_t _gyro_raw_sample_rate(uint8_t instance) const {
191  return _imu._gyro_raw_sample_rates[instance];
192  }
193 
194  // set gyro raw sample rate
195  void _set_gyro_raw_sample_rate(uint8_t instance, uint16_t rate_hz) {
196  _imu._gyro_raw_sample_rates[instance] = rate_hz;
197  }
198 
199  // publish a temperature value
200  void _publish_temperature(uint8_t instance, float temperature);
201 
202  // set accelerometer error_count
203  void _set_accel_error_count(uint8_t instance, uint32_t error_count);
204 
205  // set gyro error_count
206  void _set_gyro_error_count(uint8_t instance, uint32_t error_count);
207 
208  // increment accelerometer error_count
209  void _inc_accel_error_count(uint8_t instance);
210 
211  // increment gyro error_count
212  void _inc_gyro_error_count(uint8_t instance);
213 
214  // backend unique identifier or -1 if backend doesn't identify itself
215  int16_t _id = -1;
216 
217  // return the default filter frequency in Hz for the sample rate
218  uint8_t _accel_filter_cutoff(void) const { return _imu._accel_filter_cutoff; }
219 
220  // return the default filter frequency in Hz for the sample rate
221  uint8_t _gyro_filter_cutoff(void) const { return _imu._gyro_filter_cutoff; }
222 
223  // return the requested sample rate in Hz
224  uint16_t get_sample_rate_hz(void) const;
225 
226  // common gyro update function for all backends
227  void update_gyro(uint8_t instance);
228 
229  // common accel update function for all backends
230  void update_accel(uint8_t instance);
231 
232  // support for updating filter at runtime
233  int8_t _last_accel_filter_hz[INS_MAX_INSTANCES];
234  int8_t _last_gyro_filter_hz[INS_MAX_INSTANCES];
235 
236  void set_gyro_orientation(uint8_t instance, enum Rotation rotation) {
237  _imu._gyro_orientation[instance] = rotation;
238  }
239 
240  void set_accel_orientation(uint8_t instance, enum Rotation rotation) {
241  _imu._accel_orientation[instance] = rotation;
242  }
243 
244  // increment clipping counted. Used by drivers that do decimation before supplying
245  // samples to the frontend
246  void increment_clip_count(uint8_t instance) {
247  _imu._accel_clip_count[instance]++;
248  }
249 
250  // should fast sampling be enabled on this IMU?
251  bool enable_fast_sampling(uint8_t instance) {
252  return (_imu._fast_sampling_mask & (1U<<instance)) != 0;
253  }
254 
255  // called by subclass when data is received from the sensor, thus
256  // at the 'sensor rate'
257  void _notify_new_accel_sensor_rate_sample(uint8_t instance, const Vector3f &accel);
258  void _notify_new_gyro_sensor_rate_sample(uint8_t instance, const Vector3f &gyro);
259 
260  /*
261  notify of a FIFO reset so we don't use bad data to update observed sensor rate
262  */
263  void notify_accel_fifo_reset(uint8_t instance);
264  void notify_gyro_fifo_reset(uint8_t instance);
265 
266  // note that each backend is also expected to have a static detect()
267  // function which instantiates an instance of the backend sensor
268  // driver if the sensor is available
269 
270 private:
271 
272  bool should_log_imu_raw() const;
273  void log_accel_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &accel);
274  void log_gyro_raw(uint8_t instance, const uint64_t sample_us, const Vector3f &gryo);
275 
276 };
uint32_t _gyro_raw_sample_rate(uint8_t instance) const
void set_gyro_orientation(uint8_t instance, enum Rotation rotation)
void _set_raw_sampl_gyro_multiplier(uint8_t instance, uint16_t mul)
void _set_gyro_raw_sample_rate(uint8_t instance, uint16_t rate_hz)
float _accel_raw_sample_rates[INS_MAX_INSTANCES]
uint32_t _accel_raw_sample_rate(uint8_t instance) const
bool enable_fast_sampling(uint8_t instance)
Rotation
Definition: rotations.h:27
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
uint16_t _accel_raw_sampling_multiplier[INS_MAX_INSTANCES]
float _gyro_raw_sample_rates[INS_MAX_INSTANCES]
float temperature
Definition: Airspeed.cpp:32
uint8_t _accel_filter_cutoff(void) const
void increment_clip_count(uint8_t instance)
virtual AuxiliaryBus * get_auxiliary_bus()
void _set_gyro_sensor_rate_sampling_enabled(uint8_t instance, bool value)
uint16_t _gyro_raw_sampling_multiplier[INS_MAX_INSTANCES]
void _set_accel_sensor_rate_sampling_enabled(uint8_t instance, bool value)
uint8_t _accel_sensor_rate_sampling_enabled
void set_accel_orientation(uint8_t instance, enum Rotation rotation)
void _set_accel_raw_sample_rate(uint8_t instance, uint16_t rate_hz)
float value
enum Rotation _accel_orientation[INS_MAX_INSTANCES]
uint32_t _accel_clip_count[INS_MAX_INSTANCES]
#define INS_MAX_INSTANCES
void _set_raw_sample_accel_multiplier(uint8_t instance, uint16_t mul)
enum Rotation _gyro_orientation[INS_MAX_INSTANCES]
uint8_t _gyro_sensor_rate_sampling_enabled