From 83aaeb7bdd8c0feb2fcdb7bd5f1595e81ca5b1d5 Mon Sep 17 00:00:00 2001 From: muramura Date: Thu, 12 Sep 2024 00:02:01 +0900 Subject: [PATCH] Fence: Change AC_FENCE_ACTION to an ENUM --- libraries/AC_Fence/AC_Fence.cpp | 4 ++-- libraries/AC_Fence/AC_Fence.h | 18 ++++++++++-------- 2 files changed, 12 insertions(+), 10 deletions(-) diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index db214b2e494e17..491809a5decc80 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -69,7 +69,7 @@ const AP_Param::GroupInfo AC_Fence::var_info[] = { // @Values{Plane}: 0:Report Only,1:RTL,6:Guided,7:GuidedThrottlePass // @Values: 0:Report Only,1:RTL or Land // @User: Standard - AP_GROUPINFO("ACTION", 2, AC_Fence, _action, AC_FENCE_ACTION_RTL_AND_LAND), + AP_GROUPINFO("ACTION", 2, AC_Fence, _action, uint8_t(AC_FENCE_ACTION::RTL_AND_LAND)), // @Param{Copter, Plane, Sub}: ALT_MAX // @DisplayName: Fence Maximum Altitude @@ -878,7 +878,7 @@ bool AC_Fence::sys_status_enabled() const if (!sys_status_present()) { return false; } - if (_action == AC_FENCE_ACTION_REPORT_ONLY) { + if (_action == uint8_t(AC_FENCE_ACTION::REPORT_ONLY)) { return false; } // Fence is only enabled when the flag is enabled diff --git a/libraries/AC_Fence/AC_Fence.h b/libraries/AC_Fence/AC_Fence.h index 3165d7b73d4d33..325e8ddef9c6fe 100644 --- a/libraries/AC_Fence/AC_Fence.h +++ b/libraries/AC_Fence/AC_Fence.h @@ -20,14 +20,16 @@ #define AC_FENCE_ALL_FENCES (AC_FENCE_ARMING_FENCES | AC_FENCE_TYPE_ALT_MIN) // valid actions should a fence be breached -#define AC_FENCE_ACTION_REPORT_ONLY 0 // report to GCS that boundary has been breached but take no further action -#define AC_FENCE_ACTION_RTL_AND_LAND 1 // return to launch and, if that fails, land -#define AC_FENCE_ACTION_ALWAYS_LAND 2 // always land -#define AC_FENCE_ACTION_SMART_RTL 3 // smartRTL, if that fails, RTL, it that still fails, land -#define AC_FENCE_ACTION_BRAKE 4 // brake, if that fails, land -#define AC_FENCE_ACTION_SMART_RTL_OR_LAND 5 // SmartRTL, if that fails, Land -#define AC_FENCE_ACTION_GUIDED 6 // guided mode, with target waypoint as fence return point -#define AC_FENCE_ACTION_GUIDED_THROTTLE_PASS 7 // guided mode, but pilot retains manual throttle control +enum class AC_FENCE_ACTION : uint8_t { + REPORT_ONLY = 0, // report to GCS that boundary has been breached but take no further action + RTL_AND_LAND = 1, // return to launch and, if that fails, land + ALWAYS_LAND = 2, // always land + SMART_RTL = 3, // smartRTL, if that fails, RTL, it that still fails, land + BRAKE = 4, // brake, if that fails, land + SMART_RTL_OR_LAND = 5, // SmartRTL, if that fails, Land + GUIDED = 6, // guided mode, with target waypoint as fence return point + GUIDED_THROTTLE_PASS = 7, // guided mode, but pilot retains manual throttle control +}; // give up distance #define AC_FENCE_GIVE_UP_DISTANCE 100.0f // distance outside the fence at which we should give up and just land. Note: this is not used by library directly but is intended to be used by the main code