Plane: reset rudder input during RC failsafe

This commit is contained in:
Andrew Tridgell 2018-08-23 11:39:35 +10:00
parent a80d27eeff
commit d9b72f6821
1 changed files with 1 additions and 0 deletions

View File

@ -239,6 +239,7 @@ void Plane::control_failsafe()
channel_roll->set_radio_in(channel_roll->get_radio_trim());
channel_pitch->set_radio_in(channel_pitch->get_radio_trim());
channel_rudder->set_radio_in(channel_rudder->get_radio_trim());
rudder_input = 0;
// note that we don't set channel_throttle->radio_in to radio_trim,
// as that would cause throttle failsafe to not activate