Browse Source

AP_GPS: drop default GPS lag to 0.1s

this impacts UAVCAN GPS modules, which these days usually have at
least u-blox M8
gps-1.3.1
Andrew Tridgell 3 years ago
parent
commit
09cd7558c3
  1. 2
      libraries/AP_GPS/AP_GPS.cpp

2
libraries/AP_GPS/AP_GPS.cpp

@ -1469,7 +1469,7 @@ void AP_GPS::Write_AP_Logger_Log_Startup_messages() @@ -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;

Loading…
Cancel
Save