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 d31b44fa79
commit 62354527d4

View File

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