AP_AIS: correct number of bytes to read from device

This commit is contained in:
Peter Barker 2021-12-20 19:08:33 +11:00 committed by Randy Mackay
parent a9c78fe7e3
commit f6fa676411

View File

@ -89,7 +89,7 @@ void AP_AIS::update()
} }
// read any available lines // read any available lines
uint32_t nbytes = MAX(_uart->available(),1024U); uint32_t nbytes = MIN(_uart->available(),1024U);
while (nbytes-- > 0) { while (nbytes-- > 0) {
const int16_t byte = _uart->read(); const int16_t byte = _uart->read();
if (byte == -1) { if (byte == -1) {