mirror of https://github.com/ArduPilot/ardupilot
Rover: fix ModeReason on fence breaches
This commit is contained in:
parent
38ca478178
commit
dabc34e7de
|
@ -84,17 +84,17 @@ void Rover::failsafe_trigger(uint8_t failsafe_type, const char* type_str, bool o
|
||||||
case FailsafeAction::None:
|
case FailsafeAction::None:
|
||||||
break;
|
break;
|
||||||
case FailsafeAction::SmartRTL:
|
case FailsafeAction::SmartRTL:
|
||||||
if (set_mode(mode_smartrtl, ModeReason::BATTERY_FAILSAFE)) {
|
if (set_mode(mode_smartrtl, ModeReason::FAILSAFE)) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
case FailsafeAction::RTL:
|
case FailsafeAction::RTL:
|
||||||
if (set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE)) {
|
if (set_mode(mode_rtl, ModeReason::FAILSAFE)) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
case FailsafeAction::Hold:
|
case FailsafeAction::Hold:
|
||||||
set_mode(mode_hold, ModeReason::BATTERY_FAILSAFE);
|
set_mode(mode_hold, ModeReason::FAILSAFE);
|
||||||
break;
|
break;
|
||||||
case FailsafeAction::SmartRTL_Hold:
|
case FailsafeAction::SmartRTL_Hold:
|
||||||
if (!set_mode(mode_smartrtl, ModeReason::FAILSAFE)) {
|
if (!set_mode(mode_smartrtl, ModeReason::FAILSAFE)) {
|
||||||
|
|
|
@ -25,17 +25,17 @@ void Rover::fence_check()
|
||||||
case FailsafeAction::None:
|
case FailsafeAction::None:
|
||||||
break;
|
break;
|
||||||
case FailsafeAction::SmartRTL:
|
case FailsafeAction::SmartRTL:
|
||||||
if (set_mode(mode_smartrtl, ModeReason::BATTERY_FAILSAFE)) {
|
if (set_mode(mode_smartrtl, ModeReason::FENCE_BREACHED)) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
case FailsafeAction::RTL:
|
case FailsafeAction::RTL:
|
||||||
if (set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE)) {
|
if (set_mode(mode_rtl, ModeReason::FENCE_BREACHED)) {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
FALLTHROUGH;
|
FALLTHROUGH;
|
||||||
case FailsafeAction::Hold:
|
case FailsafeAction::Hold:
|
||||||
set_mode(mode_hold, ModeReason::BATTERY_FAILSAFE);
|
set_mode(mode_hold, ModeReason::FENCE_BREACHED);
|
||||||
break;
|
break;
|
||||||
case FailsafeAction::SmartRTL_Hold:
|
case FailsafeAction::SmartRTL_Hold:
|
||||||
if (!set_mode(mode_smartrtl, ModeReason::FENCE_BREACHED)) {
|
if (!set_mode(mode_smartrtl, ModeReason::FENCE_BREACHED)) {
|
||||||
|
|
Loading…
Reference in New Issue