From 5e8e08897823c4eee68843b6f00c29cd8d70efda Mon Sep 17 00:00:00 2001 From: Hwurzburg Date: Thu, 12 Nov 2020 15:57:34 -0600 Subject: [PATCH] ArduPlane:Add safety limit on tailsitter VTOL transition throttle Co-authored-by: Peter Hall <33176108+IamPete1@users.noreply.github.com> --- ArduPlane/tailsitter.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index e65ecd7fe2..8884269b4c 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -84,6 +84,7 @@ void QuadPlane::tailsitter_output(void) integrator to the same throttle level */ throttle = motors->get_throttle_hover() * 100; + throttle = MAX(throttle,plane.aparm.throttle_cruise.get()); SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, 0); pos_control->get_accel_z_pid().set_integrator(throttle*10);