mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: avoid use of int16_t-read call
This commit is contained in:
parent
2025712505
commit
31f3a796f1
|
@ -99,11 +99,11 @@ void AP_Proximity_LightWareSF45B::process_replies()
|
||||||
// process up to 1K of characters per iteration
|
// process up to 1K of characters per iteration
|
||||||
uint32_t nbytes = MIN(_uart->available(), 1024U);
|
uint32_t nbytes = MIN(_uart->available(), 1024U);
|
||||||
while (nbytes-- > 0) {
|
while (nbytes-- > 0) {
|
||||||
const int16_t r = _uart->read();
|
uint8_t c;
|
||||||
if ((r < 0) || (r > 0xFF)) {
|
if (!_uart->read(c)) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
if (parse_byte((uint8_t)r)) {
|
if (parse_byte(c)) {
|
||||||
process_message();
|
process_message();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -65,8 +65,8 @@ bool AP_Proximity_TeraRangerTower::read_sensor_data()
|
||||||
int16_t nbytes = _uart->available();
|
int16_t nbytes = _uart->available();
|
||||||
|
|
||||||
while (nbytes-- > 0) {
|
while (nbytes-- > 0) {
|
||||||
int16_t c = _uart->read();
|
uint8_t c;
|
||||||
if (c==-1) {
|
if (!_uart->read(c)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
if (char(c) == 'T' ) {
|
if (char(c) == 'T' ) {
|
||||||
|
|
Loading…
Reference in New Issue