Browse Source

AP_GPS: With a ublox driver, accept a packet if it will fit in the buffer

mission-4.1.18
Michael du Breuil 10 years ago committed by Andrew Tridgell
parent
commit
09fef505e0
  1. 4
      libraries/AP_GPS/AP_GPS_UBLOX.cpp

4
libraries/AP_GPS/AP_GPS_UBLOX.cpp

@ -229,9 +229,9 @@ AP_GPS_UBLOX::read(void) @@ -229,9 +229,9 @@ AP_GPS_UBLOX::read(void)
_ck_b += (_ck_a += data); // checksum byte
_payload_length += (uint16_t)(data<<8);
if (_payload_length > 512) {
if (_payload_length > sizeof(_buffer)) {
Debug("large payload %u", (unsigned)_payload_length);
// assume very large payloads are line noise
// assume any payload bigger then what we know about is noise
_payload_length = 0;
_step = 0;
goto reset;

Loading…
Cancel
Save