mirror of https://github.com/ArduPilot/ardupilot
Rover: honor the FS_GCS_ENABLE parameter
GCS failsafe was always enabled
This commit is contained in:
parent
d16587340d
commit
df66dc1889
|
@ -690,7 +690,9 @@ static void mount_update(void)
|
|||
*/
|
||||
static void failsafe_check(void)
|
||||
{
|
||||
failsafe_trigger(FAILSAFE_EVENT_GCS, last_heartbeat_ms != 0 && (millis() - last_heartbeat_ms) > 2000);
|
||||
if (g.fs_gcs_enable) {
|
||||
failsafe_trigger(FAILSAFE_EVENT_GCS, last_heartbeat_ms != 0 && (millis() - last_heartbeat_ms) > 2000);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue