Skip to content

Commit 16ea63c

Browse files
committed
Copter: ModeGuided: add an option_is_enabled method, use it
1 parent 91423d4 commit 16ea63c

File tree

2 files changed

+14
-7
lines changed

2 files changed

+14
-7
lines changed

ArduCopter/mode.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1127,7 +1127,7 @@ class ModeGuided : public Mode {
11271127
private:
11281128

11291129
// enum for GUID_OPTIONS parameter
1130-
enum class Options : int32_t {
1130+
enum class Option : int32_t {
11311131
AllowArmingFromTX = (1U << 0),
11321132
// this bit is still available, pilot yaw was mapped to bit 2 for symmetry with auto
11331133
IgnorePilotYaw = (1U << 2),
@@ -1138,6 +1138,8 @@ class ModeGuided : public Mode {
11381138
AllowWeatherVaning = (1U << 7)
11391139
};
11401140

1141+
bool option_is_enabled(Option option) const;
1142+
11411143
// wp controller
11421144
void wp_control_start();
11431145
void wp_control_run();

ArduCopter/mode_guided.cpp

Lines changed: 11 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -97,6 +97,11 @@ void ModeGuided::run()
9797
}
9898
}
9999

100+
bool ModeGuided::option_is_enabled() const
101+
{
102+
return copter.g2.guided_options.get() & (uint32_t)option) != 0;
103+
}
104+
100105
bool ModeGuided::allows_arming(AP_Arming::Method method) const
101106
{
102107
// always allow arming from the ground station or scripting
@@ -105,13 +110,13 @@ bool ModeGuided::allows_arming(AP_Arming::Method method) const
105110
}
106111

107112
// optionally allow arming from the transmitter
108-
return (copter.g2.guided_options & (uint32_t)Options::AllowArmingFromTX) != 0;
113+
return option_is_enabled(Option::AllowArmingFromTX);
109114
};
110115

111116
#if WEATHERVANE_ENABLED == ENABLED
112117
bool ModeGuided::allows_weathervaning() const
113118
{
114-
return (copter.g2.guided_options.get() & (uint32_t)Options::AllowWeatherVaning) != 0;
119+
return option_is_enabled(Option::AllowWeatherVaning);
115120
}
116121
#endif
117122

@@ -607,25 +612,25 @@ bool ModeGuided::set_destination_posvelaccel(const Vector3f& destination, const
607612
// returns true if GUIDED_OPTIONS param suggests SET_ATTITUDE_TARGET's "thrust" field should be interpreted as thrust instead of climb rate
608613
bool ModeGuided::set_attitude_target_provides_thrust() const
609614
{
610-
return ((copter.g2.guided_options.get() & uint32_t(Options::SetAttitudeTarget_ThrustAsThrust)) != 0);
615+
return option_is_enabled(Option::SetAttitudeTarget_ThrustAsThrust);
611616
}
612617

613618
// returns true if GUIDED_OPTIONS param specifies position should be controlled (when velocity and/or acceleration control is active)
614619
bool ModeGuided::stabilizing_pos_xy() const
615620
{
616-
return !((copter.g2.guided_options.get() & uint32_t(Options::DoNotStabilizePositionXY)) != 0);
621+
return !option_is_enabled(Option::DoNotStabilizePositionXY);
617622
}
618623

619624
// returns true if GUIDED_OPTIONS param specifies velocity should be controlled (when acceleration control is active)
620625
bool ModeGuided::stabilizing_vel_xy() const
621626
{
622-
return !((copter.g2.guided_options.get() & uint32_t(Options::DoNotStabilizeVelocityXY)) != 0);
627+
return !option_is_enabled(Option::DoNotStabilizeVelocityXY);
623628
}
624629

625630
// returns true if GUIDED_OPTIONS param specifies waypoint navigation should be used for position control (allow path planning to be used but updates must be slower)
626631
bool ModeGuided::use_wpnav_for_position_control() const
627632
{
628-
return ((copter.g2.guided_options.get() & uint32_t(Options::WPNavUsedForPosControl)) != 0);
633+
return option_is_enabled(Option::WPNavUsedForPosControl);
629634
}
630635

631636
// Sets guided's angular target submode: Using a rotation quaternion, angular velocity, and climbrate or thrust (depends on user option)

0 commit comments

Comments
 (0)