Plane: failsafe events to use enums instead of magical numbers : Non-functional change
This commit is contained in:
parent
103e2cc711
commit
512b327cd4
@ -35,7 +35,7 @@ bool AP_Arming_Plane::pre_arm_checks(bool report)
|
||||
// Check airspeed sensor
|
||||
ret &= AP_Arming::airspeed_checks(report);
|
||||
|
||||
if (plane.g.long_fs_timeout < plane.g.short_fs_timeout && plane.g.short_fs_action != SHORT_FS_ACTION_DISABLED) {
|
||||
if (plane.g.fs_timeout_long < plane.g.fs_timeout_short && plane.g.fs_action_short != FS_ACTION_SHORT_DISABLED) {
|
||||
if (report) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: FS_LONG_TIMEOUT < FS_SHORT_TIMEOUT");
|
||||
}
|
||||
|
@ -684,7 +684,7 @@ void Plane::update_flight_mode(void)
|
||||
if (fly_inverted()) {
|
||||
nav_pitch_cd = -nav_pitch_cd;
|
||||
}
|
||||
if (failsafe.rc_failsafe && g.short_fs_action == 2) {
|
||||
if (failsafe.rc_failsafe && g.fs_action_short == FS_ACTION_SHORT_FBWA) {
|
||||
// FBWA failsafe glide
|
||||
nav_roll_cd = 0;
|
||||
nav_pitch_cd = 0;
|
||||
|
@ -49,7 +49,7 @@ bool Plane::stick_mixing_enabled(void)
|
||||
}
|
||||
}
|
||||
|
||||
if (failsafe.rc_failsafe && g.short_fs_action == 2) {
|
||||
if (failsafe.rc_failsafe && g.fs_action_short == FS_ACTION_SHORT_FBWA) {
|
||||
// don't do stick mixing in FBWA glide mode
|
||||
return false;
|
||||
}
|
||||
|
@ -503,7 +503,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Description: The action to take on a short (FS_SHORT_TIMEOUT) failsafe event. A short failsafe even can be triggered either by loss of RC control (see THR_FS_VALUE) or by loss of GCS control (see FS_GCS_ENABL). If in CIRCLE or RTL mode this parameter is ignored. A short failsafe event in stabilization and manual modes will cause an change to CIRCLE mode if FS_SHORT_ACTN is 0 or 1, and a change to FBWA mode if FS_SHORT_ACTN is 2. In all other modes (AUTO, GUIDED and LOITER) a short failsafe event will cause no mode change is FS_SHORT_ACTN is set to 0, will cause a change to CIRCLE mode if set to 1 and will change to FBWA mode if set to 2. Please see the documentation for FS_LONG_ACTN for the behaviour after FS_LONG_TIMEOUT seconds of failsafe.
|
||||
// @Values: 0:CIRCLE/no change(if already in AUTO|GUIDED|LOITER),1:CIRCLE,2:FBWA,3:Disable
|
||||
// @User: Standard
|
||||
GSCALAR(short_fs_action, "FS_SHORT_ACTN", 0),
|
||||
GSCALAR(fs_action_short, "FS_SHORT_ACTN", FS_ACTION_SHORT_BESTGUESS),
|
||||
|
||||
// @Param: FS_SHORT_TIMEOUT
|
||||
// @DisplayName: Short failsafe timeout
|
||||
@ -512,14 +512,14 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Range: 1 100
|
||||
// @Increment: 0.5
|
||||
// @User: Standard
|
||||
GSCALAR(short_fs_timeout, "FS_SHORT_TIMEOUT", 1.5f),
|
||||
GSCALAR(fs_timeout_short, "FS_SHORT_TIMEOUT", 1.5f),
|
||||
|
||||
// @Param: FS_LONG_ACTN
|
||||
// @DisplayName: Long failsafe action
|
||||
// @Description: The action to take on a long (FS_LONG_TIMEOUT seconds) failsafe event. If the aircraft was in a stabilization or manual mode when failsafe started and a long failsafe occurs then it will change to RTL mode if FS_LONG_ACTN is 0 or 1, and will change to FBWA if FS_LONG_ACTN is set to 2. If the aircraft was in an auto mode (such as AUTO or GUIDED) when the failsafe started then it will continue in the auto mode if FS_LONG_ACTN is set to 0, will change to RTL mode if FS_LONG_ACTN is set to 1 and will change to FBWA mode if FS_LONG_ACTN is set to 2. If FS_LONG_ACTION is set to 3, the parachute will be deployed (make sure the chute is configured and enabled).
|
||||
// @Values: 0:Continue,1:ReturnToLaunch,2:Glide,3:Deploy Parachute
|
||||
// @User: Standard
|
||||
GSCALAR(long_fs_action, "FS_LONG_ACTN", 0),
|
||||
GSCALAR(fs_action_long, "FS_LONG_ACTN", FS_ACTION_LONG_CONTINUE),
|
||||
|
||||
// @Param: FS_LONG_TIMEOUT
|
||||
// @DisplayName: Long failsafe timeout
|
||||
@ -528,7 +528,7 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Range: 1 300
|
||||
// @Increment: 0.5
|
||||
// @User: Standard
|
||||
GSCALAR(long_fs_timeout, "FS_LONG_TIMEOUT", 5),
|
||||
GSCALAR(fs_timeout_long, "FS_LONG_TIMEOUT", 5),
|
||||
|
||||
// @Param: FS_BATT_VOLTAGE
|
||||
// @DisplayName: Failsafe battery voltage
|
||||
|
@ -265,8 +265,8 @@ public:
|
||||
k_param_throttle_fs_value,
|
||||
k_param_throttle_cruise,
|
||||
|
||||
k_param_short_fs_action,
|
||||
k_param_long_fs_action,
|
||||
k_param_fs_action_short,
|
||||
k_param_fs_action_long,
|
||||
k_param_gcs_heartbeat_fs_enabled,
|
||||
k_param_throttle_slewrate,
|
||||
k_param_throttle_suppress_manual,
|
||||
@ -274,8 +274,8 @@ public:
|
||||
k_param_rc_12_old,
|
||||
k_param_fs_batt_voltage,
|
||||
k_param_fs_batt_mah,
|
||||
k_param_short_fs_timeout,
|
||||
k_param_long_fs_timeout,
|
||||
k_param_fs_timeout_short,
|
||||
k_param_fs_timeout_long,
|
||||
k_param_rc_13_old,
|
||||
k_param_rc_14_old,
|
||||
k_param_tuning,
|
||||
@ -425,10 +425,10 @@ public:
|
||||
AP_Int16 use_reverse_thrust;
|
||||
|
||||
// Failsafe
|
||||
AP_Int8 short_fs_action;
|
||||
AP_Int8 long_fs_action;
|
||||
AP_Float short_fs_timeout;
|
||||
AP_Float long_fs_timeout;
|
||||
AP_Int8 fs_action_short;
|
||||
AP_Int8 fs_action_long;
|
||||
AP_Float fs_timeout_short;
|
||||
AP_Float fs_timeout_long;
|
||||
AP_Int8 gcs_heartbeat_fs_enabled;
|
||||
AP_Float fs_batt_voltage;
|
||||
AP_Float fs_batt_mah;
|
||||
|
@ -323,16 +323,16 @@ private:
|
||||
struct {
|
||||
// Used to track if the value on channel 3 (throtttle) has fallen below the failsafe threshold
|
||||
// RC receiver should be set up to output a low throttle value when signal is lost
|
||||
uint8_t rc_failsafe:1;
|
||||
bool rc_failsafe:1;
|
||||
|
||||
// has the saved mode for failsafe been set?
|
||||
uint8_t saved_mode_set:1;
|
||||
bool saved_mode_set:1;
|
||||
|
||||
// flag to hold whether battery low voltage threshold has been breached
|
||||
uint8_t low_battery:1;
|
||||
bool low_battery:1;
|
||||
|
||||
// true if an adsb related failsafe has occurred
|
||||
uint8_t adsb:1;
|
||||
bool adsb:1;
|
||||
|
||||
// saved flight mode
|
||||
enum FlightMode saved_mode;
|
||||
|
@ -31,11 +31,18 @@ enum gcs_failsafe {
|
||||
// while in AUTO mode
|
||||
};
|
||||
|
||||
enum short_failsafe_action {
|
||||
SHORT_FS_ACTION_BESTGUESS = 0,
|
||||
SHORT_FS_ACTION_CIRCLE = 1,
|
||||
SHORT_FS_ACTION_FBWA = 2,
|
||||
SHORT_FS_ACTION_DISABLED = 3,
|
||||
enum failsafe_action_short {
|
||||
FS_ACTION_SHORT_BESTGUESS = 0, // CIRCLE/no change(if already in AUTO|GUIDED|LOITER)
|
||||
FS_ACTION_SHORT_CIRCLE = 1,
|
||||
FS_ACTION_SHORT_FBWA = 2,
|
||||
FS_ACTION_SHORT_DISABLED = 3,
|
||||
};
|
||||
|
||||
enum failsafe_action_long {
|
||||
FS_ACTION_LONG_CONTINUE = 0,
|
||||
FS_ACTION_LONG_RTL = 1,
|
||||
FS_ACTION_LONG_GLIDE = 2,
|
||||
FS_ACTION_LONG_PARACHUTE = 3,
|
||||
};
|
||||
|
||||
enum FlightMode {
|
||||
|
@ -17,8 +17,8 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, mode_reason_t re
|
||||
case CRUISE:
|
||||
case TRAINING:
|
||||
failsafe.saved_mode = control_mode;
|
||||
failsafe.saved_mode_set = 1;
|
||||
if(g.short_fs_action == 2) {
|
||||
failsafe.saved_mode_set = true;
|
||||
if(g.fs_action_short == FS_ACTION_SHORT_FBWA) {
|
||||
set_mode(FLY_BY_WIRE_A, reason);
|
||||
} else {
|
||||
set_mode(CIRCLE, reason);
|
||||
@ -29,7 +29,7 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, mode_reason_t re
|
||||
case QLOITER:
|
||||
case QHOVER:
|
||||
failsafe.saved_mode = control_mode;
|
||||
failsafe.saved_mode_set = 1;
|
||||
failsafe.saved_mode_set = true;
|
||||
set_mode(QLAND, reason);
|
||||
break;
|
||||
|
||||
@ -37,10 +37,10 @@ void Plane::failsafe_short_on_event(enum failsafe_state fstype, mode_reason_t re
|
||||
case AVOID_ADSB:
|
||||
case GUIDED:
|
||||
case LOITER:
|
||||
if(g.short_fs_action != 0) {
|
||||
if(g.fs_action_short != FS_ACTION_SHORT_BESTGUESS) {
|
||||
failsafe.saved_mode = control_mode;
|
||||
failsafe.saved_mode_set = 1;
|
||||
if(g.short_fs_action == 2) {
|
||||
failsafe.saved_mode_set = true;
|
||||
if(g.fs_action_short == FS_ACTION_SHORT_FBWA) {
|
||||
set_mode(FLY_BY_WIRE_A, reason);
|
||||
} else {
|
||||
set_mode(CIRCLE, reason);
|
||||
@ -76,11 +76,11 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, mode_reason_t rea
|
||||
case CRUISE:
|
||||
case TRAINING:
|
||||
case CIRCLE:
|
||||
if(g.long_fs_action == 3) {
|
||||
if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) {
|
||||
#if PARACHUTE == ENABLED
|
||||
parachute_release();
|
||||
#endif
|
||||
} else if (g.long_fs_action == 2) {
|
||||
} else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) {
|
||||
set_mode(FLY_BY_WIRE_A, reason);
|
||||
} else {
|
||||
set_mode(RTL, reason);
|
||||
@ -97,13 +97,13 @@ void Plane::failsafe_long_on_event(enum failsafe_state fstype, mode_reason_t rea
|
||||
case AVOID_ADSB:
|
||||
case GUIDED:
|
||||
case LOITER:
|
||||
if(g.long_fs_action == 3) {
|
||||
if(g.fs_action_long == FS_ACTION_LONG_PARACHUTE) {
|
||||
#if PARACHUTE == ENABLED
|
||||
parachute_release();
|
||||
#endif
|
||||
} else if (g.long_fs_action == 2) {
|
||||
} else if (g.fs_action_long == FS_ACTION_LONG_GLIDE) {
|
||||
set_mode(FLY_BY_WIRE_A, reason);
|
||||
} else if (g.long_fs_action == 1) {
|
||||
} else if (g.fs_action_long == FS_ACTION_LONG_RTL) {
|
||||
set_mode(RTL, reason);
|
||||
}
|
||||
break;
|
||||
@ -126,7 +126,7 @@ void Plane::failsafe_short_off_event(mode_reason_t reason)
|
||||
// re-read the switch so we can return to our preferred mode
|
||||
// --------------------------------------------------------
|
||||
if (control_mode == CIRCLE && failsafe.saved_mode_set) {
|
||||
failsafe.saved_mode_set = 0;
|
||||
failsafe.saved_mode_set = false;
|
||||
set_mode(failsafe.saved_mode, reason);
|
||||
}
|
||||
}
|
||||
|
@ -488,26 +488,26 @@ void Plane::check_long_failsafe()
|
||||
radio_timeout_ms = failsafe.short_timer_ms;
|
||||
}
|
||||
if (failsafe.rc_failsafe &&
|
||||
(tnow - radio_timeout_ms) > g.long_fs_timeout*1000) {
|
||||
(tnow - radio_timeout_ms) > g.fs_timeout_long*1000) {
|
||||
failsafe_long_on_event(FAILSAFE_LONG, MODE_REASON_RADIO_FAILSAFE);
|
||||
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HB_AUTO && control_mode == AUTO &&
|
||||
failsafe.last_heartbeat_ms != 0 &&
|
||||
(tnow - failsafe.last_heartbeat_ms) > g.long_fs_timeout*1000) {
|
||||
(tnow - failsafe.last_heartbeat_ms) > g.fs_timeout_long*1000) {
|
||||
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);
|
||||
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HEARTBEAT &&
|
||||
failsafe.last_heartbeat_ms != 0 &&
|
||||
(tnow - failsafe.last_heartbeat_ms) > g.long_fs_timeout*1000) {
|
||||
(tnow - failsafe.last_heartbeat_ms) > g.fs_timeout_long*1000) {
|
||||
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);
|
||||
} else if (g.gcs_heartbeat_fs_enabled == GCS_FAILSAFE_HB_RSSI &&
|
||||
gcs().chan(0).last_radio_status_remrssi_ms != 0 &&
|
||||
(tnow - gcs().chan(0).last_radio_status_remrssi_ms) > g.long_fs_timeout*1000) {
|
||||
(tnow - gcs().chan(0).last_radio_status_remrssi_ms) > g.fs_timeout_long*1000) {
|
||||
failsafe_long_on_event(FAILSAFE_GCS, MODE_REASON_GCS_FAILSAFE);
|
||||
}
|
||||
} else {
|
||||
uint32_t timeout_seconds = g.long_fs_timeout;
|
||||
if (g.short_fs_action != SHORT_FS_ACTION_DISABLED) {
|
||||
uint32_t timeout_seconds = g.fs_timeout_long;
|
||||
if (g.fs_action_short != FS_ACTION_SHORT_DISABLED) {
|
||||
// avoid dropping back into short timeout
|
||||
timeout_seconds = g.short_fs_timeout;
|
||||
timeout_seconds = g.fs_timeout_short;
|
||||
}
|
||||
// We do not change state but allow for user to change mode
|
||||
if (failsafe.state == FAILSAFE_GCS &&
|
||||
@ -524,7 +524,7 @@ void Plane::check_short_failsafe()
|
||||
{
|
||||
// only act on changes
|
||||
// -------------------
|
||||
if (g.short_fs_action != SHORT_FS_ACTION_DISABLED &&
|
||||
if (g.fs_action_short != FS_ACTION_SHORT_DISABLED &&
|
||||
failsafe.state == FAILSAFE_NONE &&
|
||||
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
||||
// The condition is checked and the flag rc_failsafe is set in radio.cpp
|
||||
@ -534,7 +534,7 @@ void Plane::check_short_failsafe()
|
||||
}
|
||||
|
||||
if(failsafe.state == FAILSAFE_SHORT) {
|
||||
if(!failsafe.rc_failsafe || g.short_fs_action == SHORT_FS_ACTION_DISABLED) {
|
||||
if(!failsafe.rc_failsafe || g.fs_action_short == FS_ACTION_SHORT_DISABLED) {
|
||||
failsafe_short_off_event(MODE_REASON_RADIO_FAILSAFE);
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user