mirror of https://github.com/ArduPilot/ardupilot
AP_Arming: add Bitmask parameter description
Also moved ARMING_CHECK to standard category
This commit is contained in:
parent
0cc4b6977e
commit
304a23923a
|
@ -38,7 +38,8 @@ const AP_Param::GroupInfo AP_Arming::var_info[] PROGMEM = {
|
|||
// @DisplayName: Arm Checks to Peform (bitmask)
|
||||
// @Description: Checks prior to arming motor. This is a bitmask of checks that will be performed befor allowing arming. The default is no checks, allowing arming at any time. You can select whatever checks you prefer by adding together the values of each check type to set this parameter. For example, to only allow arming when you have GPS lock and no RC failsafe you would set ARMING_CHECK to 72. For most users it is recommended that you set this to 1 to enable all checks.
|
||||
// @Values: 0:None,1:All,2:Barometer,4:Compass,8:GPS,16:INS(INertial Sensors - accels & gyros),32:Parameters(unused),64:RC Failsafe,128:Board voltage,256:Battery Level,512:Airspeed,1024:LoggingAvailable
|
||||
// @User: Advanced
|
||||
// @Bitmask: 0:All,1:Barometer,2:Compass,3:GPS,4:INS,5:Parameters,6:RC,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("CHECK", 2, AP_Arming, checks_to_perform, ARMING_CHECK_ALL),
|
||||
|
||||
AP_GROUPEND
|
||||
|
|
Loading…
Reference in New Issue