ArduPlane:Add safety limit on tailsitter VTOL transition throttle

Co-authored-by: Peter Hall <33176108+IamPete1@users.noreply.github.com>
This commit is contained in:
Hwurzburg 2020-11-12 15:57:34 -06:00 committed by Andrew Tridgell
parent 6eca18c08b
commit 5e8e088978
1 changed files with 1 additions and 0 deletions

View File

@ -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);