mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
ArduCopter: Ensure fence has opportunity to auto disable for landing
This commit is contained in:
parent
cfb648e1c5
commit
f14e1c2799
@ -252,6 +252,7 @@ void ModeAuto::land_start(const Vector3f& destination)
|
||||
copter.landinggear.deploy_for_landing();
|
||||
|
||||
#if AC_FENCE == ENABLED
|
||||
// disable the fence on landing
|
||||
copter.fence.auto_disable_fence_for_landing();
|
||||
#endif
|
||||
}
|
||||
|
@ -277,6 +277,11 @@ void ModeRTL::descent_start()
|
||||
|
||||
// optionally deploy landing gear
|
||||
copter.landinggear.deploy_for_landing();
|
||||
|
||||
#if AC_FENCE == ENABLED
|
||||
// disable the fence on landing
|
||||
copter.fence.auto_disable_fence_for_landing();
|
||||
#endif
|
||||
}
|
||||
|
||||
// rtl_descent_run - implements the final descent to the RTL_ALT
|
||||
@ -365,6 +370,11 @@ void ModeRTL::land_start()
|
||||
|
||||
// optionally deploy landing gear
|
||||
copter.landinggear.deploy_for_landing();
|
||||
|
||||
#if AC_FENCE == ENABLED
|
||||
// disable the fence on landing
|
||||
copter.fence.auto_disable_fence_for_landing();
|
||||
#endif
|
||||
}
|
||||
|
||||
bool ModeRTL::is_landing() const
|
||||
|
Loading…
Reference in New Issue
Block a user