mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: corrected return type of uart::read()
This commit is contained in:
parent
2a53934579
commit
b9d718c938
|
@ -43,7 +43,7 @@ void AP_Proximity_Cygbot_D1::read_sensor_data()
|
|||
{
|
||||
uint32_t nbytes = _uart->available();
|
||||
while (nbytes-- > 0) {
|
||||
uint8_t byte = _uart->read();
|
||||
int16_t byte = _uart->read();
|
||||
if (!parse_byte(byte)) {
|
||||
// reset
|
||||
reset();
|
||||
|
|
|
@ -163,7 +163,7 @@ void AP_Proximity_RPLidarA2::get_readings()
|
|||
|
||||
while (nbytes-- > 0) {
|
||||
|
||||
uint8_t c = _uart->read();
|
||||
int16_t c = _uart->read();
|
||||
Debug(2, "UART READ %x <%c>", c, c); //show HEX values
|
||||
|
||||
STATE:
|
||||
|
|
|
@ -62,8 +62,11 @@ bool AP_Proximity_TeraRangerTower::read_sensor_data()
|
|||
int16_t nbytes = _uart->available();
|
||||
|
||||
while (nbytes-- > 0) {
|
||||
char c = _uart->read();
|
||||
if (c == 'T' ) {
|
||||
int16_t c = _uart->read();
|
||||
if (c==-1) {
|
||||
return false;
|
||||
}
|
||||
if (char(c) == 'T' ) {
|
||||
buffer_count = 0;
|
||||
}
|
||||
|
||||
|
|
|
@ -116,8 +116,11 @@ bool AP_Proximity_TeraRangerTowerEvo::read_sensor_data()
|
|||
}
|
||||
|
||||
while (nbytes-- > 0) {
|
||||
char c = _uart->read();
|
||||
if (c == 'T' ) {
|
||||
int16_t c = _uart->read();
|
||||
if (c==-1) {
|
||||
return false;
|
||||
}
|
||||
if (char(c) == 'T' ) {
|
||||
buffer_count = 0;
|
||||
}
|
||||
buffer[buffer_count++] = c;
|
||||
|
|
Loading…
Reference in New Issue