mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_GPS: reset _fix_count to 0 on nav settings update
this makes it run every 20s exactly
This commit is contained in:
parent
879d44f930
commit
5484b97419
@ -303,6 +303,7 @@ AP_GPS_UBLOX::_parse_gps(void)
|
|||||||
// ask for nav settings every 20 seconds
|
// ask for nav settings every 20 seconds
|
||||||
Debug("Asking for engine setting\n");
|
Debug("Asking for engine setting\n");
|
||||||
_send_message(CLASS_CFG, MSG_CFG_NAV_SETTINGS, NULL, 0);
|
_send_message(CLASS_CFG, MSG_CFG_NAV_SETTINGS, NULL, 0);
|
||||||
|
_fix_count = 0;
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user