AP_Arming: mark ARMING_REQUIRE as plane and rover only

This commit is contained in:
Andrew Tridgell 2017-02-08 10:47:01 +11:00
parent 108cbe1dab
commit 4626b3a269

View File

@ -32,14 +32,14 @@ extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo AP_Arming::var_info[] = {
#if !APM_BUILD_TYPE(APM_BUILD_ArduCopter)
// @Param: REQUIRE
// @DisplayName: Require Arming Motors
// @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. This parameter is relevant for ArduPlane only.
// @Values: 0:Disabled,1:THR_MIN PWM when disarmed,2:0 PWM when disarmed
// @User: Advanced
AP_GROUPINFO_FLAGS("REQUIRE", 0, AP_Arming, require, 1, AP_PARAM_NO_SHIFT),
#endif
AP_GROUPINFO_FLAGS_FRAME("REQUIRE", 0, AP_Arming, require, 1,
AP_PARAM_NO_SHIFT,
AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_ROVER),
// @Param: CHECK
// @DisplayName: Arm Checks to Peform (bitmask)