From 09cd7558c3ada5bdc96261b863fd4f905d8225c0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 3 Jan 2022 15:30:34 +1100 Subject: [PATCH] AP_GPS: drop default GPS lag to 0.1s this impacts UAVCAN GPS modules, which these days usually have at least u-blox M8 --- libraries/AP_GPS/AP_GPS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 431af2e12c..8cfb06cae5 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -1469,7 +1469,7 @@ void AP_GPS::Write_AP_Logger_Log_Startup_messages() bool AP_GPS::get_lag(uint8_t instance, float &lag_sec) const { // always enusre a lag is provided - lag_sec = 0.22f; + lag_sec = 0.1f; if (instance >= GPS_MAX_INSTANCES) { return false;