APM:Libraries
AP_InertialSensor.cpp
Go to the documentation of this file.
1 #include <assert.h>
2 
3 #include <AP_Common/AP_Common.h>
4 #include <AP_HAL/AP_HAL.h>
5 #include <AP_HAL/I2CDevice.h>
6 #include <AP_HAL/SPIDevice.h>
7 #include <AP_Math/AP_Math.h>
8 #include <AP_Notify/AP_Notify.h>
11 #include <AP_AHRS/AP_AHRS.h>
12 
13 #include "AP_InertialSensor.h"
16 #include "AP_InertialSensor_HIL.h"
21 #include "AP_InertialSensor_PX4.h"
22 #include "AP_InertialSensor_SITL.h"
23 #include "AP_InertialSensor_RST.h"
24 #include "AP_InertialSensor_Revo.h"
25 
26 /* Define INS_TIMING_DEBUG to track down scheduling issues with the main loop.
27  * Output is on the debug console. */
28 #ifdef INS_TIMING_DEBUG
29 #include <stdio.h>
30 #define timing_printf(fmt, args...) do { printf("[timing] " fmt, ##args); } while(0)
31 #else
32 #define timing_printf(fmt, args...)
33 #endif
34 
35 extern const AP_HAL::HAL& hal;
36 
37 #if APM_BUILD_TYPE(APM_BUILD_ArduCopter)
38 #define DEFAULT_GYRO_FILTER 20
39 #define DEFAULT_ACCEL_FILTER 20
40 #define DEFAULT_STILL_THRESH 2.5f
41 #elif APM_BUILD_TYPE(APM_BUILD_APMrover2)
42 #define DEFAULT_GYRO_FILTER 4
43 #define DEFAULT_ACCEL_FILTER 10
44 #define DEFAULT_STILL_THRESH 0.1f
45 #else
46 #define DEFAULT_GYRO_FILTER 20
47 #define DEFAULT_ACCEL_FILTER 20
48 #define DEFAULT_STILL_THRESH 0.1f
49 #endif
50 
51 #define SAMPLE_UNIT 1
52 
53 #define GYRO_INIT_MAX_DIFF_DPS 0.1f
54 
55 // Class level parameters
57  // @Param: PRODUCT_ID
58  // @DisplayName: IMU Product ID
59  // @Description: unused
60  // @User: Advanced
61  AP_GROUPINFO("PRODUCT_ID", 0, AP_InertialSensor, _old_product_id, 0),
62 
63  /*
64  The following parameter indexes and reserved from previous use
65  as accel offsets and scaling from before the 16g change in the
66  PX4 backend:
67 
68  ACCSCAL : 1
69  ACCOFFS : 2
70  MPU6K_FILTER: 4
71  ACC2SCAL : 5
72  ACC2OFFS : 6
73  ACC3SCAL : 8
74  ACC3OFFS : 9
75  CALSENSFRAME : 11
76  */
77 
78  // @Param: GYROFFS_X
79  // @DisplayName: Gyro offsets of X axis
80  // @Description: Gyro sensor offsets of X axis. This is setup on each boot during gyro calibrations
81  // @Units: rad/s
82  // @User: Advanced
83 
84  // @Param: GYROFFS_Y
85  // @DisplayName: Gyro offsets of Y axis
86  // @Description: Gyro sensor offsets of Y axis. This is setup on each boot during gyro calibrations
87  // @Units: rad/s
88  // @User: Advanced
89 
90  // @Param: GYROFFS_Z
91  // @DisplayName: Gyro offsets of Z axis
92  // @Description: Gyro sensor offsets of Z axis. This is setup on each boot during gyro calibrations
93  // @Units: rad/s
94  // @User: Advanced
95  AP_GROUPINFO("GYROFFS", 3, AP_InertialSensor, _gyro_offset[0], 0),
96 
97  // @Param: GYR2OFFS_X
98  // @DisplayName: Gyro2 offsets of X axis
99  // @Description: Gyro2 sensor offsets of X axis. This is setup on each boot during gyro calibrations
100  // @Units: rad/s
101  // @User: Advanced
102 
103  // @Param: GYR2OFFS_Y
104  // @DisplayName: Gyro2 offsets of Y axis
105  // @Description: Gyro2 sensor offsets of Y axis. This is setup on each boot during gyro calibrations
106  // @Units: rad/s
107  // @User: Advanced
108 
109  // @Param: GYR2OFFS_Z
110  // @DisplayName: Gyro2 offsets of Z axis
111  // @Description: Gyro2 sensor offsets of Z axis. This is setup on each boot during gyro calibrations
112  // @Units: rad/s
113  // @User: Advanced
114  AP_GROUPINFO("GYR2OFFS", 7, AP_InertialSensor, _gyro_offset[1], 0),
115 
116  // @Param: GYR3OFFS_X
117  // @DisplayName: Gyro3 offsets of X axis
118  // @Description: Gyro3 sensor offsets of X axis. This is setup on each boot during gyro calibrations
119  // @Units: rad/s
120  // @User: Advanced
121 
122  // @Param: GYR3OFFS_Y
123  // @DisplayName: Gyro3 offsets of Y axis
124  // @Description: Gyro3 sensor offsets of Y axis. This is setup on each boot during gyro calibrations
125  // @Units: rad/s
126  // @User: Advanced
127 
128  // @Param: GYR3OFFS_Z
129  // @DisplayName: Gyro3 offsets of Z axis
130  // @Description: Gyro3 sensor offsets of Z axis. This is setup on each boot during gyro calibrations
131  // @Units: rad/s
132  // @User: Advanced
133  AP_GROUPINFO("GYR3OFFS", 10, AP_InertialSensor, _gyro_offset[2], 0),
134 
135  // @Param: ACCSCAL_X
136  // @DisplayName: Accelerometer scaling of X axis
137  // @Description: Accelerometer scaling of X axis. Calculated during acceleration calibration routine
138  // @Range: 0.8 1.2
139  // @User: Advanced
140 
141  // @Param: ACCSCAL_Y
142  // @DisplayName: Accelerometer scaling of Y axis
143  // @Description: Accelerometer scaling of Y axis Calculated during acceleration calibration routine
144  // @Range: 0.8 1.2
145  // @User: Advanced
146 
147  // @Param: ACCSCAL_Z
148  // @DisplayName: Accelerometer scaling of Z axis
149  // @Description: Accelerometer scaling of Z axis Calculated during acceleration calibration routine
150  // @Range: 0.8 1.2
151  // @User: Advanced
152  AP_GROUPINFO("ACCSCAL", 12, AP_InertialSensor, _accel_scale[0], 0),
153 
154  // @Param: ACCOFFS_X
155  // @DisplayName: Accelerometer offsets of X axis
156  // @Description: Accelerometer offsets of X axis. This is setup using the acceleration calibration or level operations
157  // @Units: m/s/s
158  // @Range: -3.5 3.5
159  // @User: Advanced
160 
161  // @Param: ACCOFFS_Y
162  // @DisplayName: Accelerometer offsets of Y axis
163  // @Description: Accelerometer offsets of Y axis. This is setup using the acceleration calibration or level operations
164  // @Units: m/s/s
165  // @Range: -3.5 3.5
166  // @User: Advanced
167 
168  // @Param: ACCOFFS_Z
169  // @DisplayName: Accelerometer offsets of Z axis
170  // @Description: Accelerometer offsets of Z axis. This is setup using the acceleration calibration or level operations
171  // @Units: m/s/s
172  // @Range: -3.5 3.5
173  // @User: Advanced
174  AP_GROUPINFO("ACCOFFS", 13, AP_InertialSensor, _accel_offset[0], 0),
175 
176  // @Param: ACC2SCAL_X
177  // @DisplayName: Accelerometer2 scaling of X axis
178  // @Description: Accelerometer2 scaling of X axis. Calculated during acceleration calibration routine
179  // @Range: 0.8 1.2
180  // @User: Advanced
181 
182  // @Param: ACC2SCAL_Y
183  // @DisplayName: Accelerometer2 scaling of Y axis
184  // @Description: Accelerometer2 scaling of Y axis Calculated during acceleration calibration routine
185  // @Range: 0.8 1.2
186  // @User: Advanced
187 
188  // @Param: ACC2SCAL_Z
189  // @DisplayName: Accelerometer2 scaling of Z axis
190  // @Description: Accelerometer2 scaling of Z axis Calculated during acceleration calibration routine
191  // @Range: 0.8 1.2
192  // @User: Advanced
193  AP_GROUPINFO("ACC2SCAL", 14, AP_InertialSensor, _accel_scale[1], 0),
194 
195  // @Param: ACC2OFFS_X
196  // @DisplayName: Accelerometer2 offsets of X axis
197  // @Description: Accelerometer2 offsets of X axis. This is setup using the acceleration calibration or level operations
198  // @Units: m/s/s
199  // @Range: -3.5 3.5
200  // @User: Advanced
201 
202  // @Param: ACC2OFFS_Y
203  // @DisplayName: Accelerometer2 offsets of Y axis
204  // @Description: Accelerometer2 offsets of Y axis. This is setup using the acceleration calibration or level operations
205  // @Units: m/s/s
206  // @Range: -3.5 3.5
207  // @User: Advanced
208 
209  // @Param: ACC2OFFS_Z
210  // @DisplayName: Accelerometer2 offsets of Z axis
211  // @Description: Accelerometer2 offsets of Z axis. This is setup using the acceleration calibration or level operations
212  // @Units: m/s/s
213  // @Range: -3.5 3.5
214  // @User: Advanced
215  AP_GROUPINFO("ACC2OFFS", 15, AP_InertialSensor, _accel_offset[1], 0),
216 
217  // @Param: ACC3SCAL_X
218  // @DisplayName: Accelerometer3 scaling of X axis
219  // @Description: Accelerometer3 scaling of X axis. Calculated during acceleration calibration routine
220  // @Range: 0.8 1.2
221  // @User: Advanced
222 
223  // @Param: ACC3SCAL_Y
224  // @DisplayName: Accelerometer3 scaling of Y axis
225  // @Description: Accelerometer3 scaling of Y axis Calculated during acceleration calibration routine
226  // @Range: 0.8 1.2
227  // @User: Advanced
228 
229  // @Param: ACC3SCAL_Z
230  // @DisplayName: Accelerometer3 scaling of Z axis
231  // @Description: Accelerometer3 scaling of Z axis Calculated during acceleration calibration routine
232  // @Range: 0.8 1.2
233  // @User: Advanced
234  AP_GROUPINFO("ACC3SCAL", 16, AP_InertialSensor, _accel_scale[2], 0),
235 
236  // @Param: ACC3OFFS_X
237  // @DisplayName: Accelerometer3 offsets of X axis
238  // @Description: Accelerometer3 offsets of X axis. This is setup using the acceleration calibration or level operations
239  // @Units: m/s/s
240  // @Range: -3.5 3.5
241  // @User: Advanced
242 
243  // @Param: ACC3OFFS_Y
244  // @DisplayName: Accelerometer3 offsets of Y axis
245  // @Description: Accelerometer3 offsets of Y axis. This is setup using the acceleration calibration or level operations
246  // @Units: m/s/s
247  // @Range: -3.5 3.5
248  // @User: Advanced
249 
250  // @Param: ACC3OFFS_Z
251  // @DisplayName: Accelerometer3 offsets of Z axis
252  // @Description: Accelerometer3 offsets of Z axis. This is setup using the acceleration calibration or level operations
253  // @Units: m/s/s
254  // @Range: -3.5 3.5
255  // @User: Advanced
256  AP_GROUPINFO("ACC3OFFS", 17, AP_InertialSensor, _accel_offset[2], 0),
257 
258  // @Param: GYRO_FILTER
259  // @DisplayName: Gyro filter cutoff frequency
260  // @Description: Filter cutoff frequency for gyroscopes. This can be set to a lower value to try to cope with very high vibration levels in aircraft. This option takes effect on the next reboot. A value of zero means no filtering (not recommended!)
261  // @Units: Hz
262  // @Range: 0 127
263  // @User: Advanced
264  AP_GROUPINFO("GYRO_FILTER", 18, AP_InertialSensor, _gyro_filter_cutoff, DEFAULT_GYRO_FILTER),
265 
266  // @Param: ACCEL_FILTER
267  // @DisplayName: Accel filter cutoff frequency
268  // @Description: Filter cutoff frequency for accelerometers. This can be set to a lower value to try to cope with very high vibration levels in aircraft. This option takes effect on the next reboot. A value of zero means no filtering (not recommended!)
269  // @Units: Hz
270  // @Range: 0 127
271  // @User: Advanced
272  AP_GROUPINFO("ACCEL_FILTER", 19, AP_InertialSensor, _accel_filter_cutoff, DEFAULT_ACCEL_FILTER),
273 
274  // @Param: USE
275  // @DisplayName: Use first IMU for attitude, velocity and position estimates
276  // @Description: Use first IMU for attitude, velocity and position estimates
277  // @Values: 0:Disabled,1:Enabled
278  // @User: Advanced
279  AP_GROUPINFO("USE", 20, AP_InertialSensor, _use[0], 1),
280 
281  // @Param: USE2
282  // @DisplayName: Use second IMU for attitude, velocity and position estimates
283  // @Description: Use second IMU for attitude, velocity and position estimates
284  // @Values: 0:Disabled,1:Enabled
285  // @User: Advanced
286  AP_GROUPINFO("USE2", 21, AP_InertialSensor, _use[1], 1),
287 
288  // @Param: USE3
289  // @DisplayName: Use third IMU for attitude, velocity and position estimates
290  // @Description: Use third IMU for attitude, velocity and position estimates
291  // @Values: 0:Disabled,1:Enabled
292  // @User: Advanced
293  AP_GROUPINFO("USE3", 22, AP_InertialSensor, _use[2], 0),
294 
295  // @Param: STILL_THRESH
296  // @DisplayName: Stillness threshold for detecting if we are moving
297  // @Description: Threshold to tolerate vibration to determine if vehicle is motionless. This depends on the frame type and if there is a constant vibration due to motors before launch or after landing. Total motionless is about 0.05. Suggested values: Planes/rover use 0.1, multirotors use 1, tradHeli uses 5
298  // @Range: 0.05 50
299  // @User: Advanced
300  AP_GROUPINFO("STILL_THRESH", 23, AP_InertialSensor, _still_threshold, DEFAULT_STILL_THRESH),
301 
302  // @Param: GYR_CAL
303  // @DisplayName: Gyro Calibration scheme
304  // @Description: Conrols when automatic gyro calibration is performed
305  // @Values: 0:Never, 1:Start-up only
306  // @User: Advanced
307  AP_GROUPINFO("GYR_CAL", 24, AP_InertialSensor, _gyro_cal_timing, 1),
308 
309  // @Param: TRIM_OPTION
310  // @DisplayName: Accel cal trim option
311  // @Description: Specifies how the accel cal routine determines the trims
312  // @User: Advanced
313  // @Values: 0:Don't adjust the trims,1:Assume first orientation was level,2:Assume ACC_BODYFIX is perfectly aligned to the vehicle
314  AP_GROUPINFO("TRIM_OPTION", 25, AP_InertialSensor, _trim_option, 1),
315 
316  // @Param: ACC_BODYFIX
317  // @DisplayName: Body-fixed accelerometer
318  // @Description: The body-fixed accelerometer to be used for trim calculation
319  // @User: Advanced
320  // @Values: 1:IMU 1,2:IMU 2,3:IMU 3
321  AP_GROUPINFO("ACC_BODYFIX", 26, AP_InertialSensor, _acc_body_aligned, 2),
322 
323  // @Param: POS1_X
324  // @DisplayName: IMU accelerometer X position
325  // @Description: X position of the first IMU Accelerometer in body frame. Positive X is forward of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
326  // @Units: m
327  // @User: Advanced
328 
329  // @Param: POS1_Y
330  // @DisplayName: IMU accelerometer Y position
331  // @Description: Y position of the first IMU accelerometer in body frame. Positive Y is to the right of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
332  // @Units: m
333  // @User: Advanced
334 
335  // @Param: POS1_Z
336  // @DisplayName: IMU accelerometer Z position
337  // @Description: Z position of the first IMU accelerometer in body frame. Positive Z is down from the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
338  // @Units: m
339  // @User: Advanced
340  AP_GROUPINFO("POS1", 27, AP_InertialSensor, _accel_pos[0], 0.0f),
341 
342  // @Param: POS2_X
343  // @DisplayName: IMU accelerometer X position
344  // @Description: X position of the second IMU accelerometer in body frame. Positive X is forward of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
345  // @Units: m
346  // @User: Advanced
347 
348  // @Param: POS2_Y
349  // @DisplayName: IMU accelerometer Y position
350  // @Description: Y position of the second IMU accelerometer in body frame. Positive Y is to the right of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
351  // @Units: m
352  // @User: Advanced
353 
354  // @Param: POS2_Z
355  // @DisplayName: IMU accelerometer Z position
356  // @Description: Z position of the second IMU accelerometer in body frame. Positive Z is down from the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
357  // @Units: m
358  // @User: Advanced
359  AP_GROUPINFO("POS2", 28, AP_InertialSensor, _accel_pos[1], 0.0f),
360 
361  // @Param: POS3_X
362  // @DisplayName: IMU accelerometer X position
363  // @Description: X position of the third IMU accelerometer in body frame. Positive X is forward of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
364  // @Units: m
365  // @User: Advanced
366 
367  // @Param: POS3_Y
368  // @DisplayName: IMU accelerometer Y position
369  // @Description: Y position of the third IMU accelerometer in body frame. Positive Y is to the right of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
370  // @Units: m
371  // @User: Advanced
372 
373  // @Param: POS3_Z
374  // @DisplayName: IMU accelerometer Z position
375  // @Description: Z position of the third IMU accelerometer in body frame. Positive Z is down from the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
376  // @Units: m
377  // @User: Advanced
378  AP_GROUPINFO("POS3", 29, AP_InertialSensor, _accel_pos[2], 0.0f),
379 
380  // @Param: GYR_ID
381  // @DisplayName: Gyro ID
382  // @Description: Gyro sensor ID, taking into account its type, bus and instance
383  // @ReadOnly: True
384  // @User: Advanced
385  AP_GROUPINFO("GYR_ID", 30, AP_InertialSensor, _gyro_id[0], 0),
386 
387  // @Param: GYR2_ID
388  // @DisplayName: Gyro2 ID
389  // @Description: Gyro2 sensor ID, taking into account its type, bus and instance
390  // @ReadOnly: True
391  // @User: Advanced
392  AP_GROUPINFO("GYR2_ID", 31, AP_InertialSensor, _gyro_id[1], 0),
393 
394  // @Param: GYR3_ID
395  // @DisplayName: Gyro3 ID
396  // @Description: Gyro3 sensor ID, taking into account its type, bus and instance
397  // @ReadOnly: True
398  // @User: Advanced
399  AP_GROUPINFO("GYR3_ID", 32, AP_InertialSensor, _gyro_id[2], 0),
400 
401  // @Param: ACC_ID
402  // @DisplayName: Accelerometer ID
403  // @Description: Accelerometer sensor ID, taking into account its type, bus and instance
404  // @ReadOnly: True
405  // @User: Advanced
406  AP_GROUPINFO("ACC_ID", 33, AP_InertialSensor, _accel_id[0], 0),
407 
408  // @Param: ACC2_ID
409  // @DisplayName: Accelerometer2 ID
410  // @Description: Accelerometer2 sensor ID, taking into account its type, bus and instance
411  // @ReadOnly: True
412  // @User: Advanced
413  AP_GROUPINFO("ACC2_ID", 34, AP_InertialSensor, _accel_id[1], 0),
414 
415  // @Param: ACC3_ID
416  // @DisplayName: Accelerometer3 ID
417  // @Description: Accelerometer3 sensor ID, taking into account its type, bus and instance
418  // @ReadOnly: True
419  // @User: Advanced
420  AP_GROUPINFO("ACC3_ID", 35, AP_InertialSensor, _accel_id[2], 0),
421 
422  // @Param: FAST_SAMPLE
423  // @DisplayName: Fast sampling mask
424  // @Description: Mask of IMUs to enable fast sampling on, if available
425  // @User: Advanced
426  // @Values: 1:FirstIMUOnly,3:FirstAndSecondIMU
427  // @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU
428  AP_GROUPINFO("FAST_SAMPLE", 36, AP_InertialSensor, _fast_sampling_mask, 0),
429 
430  // @Group: NOTCH_
431  // @Path: ../Filter/NotchFilter.cpp
432  AP_SUBGROUPINFO(_notch_filter, "NOTCH_", 37, AP_InertialSensor, NotchFilterVector3fParam),
433 
434  // @Group: LOG_
435  // @Path: ../AP_InertialSensor/BatchSampler.cpp
437 
438  // @Group: ENABLE_MASK
439  // @DisplayName: IMU enable mask
440  // @Description: This is a bitmask of IMUs to enable. It can be used to prevent startup of specific detected IMUs
441  // @User: Advanced
442  // @Values: 1:FirstIMUOnly,3:FirstAndSecondIMU,7:FirstSecondAndThirdIMU,127:AllIMUs
443  // @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU
444  AP_GROUPINFO("ENABLE_MASK", 40, AP_InertialSensor, _enable_mask, 0x7F),
445 
446  /*
447  NOTE: parameter indexes have gaps above. When adding new
448  parameters check for conflicts carefully
449  */
451 };
452 
454 
456  _board_orientation(ROTATION_NONE),
457  _log_raw_bit(-1)
458 {
459  if (_s_instance) {
460  AP_HAL::panic("Too many inertial sensors");
461  }
462  _s_instance = this;
464  for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
465  _gyro_cal_ok[i] = true;
466  _accel_max_abs_offsets[i] = 3.5f;
467  }
468  for (uint8_t i=0; i<INS_VIBRATION_CHECK_INSTANCES; i++) {
471  }
472 
474 }
475 
476 /*
477  * Get the AP_InertialSensor singleton
478  */
480 {
481  if (!_s_instance) {
483  }
484  return _s_instance;
485 }
486 
487 /*
488  register a new gyro instance
489  */
490 uint8_t AP_InertialSensor::register_gyro(uint16_t raw_sample_rate_hz,
491  uint32_t id)
492 {
494  AP_HAL::panic("Too many gyros");
495  }
496 
497  _gyro_raw_sample_rates[_gyro_count] = raw_sample_rate_hz;
500 
501  bool saved = _gyro_id[_gyro_count].load();
502 
503  if (saved && (uint32_t)_gyro_id[_gyro_count] != id) {
504  // inconsistent gyro id - mark it as needing calibration
505  _gyro_cal_ok[_gyro_count] = false;
506  }
507 
508  _gyro_id[_gyro_count].set((int32_t) id);
509 
510 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN || CONFIG_HAL_BOARD == HAL_BOARD_SITL
511  if (!saved) {
512  // assume this is the same sensor and save its ID to allow seamless
513  // transition from when we didn't have the IDs.
514  _gyro_id[_gyro_count].save();
515  }
516 #endif
517 
518  return _gyro_count++;
519 }
520 
521 /*
522  register a new accel instance
523  */
524 uint8_t AP_InertialSensor::register_accel(uint16_t raw_sample_rate_hz,
525  uint32_t id)
526 {
528  AP_HAL::panic("Too many accels");
529  }
530 
531  _accel_raw_sample_rates[_accel_count] = raw_sample_rate_hz;
534 
535  bool saved = _accel_id[_accel_count].load();
536 
537  if (!saved) {
538  // inconsistent accel id
539  _accel_id_ok[_accel_count] = false;
540  } else if ((uint32_t)_accel_id[_accel_count] != id) {
541  // inconsistent accel id
542  _accel_id_ok[_accel_count] = false;
543  } else {
544  _accel_id_ok[_accel_count] = true;
545  }
546 
547  _accel_id[_accel_count].set((int32_t) id);
548 
549 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN || CONFIG_HAL_BOARD == HAL_BOARD_SITL
550  // assume this is the same sensor and save its ID to allow seamless
551  // transition from when we didn't have the IDs.
552  _accel_id_ok[_accel_count] = true;
553  _accel_id[_accel_count].save();
554 #endif
555 
556  return _accel_count++;
557 }
558 
559 /*
560  * Start all backends for gyro and accel measurements. It automatically calls
561  * detect_backends() if it has not been called already.
562  */
564 
565 {
566  detect_backends();
567 
568  for (uint8_t i = 0; i < _backend_count; i++) {
569  _backends[i]->start();
570  }
571 
572  if (_gyro_count == 0 || _accel_count == 0) {
573  AP_HAL::panic("INS needs at least 1 gyro and 1 accel");
574  }
575 
576  // clear IDs for unused sensor instances
577  for (uint8_t i=get_accel_count(); i<INS_MAX_INSTANCES; i++) {
578  _accel_id[i].set(0);
579  }
580  for (uint8_t i=get_gyro_count(); i<INS_MAX_INSTANCES; i++) {
581  _gyro_id[i].set(0);
582  }
583 }
584 
585 /* Find the N instance of the backend that has already been successfully detected */
586 AP_InertialSensor_Backend *AP_InertialSensor::_find_backend(int16_t backend_id, uint8_t instance)
587 {
588  assert(_backends_detected);
589  uint8_t found = 0;
590 
591  for (uint8_t i = 0; i < _backend_count; i++) {
592  int16_t id = _backends[i]->get_id();
593 
594  if (id < 0 || id != backend_id) {
595  continue;
596  }
597 
598  if (instance == found) {
599  return _backends[i];
600  } else {
601  found++;
602  }
603  }
604 
605  return nullptr;
606 }
607 
608 void
609 AP_InertialSensor::init(uint16_t sample_rate)
610 {
611  // remember the sample rate
612  _sample_rate = sample_rate;
613  _loop_delta_t = 1.0f / sample_rate;
614 
615  // we don't allow deltat values greater than 10x the normal loop
616  // time to be exposed outside of INS. Large deltat values can
617  // cause divergence of state estimators
619 
620  if (_gyro_count == 0 && _accel_count == 0) {
621  _start_backends();
622  }
623 
624  // initialise accel scale if need be. This is needed as we can't
625  // give non-zero default values for vectors in AP_Param
626  for (uint8_t i=0; i<get_accel_count(); i++) {
627  if (_accel_scale[i].get().is_zero()) {
628  _accel_scale[i].set(Vector3f(1,1,1));
629  }
630  }
631 
632  // calibrate gyros unless gyro calibration has been disabled
634  init_gyro();
635  }
636 
637  _sample_period_usec = 1000*1000UL / _sample_rate;
638 
639  _notch_filter.init(sample_rate);
640 
641  // establish the baseline time between samples
642  _delta_time = 0;
643  _next_sample_usec = 0;
644  _last_sample_usec = 0;
645  _have_sample = false;
646 
647  // initialise IMU batch logging
648  batchsampler.init();
649 }
650 
652 {
653 
654  if (!backend) {
655  return false;
656  }
658  AP_HAL::panic("Too many INS backends");
659  }
660  _backends[_backend_count++] = backend;
661  return true;
662 }
663 
664 /*
665  detect available backends for this board
666  */
667 void
669 {
670  if (_backends_detected) {
671  return;
672  }
673 
674  _backends_detected = true;
675 
676  uint8_t probe_count = 0;
677  uint8_t enable_mask = uint8_t(_enable_mask.get());
678  uint8_t found_mask = 0;
679 
680  /*
681  use ADD_BACKEND() macro to allow for INS_ENABLE_MASK for enabling/disabling INS backends
682  */
683 #define ADD_BACKEND(x) do { \
684  if (((1U<<probe_count)&enable_mask) && _add_backend(x)) { \
685  found_mask |= (1U<<probe_count); \
686  } \
687  probe_count++; \
688 } while (0)
689 
690  if (_hil_mode) {
692  return;
693  }
694 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
696 #elif HAL_INS_DEFAULT == HAL_INS_HIL
698 #elif CONFIG_HAL_BOARD == HAL_BOARD_F4LIGHT
700 #elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_SPI && defined(HAL_INS_DEFAULT_ROTATION)
703 #elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_SPI
705 #elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_I2C && defined(HAL_INS_DEFAULT_ROTATION)
706  ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.i2c_mgr->get_device(HAL_INS_MPU60x0_I2C_BUS, HAL_INS_MPU60x0_I2C_ADDR),
708 #elif HAL_INS_DEFAULT == HAL_INS_MPU60XX_I2C
709  ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.i2c_mgr->get_device(HAL_INS_MPU60x0_I2C_BUS, HAL_INS_MPU60x0_I2C_ADDR)));
710 #elif HAL_INS_DEFAULT == HAL_INS_BH
711  ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.i2c_mgr->get_device(HAL_INS_MPU60x0_I2C_BUS, HAL_INS_MPU60x0_I2C_ADDR)));
713 #elif AP_FEATURE_BOARD_DETECT
714  switch (AP_BoardConfig::get_board_type()) {
717  break;
718 
727  break;
728 
730  // older Pixhawk2 boards have the MPU6000 instead of MPU9250
731  _fast_sampling_mask.set_default(1);
740  break;
741 
743  _fast_sampling_mask.set_default(1);
746  break;
747 
749  // only do fast samplng on ICM-20608. The MPU9250 doesn't handle high rate well when it has a mag enabled
750  _fast_sampling_mask.set_default(1);
753  break;
754 
756  _fast_sampling_mask.set_default(3);
759  break;
760 
762  // PHMINI uses ICM20608 on the ACCEL_MAG device and a MPU9250 on the old MPU6000 CS line
763  _fast_sampling_mask.set_default(3);
766  break;
767 
769  // AUAV2.1 uses ICM20608 on the ACCEL_MAG device and a MPU9250 on the old MPU6000 CS line
770  _fast_sampling_mask.set_default(3);
773  break;
774 
776  _fast_sampling_mask.set_default(1);
778  break;
779 
781  _fast_sampling_mask.set_default(1);
783  break;
784 
792  ROTATION_YAW_90));
793  break;
794 
796  _fast_sampling_mask.set_default(7);
799 #ifdef HAL_INS_MPU60x0_IMU_NAME
801 #endif
802  break;
803 
811  break;
812 
815  break;
816 
817  default:
818  break;
819  }
820 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
821  // also add any PX4 backends (eg. canbus sensors)
823 #endif
824 #elif HAL_INS_DEFAULT == HAL_INS_MPU9250_SPI && defined(HAL_INS_DEFAULT_ROTATION)
826 #elif HAL_INS_DEFAULT == HAL_INS_MPU9250_SPI
828 #elif HAL_INS_DEFAULT == HAL_INS_EDGE
830  ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU60x0_NAME_EXT), ROTATION_YAW_90));
831 #elif HAL_INS_DEFAULT == HAL_INS_LSM9DS1
832  ADD_BACKEND(AP_InertialSensor_LSM9DS1::probe(*this, hal.spi->get_device(HAL_INS_LSM9DS1_NAME)));
833 #elif HAL_INS_DEFAULT == HAL_INS_LSM9DS0
837 #elif HAL_INS_DEFAULT == HAL_INS_L3G4200D
838  ADD_BACKEND(AP_InertialSensor_L3G4200D::probe(*this, hal.i2c_mgr->get_device(HAL_INS_L3G4200D_I2C_BUS, HAL_INS_L3G4200D_I2C_ADDR)));
839 #elif HAL_INS_DEFAULT == HAL_INS_MPU9250_I2C
840  ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.i2c_mgr->get_device(HAL_INS_MPU9250_I2C_BUS, HAL_INS_MPU9250_I2C_ADDR)));
841 #elif HAL_INS_DEFAULT == HAL_INS_BBBMINI
843  ADD_BACKEND(AP_InertialSensor_Invensense::probe(*this, hal.spi->get_device(HAL_INS_MPU9250_NAME_EXT)));
844 #elif HAL_INS_DEFAULT == HAL_INS_AERO
846 #elif HAL_INS_DEFAULT == HAL_INS_RST
847  ADD_BACKEND(AP_InertialSensor_RST::probe(*this, hal.spi->get_device(HAL_INS_RST_G_NAME),
848  hal.spi->get_device(HAL_INS_RST_A_NAME),
849  HAL_INS_DEFAULT_G_ROTATION,
850  HAL_INS_DEFAULT_A_ROTATION));
851 #elif HAL_INS_DEFAULT == HAL_INS_ICM20789_SPI
853 #elif CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_OMNIBUSF7V2
856 #elif HAL_INS_DEFAULT == HAL_INS_NONE
857  // no INS device
858 #else
859  #error Unrecognised HAL_INS_TYPE setting
860 #endif
861 
862  _enable_mask.set(found_mask);
863 
864  if (_backend_count == 0) {
865  AP_BoardConfig::sensor_config_error("INS: unable to initialise driver");
866  }
867 }
868 
869 // Armed, Copter, PixHawk:
870 // ins_periodic: 57500 events, 0 overruns, 208754us elapsed, 3us avg, min 1us max 218us 40.662us rms
872 {
874 }
875 
876 
877 /*
878  _calculate_trim - calculates the x and y trim angles. The
879  accel_sample must be correctly scaled, offset and oriented for the
880  board
881 */
882 bool AP_InertialSensor::_calculate_trim(const Vector3f &accel_sample, float& trim_roll, float& trim_pitch)
883 {
884  trim_pitch = atan2f(accel_sample.x, norm(accel_sample.y, accel_sample.z));
885  trim_roll = atan2f(-accel_sample.y, -accel_sample.z);
886  if (fabsf(trim_roll) > radians(10) ||
887  fabsf(trim_pitch) > radians(10)) {
888  hal.console->printf("trim over maximum of 10 degrees\n");
889  return false;
890  }
891  hal.console->printf("Trim OK: roll=%.2f pitch=%.2f\n",
892  (double)degrees(trim_roll),
893  (double)degrees(trim_pitch));
894  return true;
895 }
896 
897 void
899 {
900  _init_gyro();
901 
902  // save calibration
904 }
905 
906 // accelerometer clipping reporting
907 uint32_t AP_InertialSensor::get_accel_clip_count(uint8_t instance) const
908 {
909  if (instance >= get_accel_count()) {
910  return 0;
911  }
912  return _accel_clip_count[instance];
913 }
914 
915 // get_gyro_health_all - return true if all gyros are healthy
917 {
918  for (uint8_t i=0; i<get_gyro_count(); i++) {
919  if (!get_gyro_health(i)) {
920  return false;
921  }
922  }
923  // return true if we have at least one gyro
924  return (get_gyro_count() > 0);
925 }
926 
927 // gyro_calibration_ok_all - returns true if all gyros were calibrated successfully
929 {
930  for (uint8_t i=0; i<get_gyro_count(); i++) {
931  if (!gyro_calibrated_ok(i)) {
932  return false;
933  }
934  }
935  for (uint8_t i=get_gyro_count(); i<INS_MAX_INSTANCES; i++) {
936  if (_gyro_id[i] != 0) {
937  // missing gyro
938  return false;
939  }
940  }
941  return (get_gyro_count() > 0);
942 }
943 
944 // return true if gyro instance should be used (must be healthy and have it's use parameter set to 1)
945 bool AP_InertialSensor::use_gyro(uint8_t instance) const
946 {
947  if (instance >= INS_MAX_INSTANCES) {
948  return false;
949  }
950 
951  return (get_gyro_health(instance) && _use[instance]);
952 }
953 
954 // get_accel_health_all - return true if all accels are healthy
956 {
957  for (uint8_t i=0; i<get_accel_count(); i++) {
958  if (!get_accel_health(i)) {
959  return false;
960  }
961  }
962  // return true if we have at least one accel
963  return (get_accel_count() > 0);
964 }
965 
966 
967 /*
968  calculate the trim_roll and trim_pitch. This is used for redoing the
969  trim without needing a full accel cal
970  */
971 bool AP_InertialSensor::calibrate_trim(float &trim_roll, float &trim_pitch)
972 {
973  Vector3f level_sample;
974 
975  // exit immediately if calibration is already in progress
976  if (_calibrating) {
977  return false;
978  }
979 
980  _calibrating = true;
981 
982  const uint8_t update_dt_milliseconds = (uint8_t)(1000.0f/get_sample_rate()+0.5f);
983 
984  // wait 100ms for ins filter to rise
985  for (uint8_t k=0; k<100/update_dt_milliseconds; k++) {
986  wait_for_sample();
987  update();
988  hal.scheduler->delay(update_dt_milliseconds);
989  }
990 
991  uint32_t num_samples = 0;
992  while (num_samples < 400/update_dt_milliseconds) {
993  wait_for_sample();
994  // read samples from ins
995  update();
996  // capture sample
997  Vector3f samp;
998  samp = get_accel(0);
999  level_sample += samp;
1000  if (!get_accel_health(0)) {
1001  goto failed;
1002  }
1003  hal.scheduler->delay(update_dt_milliseconds);
1004  num_samples++;
1005  }
1006  level_sample /= num_samples;
1007 
1008  if (!_calculate_trim(level_sample, trim_roll, trim_pitch)) {
1009  goto failed;
1010  }
1011 
1012  _calibrating = false;
1013  return true;
1014 
1015 failed:
1016  _calibrating = false;
1017  return false;
1018 }
1019 
1020 /*
1021  check if the accelerometers are calibrated in 3D and that current number of accels matched number when calibrated
1022  */
1024 {
1025  // calibration is not applicable for HIL mode
1026  if (_hil_mode) {
1027  return true;
1028  }
1029 
1030  // check each accelerometer has offsets saved
1031  for (uint8_t i=0; i<get_accel_count(); i++) {
1032  if (!_accel_id_ok[i]) {
1033  return false;
1034  }
1035  // exactly 0.0 offset is extremely unlikely
1036  if (_accel_offset[i].get().is_zero()) {
1037  return false;
1038  }
1039  // zero scaling also indicates not calibrated
1040  if (_accel_scale[i].get().is_zero()) {
1041  return false;
1042  }
1043  }
1044  for (uint8_t i=get_accel_count(); i<INS_MAX_INSTANCES; i++) {
1045  if (_accel_id[i] != 0) {
1046  // missing accel
1047  return false;
1048  }
1049  }
1050 
1051  // check calibrated accels matches number of accels (no unused accels should have offsets or scaling)
1053  for (uint8_t i=get_accel_count(); i<INS_MAX_INSTANCES; i++) {
1054  const Vector3f &scaling = _accel_scale[i].get();
1055  bool have_scaling = (!is_zero(scaling.x) && !is_equal(scaling.x,1.0f)) || (!is_zero(scaling.y) && !is_equal(scaling.y,1.0f)) || (!is_zero(scaling.z) && !is_equal(scaling.z,1.0f));
1056  bool have_offsets = !_accel_offset[i].get().is_zero();
1057  if (have_scaling || have_offsets) {
1058  return false;
1059  }
1060  }
1061  }
1062 
1063  // if we got this far the accelerometers must have been calibrated
1064  return true;
1065 }
1066 
1067 // return true if accel instance should be used (must be healthy and have it's use parameter set to 1)
1068 bool AP_InertialSensor::use_accel(uint8_t instance) const
1069 {
1070  if (instance >= INS_MAX_INSTANCES) {
1071  return false;
1072  }
1073 
1074  return (get_accel_health(instance) && _use[instance]);
1075 }
1076 
1077 void
1079 {
1080  uint8_t num_gyros = MIN(get_gyro_count(), INS_MAX_INSTANCES);
1081  Vector3f last_average[INS_MAX_INSTANCES], best_avg[INS_MAX_INSTANCES];
1082  Vector3f new_gyro_offset[INS_MAX_INSTANCES];
1083  float best_diff[INS_MAX_INSTANCES];
1084  bool converged[INS_MAX_INSTANCES];
1085 
1086  // exit immediately if calibration is already in progress
1087  if (_calibrating) {
1088  return;
1089  }
1090 
1091  // record we are calibrating
1092  _calibrating = true;
1093 
1094  // flash leds to tell user to keep the IMU still
1096 
1097  // cold start
1098  hal.console->printf("Init Gyro");
1099 
1100  /*
1101  we do the gyro calibration with no board rotation. This avoids
1102  having to rotate readings during the calibration
1103  */
1104  enum Rotation saved_orientation = _board_orientation;
1106 
1107  // remove existing gyro offsets
1108  for (uint8_t k=0; k<num_gyros; k++) {
1109  _gyro_offset[k].set(Vector3f());
1110  new_gyro_offset[k].zero();
1111  best_diff[k] = -1.f;
1112  last_average[k].zero();
1113  converged[k] = false;
1114  }
1115 
1116  for(int8_t c = 0; c < 5; c++) {
1117  hal.scheduler->delay(5);
1118  update();
1119  }
1120 
1121  // the strategy is to average 50 points over 0.5 seconds, then do it
1122  // again and see if the 2nd average is within a small margin of
1123  // the first
1124 
1125  uint8_t num_converged = 0;
1126 
1127  // we try to get a good calibration estimate for up to 30 seconds
1128  // if the gyros are stable, we should get it in 1 second
1129  for (int16_t j = 0; j <= 30*4 && num_converged < num_gyros; j++) {
1130  Vector3f gyro_sum[INS_MAX_INSTANCES], gyro_avg[INS_MAX_INSTANCES], gyro_diff[INS_MAX_INSTANCES];
1131  Vector3f accel_start;
1132  float diff_norm[INS_MAX_INSTANCES];
1133  uint8_t i;
1134 
1135  memset(diff_norm, 0, sizeof(diff_norm));
1136 
1137  hal.console->printf("*");
1138 
1139  for (uint8_t k=0; k<num_gyros; k++) {
1140  gyro_sum[k].zero();
1141  }
1142  accel_start = get_accel(0);
1143  for (i=0; i<50; i++) {
1144  update();
1145  for (uint8_t k=0; k<num_gyros; k++) {
1146  gyro_sum[k] += get_gyro(k);
1147  }
1148  hal.scheduler->delay(5);
1149  }
1150 
1151  Vector3f accel_diff = get_accel(0) - accel_start;
1152  if (accel_diff.length() > 0.2f) {
1153  // the accelerometers changed during the gyro sum. Skip
1154  // this sample. This copes with doing gyro cal on a
1155  // steadily moving platform. The value 0.2 corresponds
1156  // with around 5 degrees/second of rotation.
1157  continue;
1158  }
1159 
1160  for (uint8_t k=0; k<num_gyros; k++) {
1161  gyro_avg[k] = gyro_sum[k] / i;
1162  gyro_diff[k] = last_average[k] - gyro_avg[k];
1163  diff_norm[k] = gyro_diff[k].length();
1164  }
1165 
1166  for (uint8_t k=0; k<num_gyros; k++) {
1167  if (best_diff[k] < 0) {
1168  best_diff[k] = diff_norm[k];
1169  best_avg[k] = gyro_avg[k];
1170  } else if (gyro_diff[k].length() < ToRad(GYRO_INIT_MAX_DIFF_DPS)) {
1171  // we want the average to be within 0.1 bit, which is 0.04 degrees/s
1172  last_average[k] = (gyro_avg[k] * 0.5f) + (last_average[k] * 0.5f);
1173  if (!converged[k] || last_average[k].length() < new_gyro_offset[k].length()) {
1174  new_gyro_offset[k] = last_average[k];
1175  }
1176  if (!converged[k]) {
1177  converged[k] = true;
1178  num_converged++;
1179  }
1180  } else if (diff_norm[k] < best_diff[k]) {
1181  best_diff[k] = diff_norm[k];
1182  best_avg[k] = (gyro_avg[k] * 0.5f) + (last_average[k] * 0.5f);
1183  }
1184  last_average[k] = gyro_avg[k];
1185  }
1186  }
1187 
1188  // we've kept the user waiting long enough - use the best pair we
1189  // found so far
1190  hal.console->printf("\n");
1191  for (uint8_t k=0; k<num_gyros; k++) {
1192  if (!converged[k]) {
1193  hal.console->printf("gyro[%u] did not converge: diff=%f dps (expected < %f)\n",
1194  (unsigned)k,
1195  (double)ToDeg(best_diff[k]),
1196  (double)GYRO_INIT_MAX_DIFF_DPS);
1197  _gyro_offset[k] = best_avg[k];
1198  // flag calibration as failed for this gyro
1199  _gyro_cal_ok[k] = false;
1200  } else {
1201  _gyro_cal_ok[k] = true;
1202  _gyro_offset[k] = new_gyro_offset[k];
1203  }
1204  }
1205 
1206  // restore orientation
1207  _board_orientation = saved_orientation;
1208 
1209  // record calibration complete
1210  _calibrating = false;
1211 
1212  // stop flashing leds
1214 }
1215 
1216 // save parameters to eeprom
1218 {
1219  for (uint8_t i=0; i<_gyro_count; i++) {
1220  _gyro_offset[i].save();
1221  _gyro_id[i].save();
1222  }
1223  for (uint8_t i=_gyro_count; i<INS_MAX_INSTANCES; i++) {
1224  _gyro_offset[i].set_and_save(Vector3f());
1225  _gyro_id[i].set_and_save(0);
1226  }
1227 }
1228 
1229 
1230 /*
1231  update gyro and accel values from backends
1232  */
1234 {
1235  // during initialisation update() may be called without
1236  // wait_for_sample(), and a wait is implied
1237  wait_for_sample();
1238 
1239  if (!_hil_mode) {
1240  for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
1241  // mark sensors unhealthy and let update() in each backend
1242  // mark them healthy via _publish_gyro() and
1243  // _publish_accel()
1244  _gyro_healthy[i] = false;
1245  _accel_healthy[i] = false;
1246  _delta_velocity_valid[i] = false;
1247  _delta_angle_valid[i] = false;
1248  }
1249  for (uint8_t i=0; i<_backend_count; i++) {
1250  _backends[i]->update();
1251  }
1252 
1253  // clear accumulators
1254  for (uint8_t i = 0; i < INS_MAX_INSTANCES; i++) {
1256  _delta_velocity_acc_dt[i] = 0;
1257  _delta_angle_acc[i].zero();
1258  _delta_angle_acc_dt[i] = 0;
1259  }
1260 
1262  for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
1265  }
1266 
1267  if (_startup_ms == 0) {
1269  } else if (AP_HAL::millis()-_startup_ms > 2000) {
1271  }
1272  }
1273 
1274  for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
1277  }
1280  }
1281  }
1282 
1283  // adjust health status if a sensor has a non-zero error count
1284  // but another sensor doesn't.
1285  bool have_zero_accel_error_count = false;
1286  bool have_zero_gyro_error_count = false;
1287  for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
1289  have_zero_accel_error_count = true;
1290  }
1292  have_zero_gyro_error_count = true;
1293  }
1294  }
1295 
1296  for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
1297  if (_gyro_healthy[i] && _gyro_error_count[i] > _gyro_startup_error_count[i] && have_zero_gyro_error_count) {
1298  // we prefer not to use a gyro that has had errors
1299  _gyro_healthy[i] = false;
1300  }
1301  if (_accel_healthy[i] && _accel_error_count[i] > _accel_startup_error_count[i] && have_zero_accel_error_count) {
1302  // we prefer not to use a accel that has had errors
1303  _accel_healthy[i] = false;
1304  }
1305  }
1306 
1307  // set primary to first healthy accel and gyro
1308  for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
1309  if (_gyro_healthy[i] && _use[i]) {
1310  _primary_gyro = i;
1311  break;
1312  }
1313  }
1314  for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
1315  if (_accel_healthy[i] && _use[i]) {
1316  _primary_accel = i;
1317  break;
1318  }
1319  }
1320  }
1321 
1322  // apply notch filter to primary gyro
1324 
1326 
1327  _have_sample = false;
1328 }
1329 
1330 /*
1331  wait for a sample to be available. This is the function that
1332  determines the timing of the main loop in ardupilot.
1333 
1334  Ideally this function would return at exactly the rate given by the
1335  sample_rate argument given to AP_InertialSensor::init().
1336 
1337  The key output of this function is _delta_time, which is the time
1338  over which the gyro and accel integration will happen for this
1339  sample. We want that to be a constant time if possible, but if
1340  delays occur we need to cope with them. The long term sum of
1341  _delta_time should be exactly equal to the wall clock elapsed time
1342  */
1344 {
1345  if (_have_sample) {
1346  // the user has called wait_for_sample() again without
1347  // consuming the sample with update()
1348  return;
1349  }
1350 
1351  uint32_t now = AP_HAL::micros();
1352 
1353  if (_next_sample_usec == 0 && _delta_time <= 0) {
1354  // this is the first call to wait_for_sample()
1357  goto check_sample;
1358  }
1359 
1360  // see how long it is till the next sample is due
1361  if (_next_sample_usec - now <=_sample_period_usec) {
1362  // we're ahead on time, schedule next sample at expected period
1363  uint32_t wait_usec = _next_sample_usec - now;
1364  hal.scheduler->delay_microseconds_boost(wait_usec);
1365  uint32_t now2 = AP_HAL::micros();
1366  if (now2+100 < _next_sample_usec) {
1367  timing_printf("shortsleep %u\n", (unsigned)(_next_sample_usec-now2));
1368  }
1369  if (now2 > _next_sample_usec+400) {
1370  timing_printf("longsleep %u wait_usec=%u\n",
1371  (unsigned)(now2-_next_sample_usec),
1372  (unsigned)wait_usec);
1373  }
1375  } else if (now - _next_sample_usec < _sample_period_usec/8) {
1376  // we've overshot, but only by a small amount, keep on
1377  // schedule with no delay
1378  timing_printf("overshoot1 %u\n", (unsigned)(now-_next_sample_usec));
1380  } else {
1381  // we've overshot by a larger amount, re-zero scheduling with
1382  // no delay
1383  timing_printf("overshoot2 %u\n", (unsigned)(now-_next_sample_usec));
1385  }
1386 
1387 check_sample:
1388  if (!_hil_mode) {
1389  // we also wait for at least one backend to have a sample of both
1390  // accel and gyro. This normally completes immediately.
1391  bool gyro_available = false;
1392  bool accel_available = false;
1393  while (true) {
1394  for (uint8_t i=0; i<_backend_count; i++) {
1395  _backends[i]->accumulate();
1396  }
1397 
1398  for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
1399  gyro_available |= _new_gyro_data[i];
1400  accel_available |= _new_accel_data[i];
1401  }
1402 
1403  if (gyro_available && accel_available) {
1404  break;
1405  }
1406 
1407  hal.scheduler->delay_microseconds(100);
1408  }
1409  }
1410 
1411  now = AP_HAL::micros();
1412  if (_hil_mode && _hil.delta_time > 0) {
1413  _delta_time = _hil.delta_time;
1414  _hil.delta_time = 0;
1415  } else {
1416  _delta_time = (now - _last_sample_usec) * 1.0e-6f;
1417  }
1418  _last_sample_usec = now;
1419 
1420 #if 0
1421  {
1422  static uint64_t delta_time_sum;
1423  static uint16_t counter;
1424  if (delta_time_sum == 0) {
1425  delta_time_sum = _sample_period_usec;
1426  }
1427  delta_time_sum += _delta_time * 1.0e6f;
1428  if (counter++ == 400) {
1429  counter = 0;
1430  hal.console->printf("now=%lu _delta_time_sum=%lu diff=%ld\n",
1431  (unsigned long)now,
1432  (unsigned long)delta_time_sum,
1433  (long)(now - delta_time_sum));
1434  }
1435  }
1436 #endif
1437 
1438  _have_sample = true;
1439 }
1440 
1441 
1442 /*
1443  get delta angles
1444  */
1445 bool AP_InertialSensor::get_delta_angle(uint8_t i, Vector3f &delta_angle) const
1446 {
1447  if (_delta_angle_valid[i]) {
1448  delta_angle = _delta_angle[i];
1449  return true;
1450  } else if (get_gyro_health(i)) {
1451  // provide delta angle from raw gyro, so we use the same code
1452  // at higher level
1453  delta_angle = get_gyro(i) * get_delta_time();
1454  return true;
1455  }
1456  return false;
1457 }
1458 
1459 /*
1460  get delta velocity if available
1461 */
1462 bool AP_InertialSensor::get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const
1463 {
1464  if (_delta_velocity_valid[i]) {
1465  delta_velocity = _delta_velocity[i];
1466  return true;
1467  } else if (get_accel_health(i)) {
1468  delta_velocity = get_accel(i) * get_delta_time();
1469  return true;
1470  }
1471  return false;
1472 }
1473 
1474 /*
1475  return delta_time for the delta_velocity
1476  */
1478 {
1479  float ret;
1480  if (_delta_velocity_valid[i]) {
1481  ret = _delta_velocity_dt[i];
1482  } else {
1483  ret = get_delta_time();
1484  }
1485  ret = MIN(ret, _loop_delta_t_max);
1486  return ret;
1487 }
1488 
1489 /*
1490  return delta_time for the delta_angle
1491  */
1493 {
1494  float ret;
1495  if (_delta_angle_valid[i] && _delta_angle_dt[i] > 0) {
1496  ret = _delta_angle_dt[i];
1497  } else {
1498  ret = get_delta_time();
1499  }
1500  ret = MIN(ret, _loop_delta_t_max);
1501  return ret;
1502 }
1503 
1504 
1505 /*
1506  support for setting accel and gyro vectors, for use by HIL
1507  */
1508 void AP_InertialSensor::set_accel(uint8_t instance, const Vector3f &accel)
1509 {
1510  if (_accel_count == 0) {
1511  // we haven't initialised yet
1512  return;
1513  }
1514  if (instance < INS_MAX_INSTANCES) {
1515  _accel[instance] = accel;
1516  _accel_healthy[instance] = true;
1517  if (_accel_count <= instance) {
1518  _accel_count = instance+1;
1519  }
1521  _primary_accel = instance;
1522  }
1523  }
1524 }
1525 
1526 void AP_InertialSensor::set_gyro(uint8_t instance, const Vector3f &gyro)
1527 {
1528  if (_gyro_count == 0) {
1529  // we haven't initialised yet
1530  return;
1531  }
1532  if (instance < INS_MAX_INSTANCES) {
1533  _gyro[instance] = gyro;
1534  _gyro_healthy[instance] = true;
1535  if (_gyro_count <= instance) {
1536  _gyro_count = instance+1;
1537  _gyro_cal_ok[instance] = true;
1538  }
1540  _primary_accel = instance;
1541  }
1542  }
1543 }
1544 
1545 /*
1546  set delta time for next ins.update()
1547  */
1549 {
1550  _hil.delta_time = delta_time;
1551 }
1552 
1553 /*
1554  set delta velocity for next update
1555  */
1556 void AP_InertialSensor::set_delta_velocity(uint8_t instance, float deltavt, const Vector3f &deltav)
1557 {
1558  if (instance < INS_MAX_INSTANCES) {
1559  _delta_velocity_valid[instance] = true;
1560  _delta_velocity[instance] = deltav;
1561  _delta_velocity_dt[instance] = deltavt;
1562  }
1563 }
1564 
1565 /*
1566  set delta angle for next update
1567  */
1568 void AP_InertialSensor::set_delta_angle(uint8_t instance, const Vector3f &deltaa, float deltaat)
1569 {
1570  if (instance < INS_MAX_INSTANCES) {
1571  _delta_angle_valid[instance] = true;
1572  _delta_angle[instance] = deltaa;
1573  _delta_angle_dt[instance] = deltaat;
1574  }
1575 }
1576 
1577 /*
1578  * Get an AuxiliaryBus of N @instance of backend identified by @backend_id
1579  */
1580 AuxiliaryBus *AP_InertialSensor::get_auxiliary_bus(int16_t backend_id, uint8_t instance)
1581 {
1582  detect_backends();
1583 
1584  AP_InertialSensor_Backend *backend = _find_backend(backend_id, instance);
1585  if (backend == nullptr) {
1586  return nullptr;
1587  }
1588 
1589  return backend->get_auxiliary_bus();
1590 }
1591 
1592 // calculate vibration levels and check for accelerometer clipping (called by a backends)
1593 void AP_InertialSensor::calc_vibration_and_clipping(uint8_t instance, const Vector3f &accel, float dt)
1594 {
1595  // check for clipping
1596  if (fabsf(accel.x) > AP_INERTIAL_SENSOR_ACCEL_CLIP_THRESH_MSS ||
1599  _accel_clip_count[instance]++;
1600  }
1601 
1602  // calculate vibration levels
1603  if (instance < INS_VIBRATION_CHECK_INSTANCES) {
1604  // filter accel at 5hz
1605  Vector3f accel_filt = _accel_vibe_floor_filter[instance].apply(accel, dt);
1606 
1607  // calc difference from this sample and 5hz filtered value, square and filter at 2hz
1608  Vector3f accel_diff = (accel - accel_filt);
1609  accel_diff.x *= accel_diff.x;
1610  accel_diff.y *= accel_diff.y;
1611  accel_diff.z *= accel_diff.z;
1612  _accel_vibe_filter[instance].apply(accel_diff, dt);
1613  }
1614 }
1615 
1616 // peak hold detector for slower mechanisms to detect spikes
1617 void AP_InertialSensor::set_accel_peak_hold(uint8_t instance, const Vector3f &accel)
1618 {
1619  if (instance != _primary_accel) {
1620  // we only record for primary accel
1621  return;
1622  }
1623  uint32_t now = AP_HAL::millis();
1624 
1625  // negative x peak(min) hold detector
1630  }
1631 }
1632 
1633 // retrieve latest calculated vibration levels
1635 {
1636  Vector3f vibe;
1637  if (instance < INS_VIBRATION_CHECK_INSTANCES) {
1638  vibe = _accel_vibe_filter[instance].get();
1639  vibe.x = safe_sqrt(vibe.x);
1640  vibe.y = safe_sqrt(vibe.y);
1641  vibe.z = safe_sqrt(vibe.z);
1642  }
1643  return vibe;
1644 }
1645 
1646 // check for vibration movement. Return true if all axis show nearly zero movement
1648 {
1649  Vector3f vibe = get_vibration_levels();
1650  return (vibe.x < _still_threshold) &&
1651  (vibe.y < _still_threshold) &&
1652  (vibe.z < _still_threshold);
1653 }
1654 
1655 // initialise and register accel calibrator
1656 // called during the startup of accel cal
1658 {
1659  // NOTE: these objects are never deallocated because the pre-arm checks force a reboot
1660  if (_acal == nullptr) {
1661  _acal = new AP_AccelCal;
1662  }
1663  if (_accel_calibrator == nullptr) {
1665  }
1666 }
1667 
1668 // update accel calibrator
1670 {
1671  if(_acal == nullptr) {
1672  return;
1673  }
1674 
1675  _acal->update();
1676 
1678  _acal->cancel();
1679  }
1680 }
1681 
1682 /*
1683  set and save accelerometer bias along with trim calculation
1684 */
1686 {
1687  Vector3f bias, gain;
1688  for (uint8_t i=0; i<_accel_count; i++) {
1689  if (_accel_calibrator[i].get_status() == ACCEL_CAL_SUCCESS) {
1690  _accel_calibrator[i].get_calibration(bias, gain);
1691  _accel_offset[i].set_and_save(bias);
1692  _accel_scale[i].set_and_save(gain);
1693  _accel_id[i].save();
1694  _accel_id_ok[i] = true;
1695  } else {
1696  _accel_offset[i].set_and_save(Vector3f());
1697  _accel_scale[i].set_and_save(Vector3f());
1698  }
1699  }
1700 
1701  // clear any unused accels
1702  for (uint8_t i=_accel_count; i<INS_MAX_INSTANCES; i++) {
1703  _accel_id[i].set_and_save(0);
1704  _accel_offset[i].set_and_save(Vector3f());
1705  _accel_scale[i].set_and_save(Vector3f());
1706  }
1707 
1708  Vector3f aligned_sample;
1709  Vector3f misaligned_sample;
1710  switch(_trim_option) {
1711  case 0:
1712  break;
1713  case 1:
1714  // The first level step of accel cal will be taken as gnd truth,
1715  // i.e. trim will be set as per the output of primary accel from the level step
1716  get_primary_accel_cal_sample_avg(0,aligned_sample);
1717  _trim_pitch = atan2f(aligned_sample.x, norm(aligned_sample.y, aligned_sample.z));
1718  _trim_roll = atan2f(-aligned_sample.y, -aligned_sample.z);
1719  _new_trim = true;
1720  break;
1721  case 2:
1722  // Reference accel is truth, in this scenario there is a reference accel
1723  // as mentioned in ACC_BODY_ALIGNED
1724  if (get_primary_accel_cal_sample_avg(0,misaligned_sample) && get_fixed_mount_accel_cal_sample(0,aligned_sample)) {
1725  // determine trim from aligned sample vs misaligned sample
1726  Vector3f cross = (misaligned_sample%aligned_sample);
1727  float dot = (misaligned_sample*aligned_sample);
1728  Quaternion q(safe_sqrt(sq(misaligned_sample.length())*sq(aligned_sample.length()))+dot, cross.x, cross.y, cross.z);
1729  q.normalize();
1730  _trim_roll = q.get_euler_roll();
1731  _trim_pitch = q.get_euler_pitch();
1732  _new_trim = true;
1733  }
1734  break;
1735  default:
1736  _new_trim = false;
1737  /* no break */
1738  }
1739 
1740  if (fabsf(_trim_roll) > radians(10) ||
1741  fabsf(_trim_pitch) > radians(10)) {
1742  hal.console->printf("ERR: Trim over maximum of 10 degrees!!");
1743  _new_trim = false; //we have either got faulty level during acal or highly misaligned accelerometers
1744  }
1745 
1747 }
1748 
1750 {
1751  for (uint8_t i=0; i<_accel_count; i++) {
1752  _accel_offset[i].set_and_notify(Vector3f(0,0,0));
1753  _accel_scale[i].set_and_notify(Vector3f(1,1,1));
1754  }
1755 }
1756 
1757 /*
1758  Returns true if new valid trim values are available and passes them to reference vars
1759 */
1760 bool AP_InertialSensor::get_new_trim(float& trim_roll, float &trim_pitch)
1761 {
1762  if (_new_trim) {
1763  trim_roll = _trim_roll;
1764  trim_pitch = _trim_pitch;
1765  _new_trim = false;
1766  return true;
1767  }
1768  return false;
1769 }
1770 
1771 /*
1772  Returns body fixed accelerometer level data averaged during accel calibration's first step
1773 */
1775 {
1776  if (_accel_count <= (_acc_body_aligned-1) || _accel_calibrator[2].get_status() != ACCEL_CAL_SUCCESS || sample_num>=_accel_calibrator[2].get_num_samples_collected()) {
1777  return false;
1778  }
1781  ret = *_custom_rotation * ret;
1782  } else {
1784  }
1785  return true;
1786 }
1787 
1788 /*
1789  Returns Primary accelerometer level data averaged during accel calibration's first step
1790 */
1792 {
1793  uint8_t count = 0;
1794  Vector3f avg = Vector3f(0,0,0);
1795  for (uint8_t i=0; i<MIN(_accel_count,2); i++) {
1796  if (_accel_calibrator[i].get_status() != ACCEL_CAL_SUCCESS || sample_num>=_accel_calibrator[i].get_num_samples_collected()) {
1797  continue;
1798  }
1799  Vector3f sample;
1800  _accel_calibrator[i].get_sample_corrected(sample_num, sample);
1801  avg += sample;
1802  count++;
1803  }
1804  if (count == 0) {
1805  return false;
1806  }
1807  avg /= count;
1808  ret = avg;
1810  ret = *_custom_rotation * ret;
1811  } else {
1813  }
1814  return true;
1815 }
1816 
1817 /*
1818  perform a simple 1D accel calibration, returning mavlink result code
1819  */
1821 {
1822  uint8_t num_accels = MIN(get_accel_count(), INS_MAX_INSTANCES);
1823  Vector3f last_average[INS_MAX_INSTANCES];
1824  Vector3f new_accel_offset[INS_MAX_INSTANCES];
1825  Vector3f saved_offsets[INS_MAX_INSTANCES];
1826  Vector3f saved_scaling[INS_MAX_INSTANCES];
1827  bool converged[INS_MAX_INSTANCES];
1828  const float accel_convergence_limit = 0.05;
1829  Vector3f rotated_gravity(0, 0, -GRAVITY_MSS);
1830 
1831  // exit immediately if calibration is already in progress
1832  if (_calibrating) {
1833  return MAV_RESULT_TEMPORARILY_REJECTED;
1834  }
1835 
1836  // record we are calibrating
1837  _calibrating = true;
1838 
1839  // flash leds to tell user to keep the IMU still
1841 
1842  hal.console->printf("Simple accel cal");
1843 
1844  /*
1845  we do the accel calibration with no board rotation. This avoids
1846  having to rotate readings during the calibration
1847  */
1848  enum Rotation saved_orientation = _board_orientation;
1850 
1851  // get the rotated gravity vector which will need to be applied to the offsets
1852  rotated_gravity.rotate_inverse(saved_orientation);
1853 
1854  // save existing accel offsets
1855  for (uint8_t k=0; k<num_accels; k++) {
1856  saved_offsets[k] = _accel_offset[k];
1857  saved_scaling[k] = _accel_scale[k];
1858  }
1859 
1860  // remove existing accel offsets and scaling
1861  for (uint8_t k=0; k<num_accels; k++) {
1862  _accel_offset[k].set(Vector3f());
1863  _accel_scale[k].set(Vector3f(1,1,1));
1864  new_accel_offset[k].zero();
1865  last_average[k].zero();
1866  converged[k] = false;
1867  }
1868 
1869  for (uint8_t c = 0; c < 5; c++) {
1870  hal.scheduler->delay(5);
1871  update();
1872  }
1873 
1874  // the strategy is to average 50 points over 0.5 seconds, then do it
1875  // again and see if the 2nd average is within a small margin of
1876  // the first
1877 
1878  uint8_t num_converged = 0;
1879 
1880  // we try to get a good calibration estimate for up to 10 seconds
1881  // if the accels are stable, we should get it in 1 second
1882  for (int16_t j = 0; j <= 10*4 && num_converged < num_accels; j++) {
1883  Vector3f accel_sum[INS_MAX_INSTANCES], accel_avg[INS_MAX_INSTANCES], accel_diff[INS_MAX_INSTANCES];
1884  float diff_norm[INS_MAX_INSTANCES];
1885  uint8_t i;
1886 
1887  memset(diff_norm, 0, sizeof(diff_norm));
1888 
1889  hal.console->printf("*");
1890 
1891  for (uint8_t k=0; k<num_accels; k++) {
1892  accel_sum[k].zero();
1893  }
1894  for (i=0; i<50; i++) {
1895  update();
1896  for (uint8_t k=0; k<num_accels; k++) {
1897  accel_sum[k] += get_accel(k);
1898  }
1899  hal.scheduler->delay(5);
1900  }
1901 
1902  for (uint8_t k=0; k<num_accels; k++) {
1903  accel_avg[k] = accel_sum[k] / i;
1904  accel_diff[k] = last_average[k] - accel_avg[k];
1905  diff_norm[k] = accel_diff[k].length();
1906  }
1907 
1908  for (uint8_t k=0; k<num_accels; k++) {
1909  if (j > 0 && diff_norm[k] < accel_convergence_limit) {
1910  last_average[k] = (accel_avg[k] * 0.5f) + (last_average[k] * 0.5f);
1911  if (!converged[k] || last_average[k].length() < new_accel_offset[k].length()) {
1912  new_accel_offset[k] = last_average[k];
1913  }
1914  if (!converged[k]) {
1915  converged[k] = true;
1916  num_converged++;
1917  }
1918  } else {
1919  last_average[k] = accel_avg[k];
1920  }
1921  }
1922  }
1923 
1924  MAV_RESULT result = MAV_RESULT_ACCEPTED;
1925 
1926  // see if we've passed
1927  for (uint8_t k=0; k<num_accels; k++) {
1928  if (!converged[k]) {
1929  result = MAV_RESULT_FAILED;
1930  }
1931  }
1932 
1933  // restore orientation
1934  _board_orientation = saved_orientation;
1935 
1936  if (result == MAV_RESULT_ACCEPTED) {
1937  hal.console->printf("\nPASSED\n");
1938  for (uint8_t k=0; k<num_accels; k++) {
1939  // remove rotated gravity
1940  new_accel_offset[k] -= rotated_gravity;
1941  _accel_offset[k].set_and_save(new_accel_offset[k]);
1942  _accel_scale[k].save();
1943  _accel_id[k].save();
1944  _accel_id_ok[k] = true;
1945  }
1946 
1947  // force trim to zero
1948  AP::ahrs().set_trim(Vector3f(0, 0, 0));
1949  } else {
1950  hal.console->printf("\nFAILED\n");
1951  // restore old values
1952  for (uint8_t k=0; k<num_accels; k++) {
1953  _accel_offset[k] = saved_offsets[k];
1954  _accel_scale[k] = saved_scaling[k];
1955  }
1956  }
1957 
1958  // record calibration complete
1959  _calibrating = false;
1960 
1961  // throw away any existing samples that may have the wrong
1962  // orientation. We do this by throwing samples away for 0.5s,
1963  // which is enough time for the filters to settle
1964  uint32_t start_ms = AP_HAL::millis();
1965  while (AP_HAL::millis() - start_ms < 500) {
1966  update();
1967  }
1968 
1969  // and reset state estimators
1970  AP::ahrs().reset();
1971 
1972  // stop flashing leds
1974 
1975  return result;
1976 }
1977 
1978 
1979 namespace AP {
1980 
1982 {
1984 }
1985 
1986 };
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
float scaling
Definition: AnalogIn.cpp:40
bool get_sample_corrected(uint8_t i, Vector3f &s) const
bool get_soft_armed() const
Definition: Util.h:15
#define HAL_INS_MPU60x0_IMU_NAME
Definition: vrbrain.h:59
struct AP_InertialSensor::@119 _hil
void set_delta_velocity(uint8_t instance, float deltavt, const Vector3f &deltav)
#define HAL_INS_MPU9250_EXT_NAME
Definition: chibios.h:65
static uint8_t counter
uint32_t _accel_startup_error_count[INS_MAX_INSTANCES]
void set_delta_time(float delta_time)
#define AP_INERTIAL_SENSOR_ACCEL_PEAK_DETECT_TIMEOUT_MS
Vector3< float > Vector3f
Definition: vector3.h:246
uint32_t _accel_error_count[INS_MAX_INSTANCES]
static AP_InertialSensor * _s_instance
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)
static enum px4_board_type get_board_type(void)
const Vector3f & get_accel(void) const
float safe_sqrt(const T v)
Definition: AP_Math.cpp:64
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
bool _gyro_healthy[INS_MAX_INSTANCES]
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev, enum Rotation rotation=ROTATION_NONE)
#define GYRO_INIT_MAX_DIFF_DPS
bool _new_gyro_data[INS_MAX_INSTANCES]
AP_HAL::UARTDriver * console
Definition: HAL.h:110
#define ToRad(x)
Definition: AP_Common.h:53
void rotate_inverse(enum Rotation rotation)
Definition: vector3.cpp:253
#define HAL_INS_LSM9DS0_A_NAME
Definition: chibios.h:59
void init(float sample_freq_hz)
AP_Int8 _use[INS_MAX_INSTANCES]
uint8_t register_gyro(uint16_t raw_sample_rate_hz, uint32_t id)
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
float _accel_raw_sample_rates[INS_MAX_INSTANCES]
Vector3f apply(const Vector3f &sample)
void set_delta_angle(uint8_t instance, const Vector3f &deltaa, float deltaat)
AP_InertialSensor_Backend * _backends[INS_MAX_BACKENDS]
AP_HAL::Util * util
Definition: HAL.h:115
LowPassFilterVector3f _accel_vibe_floor_filter[INS_VIBRATION_CHECK_INSTANCES]
virtual void reset(bool recover_eulers=false)=0
static const struct AP_Param::GroupInfo var_info[]
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev, enum Rotation rotation=ROTATION_NONE)
bool gyro_calibrated_ok(uint8_t instance) const
bool _delta_angle_valid[INS_MAX_INSTANCES]
float _delta_velocity_dt[INS_MAX_INSTANCES]
bool get_delta_velocity(uint8_t i, Vector3f &delta_velocity) const
const Vector3f & get_gyro(void) const
float _delta_velocity_acc_dt[INS_MAX_INSTANCES]
bool _add_backend(AP_InertialSensor_Backend *backend)
#define HAL_INS_MPU60x0_EXT_NAME
Definition: chibios.h:56
bool use_accel(uint8_t instance) const
#define DEFAULT_STILL_THRESH
const char * result
Definition: Printf.cpp:16
#define AP_INERTIAL_SENSOR_ACCEL_VIBE_FLOOR_FILT_HZ
friend class AP_AccelCal
Definition: AP_AccelCal.h:81
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_gyro, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_accel, enum Rotation rotation_a=ROTATION_NONE, enum Rotation rotation_g=ROTATION_NONE, enum Rotation rotation_gH=ROTATION_NONE)
Matrix3f * _custom_rotation
Rotation
Definition: rotations.h:27
float _accel_max_abs_offsets[INS_MAX_INSTANCES]
void get_calibration(Vector3f &offset) const
#define MIN(a, b)
Definition: usb_conf.h:215
uint16_t _accel_raw_sampling_multiplier[INS_MAX_INSTANCES]
static void register_client(AP_AccelCal_Client *client)
void set_cutoff_frequency(float cutoff_freq)
#define ToDeg(x)
Definition: AP_Common.h:54
#define DEFAULT_GYRO_FILTER
#define HAL_INS_ICM20608_AM_NAME
Definition: chibios.h:70
uint8_t get_num_samples_collected() const
Vector3f _delta_angle_acc[INS_MAX_INSTANCES]
float _gyro_raw_sample_rates[INS_MAX_INSTANCES]
#define INS_VIBRATION_CHECK_INSTANCES
virtual void delay(uint16_t ms)=0
bool _accel_id_ok[INS_MAX_INSTANCES]
AP_Vector3f _accel_scale[INS_MAX_INSTANCES]
bool get_delta_angle(uint8_t i, Vector3f &delta_angle) const
Vector3f _delta_angle[INS_MAX_INSTANCES]
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
AP_InertialSensor_Backend * _find_backend(int16_t backend_id, uint8_t instance)
AP_Int32 _gyro_id[INS_MAX_INSTANCES]
bool _new_accel_data[INS_MAX_INSTANCES]
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint8_t register_accel(uint16_t raw_sample_rate_hz, uint32_t id)
virtual void set_trim(Vector3f new_trim)
Definition: AP_AHRS.cpp:190
#define ADD_BACKEND(x)
virtual OwnPtr< SPIDevice > get_device(const char *name)
Definition: SPIDevice.h:68
uint8_t _gyro_over_sampling[INS_MAX_INSTANCES]
Definition: AP_AHRS.cpp:486
bool get_accel_health_all(void) const
accel_cal_status_t get_status()
Definition: AP_AccelCal.h:28
bool _calculate_trim(const Vector3f &accel_sample, float &trim_roll, float &trim_pitch)
bool use_gyro(uint8_t instance) const
#define GRAVITY_MSS
Definition: definitions.h:47
#define HAL_INS_MPU60x0_NAME
Definition: chibios.h:55
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
uint32_t _gyro_error_count[INS_MAX_INSTANCES]
T y
Definition: vector3.h:67
#define timing_printf(fmt, args...)
void set_accel(uint8_t instance, const Vector3f &accel)
virtual AuxiliaryBus * get_auxiliary_bus()
uint32_t millis()
Definition: system.cpp:157
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)
AP_Int32 _accel_id[INS_MAX_INSTANCES]
LowPassFilterVector3f _accel_vibe_filter[INS_VIBRATION_CHECK_INSTANCES]
float _delta_angle_acc_dt[INS_MAX_INSTANCES]
T z
Definition: vector3.h:67
#define HAL_INS_LSM9DS0_EXT_A_NAME
Definition: chibios.h:62
#define DEFAULT_ACCEL_FILTER
bool _gyro_cal_ok[INS_MAX_INSTANCES]
uint32_t get_accel_clip_count(uint8_t instance) const
bool _delta_velocity_valid[INS_MAX_INSTANCES]
#define HAL_INS_ICM20608_NAME
Definition: chibios.h:69
AP_HAL::SPIDeviceManager * spi
Definition: HAL.h:107
#define HAL_INS_MPU9250_NAME
Definition: chibios.h:64
Vector3f _gyro[INS_MAX_INSTANCES]
uint16_t get_sample_rate(void) const
MAV_RESULT simple_accel_cal()
Vector3f _delta_velocity[INS_MAX_INSTANCES]
Gyro_Calibration_Timing gyro_calibration_timing()
void set_accel_peak_hold(uint8_t instance, const Vector3f &accel)
bool get_gyro_health(void) const
float get_delta_time() const
bool get_primary_accel_cal_sample_avg(uint8_t sample_num, Vector3f &ret) const
const T & get() const
uint16_t _gyro_raw_sampling_multiplier[INS_MAX_INSTANCES]
bool calibrate_trim(float &trim_roll, float &trim_pitch)
float length(void) const
Definition: vector3.cpp:288
AP_HAL::I2CDeviceManager * i2c_mgr
Definition: HAL.h:106
bool get_accel_health(void) const
void rotate(enum Rotation rotation)
Definition: vector3.cpp:28
void update()
Definition: AP_AccelCal.cpp:28
enum Rotation _board_orientation
Common definitions and utility routines for the ArduPilot libraries.
virtual bool update()=0
void set_gyro(uint8_t instance, const Vector3f &gyro)
void normalize()
Definition: quaternion.cpp:297
AP_AHRS & ahrs()
Definition: AP_AHRS.cpp:488
virtual void delay_microseconds_boost(uint16_t us)
Definition: Scheduler.h:30
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
static constexpr float radians(float deg)
Definition: AP_Math.h:158
static struct notify_flags_and_values_type flags
Definition: AP_Notify.h:117
void init(uint16_t sample_rate_hz)
BatchSampler batchsampler
struct AP_InertialSensor::PeakHoldState _peak_hold_state
AuxiliaryBus * get_auxiliary_bus(int16_t backend_id)
#define INS_MAX_BACKENDS
virtual void delay_microseconds(uint16_t us)=0
bool gyro_calibrated_ok_all() const
float sq(const T val)
Definition: AP_Math.h:170
float _delta_angle_dt[INS_MAX_INSTANCES]
AP_Vector3f _gyro_offset[INS_MAX_INSTANCES]
bool get_new_trim(float &trim_roll, float &trim_pitch)
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::I2CDevice > dev)
Vector3f _delta_velocity_acc[INS_MAX_INSTANCES]
uint8_t get_gyro_count(void) const
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_gyro, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev_accel, enum Rotation rotation_a, enum Rotation rotation_g)
AP_InertialSensor & ins()
void calc_vibration_and_clipping(uint8_t instance, const Vector3f &accel, float dt)
#define HAL_INS_LSM9DS0_EXT_G_NAME
Definition: chibios.h:61
uint8_t _accel_over_sampling[INS_MAX_INSTANCES]
uint32_t _accel_clip_count[INS_MAX_INSTANCES]
#define degrees(x)
Definition: moduletest.c:23
bool _accel_healthy[INS_MAX_INSTANCES]
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
virtual OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4)=0
float get_delta_velocity_dt() const
#define HAL_INS_MPU6500_NAME
Definition: chibios.h:67
#define INS_MAX_INSTANCES
AP_Vector3f _accel_offset[INS_MAX_INSTANCES]
#define AP_INERTIAL_SENSOR_ACCEL_VIBE_FILT_HZ
#define AP_SUBGROUPINFO(element, name, idx, thisclazz, elclazz)
Definition: AP_Param.h:109
static AP_InertialSensor * get_instance()
float get_delta_angle_dt() const
bool accel_calibrated_ok_all() const
Vector3f get_vibration_levels() const
static AP_InertialSensor_Backend * probe(AP_InertialSensor &imu, AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev)
Vector3f _accel[INS_MAX_INSTANCES]
NotchFilterVector3fParam _notch_filter
uint32_t _gyro_startup_error_count[INS_MAX_INSTANCES]
AccelCalibrator * _accel_calibrator
uint32_t micros()
Definition: system.cpp:152
#define HAL_INS_LSM9DS0_G_NAME
Definition: chibios.h:58
bool get_gyro_health_all(void) const
#define AP_GROUPEND
Definition: AP_Param.h:121
static AP_InertialSensor_Backend * detect(AP_InertialSensor &imu)
#define AP_INERTIAL_SENSOR_ACCEL_CLIP_THRESH_MSS
void zero()
Definition: vector3.h:182
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
bool get_fixed_mount_accel_cal_sample(uint8_t sample_num, Vector3f &ret) const
T x
Definition: vector3.h:67
uint8_t get_accel_count(void) const
T apply(T sample, float dt)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
#define HAL_INS_DEFAULT_ROTATION
Definition: f4light.h:24
static void sensor_config_error(const char *reason)