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:
Peter Barker 2023-02-21 20:35:57 +11:00 committed by Peter Barker
parent 14089d4919
commit 74207ea687
1 changed files with 2 additions and 3 deletions

View File

@ -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;
}