Skip to content

Commit

Permalink
Copter: Change AC_FENCE_ACTION to an ENUM
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Sep 11, 2024
1 parent 66a2788 commit 40a6766
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
14 changes: 7 additions & 7 deletions ArduCopter/fence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@ void Copter::fence_check()
}

// if the user wants some kind of response and motors are armed
uint8_t fence_act = fence.get_action();
if (fence_act != AC_FENCE_ACTION_REPORT_ONLY ) {
AC_FENCE_ACTION fence_act = static_cast<AC_FENCE_ACTION>(fence.get_action());
if (fence_act != AC_FENCE_ACTION::REPORT_ONLY ) {

// disarm immediately if we think we are on the ground or in a manual flight mode with zero throttle
// don't disarm if the high-altitude fence has been broken because it's likely the user has pulled their throttle to zero to bring it down
Expand All @@ -45,32 +45,32 @@ void Copter::fence_check()
set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);
} else {
switch (fence_act) {
case AC_FENCE_ACTION_RTL_AND_LAND:
case AC_FENCE_ACTION::RTL_AND_LAND:
default:
// switch to RTL, if that fails then Land
if (!set_mode(Mode::Number::RTL, ModeReason::FENCE_BREACHED)) {
set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);
}
break;
case AC_FENCE_ACTION_ALWAYS_LAND:
case AC_FENCE_ACTION::ALWAYS_LAND:
// if always land option mode is specified, land
set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);
break;
case AC_FENCE_ACTION_SMART_RTL:
case AC_FENCE_ACTION::SMART_RTL:
// Try SmartRTL, if that fails, RTL, if that fails Land
if (!set_mode(Mode::Number::SMART_RTL, ModeReason::FENCE_BREACHED)) {
if (!set_mode(Mode::Number::RTL, ModeReason::FENCE_BREACHED)) {
set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);
}
}
break;
case AC_FENCE_ACTION_BRAKE:
case AC_FENCE_ACTION::BRAKE:
// Try Brake, if that fails Land
if (!set_mode(Mode::Number::BRAKE, ModeReason::FENCE_BREACHED)) {
set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);
}
break;
case AC_FENCE_ACTION_SMART_RTL_OR_LAND:
case AC_FENCE_ACTION::SMART_RTL_OR_LAND:
// Try SmartRTL, if that fails, Land
if (!set_mode(Mode::Number::SMART_RTL, ModeReason::FENCE_BREACHED)) {
set_mode(Mode::Number::LAND, ModeReason::FENCE_BREACHED);
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/mode.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -385,7 +385,7 @@ bool Copter::set_mode(Mode::Number mode, ModeReason reason)
#endif

#if AP_FENCE_ENABLED
if (fence.get_action() != AC_FENCE_ACTION_REPORT_ONLY) {
if (static_cast<AC_FENCE_ACTION>(fence.get_action()) != AC_FENCE_ACTION::REPORT_ONLY) {
// pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover
// this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe)
// but it should be harmless to disable the fence temporarily in these situations as well
Expand Down

0 comments on commit 40a6766

Please sign in to comment.