Browse Source

Plane: read RC input in failsafe handler

mission-4.1.18
Andrew Tridgell 6 years ago
parent
commit
11e8243bc9
  1. 4
      ArduPlane/failsafe.cpp

4
ArduPlane/failsafe.cpp

@ -39,6 +39,10 @@ void Plane::failsafe_check(void) @@ -39,6 +39,10 @@ void Plane::failsafe_check(void)
}
if (in_failsafe && tnow - last_timestamp > 20000) {
// ensure we have the latest RC inputs
rc().read_input();
last_timestamp = tnow;
rc().read_input();

Loading…
Cancel
Save