Plane: zero throttle nudge in RC failsafe

This commit is contained in:
Iampete1 2020-07-25 15:57:46 +01:00 committed by Andrew Tridgell
parent be52098c82
commit 8494169aa9

View File

@ -179,6 +179,8 @@ void Plane::read_radio()
{
if (!rc().read_input()) {
control_failsafe();
airspeed_nudge_cm = 0;
throttle_nudge = 0;
return;
}