diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp index 47e0e28e8e..1911ea9126 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp @@ -99,11 +99,11 @@ void AP_Proximity_LightWareSF45B::process_replies() // process up to 1K of characters per iteration uint32_t nbytes = MIN(_uart->available(), 1024U); while (nbytes-- > 0) { - const int16_t r = _uart->read(); - if ((r < 0) || (r > 0xFF)) { + uint8_t c; + if (!_uart->read(c)) { continue; } - if (parse_byte((uint8_t)r)) { + if (parse_byte(c)) { process_message(); } } diff --git a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp index f467045035..4fe6fb6db0 100644 --- a/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp +++ b/libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp @@ -65,8 +65,8 @@ bool AP_Proximity_TeraRangerTower::read_sensor_data() int16_t nbytes = _uart->available(); while (nbytes-- > 0) { - int16_t c = _uart->read(); - if (c==-1) { + uint8_t c; + if (!_uart->read(c)) { return false; } if (char(c) == 'T' ) {