From 065cb2decb32dd77d7150b264ebe74ecc0bc1b9f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 5 Nov 2021 13:48:57 +1100 Subject: [PATCH] AP_GPS_UBLOX: tidy reading of uart data Neither of the return types used for data and numc were actually correct for the values being returned from the uartdriver functions. --- libraries/AP_GPS/AP_GPS_UBLOX.cpp | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 6845696c09..7fd64ad1e6 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -550,8 +550,6 @@ AP_GPS_UBLOX::_request_port(void) bool AP_GPS_UBLOX::read(void) { - uint8_t data; - int16_t numc; bool parsed = false; uint32_t millis_now = AP_HAL::millis(); @@ -580,11 +578,15 @@ AP_GPS_UBLOX::read(void) } } - numc = port->available(); - for (int16_t i = 0; i < numc; i++) { // Process bytes received + const uint16_t numc = MIN(port->available(), 8192U); + for (uint16_t i = 0; i < numc; i++) { // Process bytes received // read the next byte - data = port->read(); + const int16_t rdata = port->read(); + if (rdata < 0) { + break; + } + const uint8_t data = rdata; #if GPS_MOVING_BASELINE if (rtcm3_parser) {