From 2a539345791c92f1eed10ccbb05f25656744c726 Mon Sep 17 00:00:00 2001 From: Prathamesh Patil Date: Sat, 18 Feb 2023 11:52:35 +0530 Subject: [PATCH] AP_Airspeed: corrected return type of uart::read()' --- libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp b/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp index 3e3d014266..d085e5bd99 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_NMEA.cpp @@ -73,8 +73,11 @@ bool AP_Airspeed_NMEA::get_airspeed(float &airspeed) uint16_t count = 0; int16_t nbytes = _uart->available(); while (nbytes-- > 0) { - char c = _uart->read(); - if (decode(c)) { + int16_t c = _uart->read(); + if (c==-1) { + return false; + } + if (decode(char(c))) { _last_update_ms = now; if (_sentence_type == TYPE_VHW) { sum += _speed;