Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fence: Change AC_FENCE_ACTION to an enum #28081

Open
wants to merge 5 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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());
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
AC_Fence::Action fence_act = static_cast<AC_Fence::Action>(fence.get_action());
const 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
10 changes: 5 additions & 5 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1463,22 +1463,22 @@ void Plane::load_parameters(void)
if (AP_Param::find_old_parameter(&fence_action_info_old, &fence_action_old)) {
enum ap_var_type ptype;
AP_Int8 *fence_action_new = (AP_Int8*)AP_Param::find(&fence_action_info_old.new_name[0], &ptype);
uint8_t fence_action_new_val;
AC_Fence::Action fence_action_new_val;
if (fence_action_new && !fence_action_new->configured()) {
switch(fence_action_old.get()) {
case 0: // FENCE_ACTION_NONE
case 2: // FENCE_ACTION_REPORT_ONLY
default:
fence_action_new_val = AC_FENCE_ACTION_REPORT_ONLY;
fence_action_new_val = AC_Fence::Action::REPORT_ONLY;
break;
case 1: // FENCE_ACTION_GUIDED
fence_action_new_val = AC_FENCE_ACTION_GUIDED;
fence_action_new_val = AC_Fence::Action::GUIDED;
break;
case 3: // FENCE_ACTION_GUIDED_THR_PASS
fence_action_new_val = AC_FENCE_ACTION_GUIDED_THROTTLE_PASS;
fence_action_new_val = AC_Fence::Action::GUIDED_THROTTLE_PASS;
break;
case 4: // FENCE_ACTION_RTL
fence_action_new_val = AC_FENCE_ACTION_RTL_AND_LAND;
fence_action_new_val = AC_Fence::Action::RTL_AND_LAND;
break;
}
fence_action_new->set_and_save((int8_t)fence_action_new_val);
Expand Down
30 changes: 17 additions & 13 deletions ArduPlane/fence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,10 @@ void Plane::fence_check()
if (!fence.enabled()) {
// Switch back to the chosen control mode if still in
// GUIDED to the return point
switch(fence.get_action()) {
case AC_FENCE_ACTION_GUIDED:
case AC_FENCE_ACTION_GUIDED_THROTTLE_PASS:
case AC_FENCE_ACTION_RTL_AND_LAND:
switch(static_cast<AC_Fence::Action>(fence.get_action())) {
case AC_Fence::Action::GUIDED:
case AC_Fence::Action::GUIDED_THROTTLE_PASS:
case AC_Fence::Action::RTL_AND_LAND:
if (plane.control_mode_reason == ModeReason::FENCE_BREACHED &&
control_mode->is_guided_mode()) {
set_mode(*previous_mode, ModeReason::FENCE_RETURN_PREVIOUS_MODE);
Expand Down Expand Up @@ -76,14 +76,18 @@ void Plane::fence_check()
fence.print_fence_message("breached", new_breaches);

// if the user wants some kind of response and motors are armed
const uint8_t fence_act = fence.get_action();
const AC_Fence::Action fence_act = static_cast<AC_Fence::Action>(fence.get_action());
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why does this need a static cast? Similar question elsewhere.

Surely get_action should return an AC_Fence::Action now?

switch (fence_act) {
case AC_FENCE_ACTION_REPORT_ONLY:
case AC_Fence::Action::REPORT_ONLY:
case AC_Fence::Action::ALWAYS_LAND:
case AC_Fence::Action::SMART_RTL:
case AC_Fence::Action::BRAKE:
case AC_Fence::Action::SMART_RTL_OR_LAND:
break;
case AC_FENCE_ACTION_GUIDED:
case AC_FENCE_ACTION_GUIDED_THROTTLE_PASS:
case AC_FENCE_ACTION_RTL_AND_LAND:
if (fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {
case AC_Fence::Action::GUIDED:
case AC_Fence::Action::GUIDED_THROTTLE_PASS:
case AC_Fence::Action::RTL_AND_LAND:
if (fence_act == AC_Fence::Action::RTL_AND_LAND) {
if (control_mode == &mode_auto &&
mission.get_in_landing_sequence_flag() &&
(g.rtl_autoland == RtlAutoland::RTL_THEN_DO_LAND_START ||
Expand All @@ -97,7 +101,7 @@ void Plane::fence_check()
}

Location loc;
if (fence.get_return_rally() != 0 || fence_act == AC_FENCE_ACTION_RTL_AND_LAND) {
if (fence.get_return_rally() != 0 || fence_act == AC_Fence::Action::RTL_AND_LAND) {
loc = calc_best_rally_or_home_location(current_loc, get_RTL_altitude_cm());
} else {
//return to fence return point, not a rally point
Expand Down Expand Up @@ -126,12 +130,12 @@ void Plane::fence_check()
}
}

if (fence.get_action() != AC_FENCE_ACTION_RTL_AND_LAND) {
if (static_cast<AC_Fence::Action>(fence.get_action()) != AC_Fence::Action::RTL_AND_LAND) {
setup_terrain_target_alt(loc);
set_guided_WP(loc);
}

if (fence.get_action() == AC_FENCE_ACTION_GUIDED_THROTTLE_PASS) {
if (static_cast<AC_Fence::Action>(fence.get_action()) == AC_Fence::Action::GUIDED_THROTTLE_PASS) {
guided_throttle_passthru = true;
}
break;
Expand Down
2 changes: 1 addition & 1 deletion ArduSub/fence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ void Sub::fence_check()
if (new_breaches) {

// if the user wants some kind of response and motors are armed
if (fence.get_action() != AC_FENCE_ACTION_REPORT_ONLY) {
if (static_cast<AC_Fence::Action>(fence.get_action()) != 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 Down
4 changes: 2 additions & 2 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -1523,7 +1523,7 @@ def FenceStatic(self):
# test a rather unfortunate behaviour:
self.progress("Killing a live fence with fence-clear")
self.load_fence("CMAC-fence.txt")
self.set_parameter("FENCE_ACTION", 1) # AC_FENCE_ACTION_RTL_AND_LAND == 1. mavutil.mavlink.FENCE_ACTION_RTL == 4
self.set_parameter("FENCE_ACTION", 1) # AC_Fence::Action::RTL_AND_LAND == 1. mavutil.mavlink.FENCE_ACTION_RTL == 4
self.do_fence_enable()
self.assert_fence_sys_status(True, True, True)
self.clear_fence()
Expand Down Expand Up @@ -1602,7 +1602,7 @@ def test_fence_breach_circle_at(self, loc, disable_on_breach=False):
self.set_parameters({
"RTL_RADIUS": want_radius,
"NAVL1_LIM_BANK": 60,
"FENCE_ACTION": 1, # AC_FENCE_ACTION_RTL_AND_LAND == 1. mavutil.mavlink.FENCE_ACTION_RTL == 4
"FENCE_ACTION": 1, # AC_Fence::Action::RTL_AND_LAND == 1. mavutil.mavlink.FENCE_ACTION_RTL == 4
})

self.wait_ready_to_arm() # need an origin to load fence
Expand Down
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 (static_cast<AC_Fence::Action>(static_cast<uint8_t>(_action)) == AC_Fence::Action::REPORT_ONLY) {
return false;
}
// Fence is only enabled when the flag is enabled
Expand Down
23 changes: 13 additions & 10 deletions libraries/AC_Fence/AC_Fence.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,16 +19,6 @@
#define AC_FENCE_ARMING_FENCES (AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON)
#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

// 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 All @@ -52,6 +42,19 @@ class AC_Fence
DISABLE_ALT_MIN_FENCE = 2
};

// valid actions should a fence be breached
enum class 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
};

AC_Fence();

/* Do not allow copies */
Expand Down
Loading