Browse Source

Plane: set fence manual recovery on mode change

master
Iampete1 3 years ago committed by Andrew Tridgell
parent
commit
367984a6b8
  1. 7
      ArduPlane/mode.cpp

7
ArduPlane/mode.cpp

@ -101,6 +101,13 @@ bool Mode::enter() @@ -101,6 +101,13 @@ bool Mode::enter()
// update RC failsafe, as mode change may have necessitated changing the failsafe throttle
plane.control_failsafe();
#if AP_FENCE_ENABLED
// pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover
// this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe)
// but it should be harmless to disable the fence temporarily in these situations as well
plane.fence.manual_recovery_start();
#endif
}
return enter_result;

Loading…
Cancel
Save