Skip to content

Commit

Permalink
Fence: Change AC_FENCE_ACTION to an ENUM
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura committed Sep 12, 2024
1 parent 88ed5a3 commit f4f02dd
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 10 deletions.
4 changes: 2 additions & 2 deletions libraries/AC_Fence/AC_Fence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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, static_cast<uint8_t>(AC_FENCE_ACTION::RTL_AND_LAND)),

// @Param{Copter, Plane, Sub}: ALT_MAX
// @DisplayName: Fence Maximum Altitude
Expand Down Expand Up @@ -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
Expand Down
18 changes: 10 additions & 8 deletions libraries/AC_Fence/AC_Fence.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit f4f02dd

Please sign in to comment.