mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Plane: set tailsitter throttle output when disarmed
This commit is contained in:
parent
000ff90a71
commit
0b35708f33
@ -172,6 +172,8 @@ void QuadPlane::tailsitter_output(void)
|
||||
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…
Reference in New Issue
Block a user