Skip to content

Commit

Permalink
AP_Proximity: avoid use of int16_t-read call
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Jul 9, 2024
1 parent 481e030 commit 4fe8b00
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
6 changes: 3 additions & 3 deletions libraries/AP_Proximity/AP_Proximity_LightWareSF45B.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
}
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_Proximity/AP_Proximity_TeraRangerTower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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' ) {
Expand Down

0 comments on commit 4fe8b00

Please sign in to comment.