mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Plane: add option to entirely disable short failsafe
This commit is contained in:
parent
c7c2c4ff2c
commit
01d8c506d2
@ -31,6 +31,12 @@ 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 FlightMode {
|
||||
MANUAL = 0,
|
||||
|
@ -479,8 +479,13 @@ void Plane::check_long_failsafe()
|
||||
// only act on changes
|
||||
// -------------------
|
||||
if (failsafe.state != FAILSAFE_LONG && failsafe.state != FAILSAFE_GCS && flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
||||
if (failsafe.state == FAILSAFE_SHORT &&
|
||||
(tnow - failsafe.ch3_timer_ms) > g.long_fs_timeout*1000) {
|
||||
uint32_t radio_timeout_ms = failsafe.last_valid_rc_ms;
|
||||
if (g.short_fs_action != SHORT_FS_ACTION_DISABLED) {
|
||||
// time is relative to when short failsafe enabled
|
||||
radio_timeout_ms = failsafe.ch3_timer_ms;
|
||||
}
|
||||
if (failsafe.ch3_failsafe &&
|
||||
(tnow - radio_timeout_ms) > g.long_fs_timeout*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 &&
|
||||
@ -496,9 +501,14 @@ void Plane::check_long_failsafe()
|
||||
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) {
|
||||
// avoid dropping back into short timeout
|
||||
timeout_seconds = g.short_fs_timeout;
|
||||
}
|
||||
// We do not change state but allow for user to change mode
|
||||
if (failsafe.state == FAILSAFE_GCS &&
|
||||
(tnow - failsafe.last_heartbeat_ms) < g.short_fs_timeout*1000) {
|
||||
(tnow - failsafe.last_heartbeat_ms) < timeout_seconds*1000) {
|
||||
failsafe.state = FAILSAFE_NONE;
|
||||
} else if (failsafe.state == FAILSAFE_LONG &&
|
||||
!failsafe.ch3_failsafe) {
|
||||
@ -511,7 +521,9 @@ void Plane::check_short_failsafe()
|
||||
{
|
||||
// only act on changes
|
||||
// -------------------
|
||||
if(failsafe.state == FAILSAFE_NONE && flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
||||
if (g.short_fs_action != SHORT_FS_ACTION_DISABLED &&
|
||||
failsafe.state == FAILSAFE_NONE &&
|
||||
flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
||||
// The condition is checked and the flag ch3_failsafe is set in radio.cpp
|
||||
if(failsafe.ch3_failsafe) {
|
||||
failsafe_short_on_event(FAILSAFE_SHORT, MODE_REASON_RADIO_FAILSAFE);
|
||||
@ -519,7 +531,7 @@ void Plane::check_short_failsafe()
|
||||
}
|
||||
|
||||
if(failsafe.state == FAILSAFE_SHORT) {
|
||||
if(!failsafe.ch3_failsafe) {
|
||||
if(!failsafe.ch3_failsafe || g.short_fs_action == SHORT_FS_ACTION_DISABLED) {
|
||||
failsafe_short_off_event(MODE_REASON_RADIO_FAILSAFE);
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user