mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_GPS_NOVA: avoid infinite reading of bytes
if we have a very fast stream of garbage coming in available() may never return 0
This commit is contained in:
parent
ac993753eb
commit
941e9785d4
@ -86,8 +86,11 @@ AP_GPS_NOVA::read(void)
|
||||
}
|
||||
|
||||
bool ret = false;
|
||||
while (port->available() > 0) {
|
||||
uint8_t temp = port->read();
|
||||
for (uint16_t i=0; i<8192; i++) {
|
||||
uint8_t temp;
|
||||
if (!port->read(temp)) {
|
||||
break;
|
||||
}
|
||||
#if AP_GPS_DEBUG_LOGGING_ENABLED
|
||||
log_data(&temp, 1);
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user