Copter: add comment to check throttle is not too high for guide_nogps and auto

This commit is contained in:
mihaelsubasic69@gmail.com 2023-01-30 10:13:17 +01:00 committed by Randy Mackay
parent 220e58ca6d
commit cfa3370f9f

View File

@ -628,7 +628,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
#else
const char *rc_item = "Throttle";
#endif
// check throttle is not too high - skips checks if arming from GCS in Guided
// check throttle is not too high - skips checks if arming from GCS in Guided,Guided_NoGPS or Auto
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) {