Copter: disable fences for landing by suppressing in the fence check rather than using a state machine

This commit is contained in:
Andy Piper 2024-05-31 14:13:43 +01:00 committed by Peter Barker
parent 46d6d0bf03
commit eaf001c52f
4 changed files with 5 additions and 21 deletions

View File

@ -10,8 +10,12 @@ void Copter::fence_check()
{
const uint8_t orig_breaches = fence.get_breaches();
bool is_in_landing = flightmode->mode_number() == Mode::Number::LAND
|| flightmode->mode_number() == Mode::Number::RTL
|| flightmode->mode_number() == Mode::Number::SMART_RTL;
// check for new breaches; new_breaches is bitmask of fence types breached
const uint8_t new_breaches = fence.check();
const uint8_t new_breaches = fence.check(is_in_landing);
// we still don't do anything when disarmed, but we do check for fence breaches.
// fence pre-arm check actually checks if any fence has been breached

View File

@ -488,11 +488,6 @@ void ModeAuto::land_start()
copter.landinggear.deploy_for_landing();
#endif
#if AP_FENCE_ENABLED
// disable the fence on landing
copter.fence.auto_disable_fence_for_landing();
#endif
// reset flag indicating if pilot has applied roll or pitch inputs during landing
copter.ap.land_repo_active = false;

View File

@ -41,11 +41,6 @@ bool ModeLand::init(bool ignore_checks)
copter.landinggear.deploy_for_landing();
#endif
#if AP_FENCE_ENABLED
// disable the fence on landing
copter.fence.auto_disable_fence_for_landing();
#endif
#if AC_PRECLAND_ENABLED
// initialise precland state machine
copter.precland_statemachine.init();

View File

@ -255,11 +255,6 @@ void ModeRTL::descent_start()
// optionally deploy landing gear
copter.landinggear.deploy_for_landing();
#endif
#if AP_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
@ -347,11 +342,6 @@ void ModeRTL::land_start()
// optionally deploy landing gear
copter.landinggear.deploy_for_landing();
#endif
#if AP_FENCE_ENABLED
// disable the fence on landing
copter.fence.auto_disable_fence_for_landing();
#endif
}
bool ModeRTL::is_landing() const