Browse Source

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.
mission-4.1.18
Andrew Tridgell 5 years ago committed by WickedShell
parent
commit
b5217412f9
  1. 4
      libraries/AP_GPS/AP_GPS_UBLOX.cpp

4
libraries/AP_GPS/AP_GPS_UBLOX.cpp

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

Loading…
Cancel
Save