Skip to content

Commit 6fff5e5

Browse files
committed
Copter: use an enumeration for GCS FS action
1 parent 4e6c3fd commit 6fff5e5

File tree

8 files changed

+29
-25
lines changed

8 files changed

+29
-25
lines changed

ArduCopter/AP_Arming_Copter.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -213,7 +213,7 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
213213
return false;
214214
}
215215
}
216-
if (copter.g.failsafe_gcs == FS_GCS_ENABLED_CONTINUE_MISSION) {
216+
if (copter.g.failsafe_gcs == Copter::FS_GCS_Action::CONTINUE_MISSION) {
217217
// FS_GCS_ENABLE == 2 has been removed
218218
check_failed(Check::PARAMETERS, display_failure, "FS_GCS_ENABLE=2 removed, see FS_OPTIONS");
219219
}

ArduCopter/Copter.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -419,6 +419,8 @@ class Copter : public AP_Vehicle {
419419
return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb || failsafe.deadreckon;
420420
}
421421

422+
using FS_GCS_Action = Parameters::FS_GCS_Action;
423+
422424
// dead reckoning state
423425
struct {
424426
bool active; // true if dead reckoning (position estimate using estimated airspeed, no position or velocity source)

ArduCopter/Parameters.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -98,7 +98,7 @@ const AP_Param::Info Copter::var_info[] = {
9898
// @Description: Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.
9999
// @Values: 0:Disabled/NoAction,1:RTL,2:RTL or Continue with Mission in Auto Mode (Removed in 4.0+-see FS_OPTIONS),3:SmartRTL or RTL,4:SmartRTL or Land,5:Land,6:Auto DO_LAND_START/DO_RETURN_PATH_START or RTL,7:Brake or Land
100100
// @User: Standard
101-
GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", FS_GCS_DISABLED),
101+
GSCALAR(failsafe_gcs, "FS_GCS_ENABLE", static_cast<float>(FS_GCS_Action::DISABLED)),
102102

103103
// @Param: GPS_HDOP_GOOD
104104
// @DisplayName: GPS Hdop Good

ArduCopter/Parameters.h

Lines changed: 13 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -402,7 +402,19 @@ class Parameters {
402402
AP_Enum<ModeRTL::RTLAltType> rtl_alt_type;
403403
#endif
404404

405-
AP_Int8 failsafe_gcs; // ground station failsafe behavior
405+
// GCS failsafe definitions (FS_GCS_ENABLE parameter)
406+
enum class FS_GCS_Action {
407+
DISABLED = 0,
408+
ALWAYS_RTL = 1,
409+
CONTINUE_MISSION = 2, // Removed in 4.0+, now use fs_options
410+
ALWAYS_SMARTRTL_OR_RTL = 3,
411+
ALWAYS_SMARTRTL_OR_LAND = 4,
412+
ALWAYS_LAND = 5,
413+
AUTO_RTL_OR_RTL = 6,
414+
BRAKE_OR_LAND = 7,
415+
};
416+
417+
AP_Enum<FS_GCS_Action> failsafe_gcs; // ground station failsafe behavior
406418
AP_Int16 gps_hdop_good; // GPS Hdop value at or below this value represent a good position
407419

408420
AP_Int8 super_simple;

ArduCopter/defines.h

Lines changed: 0 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -124,16 +124,6 @@ enum LoggingParameters {
124124
#define FS_THR_ENABLED_AUTO_RTL_OR_RTL 6
125125
#define FS_THR_ENABLED_BRAKE_OR_LAND 7
126126

127-
// GCS failsafe definitions (FS_GCS_ENABLE parameter)
128-
#define FS_GCS_DISABLED 0
129-
#define FS_GCS_ENABLED_ALWAYS_RTL 1
130-
#define FS_GCS_ENABLED_CONTINUE_MISSION 2 // Removed in 4.0+, now use fs_options
131-
#define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL 3
132-
#define FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_LAND 4
133-
#define FS_GCS_ENABLED_ALWAYS_LAND 5
134-
#define FS_GCS_ENABLED_AUTO_RTL_OR_RTL 6
135-
#define FS_GCS_ENABLED_BRAKE_OR_LAND 7
136-
137127
// EKF failsafe definitions (FS_EKF_ACTION parameter)
138128
#define FS_EKF_ACTION_REPORT_ONLY 0
139129
#define FS_EKF_ACTION_LAND 1 // switch to LAND mode on EKF failsafe

ArduCopter/events.cpp

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -126,7 +126,7 @@ void Copter::handle_battery_failsafe(const char *type_str, const int8_t action)
126126
void Copter::failsafe_gcs_check()
127127
{
128128
// Bypass GCS failsafe checks if disabled or GCS never connected
129-
if (g.failsafe_gcs == FS_GCS_DISABLED) {
129+
if (g.failsafe_gcs == FS_GCS_Action::DISABLED) {
130130
return;
131131
}
132132

@@ -167,27 +167,27 @@ void Copter::failsafe_gcs_on_event(void)
167167

168168
// convert the desired failsafe response to the FailsafeAction enum
169169
FailsafeAction desired_action;
170-
switch (g.failsafe_gcs) {
171-
case FS_GCS_DISABLED:
170+
switch ((FS_GCS_Action)g.failsafe_gcs) {
171+
case FS_GCS_Action::DISABLED:
172172
desired_action = FailsafeAction::NONE;
173173
break;
174-
case FS_GCS_ENABLED_ALWAYS_RTL:
175-
case FS_GCS_ENABLED_CONTINUE_MISSION:
174+
case FS_GCS_Action::ALWAYS_RTL:
175+
case FS_GCS_Action::CONTINUE_MISSION:
176176
desired_action = FailsafeAction::RTL;
177177
break;
178-
case FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_RTL:
178+
case FS_GCS_Action::ALWAYS_SMARTRTL_OR_RTL:
179179
desired_action = FailsafeAction::SMARTRTL;
180180
break;
181-
case FS_GCS_ENABLED_ALWAYS_SMARTRTL_OR_LAND:
181+
case FS_GCS_Action::ALWAYS_SMARTRTL_OR_LAND:
182182
desired_action = FailsafeAction::SMARTRTL_LAND;
183183
break;
184-
case FS_GCS_ENABLED_ALWAYS_LAND:
184+
case FS_GCS_Action::ALWAYS_LAND:
185185
desired_action = FailsafeAction::LAND;
186186
break;
187-
case FS_GCS_ENABLED_AUTO_RTL_OR_RTL:
187+
case FS_GCS_Action::AUTO_RTL_OR_RTL:
188188
desired_action = FailsafeAction::AUTO_DO_LAND_START;
189189
break;
190-
case FS_GCS_ENABLED_BRAKE_OR_LAND:
190+
case FS_GCS_Action::BRAKE_OR_LAND:
191191
desired_action = FailsafeAction::BRAKE_LAND;
192192
break;
193193
default: // if an invalid parameter value is set, the fallback is RTL

ArduCopter/mode_turtle.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ void ModeTurtle::arm_motors()
5656

5757
// disable throttle and gcs failsafe
5858
g.failsafe_throttle.set(FS_THR_DISABLED);
59-
g.failsafe_gcs.set(FS_GCS_DISABLED);
59+
g.failsafe_gcs.set(Copter::FS_GCS_Action::DISABLED);
6060
g.fs_ekf_action.set(FS_EKF_ACTION_REPORT_ONLY);
6161

6262
// ensure the arming library is aware of our meddling

ArduCopter/motor_test.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -171,7 +171,7 @@ MAV_RESULT Copter::mavlink_motor_test_start(const GCS_MAVLINK &gcs_chan, uint8_t
171171

172172
// disable throttle and gps failsafe
173173
g.failsafe_throttle.set(FS_THR_DISABLED);
174-
g.failsafe_gcs.set(FS_GCS_DISABLED);
174+
g.failsafe_gcs.set(FS_GCS_Action::DISABLED);
175175
g.fs_ekf_action.set(FS_EKF_ACTION_REPORT_ONLY);
176176

177177
// turn on notify leds

0 commit comments

Comments
 (0)