mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 10:43:58 -04:00
Plane: zero throttle nudge in RC failsafe
This commit is contained in:
parent
be52098c82
commit
8494169aa9
@ -179,6 +179,8 @@ void Plane::read_radio()
|
|||||||
{
|
{
|
||||||
if (!rc().read_input()) {
|
if (!rc().read_input()) {
|
||||||
control_failsafe();
|
control_failsafe();
|
||||||
|
airspeed_nudge_cm = 0;
|
||||||
|
throttle_nudge = 0;
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user