mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_ExternalAHRS: add and use a "bool read(c)" method to AP_HAL
this is much less likely to not work vs the int16_t equivalent
This commit is contained in:
parent
14089d4919
commit
74207ea687
@ -111,9 +111,8 @@ void AP_ExternalAHRS_LORD::build_packet()
|
||||
WITH_SEMAPHORE(sem);
|
||||
uint32_t nbytes = MIN(uart->available(), 2048u);
|
||||
while (nbytes--> 0) {
|
||||
const int16_t b = uart->read();
|
||||
|
||||
if (b < 0) {
|
||||
uint8_t b;
|
||||
if (!uart->read(b)) {
|
||||
break;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user