mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: corrected return type of uart::read()'
This commit is contained in:
parent
906a02d98d
commit
2a53934579
|
@ -73,8 +73,11 @@ bool AP_Airspeed_NMEA::get_airspeed(float &airspeed)
|
||||||
uint16_t count = 0;
|
uint16_t count = 0;
|
||||||
int16_t nbytes = _uart->available();
|
int16_t nbytes = _uart->available();
|
||||||
while (nbytes-- > 0) {
|
while (nbytes-- > 0) {
|
||||||
char c = _uart->read();
|
int16_t c = _uart->read();
|
||||||
if (decode(c)) {
|
if (c==-1) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (decode(char(c))) {
|
||||||
_last_update_ms = now;
|
_last_update_ms = now;
|
||||||
if (_sentence_type == TYPE_VHW) {
|
if (_sentence_type == TYPE_VHW) {
|
||||||
sum += _speed;
|
sum += _speed;
|
||||||
|
|
Loading…
Reference in New Issue