AP_Arming: default to arming required

This commit is contained in:
Andrew Tridgell 2015-03-12 12:53:27 +11:00
parent a1d43e39e0
commit e0a0c3afcf

View File

@ -25,7 +25,7 @@ const AP_Param::GroupInfo AP_Arming::var_info[] PROGMEM = {
// @Description: Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, require rudder stick or GCS arming before arming motors and send THR_MIN PWM to throttle channel when disarmed. If 2, require rudder stick or GCS arming and send 0 PWM to throttle channel when disarmed. See the ARMING_CHECK_* parameters to see what checks are done before arming. Note, if setting this parameter to 0 a reboot is required to arm the plane. Also note, even with this parameter at 0, if ARMING_CHECK parameter is not also zero the plane may fail to arm throttle at boot due to a pre-arm check failure.
// @Values: 0:Disabled,1:THR_MIN PWM when disarmed,2:0 PWM when disarmed
// @User: Advanced
AP_GROUPINFO("REQUIRE", 0, AP_Arming, require, 0),
AP_GROUPINFO("REQUIRE", 0, AP_Arming, require, 1),
// @Param: DIS_RUD
// @DisplayName: Disable Rudder Arming