mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: drop default GPS lag to 0.1s
this impacts UAVCAN GPS modules, which these days usually have at least u-blox M8
This commit is contained in:
parent
b7d31b6289
commit
8df5723362
@ -1410,7 +1410,7 @@ void AP_GPS::Write_AP_Logger_Log_Startup_messages()
|
|||||||
bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const
|
bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const
|
||||||
{
|
{
|
||||||
// always enusre a lag is provided
|
// always enusre a lag is provided
|
||||||
lag_sec = 0.22f;
|
lag_sec = 0.1f;
|
||||||
|
|
||||||
if (instance >= GPS_MAX_INSTANCES) {
|
if (instance >= GPS_MAX_INSTANCES) {
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user