mirror of https://github.com/ArduPilot/ardupilot
Blimp: add temporary GCS FS behavior of disarming Blimp
This commit is contained in:
parent
a01ca35939
commit
875f3f7d97
|
@ -120,7 +120,7 @@ void Blimp::failsafe_gcs_check()
|
|||
} else if (last_gcs_update_ms > gcs_timeout_ms && !failsafe.gcs) {
|
||||
// New GCS failsafe event, trigger events
|
||||
set_failsafe_gcs(true);
|
||||
// failsafe_gcs_on_event();
|
||||
arming.disarm(AP_Arming::Method::GCSFAILSAFE); // failsafe_gcs_on_event() should replace this when written
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -174,4 +174,4 @@ void Blimp::gpsglitch_check()
|
|||
gcs().send_text(MAV_SEVERITY_CRITICAL,"GPS Glitch cleared");
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue