mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 18:08:30 -04:00
Copter: gps failsafe disabled until we get first 3d lock
This commit is contained in:
parent
f29f7d9777
commit
13fd33c2d8
@ -137,8 +137,8 @@ static void failsafe_gps_check()
|
|||||||
{
|
{
|
||||||
uint32_t last_gps_update_ms;
|
uint32_t last_gps_update_ms;
|
||||||
|
|
||||||
// return immediately if gps failsafe is disabled
|
// return immediately if gps failsafe is disabled or we have never had GPS lock
|
||||||
if( !g.failsafe_gps_enabled ) {
|
if (!g.failsafe_gps_enabled || !ap.home_is_set) {
|
||||||
// if we have just disabled the gps failsafe, ensure the gps failsafe event is cleared
|
// if we have just disabled the gps failsafe, ensure the gps failsafe event is cleared
|
||||||
if (failsafe.gps) {
|
if (failsafe.gps) {
|
||||||
failsafe_gps_off_event();
|
failsafe_gps_off_event();
|
||||||
|
Loading…
Reference in New Issue
Block a user