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:
Andrew Tridgell 2022-01-03 15:30:34 +11:00 committed by Randy Mackay
parent 1cad8ffddc
commit da52e6fb74
1 changed files with 1 additions and 1 deletions

View File

@ -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
{
// always enusre a lag is provided
lag_sec = 0.22f;
lag_sec = 0.1f;
if (instance >= GPS_MAX_INSTANCES) {
return false;