Skip to content

Commit

Permalink
Plane: 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 40a6766 commit 93126b2
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 18 deletions.
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());
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

0 comments on commit 93126b2

Please sign in to comment.