From 335c1769ee22ff49305e22eea41f49d5c0036d70 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 7 Mar 2019 20:08:51 +1100 Subject: [PATCH] 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. --- ArduCopter/mode.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/mode.cpp b/ArduCopter/mode.cpp index 174fcbe540..2b59409238 100644 --- a/ArduCopter/mode.cpp +++ b/ArduCopter/mode.cpp @@ -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");