/
ekf2_params.c
1444 lines (1324 loc) · 37.2 KB
/
ekf2_params.c
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
/****************************************************************************
*
* Copyright (c) 2015-2016 Estimation and Control Library (ECL). All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name ECL nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file ekf2_params.c
* Parameter definition for ekf2.
*
* @author Roman Bast <bapstroman@gmail.com>
*
*/
/**
* Minimum time of arrival delta between non-IMU observations before data is downsampled.
* Baro and Magnetometer data will be averaged before downsampling, other data will be point sampled resulting in loss of information.
*
* @group EKF2
* @min 10
* @max 50
* @reboot_required true
* @unit ms
*/
PARAM_DEFINE_INT32(EKF2_MIN_OBS_DT, 20);
/**
* Magnetometer measurement delay relative to IMU measurements
*
* @group EKF2
* @min 0
* @max 300
* @unit ms
* @reboot_required true
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_DELAY, 0);
/**
* Barometer measurement delay relative to IMU measurements
*
* @group EKF2
* @min 0
* @max 300
* @unit ms
* @reboot_required true
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_BARO_DELAY, 0);
/**
* GPS measurement delay relative to IMU measurements
*
* @group EKF2
* @min 0
* @max 300
* @unit ms
* @reboot_required true
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_GPS_DELAY, 110);
/**
* Optical flow measurement delay relative to IMU measurements
* Assumes measurement is timestamped at trailing edge of integration period
*
* @group EKF2
* @min 0
* @max 300
* @unit ms
* @reboot_required true
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_OF_DELAY, 5);
/**
* Range finder measurement delay relative to IMU measurements
*
* @group EKF2
* @min 0
* @max 300
* @unit ms
* @reboot_required true
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_RNG_DELAY, 5);
/**
* Airspeed measurement delay relative to IMU measurements
*
* @group EKF2
* @min 0
* @max 300
* @unit ms
* @reboot_required true
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_ASP_DELAY, 100);
/**
* Vision Position Estimator delay relative to IMU measurements
*
* @group EKF2
* @min 0
* @max 300
* @unit ms
* @reboot_required true
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_EV_DELAY, 175);
/**
* Auxillary Velocity Estimate (e.g from a landing target) delay relative to IMU measurements
*
* @group EKF2
* @min 0
* @max 300
* @unit ms
* @reboot_required true
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_AVEL_DELAY, 5);
/**
* Integer bitmask controlling GPS checks.
*
* Set bits to 1 to enable checks. Checks enabled by the following bit positions
* 0 : Minimum required sat count set by EKF2_REQ_NSATS
* 1 : Minimum required PDOP set by EKF2_REQ_PDOP
* 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH
* 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV
* 4 : Maximum allowed speed error set by EKF2_REQ_SACC
* 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter.
* 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter.
* 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter.
* 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT
*
* @group EKF2
* @min 0
* @max 511
* @bit 0 Min sat count (EKF2_REQ_NSATS)
* @bit 1 Min PDOP (EKF2_REQ_PDOP)
* @bit 2 Max horizontal position error (EKF2_REQ_EPH)
* @bit 3 Max vertical position error (EKF2_REQ_EPV)
* @bit 4 Max speed error (EKF2_REQ_SACC)
* @bit 5 Max horizontal position rate (EKF2_REQ_HDRIFT)
* @bit 6 Max vertical position rate (EKF2_REQ_VDRIFT)
* @bit 7 Max horizontal speed (EKF2_REQ_HDRIFT)
* @bit 8 Max vertical velocity discrepancy (EKF2_REQ_VDRIFT)
*/
PARAM_DEFINE_INT32(EKF2_GPS_CHECK, 245);
/**
* Required EPH to use GPS.
*
* @group EKF2
* @min 2
* @max 100
* @unit m
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_REQ_EPH, 3.0f);
/**
* Required EPV to use GPS.
*
* @group EKF2
* @min 2
* @max 100
* @unit m
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_REQ_EPV, 5.0f);
/**
* Required speed accuracy to use GPS.
*
* @group EKF2
* @min 0.5
* @max 5.0
* @unit m/s
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_REQ_SACC, 0.5f);
/**
* Required satellite count to use GPS.
*
* @group EKF2
* @min 4
* @max 12
*/
PARAM_DEFINE_INT32(EKF2_REQ_NSATS, 6);
/**
* Required PDOP to use GPS.
*
* @group EKF2
* @min 1.5
* @max 5.0
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_REQ_PDOP, 2.5f);
/**
* Maximum horizontal drift speed to use GPS.
*
* @group EKF2
* @min 0.1
* @max 1.0
* @unit m/s
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_REQ_HDRIFT, 0.1f);
/**
* Maximum vertical drift speed to use GPS.
*
* @group EKF2
* @min 0.1
* @max 1.5
* @decimal 2
* @unit m/s
*/
PARAM_DEFINE_FLOAT(EKF2_REQ_VDRIFT, 0.2f);
/**
* Rate gyro noise for covariance prediction.
*
* @group EKF2
* @min 0.0001
* @max 0.1
* @unit rad/s
* @decimal 4
*/
PARAM_DEFINE_FLOAT(EKF2_GYR_NOISE, 1.5e-2f);
/**
* Accelerometer noise for covariance prediction.
*
* @group EKF2
* @min 0.01
* @max 1.0
* @unit m/s/s
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_ACC_NOISE, 3.5e-1f);
/**
* Process noise for IMU rate gyro bias prediction.
*
* @group EKF2
* @min 0.0
* @max 0.01
* @unit rad/s**2
* @decimal 6
*/
PARAM_DEFINE_FLOAT(EKF2_GYR_B_NOISE, 1.0e-3f);
/**
* Process noise for IMU accelerometer bias prediction.
*
* @group EKF2
* @min 0.0
* @max 0.01
* @unit m/s**3
* @decimal 6
*/
PARAM_DEFINE_FLOAT(EKF2_ACC_B_NOISE, 3.0e-3f);
/**
* Process noise for body magnetic field prediction.
*
* @group EKF2
* @min 0.0
* @max 0.1
* @unit Gauss/s
* @decimal 6
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_B_NOISE, 1.0e-4f);
/**
* Process noise for earth magnetic field prediction.
*
* @group EKF2
* @min 0.0
* @max 0.1
* @unit Gauss/s
* @decimal 6
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_E_NOISE, 1.0e-3f);
/**
* Process noise for wind velocity prediction.
*
* @group EKF2
* @min 0.0
* @max 1.0
* @unit m/s/s
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_WIND_NOISE, 1.0e-1f);
/**
* Measurement noise for gps horizontal velocity.
*
* @group EKF2
* @min 0.01
* @max 5.0
* @unit m/s
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_GPS_V_NOISE, 0.5f);
/**
* Measurement noise for gps position.
*
* @group EKF2
* @min 0.01
* @max 10.0
* @unit m
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_GPS_P_NOISE, 0.5f);
/**
* Measurement noise for non-aiding position hold.
*
* @group EKF2
* @min 0.5
* @max 50.0
* @unit m
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_NOAID_NOISE, 10.0f);
/**
* Measurement noise for barometric altitude.
*
* @group EKF2
* @min 0.01
* @max 15.0
* @unit m
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_BARO_NOISE, 2.0f);
/**
* Measurement noise for magnetic heading fusion.
*
* @group EKF2
* @min 0.01
* @max 1.0
* @unit rad
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_HEAD_NOISE, 0.3f);
/**
* Measurement noise for magnetometer 3-axis fusion.
*
* @group EKF2
* @min 0.001
* @max 1.0
* @unit Gauss
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_NOISE, 5.0e-2f);
/**
* Measurement noise for airspeed fusion.
*
* @group EKF2
* @min 0.5
* @max 5.0
* @unit m/s
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_EAS_NOISE, 1.4f);
/**
* Gate size for synthetic sideslip fusion
*
* Sets the number of standard deviations used by the innovation consistency test.
*
* @group EKF2
* @min 1.0
* @unit SD
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_BETA_GATE, 5.0f);
/**
* Noise for synthetic sideslip fusion.
*
* @group EKF2
* @min 0.1
* @max 1.0
* @unit m/s
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_BETA_NOISE, 0.3f);
/**
* Magnetic declination
*
* @group EKF2
* @volatile
* @category system
* @unit deg
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_DECL, 0);
/**
* Gate size for magnetic heading fusion
*
* Sets the number of standard deviations used by the innovation consistency test.
*
* @group EKF2
* @min 1.0
* @unit SD
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_HDG_GATE, 2.6f);
/**
* Gate size for magnetometer XYZ component fusion
*
* Sets the number of standard deviations used by the innovation consistency test.
*
* @group EKF2
* @min 1.0
* @unit SD
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_GATE, 3.0f);
/**
* Integer bitmask controlling handling of magnetic declination.
*
* Set bits in the following positions to enable functions.
* 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value.
* 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms.
* 2 : Set to true to always use the declination as an observation when 3-axis magnetometer fusion is being used.
*
* @group EKF2
* @min 0
* @max 7
* @bit 0 use geo_lookup declination
* @bit 1 save EKF2_MAG_DECL on disarm
* @bit 2 use declination as an observation
* @reboot_required true
*/
PARAM_DEFINE_INT32(EKF2_DECL_TYPE, 7);
/**
* Type of magnetometer fusion
*
* Integer controlling the type of magnetometer fusion used - magnetic heading or 3-component vector. The fuson of magnetomer data as a three component vector enables vehicle body fixed hard iron errors to be learned, but requires a stable earth field.
* If set to 'Automatic' magnetic heading fusion is used when on-ground and 3-axis magnetic field fusion in-flight with fallback to magnetic heading fusion if there is insufficient motion to make yaw or magnetic field states observable.
* If set to 'Magnetic heading' magnetic heading fusion is used at all times
* If set to '3-axis' 3-axis field fusion is used at all times.
* If set to 'VTOL custom' the behaviour is the same as 'Automatic', but if fusing airspeed, magnetometer fusion is only allowed to modify the magnetic field states. This can be used by VTOL platforms with large magnetic field disturbances to prevent incorrect bias states being learned during forward flight operation which can adversely affect estimation accuracy after transition to hovering flight.
* If set to 'MC custom' the behaviour is the same as 'Automatic, but if there are no earth frame position or velocity observations being used, the magnetometer will not be used. This enables vehicles to operate with no GPS in environments where the magnetic field cannot be used to provide a heading reference. Prior to flight, the yaw angle is assumed to be constant if movement tests controlled by the EKF2_MOVE_TEST parameter indicate that the vehicle is static. This allows the vehicle to be placed on the ground to learn the yaw gyro bias prior to flight.
* If set to 'None' the magnetometer will not be used under any circumstance. Other sources of yaw may be used if selected via the EKF2_AID_MASK parameter.
* @group EKF2
* @value 0 Automatic
* @value 1 Magnetic heading
* @value 2 3-axis
* @value 3 VTOL custom
* @value 4 MC custom
* @value 5 None
* @reboot_required true
*/
PARAM_DEFINE_INT32(EKF2_MAG_TYPE, 0);
/**
* Horizontal acceleration threshold used by automatic selection of magnetometer fusion method.
* This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered horizontal acceleration is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion.
*
* @group EKF2
* @min 0.0
* @max 5.0
* @unit m/s**2
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_ACCLIM, 0.5f);
/**
* Yaw rate threshold used by automatic selection of magnetometer fusion method.
* This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered yaw rate is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion.
*
* @group EKF2
* @min 0.0
* @max 1.0
* @unit rad/s
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_MAG_YAWLIM, 0.25f);
/**
* Gate size for barometric and GPS height fusion
*
* Sets the number of standard deviations used by the innovation consistency test.
*
* @group EKF2
* @min 1.0
* @unit SD
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_BARO_GATE, 5.0f);
/**
* Baro deadzone range for height fusion
*
* Sets the value of deadzone applied to negative baro innovations.
* Deadzone is enabled when EKF2_GND_EFF_DZ > 0.
*
* @group EKF2
* @min 0.0
* @max 10.0
* @unit M
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_GND_EFF_DZ, 0.0f);
/**
* Height above ground level for ground effect zone
*
* Sets the maximum distance to the ground level where negative baro innovations are expected.
*
* @group EKF2
* @min 0.0
* @max 5.0
* @unit M
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_GND_MAX_HGT, 0.5f);
/**
* Gate size for GPS horizontal position fusion
*
* Sets the number of standard deviations used by the innovation consistency test.
*
* @group EKF2
* @min 1.0
* @unit SD
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_GPS_P_GATE, 5.0f);
/**
* Gate size for GPS velocity fusion
*
* Sets the number of standard deviations used by the innovation consistency test.
*
* @group EKF2
* @min 1.0
* @unit SD
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_GPS_V_GATE, 5.0f);
/**
* Gate size for TAS fusion
*
* Sets the number of standard deviations used by the innovation consistency test.
*
* @group EKF2
* @min 1.0
* @unit SD
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_TAS_GATE, 3.0f);
/**
* Integer bitmask controlling data fusion and aiding methods.
*
* Set bits in the following positions to enable:
* 0 : Set to true to use GPS data if available
* 1 : Set to true to use optical flow data if available
* 2 : Set to true to inhibit IMU delta velocity bias estimation
* 3 : Set to true to enable vision position fusion
* 4 : Set to true to enable vision yaw fusion. Cannot be used if bit position 7 is true.
* 5 : Set to true to enable multi-rotor drag specific force fusion
* 6 : set to true if the EV observations are in a non NED reference frame and need to be rotated before being used
* 7 : Set to true to enable GPS yaw fusion. Cannot be used if bit position 4 is true.
*
* @group EKF2
* @min 0
* @max 511
* @bit 0 use GPS
* @bit 1 use optical flow
* @bit 2 inhibit IMU bias estimation
* @bit 3 vision position fusion
* @bit 4 vision yaw fusion
* @bit 5 multi-rotor drag fusion
* @bit 6 rotate external vision
* @bit 7 GPS yaw fusion
* @bit 8 vision velocity fusion
* @reboot_required true
*/
PARAM_DEFINE_INT32(EKF2_AID_MASK, 1);
/**
* Determines the primary source of height data used by the EKF.
*
* The range sensor option should only be used when for operation over a flat surface as the local NED origin will move up and down with ground level.
*
* @group EKF2
* @value 0 Barometric pressure
* @value 1 GPS
* @value 2 Range sensor
* @value 3 Vision
* @reboot_required true
*/
PARAM_DEFINE_INT32(EKF2_HGT_MODE, 0);
/**
* Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid.
*
* @group EKF2
* @group EKF2
* @min 500000
* @max 10000000
* @unit uSec
*/
PARAM_DEFINE_INT32(EKF2_NOAID_TOUT, 5000000);
/**
* Measurement noise for range finder fusion
*
* @group EKF2
* @min 0.01
* @unit m
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_RNG_NOISE, 0.1f);
/**
* Range finder range dependant noise scaler.
*
* Specifies the increase in range finder noise with range.
*
* @group EKF2
* @min 0.0
* @max 0.2
* @unit m/m
*/
PARAM_DEFINE_FLOAT(EKF2_RNG_SFE, 0.05f);
/**
* Gate size for range finder fusion
*
* Sets the number of standard deviations used by the innovation consistency test.
*
* @group EKF2
* @min 1.0
* @unit SD
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_RNG_GATE, 5.0f);
/**
* Expected range finder reading when on ground.
*
* If the vehicle is on ground, is not moving as determined by the motion test controlled by EKF2_MOVE_TEST and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is avilable at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground.
*
* @group EKF2
* @min 0.01
* @unit m
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_MIN_RNG, 0.1f);
/**
* Whether to set the external vision observation noise from the parameter or from vision message
*
* If set to true the observation noise is set from the parameters directly, if set to false the measurement noise is taken from the vision message and the parameter are used as a lower bound.
*
* @boolean
* @group EKF2
*/
PARAM_DEFINE_INT32(EKF2_EV_NOISE_MD, 0);
/**
* Measurement noise for vision position observations used to lower bound or replace the uncertainty included in the message
*
* @group EKF2
* @min 0.01
* @unit m
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_EVP_NOISE, 0.1f);
/**
* Measurement noise for vision velocity observations used to lower bound or replace the uncertainty included in the message
*
* @group EKF2
* @min 0.01
* @unit m/s
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_EVV_NOISE, 0.1f);
/**
* Measurement noise for vision angle observations used to lower bound or replace the uncertainty included in the message
*
* @group EKF2
* @min 0.01
* @unit rad
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_EVA_NOISE, 0.05f);
/**
* Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum
*
* @group EKF2
* @min 0.05
* @unit rad/s
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_OF_N_MIN, 0.15f);
/**
* Measurement noise for the optical flow sensor.
*
* (when it's reported quality metric is at the minimum set by EKF2_OF_QMIN).
* The following condition must be met: EKF2_OF_N_MAXN >= EKF2_OF_N_MIN
*
* @group EKF2
* @min 0.05
* @unit rad/s
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_OF_N_MAX, 0.5f);
/**
* Optical Flow data will only be used if the sensor reports a quality metric >= EKF2_OF_QMIN.
*
* @group EKF2
* @min 0
* @max 255
*/
PARAM_DEFINE_INT32(EKF2_OF_QMIN, 1);
/**
* Gate size for optical flow fusion
*
* Sets the number of standard deviations used by the innovation consistency test.
*
* @group EKF2
* @min 1.0
* @unit SD
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_OF_GATE, 3.0f);
/**
* Terrain altitude process noise - accounts for instability in vehicle height estimate
*
* @group EKF2
* @min 0.5
* @unit m/s
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_TERR_NOISE, 5.0f);
/**
* Magnitude of terrain gradient
*
* @group EKF2
* @min 0.0
* @unit m/m
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_TERR_GRAD, 0.5f);
/**
* Device id of IMU
*
* Set to 0 to use system selected (sensor_combined) IMU,
* otherwise set to the device id of the desired IMU (vehicle_imu).
*
* @group EKF2
* @value 0 System Primary
* @category Developer
*
*/
PARAM_DEFINE_INT32(EKF2_IMU_ID, 0);
/**
* X position of IMU in body frame (forward axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_IMU_POS_X, 0.0f);
/**
* Y position of IMU in body frame (right axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_IMU_POS_Y, 0.0f);
/**
* Z position of IMU in body frame (down axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_IMU_POS_Z, 0.0f);
/**
* X position of GPS antenna in body frame (forward axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_GPS_POS_X, 0.0f);
/**
* Y position of GPS antenna in body frame (right axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_GPS_POS_Y, 0.0f);
/**
* Z position of GPS antenna in body frame (down axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_GPS_POS_Z, 0.0f);
/**
* X position of range finder origin in body frame (forward axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_RNG_POS_X, 0.0f);
/**
* Y position of range finder origin in body frame (right axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_RNG_POS_Y, 0.0f);
/**
* Z position of range finder origin in body frame (down axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_RNG_POS_Z, 0.0f);
/**
* X position of optical flow focal point in body frame (forward axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_OF_POS_X, 0.0f);
/**
* Y position of optical flow focal point in body frame (right axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_OF_POS_Y, 0.0f);
/**
* Z position of optical flow focal point in body frame (down axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_OF_POS_Z, 0.0f);
/**
* X position of VI sensor focal point in body frame (forward axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_EV_POS_X, 0.0f);
/**
* Y position of VI sensor focal point in body frame (right axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_EV_POS_Y, 0.0f);
/**
* Z position of VI sensor focal point in body frame (down axis with origin relative to vehicle centre of gravity)
*
* @group EKF2
* @unit m
* @decimal 3
*/
PARAM_DEFINE_FLOAT(EKF2_EV_POS_Z, 0.0f);
/**
* Airspeed fusion threshold. A value of zero will deactivate airspeed fusion. Any other positive
* value will determine the minimum airspeed which will still be fused. Set to about 90% of the vehicles stall speed.
* Both airspeed fusion and sideslip fusion must be active for the EKF to continue navigating after loss of GPS.
* Use EKF2_FUSE_BETA to activate sideslip fusion.
*
* @group EKF2
* @min 0.0
* @unit m/s
* @decimal 1
*/
PARAM_DEFINE_FLOAT(EKF2_ARSP_THR, 0.0f);
/**
* Boolean determining if synthetic sideslip measurements should fused.
*
* A value of 1 indicates that fusion is active
* Both sideslip fusion and airspeed fusion must be active for the EKF to continue navigating after loss of GPS.
* Use EKF2_ARSP_THR to activate airspeed fusion.
*
* @group EKF2
* @boolean
*/
PARAM_DEFINE_INT32(EKF2_FUSE_BETA, 0);
/**
* Time constant of the velocity output prediction and smoothing filter
*
* @group EKF2
* @max 1.0
* @unit s
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_TAU_VEL, 0.25f);
/**
* Time constant of the position output prediction and smoothing filter. Controls how tightly the output track the EKF states.
*
* @group EKF2
* @min 0.1
* @max 1.0
* @unit s
* @decimal 2
*/