diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 863ed871a1..ce05eb4afd 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -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 } diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index a9ffd1a8a7..ed597a059e 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -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