From f9580424f6b8464a25fa1a5c641d8dbf4ea23ad5 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Wed, 2 Oct 2019 18:14:34 -0700 Subject: [PATCH] Plane: Resore old default behaviour for throttle curves The change in this made QStabilize behave very differently then it had, which is quite shocking in a test flight. --- ArduPlane/quadplane.cpp | 14 +++++++++----- 1 file changed, 9 insertions(+), 5 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index e09fca8abb..0715079efe 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -982,12 +982,16 @@ float QuadPlane::get_pilot_throttle() // normalize to [0,1] throttle_in /= plane.channel_throttle->get_range(); - // get hover throttle level [0,1] - float thr_mid = motors->get_throttle_hover(); - float thrust_curve_expo = constrain_float(throttle_expo, 0.0f, 1.0f); + if (is_positive(throttle_expo)) { + // get hover throttle level [0,1] + float thr_mid = motors->get_throttle_hover(); + float thrust_curve_expo = constrain_float(throttle_expo, 0.0f, 1.0f); - // this puts mid stick at hover throttle - return throttle_curve(thr_mid, thrust_curve_expo, throttle_in);; + // this puts mid stick at hover throttle + return throttle_curve(thr_mid, thrust_curve_expo, throttle_in);; + } else { + return throttle_in; + } } /*