From ee96c538444a2157b760a89f78a79442205aef83 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Sat, 1 Sep 2018 16:16:50 -0700 Subject: [PATCH] Plane: Don't go to minimum airspeed when in RC failsafe in cruise/fbwb --- ArduPlane/navigation.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 860e7854bf..66ece417c2 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -107,9 +107,8 @@ void Plane::calc_airspeed_errors() // may be using synthetic airspeed ahrs.airspeed_estimate(&airspeed_measured); - // FBW_B airspeed target - if (control_mode == FLY_BY_WIRE_B || - control_mode == CRUISE) { + // FBW_B/cruise airspeed target + if (!failsafe.rc_failsafe && (control_mode == FLY_BY_WIRE_B || control_mode == CRUISE)) { target_airspeed_cm = ((int32_t)(aparm.airspeed_max - aparm.airspeed_min) * channel_throttle->get_control_in()) +