Plane: zero throttle nudge in RC failsafe
This commit is contained in:
parent
d31b44fa79
commit
62354527d4
@ -182,6 +182,8 @@ void Plane::read_radio()
|
||||
{
|
||||
if (!rc().read_input()) {
|
||||
control_failsafe();
|
||||
airspeed_nudge_cm = 0;
|
||||
throttle_nudge = 0;
|
||||
return;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user