From abee62abc453da8f558cbd76d34ce7b301a2e6ce Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 28 Aug 2020 18:32:38 +0100 Subject: [PATCH] Plane: use throttle in for transition max comparison --- ArduPlane/quadplane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 8130b892a5..ba83e14f16 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1760,7 +1760,7 @@ void QuadPlane::update_transition(void) plane.nav_pitch_cd, 0); // set throttle at either hover throttle or current throttle, whichever is higher, through the transition - attitude_control->set_throttle_out(MAX(motors->get_throttle_hover(),motors->get_throttle()), true, 0); + attitude_control->set_throttle_out(MAX(motors->get_throttle_hover(),attitude_control->get_throttle_in()), true, 0); break; }