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

Conversation

muramura
Copy link
Contributor

Change AC_FENCE_ACTION to an ENUM.
Using an ENUM allows for grouping actions.
I believe using an ENUM is better than indicating groups with define names.

@muramura muramura changed the title Fence: Change ac fence action to an enum Fence: Change AC_FENCE_ACTION to an enum Sep 11, 2024
#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 {
Copy link
Contributor

Choose a reason for hiding this comment

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

Move this into the fence class, and rename it to Action.

@Ryanf55
Copy link
Collaborator

Ryanf55 commented Sep 12, 2024

I like this kind of PR. Any motive for mixing of c-style cast and static cast?

@muramura muramura force-pushed the AP_Change_AC_FENCE_ACTION_to_an_ENUM branch from 83aaeb7 to f4f02dd Compare September 12, 2024 15:45
@muramura
Copy link
Contributor Author

@Ryanf55 san. I changed it to static_cast.

@muramura muramura force-pushed the AP_Change_AC_FENCE_ACTION_to_an_ENUM branch from f4f02dd to 2a7c15e Compare September 12, 2024 16:53
Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

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

I like this a lot.

Please state what testing it has had.

@@ -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());

@@ -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?

@peterbarker
Copy link
Contributor

Ping @muramura don't forget this one

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants