Plane: tailsitter: do not output throttle

This commit is contained in:
Peter Hall 2021-04-07 15:19:47 +01:00 committed by Andrew Tridgell
parent ed7db5b2b6
commit 47ab0360e7
1 changed files with 0 additions and 3 deletions

View File

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