Browse Source

Copter: GCS Failsafe to trigger if using Guided mode

master
Robert Lefebvre 10 years ago committed by Randy Mackay
parent
commit
5f19a43104
  1. 5
      ArduCopter/events.pde

5
ArduCopter/events.pde

@ -230,8 +230,9 @@ static void failsafe_gcs_check() @@ -230,8 +230,9 @@ static void failsafe_gcs_check()
{
uint32_t last_gcs_update_ms;
// return immediately if gcs failsafe is disabled, gcs has never been connected or we are not overriding rc controls from the gcs
if( g.failsafe_gcs == FS_GCS_DISABLED || failsafe.last_heartbeat_ms == 0 || !failsafe.rc_override_active) {
// return immediately if gcs failsafe is disabled, gcs has never been connected or we are not overriding rc controls from the gcs and we are not in guided mode
// this also checks to see if we have a GCS failsafe active, if we do, then must continue to process the logic for recovery from this state.
if((!failsafe.gcs)&&(g.failsafe_gcs == FS_GCS_DISABLED || failsafe.last_heartbeat_ms == 0 || (!failsafe.rc_override_active && control_mode != GUIDED))) {
return;
}

Loading…
Cancel
Save