ArduPlane: Fix throttle nudge reset due to wrong radio timing

This commit is contained in:
giacomo892 2020-11-07 15:17:59 +01:00 committed by Andrew Tridgell
parent f7daa4a93a
commit 9b4441011c

View File

@ -186,8 +186,6 @@ void Plane::read_radio()
{
if (!rc().read_input()) {
control_failsafe();
airspeed_nudge_cm = 0;
throttle_nudge = 0;
return;
}
@ -269,6 +267,9 @@ void Plane::control_failsafe()
channel_pitch->set_control_in(0);
channel_rudder->set_control_in(0);
airspeed_nudge_cm = 0;
throttle_nudge = 0;
switch (control_mode->mode_number()) {
case Mode::Number::QSTABILIZE:
case Mode::Number::QHOVER: