AP_GPS: fixed a bug in handling corrupt u-blox packets

when we have corrupt input due to loss of bytes on a UART we can end
up with a u-blox packet with zero payload bytes. When that happens we
need to bypass payload reading as otherwise we will end up keeping
reading bytes until the driver resets at 4 seconds, causing a GPS
outage.

This was causing GPS outages every few hours in copters running 3.6.7,
and was also reproduced in SITL using SIM_GPS_BYTELOSS.
This commit is contained in:
Andrew Tridgell 2019-09-26 21:14:41 +10:00 committed by WickedShell
parent 356e9f116d
commit b5217412f9
1 changed files with 4 additions and 0 deletions

View File

@ -467,6 +467,10 @@ AP_GPS_UBLOX::read(void)
goto reset;
}
_payload_counter = 0; // prepare to receive payload
if (_payload_length == 0) {
// bypass payload and go straight to checksum
_step++;
}
break;
// Receive message data