From 47ab0360e7873e76d60521ae6582b85e6981be9a Mon Sep 17 00:00:00 2001 From: Peter Hall Date: Wed, 7 Apr 2021 15:19:47 +0100 Subject: [PATCH] Plane: tailsitter: do not output throttle --- ArduPlane/tailsitter.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/ArduPlane/tailsitter.cpp b/ArduPlane/tailsitter.cpp index b4a78e74d2..08da8c53de 100644 --- a/ArduPlane/tailsitter.cpp +++ b/ArduPlane/tailsitter.cpp @@ -169,11 +169,8 @@ void QuadPlane::tailsitter_output(void) SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, (motors->get_roll()+motors->get_roll_ff())*SERVO_MAX); if (hal.util->get_soft_armed()) { - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, motors->thrust_to_actuator(motors->get_throttle()) * 100); // scale surfaces for throttle tailsitter_speed_scaling(); - } else { - SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, motors->get_throttle() * 100); } tilt_left = 0.0f;