mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 14:48:28 -04:00
Plane: set fence manual recovery on mode change
This commit is contained in:
parent
e7cb949f5f
commit
367984a6b8
@ -101,6 +101,13 @@ bool Mode::enter()
|
|||||||
|
|
||||||
// update RC failsafe, as mode change may have necessitated changing the failsafe throttle
|
// update RC failsafe, as mode change may have necessitated changing the failsafe throttle
|
||||||
plane.control_failsafe();
|
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;
|
return enter_result;
|
||||||
|
Loading…
Reference in New Issue
Block a user