Copter: do not allow change to Drift if in non-manual-throttle mode

drift acts just like stabilise or acro in terms of pilot throttle when
pilot input is maxed.
This commit is contained in:
Peter Barker 2019-03-07 20:08:51 +11:00 committed by Peter Barker
parent 25e5243b63
commit 335c1769ee

View File

@ -207,7 +207,7 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
// trigger auto takeoff), then switches into manual):
if (!ignore_checks &&
ap.land_complete &&
new_flightmode->has_manual_throttle() &&
(new_flightmode->has_manual_throttle() || new_flightmode == &mode_drift) &&
!copter.flightmode->has_manual_throttle() &&
new_flightmode->get_pilot_desired_throttle() > copter.get_non_takeoff_throttle()) {
gcs().send_text(MAV_SEVERITY_WARNING, "Mode change failed: throttle too high");