Browse Source

ArduCopter: Ensure fence has opportunity to auto disable for landing

c415-sdk
James O'Shannessy 4 years ago committed by Peter Barker
parent
commit
f14e1c2799
  1. 1
      ArduCopter/mode_auto.cpp
  2. 10
      ArduCopter/mode_rtl.cpp

1
ArduCopter/mode_auto.cpp

@ -252,6 +252,7 @@ void ModeAuto::land_start(const Vector3f& destination) @@ -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
}

10
ArduCopter/mode_rtl.cpp

@ -277,6 +277,11 @@ void ModeRTL::descent_start() @@ -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() @@ -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…
Cancel
Save