mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
Plane: fixed throttle channel during startup failsafe
This commit is contained in:
parent
d49f50db4b
commit
a369b4833a
@ -59,6 +59,9 @@ void Plane::failsafe_check(void)
|
||||
channel_pitch->set_radio_out(channel_pitch->read());
|
||||
if (hal.util->get_soft_armed()) {
|
||||
channel_throttle->set_radio_out(channel_throttle->read());
|
||||
} else {
|
||||
channel_throttle->set_servo_out(0);
|
||||
channel_throttle->calc_pwm();
|
||||
}
|
||||
channel_rudder->set_radio_out(channel_rudder->read());
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user