Copter: skip throttle high arm check when arming in AUTO

This commit is contained in:
Akshat Upadhyay 2022-10-19 00:58:13 +05:30 committed by Randy Mackay
parent 0dc878564f
commit 928c3557af
1 changed files with 1 additions and 1 deletions

View File

@ -630,7 +630,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
const char *rc_item = "Throttle";
#endif
// check throttle is not too high - skips checks if arming from GCS in Guided
if (!(method == AP_Arming::Method::MAVLINK && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS))) {
if (!(method == AP_Arming::Method::MAVLINK && (copter.flightmode->mode_number() == Mode::Number::GUIDED || copter.flightmode->mode_number() == Mode::Number::GUIDED_NOGPS || copter.flightmode->mode_number() == Mode::Number::AUTO))) {
// above top of deadband is too always high
if (copter.get_pilot_desired_climb_rate(copter.channel_throttle->get_control_in()) > 0.0f) {
check_failed(ARMING_CHECK_RC, true, "%s too high", rc_item);