5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-09 01:18:29 -04:00

AP_Mount: 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 d626197c0b
commit b644dfebc4

View File

@ -177,10 +177,8 @@ void AP_Mount_Siyi::read_incoming_packets()
// process bytes received
for (int16_t i = 0; i < nbytes; i++) {
const int16_t b = _uart->read();
// sanity check byte
if ((b < 0) || (b > 0xFF)) {
uint8_t b;
if (!_uart->read(b)) {
continue;
}