#include "Rover.h"
#if AP_FENCE_ENABLED
void Rover::fence_checks_async()
{
const uint32_t now = AP_HAL::millis();
if (!AP_HAL::timeout_expired(fence_breaches.last_check_ms, now, 100U)) {
return;
}
if (fence_breaches.have_updates) {
return;
}
fence_breaches.last_check_ms = now;
const uint8_t orig_breaches = fence.get_breaches();
fence_breaches.new_breaches = fence.check();
if (!fence_breaches.new_breaches && orig_breaches && fence.get_breaches() == 0) {
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode::ERROR_RESOLVED);
}
fence_breaches.have_updates = true;
}
void Rover::fence_check()
{
if (!fence_breaches.have_updates) {
return;
}
if (!arming.is_armed()) {
fence_breaches.have_updates = false;
return;
}
if (fence_breaches.new_breaches) {
if ((FailsafeAction)fence.get_action() != FailsafeAction::None) {
if (fence.get_breach_distance(fence_breaches.new_breaches) <= AC_FENCE_GIVE_UP_DISTANCE) {
switch ((FailsafeAction)fence.get_action()) {
case FailsafeAction::None:
break;
case FailsafeAction::SmartRTL:
if (set_mode(mode_smartrtl, ModeReason::FENCE_BREACHED)) {
break;
}
FALLTHROUGH;
case FailsafeAction::RTL:
if (set_mode(mode_rtl, ModeReason::FENCE_BREACHED)) {
break;
}
FALLTHROUGH;
case FailsafeAction::Hold:
set_mode(mode_hold, ModeReason::FENCE_BREACHED);
break;
case FailsafeAction::SmartRTL_Hold:
if (!set_mode(mode_smartrtl, ModeReason::FENCE_BREACHED)) {
set_mode(mode_hold, ModeReason::FENCE_BREACHED);
}
break;
case FailsafeAction::Loiter_Hold:
if (!set_mode(mode_loiter, ModeReason::FENCE_BREACHED)) {
set_mode(mode_hold, ModeReason::FENCE_BREACHED);
}
break;
case FailsafeAction::Terminate:
arming.disarm(AP_Arming::Method::FENCEBREACH);
break;
}
} else {
set_mode(mode_hold, ModeReason::FENCE_BREACHED);
}
}
LOGGER_WRITE_ERROR(LogErrorSubsystem::FAILSAFE_FENCE, LogErrorCode(fence_breaches.new_breaches));
}
fence_breaches.have_updates = false;
}
#endif