-
Notifications
You must be signed in to change notification settings - Fork 20.7k
Expand file tree
/
Copy pathAP_InertialSensor.cpp
More file actions
2829 lines (2465 loc) · 99.5 KB
/
AP_InertialSensor.cpp
File metadata and controls
2829 lines (2465 loc) · 99.5 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#include <assert.h>
#include "AP_InertialSensor.h"
#if AP_INERTIALSENSOR_ENABLED
#include <AP_Common/AP_Common.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_HAL/SPIDevice.h>
#include <AP_HAL/DSP.h>
#include <AP_Math/AP_Math.h>
#include <AP_Notify/AP_Notify.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_AHRS/AP_AHRS_View.h>
#include <AP_ExternalAHRS/AP_ExternalAHRS.h>
#include <AP_GyroFFT/AP_GyroFFT.h>
#include <AP_Vehicle/AP_Vehicle_Type.h>
#if !APM_BUILD_TYPE(APM_BUILD_Rover)
#include <AP_Motors/AP_Motors_Class.h>
#endif
#include <GCS_MAVLink/GCS.h>
#include "AP_InertialSensor_BMI160.h"
#include "AP_InertialSensor_BMI270.h"
#include "AP_InertialSensor_Backend.h"
#include "AP_InertialSensor_L3G4200D.h"
#include "AP_InertialSensor_LSM9DS0.h"
#include "AP_InertialSensor_LSM9DS1.h"
#include "AP_InertialSensor_Invensense.h"
#include "AP_InertialSensor_SITL.h"
#include "AP_InertialSensor_BMI055.h"
#include "AP_InertialSensor_BMI088.h"
#include "AP_InertialSensor_Invensensev2.h"
#include "AP_InertialSensor_ADIS1647x.h"
#include "AP_InertialSensor_ExternalAHRS.h"
#include "AP_InertialSensor_Invensensev3.h"
#include "AP_InertialSensor_NONE.h"
#include "AP_InertialSensor_SCHA63T.h"
#include <AP_Scheduler/AP_Scheduler.h>
/* Define INS_TIMING_DEBUG to track down scheduling issues with the main loop.
* Output is on the debug console. */
#ifdef INS_TIMING_DEBUG
#include <stdio.h>
#define timing_printf(fmt, args...) do { printf("[timing] " fmt, ##args); } while(0)
#else
#define timing_printf(fmt, args...)
#endif
#ifndef HAL_DEFAULT_INS_FAST_SAMPLE
#define HAL_DEFAULT_INS_FAST_SAMPLE 1
#endif
extern const AP_HAL::HAL& hal;
#if APM_BUILD_COPTER_OR_HELI
#define DEFAULT_GYRO_FILTER 20
#define DEFAULT_ACCEL_FILTER 20
#define DEFAULT_STILL_THRESH 2.5f
#elif APM_BUILD_TYPE(APM_BUILD_Rover)
#define DEFAULT_GYRO_FILTER 4
#define DEFAULT_ACCEL_FILTER 10
#define DEFAULT_STILL_THRESH 0.1f
#else
#define DEFAULT_GYRO_FILTER 20
#define DEFAULT_ACCEL_FILTER 20
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane) && CONFIG_HAL_BOARD == HAL_BOARD_SITL
// In steady-state level flight on SITL Plane, especially while the motor is off, the INS system
// returns ins.is_still()==true. Baseline vibes while airborne are unrealistically low: around 0.07.
// A real aircraft would be experiencing micro turbulence and be rocking around a tiny bit. Therefore,
// for Plane SIM the vibe threshold needs to be a little lower. Since plane.is_flying() uses
// ins.is_still() during gps loss to detect if we're flying, we want to make sure we are not "perfectly"
// still in the air like we are on the ground.
#define DEFAULT_STILL_THRESH 0.05f
#else
#define DEFAULT_STILL_THRESH 0.1f
#endif
#endif
#if defined(STM32H7) || defined(STM32F7)
#define MPU_FIFO_FASTSAMPLE_DEFAULT 1
#else
#define MPU_FIFO_FASTSAMPLE_DEFAULT 0
#endif
#define GYRO_INIT_MAX_DIFF_DPS 0.1f
#ifndef HAL_INS_TRIM_LIMIT_DEG
#define HAL_INS_TRIM_LIMIT_DEG 10
#endif
// Class level parameters
const AP_Param::GroupInfo AP_InertialSensor::var_info[] = {
// 0 was PRODUCT_ID
/*
The following parameter indexes and reserved from previous use
as accel offsets and scaling from before the 16g change in the
PX4 backend:
ACCSCAL : 1
ACCOFFS : 2
MPU6K_FILTER: 4
ACC2SCAL : 5
ACC2OFFS : 6
ACC3SCAL : 8
ACC3OFFS : 9
CALSENSFRAME : 11
*/
// @Param: _GYROFFS_X
// @DisplayName: Gyro offsets of X axis
// @Description: Gyro sensor offsets of X axis. This is setup on each boot during gyro calibrations
// @Units: rad/s
// @User: Advanced
// @Calibration: 1
// @Param: _GYROFFS_Y
// @DisplayName: Gyro offsets of Y axis
// @Description: Gyro sensor offsets of Y axis. This is setup on each boot during gyro calibrations
// @Units: rad/s
// @User: Advanced
// @Calibration: 1
// @Param: _GYROFFS_Z
// @DisplayName: Gyro offsets of Z axis
// @Description: Gyro sensor offsets of Z axis. This is setup on each boot during gyro calibrations
// @Units: rad/s
// @User: Advanced
// @Calibration: 1
AP_GROUPINFO("_GYROFFS", 3, AP_InertialSensor, _gyro_offset_old_param[0], 0),
// @Param: _GYR2OFFS_X
// @DisplayName: Gyro2 offsets of X axis
// @Description: Gyro2 sensor offsets of X axis. This is setup on each boot during gyro calibrations
// @Units: rad/s
// @User: Advanced
// @Calibration: 1
// @Param: _GYR2OFFS_Y
// @DisplayName: Gyro2 offsets of Y axis
// @Description: Gyro2 sensor offsets of Y axis. This is setup on each boot during gyro calibrations
// @Units: rad/s
// @User: Advanced
// @Calibration: 1
// @Param: _GYR2OFFS_Z
// @DisplayName: Gyro2 offsets of Z axis
// @Description: Gyro2 sensor offsets of Z axis. This is setup on each boot during gyro calibrations
// @Units: rad/s
// @User: Advanced
// @Calibration: 1
#if INS_MAX_INSTANCES > 1
AP_GROUPINFO("_GYR2OFFS", 7, AP_InertialSensor, _gyro_offset_old_param[1], 0),
#endif
// @Param: _GYR3OFFS_X
// @DisplayName: Gyro3 offsets of X axis
// @Description: Gyro3 sensor offsets of X axis. This is setup on each boot during gyro calibrations
// @Units: rad/s
// @User: Advanced
// @Calibration: 1
// @Param: _GYR3OFFS_Y
// @DisplayName: Gyro3 offsets of Y axis
// @Description: Gyro3 sensor offsets of Y axis. This is setup on each boot during gyro calibrations
// @Units: rad/s
// @User: Advanced
// @Calibration: 1
// @Param: _GYR3OFFS_Z
// @DisplayName: Gyro3 offsets of Z axis
// @Description: Gyro3 sensor offsets of Z axis. This is setup on each boot during gyro calibrations
// @Units: rad/s
// @User: Advanced
// @Calibration: 1
#if INS_MAX_INSTANCES > 2
AP_GROUPINFO("_GYR3OFFS", 10, AP_InertialSensor, _gyro_offset_old_param[2], 0),
#endif
// @Param: _ACCSCAL_X
// @DisplayName: Accelerometer scaling of X axis
// @Description: Accelerometer scaling of X axis. Calculated during acceleration calibration routine
// @Range: 0.8 1.2
// @User: Advanced
// @Calibration: 1
// @Param: _ACCSCAL_Y
// @DisplayName: Accelerometer scaling of Y axis
// @Description: Accelerometer scaling of Y axis Calculated during acceleration calibration routine
// @Range: 0.8 1.2
// @User: Advanced
// @Calibration: 1
// @Param: _ACCSCAL_Z
// @DisplayName: Accelerometer scaling of Z axis
// @Description: Accelerometer scaling of Z axis Calculated during acceleration calibration routine
// @Range: 0.8 1.2
// @User: Advanced
// @Calibration: 1
AP_GROUPINFO("_ACCSCAL", 12, AP_InertialSensor, _accel_scale_old_param[0], 1.0),
// @Param: _ACCOFFS_X
// @DisplayName: Accelerometer offsets of X axis
// @Description: Accelerometer offsets of X axis. This is setup using the acceleration calibration or level operations
// @Units: m/s/s
// @Range: -3.5 3.5
// @User: Advanced
// @Calibration: 1
// @Param: _ACCOFFS_Y
// @DisplayName: Accelerometer offsets of Y axis
// @Description: Accelerometer offsets of Y axis. This is setup using the acceleration calibration or level operations
// @Units: m/s/s
// @Range: -3.5 3.5
// @User: Advanced
// @Calibration: 1
// @Param: _ACCOFFS_Z
// @DisplayName: Accelerometer offsets of Z axis
// @Description: Accelerometer offsets of Z axis. This is setup using the acceleration calibration or level operations
// @Units: m/s/s
// @Range: -3.5 3.5
// @User: Advanced
// @Calibration: 1
AP_GROUPINFO("_ACCOFFS", 13, AP_InertialSensor, _accel_offset_old_param[0], 0),
// @Param: _ACC2SCAL_X
// @DisplayName: Accelerometer2 scaling of X axis
// @Description: Accelerometer2 scaling of X axis. Calculated during acceleration calibration routine
// @Range: 0.8 1.2
// @User: Advanced
// @Calibration: 1
// @Param: _ACC2SCAL_Y
// @DisplayName: Accelerometer2 scaling of Y axis
// @Description: Accelerometer2 scaling of Y axis Calculated during acceleration calibration routine
// @Range: 0.8 1.2
// @User: Advanced
// @Calibration: 1
// @Param: _ACC2SCAL_Z
// @DisplayName: Accelerometer2 scaling of Z axis
// @Description: Accelerometer2 scaling of Z axis Calculated during acceleration calibration routine
// @Range: 0.8 1.2
// @User: Advanced
// @Calibration: 1
#if INS_MAX_INSTANCES > 1
AP_GROUPINFO("_ACC2SCAL", 14, AP_InertialSensor, _accel_scale_old_param[1], 1.0),
#endif
// @Param: _ACC2OFFS_X
// @DisplayName: Accelerometer2 offsets of X axis
// @Description: Accelerometer2 offsets of X axis. This is setup using the acceleration calibration or level operations
// @Units: m/s/s
// @Range: -3.5 3.5
// @User: Advanced
// @Calibration: 1
// @Param: _ACC2OFFS_Y
// @DisplayName: Accelerometer2 offsets of Y axis
// @Description: Accelerometer2 offsets of Y axis. This is setup using the acceleration calibration or level operations
// @Units: m/s/s
// @Range: -3.5 3.5
// @User: Advanced
// @Calibration: 1
// @Param: _ACC2OFFS_Z
// @DisplayName: Accelerometer2 offsets of Z axis
// @Description: Accelerometer2 offsets of Z axis. This is setup using the acceleration calibration or level operations
// @Units: m/s/s
// @Range: -3.5 3.5
// @User: Advanced
// @Calibration: 1
#if INS_MAX_INSTANCES > 1
AP_GROUPINFO("_ACC2OFFS", 15, AP_InertialSensor, _accel_offset_old_param[1], 0),
#endif
// @Param: _ACC3SCAL_X
// @DisplayName: Accelerometer3 scaling of X axis
// @Description: Accelerometer3 scaling of X axis. Calculated during acceleration calibration routine
// @Range: 0.8 1.2
// @User: Advanced
// @Calibration: 1
// @Param: _ACC3SCAL_Y
// @DisplayName: Accelerometer3 scaling of Y axis
// @Description: Accelerometer3 scaling of Y axis Calculated during acceleration calibration routine
// @Range: 0.8 1.2
// @User: Advanced
// @Calibration: 1
// @Param: _ACC3SCAL_Z
// @DisplayName: Accelerometer3 scaling of Z axis
// @Description: Accelerometer3 scaling of Z axis Calculated during acceleration calibration routine
// @Range: 0.8 1.2
// @User: Advanced
// @Calibration: 1
#if INS_MAX_INSTANCES > 2
AP_GROUPINFO("_ACC3SCAL", 16, AP_InertialSensor, _accel_scale_old_param[2], 1.0),
#endif
// @Param: _ACC3OFFS_X
// @DisplayName: Accelerometer3 offsets of X axis
// @Description: Accelerometer3 offsets of X axis. This is setup using the acceleration calibration or level operations
// @Units: m/s/s
// @Range: -3.5 3.5
// @User: Advanced
// @Calibration: 1
// @Param: _ACC3OFFS_Y
// @DisplayName: Accelerometer3 offsets of Y axis
// @Description: Accelerometer3 offsets of Y axis. This is setup using the acceleration calibration or level operations
// @Units: m/s/s
// @Range: -3.5 3.5
// @User: Advanced
// @Calibration: 1
// @Param: _ACC3OFFS_Z
// @DisplayName: Accelerometer3 offsets of Z axis
// @Description: Accelerometer3 offsets of Z axis. This is setup using the acceleration calibration or level operations
// @Units: m/s/s
// @Range: -3.5 3.5
// @User: Advanced
// @Calibration: 1
#if INS_MAX_INSTANCES > 2
AP_GROUPINFO("_ACC3OFFS", 17, AP_InertialSensor, _accel_offset_old_param[2], 0),
#endif
// @Param: _GYRO_FILTER
// @DisplayName: Gyro filter cutoff frequency
// @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. A value of zero means no filtering (not recommended!)
// @Units: Hz
// @Range: 0 256
// @User: Advanced
AP_GROUPINFO("_GYRO_FILTER", 18, AP_InertialSensor, _gyro_filter_cutoff, DEFAULT_GYRO_FILTER),
// @Param: _ACCEL_FILTER
// @DisplayName: Accel filter cutoff frequency
// @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. A value of zero means no filtering (not recommended!)
// @Units: Hz
// @Range: 0 256
// @User: Advanced
AP_GROUPINFO("_ACCEL_FILTER", 19, AP_InertialSensor, _accel_filter_cutoff, DEFAULT_ACCEL_FILTER),
// @Param: _USE
// @DisplayName: Use first IMU for attitude, velocity and position estimates
// @Description: Use first IMU for attitude, velocity and position estimates
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
AP_GROUPINFO("_USE", 20, AP_InertialSensor, _use_old_param[0], 1),
// @Param: _USE2
// @DisplayName: Use second IMU for attitude, velocity and position estimates
// @Description: Use second IMU for attitude, velocity and position estimates
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
#if INS_MAX_INSTANCES > 1
AP_GROUPINFO("_USE2", 21, AP_InertialSensor, _use_old_param[1], 1),
#endif
// @Param: _USE3
// @DisplayName: Use third IMU for attitude, velocity and position estimates
// @Description: Use third IMU for attitude, velocity and position estimates
// @Values: 0:Disabled,1:Enabled
// @User: Advanced
#if INS_MAX_INSTANCES > 2
AP_GROUPINFO("_USE3", 22, AP_InertialSensor, _use_old_param[2], 1),
#endif
// @Param: _STILL_THRESH
// @DisplayName: Stillness threshold for detecting if we are moving
// @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
// @Range: 0.05 50
// @User: Advanced
AP_GROUPINFO("_STILL_THRESH", 23, AP_InertialSensor, _still_threshold, DEFAULT_STILL_THRESH),
// @Param: _GYR_CAL
// @DisplayName: Gyro Calibration scheme
// @Description: Conrols when automatic gyro calibration is performed
// @Values: 0:Never, 1:Start-up only
// @User: Advanced
AP_GROUPINFO("_GYR_CAL", 24, AP_InertialSensor, _gyro_cal_timing, 1),
// @Param: _TRIM_OPTION
// @DisplayName: Accel cal trim option
// @Description: Specifies how the accel cal routine determines the trims
// @User: Advanced
// @Values: 0:Don't adjust the trims,1:Assume first orientation was level,2:Assume ACC_BODYFIX is perfectly aligned to the vehicle
AP_GROUPINFO("_TRIM_OPTION", 25, AP_InertialSensor, _trim_option, 1),
// @Param: _ACC_BODYFIX
// @DisplayName: Body-fixed accelerometer
// @Description: The body-fixed accelerometer to be used for trim calculation
// @User: Advanced
// @Values: 1:IMU 1,2:IMU 2,3:IMU 3
AP_GROUPINFO("_ACC_BODYFIX", 26, AP_InertialSensor, _acc_body_aligned, 2),
// @Param: _POS1_X
// @DisplayName: IMU accelerometer X position
// @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.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced
// @Param: _POS1_Y
// @DisplayName: IMU accelerometer Y position
// @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.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced
// @Param: _POS1_Z
// @DisplayName: IMU accelerometer Z position
// @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.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced
AP_GROUPINFO("_POS1", 27, AP_InertialSensor, _accel_pos_old_param[0], 0.0f),
// @Param: _POS2_X
// @DisplayName: IMU accelerometer X position
// @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.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced
// @Param: _POS2_Y
// @DisplayName: IMU accelerometer Y position
// @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.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced
// @Param: _POS2_Z
// @DisplayName: IMU accelerometer Z position
// @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.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced
#if INS_MAX_INSTANCES > 1
AP_GROUPINFO("_POS2", 28, AP_InertialSensor, _accel_pos_old_param[1], 0.0f),
#endif
// @Param: _POS3_X
// @DisplayName: IMU accelerometer X position
// @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.
// @Units: m
// @Range: -10 10
// @User: Advanced
// @Param: _POS3_Y
// @DisplayName: IMU accelerometer Y position
// @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.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced
// @Param: _POS3_Z
// @DisplayName: IMU accelerometer Z position
// @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.
// @Units: m
// @Range: -5 5
// @Increment: 0.01
// @User: Advanced
#if INS_MAX_INSTANCES > 2
AP_GROUPINFO("_POS3", 29, AP_InertialSensor, _accel_pos_old_param[2], 0.0f),
#endif
// @Param: _GYR_ID
// @DisplayName: Gyro ID
// @Description: Gyro sensor ID, taking into account its type, bus and instance
// @ReadOnly: True
// @User: Advanced
AP_GROUPINFO("_GYR_ID", 30, AP_InertialSensor, _gyro_id_old_param[0], 0),
// @Param: _GYR2_ID
// @DisplayName: Gyro2 ID
// @Description: Gyro2 sensor ID, taking into account its type, bus and instance
// @ReadOnly: True
// @User: Advanced
#if INS_MAX_INSTANCES > 1
AP_GROUPINFO("_GYR2_ID", 31, AP_InertialSensor, _gyro_id_old_param[1], 0),
#endif
// @Param: _GYR3_ID
// @DisplayName: Gyro3 ID
// @Description: Gyro3 sensor ID, taking into account its type, bus and instance
// @ReadOnly: True
// @User: Advanced
#if INS_MAX_INSTANCES > 2
AP_GROUPINFO("_GYR3_ID", 32, AP_InertialSensor, _gyro_id_old_param[2], 0),
#endif
// @Param: _ACC_ID
// @DisplayName: Accelerometer ID
// @Description: Accelerometer sensor ID, taking into account its type, bus and instance
// @ReadOnly: True
// @User: Advanced
AP_GROUPINFO("_ACC_ID", 33, AP_InertialSensor, _accel_id_old_param[0], 0),
// @Param: _ACC2_ID
// @DisplayName: Accelerometer2 ID
// @Description: Accelerometer2 sensor ID, taking into account its type, bus and instance
// @ReadOnly: True
// @User: Advanced
#if INS_MAX_INSTANCES > 1
AP_GROUPINFO("_ACC2_ID", 34, AP_InertialSensor, _accel_id_old_param[1], 0),
#endif
// @Param: _ACC3_ID
// @DisplayName: Accelerometer3 ID
// @Description: Accelerometer3 sensor ID, taking into account its type, bus and instance
// @ReadOnly: True
// @User: Advanced
#if INS_MAX_INSTANCES > 2
AP_GROUPINFO("_ACC3_ID", 35, AP_InertialSensor, _accel_id_old_param[2], 0),
#endif
// @Param: _FAST_SAMPLE
// @DisplayName: Fast sampling mask
// @Description: Mask of IMUs to enable fast sampling on, if available
// @User: Advanced
// @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU
AP_GROUPINFO("_FAST_SAMPLE", 36, AP_InertialSensor, _fast_sampling_mask, HAL_DEFAULT_INS_FAST_SAMPLE),
// index 37 was NOTCH_
#if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED
// @Group: _LOG_
// @Path: ../AP_InertialSensor/BatchSampler.cpp
AP_SUBGROUPINFO(batchsampler, "_LOG_", 39, AP_InertialSensor, AP_InertialSensor::BatchSampler),
#endif
// @Param: _ENABLE_MASK
// @DisplayName: IMU enable mask
// @Description: Bitmask of IMUs to enable. It can be used to prevent startup of specific detected IMUs
// @User: Advanced
// @Bitmask: 0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU,6:SeventhIMU
AP_GROUPINFO("_ENABLE_MASK", 40, AP_InertialSensor, _enable_mask, 0x7F),
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
// @Group: _HNTCH_
// @Path: ../Filter/HarmonicNotchFilter.cpp
AP_SUBGROUPINFO(harmonic_notches[0].params, "_HNTCH_", 41, AP_InertialSensor, HarmonicNotchFilterParams),
#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 1
// @Group: _HNTC2_
// @Path: ../Filter/HarmonicNotchFilter.cpp
AP_SUBGROUPINFO(harmonic_notches[1].params, "_HNTC2_", 53, AP_InertialSensor, HarmonicNotchFilterParams),
#endif
#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 2
// @Group: _HNTC3_
// @Path: ../Filter/HarmonicNotchFilter.cpp
AP_SUBGROUPINFO(harmonic_notches[2].params, "_HNTC3_", 57, AP_InertialSensor, HarmonicNotchFilterParams),
#endif
#if HAL_INS_NUM_HARMONIC_NOTCH_FILTERS > 3
// @Group: _HNTC4_
// @Path: ../Filter/HarmonicNotchFilter.cpp
AP_SUBGROUPINFO(harmonic_notches[3].params, "_HNTC4_", 58, AP_InertialSensor, HarmonicNotchFilterParams),
#endif
#endif
// @Param: _GYRO_RATE
// @DisplayName: Gyro rate for IMUs with Fast Sampling enabled
// @Description: Gyro rate for IMUs with fast sampling enabled. The gyro rate is the sample rate at which the IMU filters operate and needs to be at least double the maximum filter frequency. If the sensor does not support the selected rate the next highest supported rate will be used. For IMUs which do not support fast sampling this setting is ignored and the default gyro rate of 1Khz is used.
// @User: Advanced
// @Values: 0:1kHz,1:2kHz,2:4kHz,3:8kHz
// @RebootRequired: True
AP_GROUPINFO("_GYRO_RATE", 42, AP_InertialSensor, _fast_sampling_rate, MPU_FIFO_FASTSAMPLE_DEFAULT),
#if HAL_INS_TEMPERATURE_CAL_ENABLE
// @Group: _TCAL1_
// @Path: AP_InertialSensor_tempcal.cpp
AP_SUBGROUPINFO(tcal_old_param[0], "_TCAL1_", 43, AP_InertialSensor, AP_InertialSensor_TCal),
#if INS_MAX_INSTANCES > 1
// @Group: _TCAL2_
// @Path: AP_InertialSensor_tempcal.cpp
AP_SUBGROUPINFO(tcal_old_param[1], "_TCAL2_", 44, AP_InertialSensor, AP_InertialSensor_TCal),
#endif
#if INS_MAX_INSTANCES > 2
// @Group: _TCAL3_
// @Path: AP_InertialSensor_tempcal.cpp
AP_SUBGROUPINFO(tcal_old_param[2], "_TCAL3_", 45, AP_InertialSensor, AP_InertialSensor_TCal),
#endif
// @Param: _ACC1_CALTEMP
// @DisplayName: Calibration temperature for 1st accelerometer
// @Description: Temperature that the 1st accelerometer was calibrated at
// @User: Advanced
// @Units: degC
// @Calibration: 1
AP_GROUPINFO("_ACC1_CALTEMP", 46, AP_InertialSensor, caltemp_accel_old_param[0], -300),
// @Param: _GYR1_CALTEMP
// @DisplayName: Calibration temperature for 1st gyroscope
// @Description: Temperature that the 1st gyroscope was calibrated at
// @User: Advanced
// @Units: degC
// @Calibration: 1
AP_GROUPINFO("_GYR1_CALTEMP", 47, AP_InertialSensor, caltemp_gyro_old_param[0], -300),
#if INS_MAX_INSTANCES > 1
// @Param: _ACC2_CALTEMP
// @DisplayName: Calibration temperature for 2nd accelerometer
// @Description: Temperature that the 2nd accelerometer was calibrated at
// @User: Advanced
// @Units: degC
// @Calibration: 1
AP_GROUPINFO("_ACC2_CALTEMP", 48, AP_InertialSensor, caltemp_accel_old_param[1], -300),
// @Param: _GYR2_CALTEMP
// @DisplayName: Calibration temperature for 2nd gyroscope
// @Description: Temperature that the 2nd gyroscope was calibrated at
// @User: Advanced
// @Units: degC
// @Calibration: 1
AP_GROUPINFO("_GYR2_CALTEMP", 49, AP_InertialSensor, caltemp_gyro_old_param[1], -300),
#endif
#if INS_MAX_INSTANCES > 2
// @Param: _ACC3_CALTEMP
// @DisplayName: Calibration temperature for 3rd accelerometer
// @Description: Temperature that the 3rd accelerometer was calibrated at
// @User: Advanced
// @Units: degC
// @Calibration: 1
AP_GROUPINFO("_ACC3_CALTEMP", 50, AP_InertialSensor, caltemp_accel_old_param[2], -300),
// @Param: _GYR3_CALTEMP
// @DisplayName: Calibration temperature for 3rd gyroscope
// @Description: Temperature that the 3rd gyroscope was calibrated at
// @User: Advanced
// @Units: degC
// @Calibration: 1
AP_GROUPINFO("_GYR3_CALTEMP", 51, AP_InertialSensor, caltemp_gyro_old_param[2], -300),
#endif
// @Param: _TCAL_OPTIONS
// @DisplayName: Options for temperature calibration
// @Description: This enables optional temperature calibration features. Setting of the Persist bits will save the temperature and/or accelerometer calibration parameters in the bootloader sector on the next update of the bootloader.
// @Bitmask: 0:PersistTemps, 1:PersistAccels
// @User: Advanced
AP_GROUPINFO("_TCAL_OPTIONS", 52, AP_InertialSensor, tcal_options, 0),
#endif // HAL_INS_TEMPERATURE_CAL_ENABLE
#if INS_MAX_INSTANCES > 3
// @Group: 4_
// @Path: AP_InertialSensor_Params.cpp
AP_SUBGROUPINFO(params[0], "4_", 54, AP_InertialSensor, AP_InertialSensor_Params),
#endif
#if INS_MAX_INSTANCES > 4
// @Group: 5_
// @Path: AP_InertialSensor_Params.cpp
AP_SUBGROUPINFO(params[1], "5_", 55, AP_InertialSensor, AP_InertialSensor_Params),
#endif
// @Param: _RAW_LOG_OPT
// @DisplayName: Raw logging options
// @Description: Raw logging options bitmask
// @Bitmask: 0:Log primary gyro only, 1:Log all gyros, 2:Post filter, 3: Pre and post filter
// @User: Advanced
AP_GROUPINFO("_RAW_LOG_OPT", 56, AP_InertialSensor, raw_logging_options, 0),
// indexes 57 and 58 used by INS_HNTC3 and INS_HNTC4
/*
NOTE: parameter indexes have gaps above. When adding new
parameters check for conflicts carefully
*/
AP_GROUPEND
};
AP_InertialSensor *AP_InertialSensor::_singleton = nullptr;
AP_InertialSensor::AP_InertialSensor() :
_board_orientation(ROTATION_NONE),
_log_raw_bit(-1)
{
if (_singleton) {
AP_HAL::panic("Too many inertial sensors");
}
_singleton = this;
AP_Param::setup_object_defaults(this, var_info);
for (uint8_t i=0; i<INS_MAX_INSTANCES; i++) {
_gyro_cal_ok[i] = true;
}
for (uint8_t i=0; i<INS_VIBRATION_CHECK_INSTANCES; i++) {
_accel_vibe_floor_filter[i].set_cutoff_frequency(AP_INERTIAL_SENSOR_ACCEL_VIBE_FLOOR_FILT_HZ);
_accel_vibe_filter[i].set_cutoff_frequency(AP_INERTIAL_SENSOR_ACCEL_VIBE_FILT_HZ);
}
#if HAL_INS_ACCELCAL_ENABLED
AP_AccelCal::register_client(this);
#endif
}
/*
* Get the AP_InertialSensor singleton
*/
AP_InertialSensor *AP_InertialSensor::get_singleton()
{
if (!_singleton) {
_singleton = NEW_NOTHROW AP_InertialSensor();
}
return _singleton;
}
/*
register a new gyro instance
*/
bool AP_InertialSensor::register_gyro(uint8_t &instance, uint16_t raw_sample_rate_hz, uint32_t id)
{
if (_gyro_count == INS_MAX_INSTANCES) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to register gyro id %u", unsigned(id));
return false;
}
// Loop over the existing instances and check if the instance already exists
for (uint8_t instance_to_check = 0; instance_to_check < _gyro_count; instance_to_check++) {
if ((uint32_t)_gyro_id(instance_to_check) == id) {
// if it does, then bail
return false;
}
}
_gyro_raw_sample_rates[_gyro_count] = raw_sample_rate_hz;
_gyro_over_sampling[_gyro_count] = 1;
_gyro_raw_sampling_multiplier[_gyro_count] = INT16_MAX/radians(2000);
bool saved = _gyro_id(_gyro_count).load();
if (saved && (uint32_t)_gyro_id(_gyro_count) != id) {
// inconsistent gyro id - mark it as needing calibration
_gyro_cal_ok[_gyro_count] = false;
}
_gyro_id(_gyro_count).set((int32_t) id);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (!saved) {
// assume this is the same sensor and save its ID to allow seamless
// transition from when we didn't have the IDs.
_gyro_id(_gyro_count).save();
}
#endif
instance = _gyro_count++;
return true;
}
/*
get the accel instance number we will get from register_accel()
*/
bool AP_InertialSensor::get_accel_instance(uint8_t &instance) const
{
if (_accel_count == INS_MAX_INSTANCES) {
return false;
}
instance = _accel_count;
return true;
}
/*
get the gyro instance number we will get from register_accel()
*/
bool AP_InertialSensor::get_gyro_instance(uint8_t &instance) const
{
if (_gyro_count == INS_MAX_INSTANCES) {
return false;
}
instance = _gyro_count;
return true;
}
/*
register a new accel instance
*/
bool AP_InertialSensor::register_accel(uint8_t &instance, uint16_t raw_sample_rate_hz, uint32_t id)
{
if (_accel_count == INS_MAX_INSTANCES) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to register accel id %u", unsigned(id));
return false;
}
// Loop over the existing instances and check if the instance already exists
for (uint8_t instance_to_check = 0; instance_to_check < _accel_count; instance_to_check++) {
if ((uint32_t)_accel_id(instance_to_check) == id) {
// if it does, then bail
return false;
}
}
_accel_raw_sample_rates[_accel_count] = raw_sample_rate_hz;
_accel_over_sampling[_accel_count] = 1;
_accel_raw_sampling_multiplier[_accel_count] = INT16_MAX/(16*GRAVITY_MSS);
bool saved = _accel_id(_accel_count).load();
if (!saved) {
// inconsistent accel id
_accel_id_ok[_accel_count] = false;
} else if ((uint32_t)_accel_id(_accel_count) != id) {
// inconsistent accel id
_accel_id_ok[_accel_count] = false;
} else {
_accel_id_ok[_accel_count] = true;
}
_accel_id(_accel_count).set((int32_t) id);
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || (CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && AP_SIM_ENABLED)
// assume this is the same sensor and save its ID to allow seamless
// transition from when we didn't have the IDs.
_accel_id_ok[_accel_count] = true;
_accel_id(_accel_count).save();
#endif
instance = _accel_count++;
return true;
}
/*
* Start all backends for gyro and accel measurements. It automatically calls
* detect_backends() if it has not been called already.
*/
void AP_InertialSensor::_start_backends()
{
detect_backends();
for (uint8_t i = 0; i < _backend_count; i++) {
_backends[i]->start();
}
#if AP_INERTIALSENSOR_ALLOW_NO_SENSORS
if (_gyro_count == 0 || _accel_count == 0) {
AP_HAL::panic("INS needs at least 1 gyro and 1 accel");
}
#endif
// clear IDs for unused sensor instances
for (uint8_t i=get_accel_count(); i<INS_MAX_INSTANCES; i++) {
_accel_id(i).set(0);
}
for (uint8_t i=get_gyro_count(); i<INS_MAX_INSTANCES; i++) {
_gyro_id(i).set(0);
}
}
/* Find the N instance of the backend that has already been successfully detected */
AP_InertialSensor_Backend *AP_InertialSensor::_find_backend(int16_t backend_id, uint8_t instance)
{
uint8_t found = 0;
for (uint8_t i = 0; i < _backend_count; i++) {
int16_t id = _backends[i]->get_id();
if (id < 0 || id != backend_id) {
continue;
}
if (instance == found) {
return _backends[i];
} else {
found++;
}
}
return nullptr;
}
bool AP_InertialSensor::set_gyro_window_size(uint16_t size) {
#if HAL_GYROFFT_ENABLED
_gyro_window_size = size;
// allocate FFT gyro window
for (uint8_t i = 0; i < INS_MAX_INSTANCES; i++) {
for (uint8_t j = 0; j < XYZ_AXIS_COUNT; j++) {
if (!_gyro_window[i][j].set_size(size)) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Failed to allocate window for INS");
// clean up whatever we have currently allocated
for (uint8_t ii = 0; ii <= i; ii++) {
for (uint8_t jj = 0; jj < j; jj++) {
_gyro_window[ii][jj].set_size(0);
_gyro_window_size = 0;
}
}
return false;
}
}
}
#endif
return true;
}
#if HAL_WITH_DSP && AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
bool AP_InertialSensor::has_fft_notch() const
{
for (auto ¬ch : harmonic_notches) {
if (notch.params.enabled() && notch.params.tracking_mode() == HarmonicNotchDynamicMode::UpdateGyroFFT) {
return true;
}
}
return false;
}
#endif
void
AP_InertialSensor::init(uint16_t loop_rate)
{
// remember the sample rate
_loop_rate = loop_rate;
_loop_delta_t = 1.0f / loop_rate;
// we don't allow deltat values greater than 10x the normal loop
// time to be exposed outside of INS. Large deltat values can
// cause divergence of state estimators
_loop_delta_t_max = 10 * _loop_delta_t;
#if AP_INERTIALSENSOR_HARMONICNOTCH_ENABLED
// Initialize notch params
for (auto ¬ch : harmonic_notches) {
notch.params.init();
}
#endif
if (_gyro_count == 0 && _accel_count == 0) {
_start_backends();
}
// calibrate gyros unless gyro calibration has been disabled
if (gyro_calibration_timing() != GYRO_CAL_NEVER && _gyro_count > 0) {
init_gyro();
}
_sample_period_usec = 1000*1000UL / _loop_rate;
// establish the baseline time between samples
_delta_time = 0;
_next_sample_usec = 0;
_last_sample_usec = 0;
_have_sample = false;
#if AP_INERTIALSENSOR_BATCHSAMPLER_ENABLED
// initialise IMU batch logging
batchsampler.init();
#endif
#if HAL_GYROFFT_ENABLED
AP_GyroFFT* fft = AP::fft();
bool fft_enabled = fft != nullptr && fft->enabled();
if (fft_enabled) {
_post_filter_fft = fft->using_post_filter_samples();
}
// calculate the position that the FFT window needs to be applied
// Use cases:
// Gyro -> FFT window -> FFT Notch1/2 -> Non-FFT Notch2/1 -> LPF -> Filtered Gyro -- Phase 0
// Gyro -> FFT window -> Non-FFT Notch1/2 -> LPF -> Filtered Gyro -- Phase 0
// Gyro -> Non-FFT Notch1 -> Filtered FFT Window -> FFT Notch2 -> LPF -> Filtered Gyro -- Phase 1
// Gyro -> Non-FFT Notch1/2 -> Non-FFT Notch1/2 -> Filtered FFT Window -> LPF -> Filtered Gyro -- Phase 2
// Gyro -> Non-FFT Notch1/2 -> Filtered FFT Window -> LPF -> Filtered Gyro -- Phase 1
// Gyro -> Filtered FFT Window -> LPF -> Filtered Gyro -- Phase 0
// Gyro -> FFT window -> LPF -> Filtered Gyro -- Phase 0
// Gyro -> Notch1/2 -> LPF -> Filtered Gyro