Browse Source

Plane: fixed throttle channel during startup failsafe

mission-4.1.18
Andrew Tridgell 8 years ago
parent
commit
a369b4833a
  1. 3
      ArduPlane/failsafe.cpp

3
ArduPlane/failsafe.cpp

@ -59,6 +59,9 @@ void Plane::failsafe_check(void) @@ -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…
Cancel
Save