mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS: have AP_GPS_UBLOX use boolean uart read
This commit is contained in:
parent
49d7d0b1c4
commit
53115c73f9
@ -594,11 +594,10 @@ AP_GPS_UBLOX::read(void)
|
||||
for (uint16_t i = 0; i < numc; i++) { // Process bytes received
|
||||
|
||||
// read the next byte
|
||||
const int16_t rdata = port->read();
|
||||
if (rdata < 0) {
|
||||
uint8_t data;
|
||||
if (!port->read(data)) {
|
||||
break;
|
||||
}
|
||||
const uint8_t data = rdata;
|
||||
#if AP_GPS_DEBUG_LOGGING_ENABLED
|
||||
log_data(&data, 1);
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user