mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Plane: reset rudder input during RC failsafe
This commit is contained in:
parent
a80d27eeff
commit
d9b72f6821
@ -239,6 +239,7 @@ void Plane::control_failsafe()
|
|||||||
channel_roll->set_radio_in(channel_roll->get_radio_trim());
|
channel_roll->set_radio_in(channel_roll->get_radio_trim());
|
||||||
channel_pitch->set_radio_in(channel_pitch->get_radio_trim());
|
channel_pitch->set_radio_in(channel_pitch->get_radio_trim());
|
||||||
channel_rudder->set_radio_in(channel_rudder->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,
|
// note that we don't set channel_throttle->radio_in to radio_trim,
|
||||||
// as that would cause throttle failsafe to not activate
|
// as that would cause throttle failsafe to not activate
|
||||||
|
Loading…
Reference in New Issue
Block a user