commander_params.c
24.6 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
1001
1002
1003
1004
1005
1006
1007
1008
1009
1010
1011
1012
1013
1014
/****************************************************************************
*
* Copyright (c) 2013-2015 PX4 Development Team. 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 PX4 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 commander_params.c
*
* Parameters defined by the sensors task.
*
* @author Lorenz Meier <lorenz@px4.io>
* @author Thomas Gubler <thomas@px4.io>
* @author Julian Oes <julian@px4.io>
*/
/**
* Roll trim
*
* The trim value is the actuator control value the system needs
* for straight and level flight. It can be calibrated by
* flying manually straight and level using the RC trims and
* copying them using the GCS.
*
* @group Radio Calibration
* @min -0.25
* @max 0.25
* @decimal 2
* @increment 0.01
*/
PARAM_DEFINE_FLOAT(TRIM_ROLL, 0.0f);
/**
* Pitch trim
*
* The trim value is the actuator control value the system needs
* for straight and level flight. It can be calibrated by
* flying manually straight and level using the RC trims and
* copying them using the GCS.
*
* @group Radio Calibration
* @min -0.25
* @max 0.25
* @decimal 2
* @increment 0.01
*/
PARAM_DEFINE_FLOAT(TRIM_PITCH, 0.0f);
/**
* Yaw trim
*
* The trim value is the actuator control value the system needs
* for straight and level flight. It can be calibrated by
* flying manually straight and level using the RC trims and
* copying them using the GCS.
*
* @group Radio Calibration
* @min -0.25
* @max 0.25
* @decimal 2
* @increment 0.01
*/
PARAM_DEFINE_FLOAT(TRIM_YAW, 0.0f);
/**
* Datalink loss time threshold
*
* After this amount of seconds without datalink the data link lost mode triggers
*
* @group Commander
* @unit s
* @min 5
* @max 300
* @decimal 1
* @increment 1
*/
PARAM_DEFINE_INT32(COM_DL_LOSS_T, 10);
/**
* High Latency Datalink loss time threshold
*
* After this amount of seconds without datalink the data link lost mode triggers
*
* @group Commander
* @unit s
* @min 60
* @max 3600
*/
PARAM_DEFINE_INT32(COM_HLDL_LOSS_T, 120);
/**
* High Latency Datalink regain time threshold
*
* After a data link loss: after this number of seconds with a healthy datalink the 'datalink loss'
* flag is set back to false
*
* @group Commander
* @unit s
* @min 0
* @max 60
*/
PARAM_DEFINE_INT32(COM_HLDL_REG_T, 0);
/**
* Engine Failure Throttle Threshold
*
* Engine failure triggers only above this throttle value
*
* @group Commander
* @unit norm
* @min 0.0
* @max 1.0
* @decimal 2
* @increment 0.01
*/
PARAM_DEFINE_FLOAT(COM_EF_THROT, 0.5f);
/**
* Engine Failure Current/Throttle Threshold
*
* Engine failure triggers only below this current value
*
* @group Commander
* @min 0.0
* @max 50.0
* @unit A/%
* @decimal 2
* @increment 1
*/
PARAM_DEFINE_FLOAT(COM_EF_C2T, 5.0f);
/**
* Engine Failure Time Threshold
*
* Engine failure triggers only if the throttle threshold and the
* current to throttle threshold are violated for this time
*
* @group Commander
* @unit s
* @min 0.0
* @max 60.0
* @decimal 1
* @increment 1
*/
PARAM_DEFINE_FLOAT(COM_EF_TIME, 10.0f);
/**
* RC loss time threshold
*
* After this amount of seconds without RC connection it's considered lost and not used anymore
*
* @group Commander
* @unit s
* @min 0
* @max 35
* @decimal 1
* @increment 0.1
*/
PARAM_DEFINE_FLOAT(COM_RC_LOSS_T, 0.5f);
/**
* Delay between RC loss and configured reaction
*
* RC signal not updated -> still use data for COM_RC_LOSS_T seconds
* Consider RC signal lost -> wait COM_RCL_ACT_T seconds on the spot waiting to regain signal
* React with failsafe action NAV_RCL_ACT
*
* A zero value disables the delay.
*
* @group Commander
* @unit s
* @min 0.0
* @max 25.0
* @decimal 3
*/
PARAM_DEFINE_FLOAT(COM_RCL_ACT_T, 15.0f);
/**
* Home set horizontal threshold
*
* The home position will be set if the estimated positioning accuracy is below the threshold.
*
* @group Commander
* @unit m
* @min 2
* @max 15
* @decimal 2
* @increment 0.5
*/
PARAM_DEFINE_FLOAT(COM_HOME_H_T, 5.0f);
/**
* Home set vertical threshold
*
* The home position will be set if the estimated positioning accuracy is below the threshold.
*
* @group Commander
* @unit m
* @min 5
* @max 25
* @decimal 2
* @increment 0.5
*/
PARAM_DEFINE_FLOAT(COM_HOME_V_T, 10.0f);
/**
* Allows setting the home position after takeoff
*
* If set to true, the autopilot is allowed to set its home position after takeoff
* The true home position is back-computed if a local position is estimate if available.
* If no local position is available, home is set to the current position.
*
* @boolean
* @group Commander
*/
PARAM_DEFINE_INT32(COM_HOME_IN_AIR, 0);
/**
* RC control input mode
*
* The default value of 0 requires a valid RC transmitter setup.
* Setting this to 1 allows joystick control and disables RC input handling and the associated checks. A value of
* 2 will generate RC control data from manual input received via MAVLink instead
* of directly forwarding the manual input data.
*
* @group Commander
* @min 0
* @max 2
* @value 0 RC Transmitter
* @value 1 Joystick/No RC Checks
* @value 2 Virtual RC by Joystick
*/
PARAM_DEFINE_INT32(COM_RC_IN_MODE, 0);
/**
* RC input arm/disarm command duration
*
* The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second.
*
* @group Commander
* @min 100
* @max 1500
* @unit ms
*/
PARAM_DEFINE_INT32(COM_RC_ARM_HYST, 1000);
/**
* Time-out for auto disarm after landing
*
* A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be
* automatically disarmed in case a landing situation has been detected during this period.
*
* A zero or negative value means that automatic disarming triggered by landing detection is disabled.
*
* @group Commander
* @unit s
* @decimal 2
*/
PARAM_DEFINE_FLOAT(COM_DISARM_LAND, 2.0f);
/**
* Time-out for auto disarm if too slow to takeoff
*
* A non-zero, positive value specifies the time after arming, in seconds, within which the
* vehicle must take off (after which it will automatically disarm).
*
* This is set to 25 seconds to ensure a system will not disarm if the pilot is not immediately
* taking off, but not so long that a system is completely forgotten about.
*
* A zero or negative value means that automatic disarming triggered by a pre-takeoff timeout is disabled.
*
* @group Commander
* @unit s
* @decimal 2
*/
PARAM_DEFINE_FLOAT(COM_DISARM_PRFLT, 25.0f);
/**
* Allow arming without GPS
*
* The default allows the vehicle to arm without GPS signal.
*
* @group Commander
* @value 0 Require GPS lock to arm
* @value 1 Allow arming without GPS
*/
PARAM_DEFINE_INT32(COM_ARM_WO_GPS, 1);
/**
* Arm switch is a momentary button
*
* 0: Arming/disarming triggers on switch transition.
* 1: Arming/disarming triggers when holding the momentary button down
* for COM_RC_ARM_HYST like the stick gesture.
*
* @group Commander
* @boolean
*/
PARAM_DEFINE_INT32(COM_ARM_SWISBTN, 0);
/**
* Battery failsafe mode
*
* Action the system takes at critical battery. See also BAT_CRIT_THR and BAT_EMERGEN_THR
* for definition of battery states.
*
* @group Commander
* @value 0 Warning
* @value 2 Land mode
* @value 3 Return at critical level, land at emergency level
* @decimal 0
* @increment 1
*/
PARAM_DEFINE_INT32(COM_LOW_BAT_ACT, 0);
/**
* Time-out to wait when offboard connection is lost before triggering offboard lost action.
*
* See COM_OBL_ACT and COM_OBL_RC_ACT to configure action.
*
* @group Commander
* @unit s
* @min 0
* @max 60
* @increment 0.01
*/
PARAM_DEFINE_FLOAT(COM_OF_LOSS_T, 1.0f);
/**
* Set offboard loss failsafe mode
*
* The offboard loss failsafe will only be entered after a timeout,
* set by COM_OF_LOSS_T in seconds.
*
* @value -1 Disabled
* @value 0 Land mode
* @value 1 Hold mode
* @value 2 Return mode
* @value 3 Terminate
* @value 4 Lockdown
*
* @group Commander
*/
PARAM_DEFINE_INT32(COM_OBL_ACT, 0);
/**
* Set offboard loss failsafe mode when RC is available
*
* The offboard loss failsafe will only be entered after a timeout,
* set by COM_OF_LOSS_T in seconds.
*
* @value -1 Disabled
* @value 0 Position mode
* @value 1 Altitude mode
* @value 2 Manual
* @value 3 Return mode
* @value 4 Land mode
* @value 5 Hold mode
* @value 6 Terminate
* @value 7 Lockdown
* @group Commander
*/
PARAM_DEFINE_INT32(COM_OBL_RC_ACT, 0);
/**
* Time-out to wait when onboard computer connection is lost before warning about loss connection.
*
* @group Commander
* @unit s
* @min 0
* @max 60
* @increment 0.01
*/
PARAM_DEFINE_FLOAT(COM_OBC_LOSS_T, 5.0f);
/**
* First flightmode slot (1000-1160)
*
* If the main switch channel is in this range the
* selected flight mode will be applied.
*
* @value -1 Unassigned
* @value 0 Manual
* @value 1 Altitude
* @value 2 Position
* @value 3 Mission
* @value 4 Hold
* @value 10 Takeoff
* @value 11 Land
* @value 5 Return
* @value 6 Acro
* @value 7 Offboard
* @value 8 Stabilized
* @value 12 Follow Me
* @group Commander
*/
PARAM_DEFINE_INT32(COM_FLTMODE1, -1);
/**
* Second flightmode slot (1160-1320)
*
* If the main switch channel is in this range the
* selected flight mode will be applied.
*
* @value -1 Unassigned
* @value 0 Manual
* @value 1 Altitude
* @value 2 Position
* @value 3 Mission
* @value 4 Hold
* @value 10 Takeoff
* @value 11 Land
* @value 5 Return
* @value 6 Acro
* @value 7 Offboard
* @value 8 Stabilized
* @value 12 Follow Me
* @group Commander
*/
PARAM_DEFINE_INT32(COM_FLTMODE2, -1);
/**
* Third flightmode slot (1320-1480)
*
* If the main switch channel is in this range the
* selected flight mode will be applied.
*
* @value -1 Unassigned
* @value 0 Manual
* @value 1 Altitude
* @value 2 Position
* @value 3 Mission
* @value 4 Hold
* @value 10 Takeoff
* @value 11 Land
* @value 5 Return
* @value 6 Acro
* @value 7 Offboard
* @value 8 Stabilized
* @value 12 Follow Me
* @group Commander
*/
PARAM_DEFINE_INT32(COM_FLTMODE3, -1);
/**
* Fourth flightmode slot (1480-1640)
*
* If the main switch channel is in this range the
* selected flight mode will be applied.
*
* @value -1 Unassigned
* @value 0 Manual
* @value 1 Altitude
* @value 2 Position
* @value 3 Mission
* @value 4 Hold
* @value 10 Takeoff
* @value 11 Land
* @value 5 Return
* @value 6 Acro
* @value 7 Offboard
* @value 8 Stabilized
* @value 12 Follow Me
* @group Commander
*/
PARAM_DEFINE_INT32(COM_FLTMODE4, -1);
/**
* Fifth flightmode slot (1640-1800)
*
* If the main switch channel is in this range the
* selected flight mode will be applied.
*
* @value -1 Unassigned
* @value 0 Manual
* @value 1 Altitude
* @value 2 Position
* @value 3 Mission
* @value 4 Hold
* @value 10 Takeoff
* @value 11 Land
* @value 5 Return
* @value 6 Acro
* @value 7 Offboard
* @value 8 Stabilized
* @value 12 Follow Me
* @group Commander
*/
PARAM_DEFINE_INT32(COM_FLTMODE5, -1);
/**
* Sixth flightmode slot (1800-2000)
*
* If the main switch channel is in this range the
* selected flight mode will be applied.
*
* @value -1 Unassigned
* @value 0 Manual
* @value 1 Altitude
* @value 2 Position
* @value 3 Mission
* @value 4 Hold
* @value 10 Takeoff
* @value 11 Land
* @value 5 Return
* @value 6 Acro
* @value 7 Offboard
* @value 8 Stabilized
* @value 12 Follow Me
* @group Commander
*/
PARAM_DEFINE_INT32(COM_FLTMODE6, -1);
/**
* Maximum EKF position innovation test ratio that will allow arming
*
* @group Commander
* @min 0.1
* @max 1.0
* @decimal 2
* @increment 0.05
*/
PARAM_DEFINE_FLOAT(COM_ARM_EKF_POS, 0.5f);
/**
* Maximum EKF velocity innovation test ratio that will allow arming
*
* @group Commander
* @min 0.1
* @max 1.0
* @decimal 2
* @increment 0.05
*/
PARAM_DEFINE_FLOAT(COM_ARM_EKF_VEL, 0.5f);
/**
* Maximum EKF height innovation test ratio that will allow arming
*
* @group Commander
* @min 0.1
* @max 1.0
* @decimal 2
* @increment 0.05
*/
PARAM_DEFINE_FLOAT(COM_ARM_EKF_HGT, 1.0f);
/**
* Maximum EKF yaw innovation test ratio that will allow arming
*
* @group Commander
* @min 0.1
* @max 1.0
* @decimal 2
* @increment 0.05
*/
PARAM_DEFINE_FLOAT(COM_ARM_EKF_YAW, 0.5f);
/**
* Maximum accelerometer inconsistency between IMU units that will allow arming
*
* @group Commander
* @unit m/s^2
* @min 0.1
* @max 1.0
* @decimal 2
* @increment 0.05
*/
PARAM_DEFINE_FLOAT(COM_ARM_IMU_ACC, 0.7f);
/**
* Maximum rate gyro inconsistency between IMU units that will allow arming
*
* @group Commander
* @unit rad/s
* @min 0.02
* @max 0.3
* @decimal 3
* @increment 0.01
*/
PARAM_DEFINE_FLOAT(COM_ARM_IMU_GYR, 0.25f);
/**
* Maximum magnetic field inconsistency between units that will allow arming
*
* Set -1 to disable the check.
*
* @group Commander
* @unit deg
* @min 3
* @max 180
*/
PARAM_DEFINE_INT32(COM_ARM_MAG_ANG, 45);
/**
* Enable mag strength preflight check
*
* Deny arming if the estimator detects a strong magnetic
* disturbance (check enabled by EKF2_MAG_CHECK)
*
* @boolean
* @group Commander
*/
PARAM_DEFINE_INT32(COM_ARM_MAG_STR, 1);
/**
* Rearming grace period
*
* Re-arming grace allows to rearm the drone with manual command without running prearmcheck during 5 s after disarming.
*
* @group Commander
* @boolean
*/
PARAM_DEFINE_INT32(COM_REARM_GRACE, 1);
/**
* Enable RC stick override of auto and/or offboard modes
*
* When RC stick override is enabled, moving the RC sticks more than COM_RC_STICK_OV from
* their center position immediately gives control back to the pilot by switching to Position mode.
* Note: Only has an effect on multicopters, and VTOLs in multicopter mode.
*
* @min 0
* @max 7
* @bit 0 Enable override during auto modes (except for in critical battery reaction)
* @bit 1 Enable override during offboard mode
* @bit 2 Ignore throttle stick
* @group Commander
*/
PARAM_DEFINE_INT32(COM_RC_OVERRIDE, 1);
/**
* RC stick override threshold
*
* If COM_RC_OVERRIDE is enabled and the joystick input is moved more than this threshold
* the autopilot the pilot takes over control.
*
* @group Commander
* @unit %
* @min 5
* @max 80
* @decimal 0
* @increment 0.05
*/
PARAM_DEFINE_FLOAT(COM_RC_STICK_OV, 30.0f);
/**
* Require valid mission to arm
*
* The default allows to arm the vehicle without a valid mission.
*
* @group Commander
* @boolean
*/
PARAM_DEFINE_INT32(COM_ARM_MIS_REQ, 0);
/**
* Position control navigation loss response.
*
* This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control.
* Navigation accuracy checks can be disabled using the CBRK_VELPOSERR parameter, but doing so will remove protection for all flight modes.
*
* @value 0 Altitude/Manual. Assume use of remote control after fallback. Switch to Altitude mode if a height estimate is available, else switch to MANUAL.
* @value 1 Land/Terminate. Assume no use of remote control after fallback. Switch to Land mode if a height estimate is available, else switch to TERMINATION.
*
* @group Commander
*/
PARAM_DEFINE_INT32(COM_POSCTL_NAVL, 0);
/**
* Require arm authorization to arm
*
* By default off. The default allows to arm the vehicle without a arm authorization.
*
* @group Commander
* @boolean
*/
PARAM_DEFINE_INT32(COM_ARM_AUTH_REQ, 0);
/**
* Arm authorizer system id
*
* Used if arm authorization is requested by COM_ARM_AUTH_REQ.
*
* @group Commander
*/
PARAM_DEFINE_INT32(COM_ARM_AUTH_ID, 10);
/**
* Arm authorization method
*
* Methods:
* - one arm: request authorization and arm when authorization is received
* - two step arm: 1st arm command request an authorization and
* 2nd arm command arm the drone if authorized
*
* Used if arm authorization is requested by COM_ARM_AUTH_REQ.
*
* @group Commander
* @value 0 one arm
* @value 1 two step arm
*/
PARAM_DEFINE_INT32(COM_ARM_AUTH_MET, 0);
/**
* Arm authorization timeout
*
* Timeout for authorizer answer.
* Used if arm authorization is requested by COM_ARM_AUTH_REQ.
*
* @group Commander
* @unit s
* @decimal 1
* @increment 0.1
*/
PARAM_DEFINE_FLOAT(COM_ARM_AUTH_TO, 1);
/**
* Loss of position failsafe activation delay.
*
* This sets number of seconds that the position checks need to be failed before the failsafe will activate.
* The default value has been optimised for rotary wing applications. For fixed wing applications, a larger value between 5 and 10 should be used.
*
* @unit s
* @reboot_required true
* @group Commander
* @min 1
* @max 100
*/
PARAM_DEFINE_INT32(COM_POS_FS_DELAY, 1);
/**
* Loss of position probation delay at takeoff.
*
* The probation delay is the number of seconds that the EKF innovation checks need to pass for the position to be declared good after it has been declared bad.
* The probation delay will be reset to this parameter value when takeoff is detected.
* After takeoff, if position checks are passing, the probation delay will reduce by one second for every lapsed second of valid position down to a minimum of 1 second.
* If position checks are failing, the probation delay will increase by COM_POS_FS_GAIN seconds for every lapsed second up to a maximum of 100 seconds.
* The default value has been optimised for rotary wing applications. For fixed wing applications, a value of 1 should be used.
*
* @unit s
* @reboot_required true
* @group Commander
* @min 1
* @max 100
*/
PARAM_DEFINE_INT32(COM_POS_FS_PROB, 30);
/**
* Loss of position probation gain factor.
*
* This sets the rate that the loss of position probation time grows when position checks are failing.
* The default value has been optimised for rotary wing applications. For fixed wing applications a value of 0 should be used.
*
* @reboot_required true
* @group Commander
*/
PARAM_DEFINE_INT32(COM_POS_FS_GAIN, 10);
/**
* Horizontal position error threshold.
*
* This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing.
*
* @unit m
* @group Commander
*/
PARAM_DEFINE_FLOAT(COM_POS_FS_EPH, 5);
/**
* Vertical position error threshold.
*
* This is the vertical position error (EPV) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing.
*
* @unit m
* @group Commander
*/
PARAM_DEFINE_FLOAT(COM_POS_FS_EPV, 10);
/**
* Horizontal velocity error threshold.
*
* This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing.
*
* @unit m/s
* @group Commander
*/
PARAM_DEFINE_FLOAT(COM_VEL_FS_EVH, 1);
/**
* Next flight UUID
*
* This number is incremented automatically after every flight on
* disarming in order to remember the next flight UUID.
* The first flight is 0.
*
* @group Commander
* @category system
* @volatile
* @min 0
*/
PARAM_DEFINE_INT32(COM_FLIGHT_UUID, 0);
/**
* Action after TAKEOFF has been accepted.
*
* The mode transition after TAKEOFF has completed successfully.
*
* @value 0 Hold
* @value 1 Mission (if valid)
* @group Mission
*/
PARAM_DEFINE_INT32(COM_TAKEOFF_ACT, 0);
/**
* Set data link loss failsafe mode
*
* The data link loss failsafe will only be entered after a timeout,
* set by COM_DL_LOSS_T in seconds. Once the timeout occurs the selected
* action will be executed.
*
* @value 0 Disabled
* @value 1 Hold mode
* @value 2 Return mode
* @value 3 Land mode
* @value 5 Terminate
* @value 6 Lockdown
*
* @group Mission
*/
PARAM_DEFINE_INT32(NAV_DLL_ACT, 0);
/**
* Set RC loss failsafe mode
*
* The RC loss failsafe will only be entered after a timeout,
* set by COM_RC_LOSS_T in seconds. If RC input checks have been disabled
* by setting the COM_RC_IN_MODE param it will not be triggered.
*
* @value 0 Disabled
* @value 1 Hold mode
* @value 2 Return mode
* @value 3 Land mode
* @value 5 Terminate
* @value 6 Lockdown
*
* @group Mission
*/
PARAM_DEFINE_INT32(NAV_RCL_ACT, 2);
/**
* Flag to enable obstacle avoidance.
*
* @boolean
* @group Mission
*/
PARAM_DEFINE_INT32(COM_OBS_AVOID, 0);
/**
* User Flight Profile
*
* Describes the intended use of the vehicle.
* Can be used by ground control software or log post processing.
* This param does not influence the behavior within the firmware. This means for example the control logic is independent of the setting of this param (but depends on other params).
*
* @value 0 Default
* @value 100 Pro User
* @value 200 Flight Tester
* @value 300 Developer
*
* @group Commander
*/
PARAM_DEFINE_INT32(COM_FLT_PROFILE, 0);
/**
* Require all the ESCs to be detected to arm.
*
* This param is specific for ESCs reporting status. Normal ESCs configurations are not affected by the change of this param.
*
* @group Commander
* @boolean
*/
PARAM_DEFINE_INT32(COM_ARM_CHK_ESCS, 1);
/**
* Condition to enter prearmed mode
*
* Condition to enter the prearmed state, an intermediate state between disarmed and armed
* in which non-throttling actuators are active.
*
* @value 0 Disabled
* @value 1 Safety button
* @value 2 Always
*
* @group Commander
*/
PARAM_DEFINE_INT32(COM_PREARM_MODE, 0);
/**
* Enable Motor Testing
*
* If set, enables the motor test interface via MAVLink (DO_MOTOR_TEST), that
* allows spinning the motors for testing purposes.
*
* @boolean
* @group Commander
*/
PARAM_DEFINE_INT32(COM_MOT_TEST_EN, 1);
/**
* Timeout value for disarming when kill switch is engaged
*
* @group Commander
* @unit s
* @min 0.0
* @max 30.0
* @increment 0.1
*/
PARAM_DEFINE_FLOAT(COM_KILL_DISARM, 5.0f);
/**
* Maximum allowed CPU load to still arm
*
* A negative value disables the check.
*
* @group Commander
* @unit %
* @min -1
* @max 100
* @increment 1
*/
PARAM_DEFINE_FLOAT(COM_CPU_MAX, 90.0f);
/**
* Required number of redundant power modules
*
* This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected.
* Note: CBRK_SUPPLY_CHK disables all power checks including this one.
*
* @group Commander
* @min 0
* @max 4
*/
PARAM_DEFINE_INT32(COM_POWER_COUNT, 1);
/**
* Timeout for detecting a failure after takeoff
*
* A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to put the vehicle into
* a lockdown state if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R.
* The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW) and Manual (FW).
* A zero or negative value means that the check is disabled.
*
* @group Commander
* @unit s
* @min -1.0
* @max 5.0
* @decimal 3
*/
PARAM_DEFINE_FLOAT(COM_LKDOWN_TKO, 3.0f);
/**
* Enable preflight check for maximal allowed airspeed when arming.
*
* Deny arming if the current airspeed measurement is greater than half the stall speed (ASPD_STALL).
* Excessive airspeed measurements on ground are either caused by wind or bad airspeed calibration.
*
* @group Commander
* @value 0 Disabled
* @value 1 Enabled
*/
PARAM_DEFINE_INT32(COM_ARM_ARSP_EN, 1);
/**
* Enable FMU SD card detection check
*
* This check detects if the FMU SD card is missing.
* Depending on the value of the parameter, the check can be
* disabled, warn only or deny arming.
*
* @group Commander
* @value 0 Disabled
* @value 1 Warning only
* @value 2 Enforce SD card presence
*/
PARAM_DEFINE_INT32(COM_ARM_SDCARD, 1);