mirror of https://github.com/ArduPilot/ardupilot
AP_OpticalFlow: 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
b644dfebc4
commit
988aa992bf
|
@ -116,11 +116,10 @@ void AP_OpticalFlow_CXOF::update(void)
|
|||
// read any available characters in the serial buffer
|
||||
int16_t nbytes = uart->available();
|
||||
while (nbytes-- > 0) {
|
||||
int16_t r = uart->read();
|
||||
if (r < 0) {
|
||||
uint8_t c;
|
||||
if (!uart->read(c)) {
|
||||
continue;
|
||||
}
|
||||
uint8_t c = (uint8_t)r;
|
||||
// if buffer is empty and this byte is header, add to buffer
|
||||
if (buf_len == 0) {
|
||||
if (c == CXOF_HEADER) {
|
||||
|
|
Loading…
Reference in New Issue