mirror of https://github.com/ArduPilot/ardupilot
GCS_Failsafe: option to trigger only in AUTO mode.
This commit is contained in:
parent
39797529fd
commit
19aa7caad0
|
@ -487,7 +487,11 @@ void Plane::check_long_failsafe()
|
|||
if (failsafe.state == FAILSAFE_SHORT &&
|
||||
(tnow - failsafe.ch3_timer_ms) > g.long_fs_timeout*1000) {
|
||||
failsafe_long_on_event(FAILSAFE_LONG);
|
||||
} else if (g.gcs_heartbeat_fs_enabled != GCS_FAILSAFE_OFF &&
|
||||
} 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) {
|
||||
failsafe_long_on_event(FAILSAFE_GCS);
|
||||
} 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) {
|
||||
failsafe_long_on_event(FAILSAFE_GCS);
|
||||
|
|
Loading…
Reference in New Issue