Browse Source

Plane: tailsitter: do not output throttle

zr-v5.1
Peter Hall 4 years ago committed by Andrew Tridgell
parent
commit
47ab0360e7
  1. 3
      ArduPlane/tailsitter.cpp

3
ArduPlane/tailsitter.cpp

@ -169,11 +169,8 @@ void QuadPlane::tailsitter_output(void) @@ -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;

Loading…
Cancel
Save