diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 31a4d2470e..66c212339f 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -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