Plane: Fix a stale rudder input that was left from rebase

This commit is contained in:
Michael du Breuil 2018-08-27 17:30:38 -07:00 committed by Andrew Tridgell
parent 3e8d9f4131
commit 3098744777
1 changed files with 0 additions and 1 deletions

View File

@ -247,7 +247,6 @@ 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