diff --git a/Rover/failsafe.cpp b/Rover/failsafe.cpp index da877c2bb7..76aec3c27a 100644 --- a/Rover/failsafe.cpp +++ b/Rover/failsafe.cpp @@ -84,17 +84,17 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, const char* type_str, bool o case FailsafeAction::None: break; case FailsafeAction::SmartRTL: - if (set_mode(mode_smartrtl, ModeReason::BATTERY_FAILSAFE)) { + if (set_mode(mode_smartrtl, ModeReason::FAILSAFE)) { break; } FALLTHROUGH; case FailsafeAction::RTL: - if (set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE)) { + if (set_mode(mode_rtl, ModeReason::FAILSAFE)) { break; } FALLTHROUGH; case FailsafeAction::Hold: - set_mode(mode_hold, ModeReason::BATTERY_FAILSAFE); + set_mode(mode_hold, ModeReason::FAILSAFE); break; case FailsafeAction::SmartRTL_Hold: if (!set_mode(mode_smartrtl, ModeReason::FAILSAFE)) { diff --git a/Rover/fence.cpp b/Rover/fence.cpp index 4c29b48d24..2706bf91d3 100644 --- a/Rover/fence.cpp +++ b/Rover/fence.cpp @@ -25,17 +25,17 @@ void Rover::fence_check() case FailsafeAction::None: break; case FailsafeAction::SmartRTL: - if (set_mode(mode_smartrtl, ModeReason::BATTERY_FAILSAFE)) { + if (set_mode(mode_smartrtl, ModeReason::FENCE_BREACHED)) { break; } FALLTHROUGH; case FailsafeAction::RTL: - if (set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE)) { + if (set_mode(mode_rtl, ModeReason::FENCE_BREACHED)) { break; } FALLTHROUGH; case FailsafeAction::Hold: - set_mode(mode_hold, ModeReason::BATTERY_FAILSAFE); + set_mode(mode_hold, ModeReason::FENCE_BREACHED); break; case FailsafeAction::SmartRTL_Hold: if (!set_mode(mode_smartrtl, ModeReason::FENCE_BREACHED)) {