diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index dc0cb16b2ec8d..9844b3b444f72 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -39,6 +39,8 @@ #include #include +#include + #define VEHICLE_TIMEOUT_MS 5000 // if no updates in this time, drop it from the list #define ADSB_SQUAWK_OCTAL_DEFAULT 1200 @@ -778,8 +780,7 @@ void AP_ADSB::set_callsign(const char* str, const bool append_icao) break; } - } else if (('A' <= str[i] && str[i] <= 'Z') || - ('0' <= str[i] && str[i] <= '9')) { + } else if (isupper(str[i]) || isdigit(str[i])) { // valid as-is // spaces are also allowed but are handled in the last else out_state.cfg.callsign[i] = str[i]; diff --git a/libraries/AP_CANManager/AP_SLCANIface.cpp b/libraries/AP_CANManager/AP_SLCANIface.cpp index 496e8850ed2c1..d172451fe3b83 100644 --- a/libraries/AP_CANManager/AP_SLCANIface.cpp +++ b/libraries/AP_CANManager/AP_SLCANIface.cpp @@ -22,6 +22,7 @@ #if AP_CAN_SLCAN_ENABLED #include #include +#include #include "AP_CANManager.h" diff --git a/libraries/AP_HAL/utility/print_vprintf.cpp b/libraries/AP_HAL/utility/print_vprintf.cpp index df7b3105364c1..776125581479d 100644 --- a/libraries/AP_HAL/utility/print_vprintf.cpp +++ b/libraries/AP_HAL/utility/print_vprintf.cpp @@ -39,6 +39,7 @@ #include "print_vprintf.h" #include +#include #include #include @@ -126,7 +127,7 @@ void print_vprintf(AP_HAL::BetterStream *s, const char *fmt, va_list ap) } if (flags < FL_LONG) { - if (c >= '0' && c <= '9') { + if (isdigit(c)) { c -= '0'; if (flags & FL_PREC) { prec = 10*prec + c; diff --git a/libraries/AP_Math/definitions.h b/libraries/AP_Math/definitions.h index c0280b54b9a23..ab4a57fd12057 100644 --- a/libraries/AP_Math/definitions.h +++ b/libraries/AP_Math/definitions.h @@ -1,6 +1,7 @@ #pragma once #include +#include #include @@ -127,3 +128,5 @@ static const double WGS84_E = (sqrt(2 * WGS84_F - WGS84_F * WGS84_F)); // kg/m^3 to g/cm^3 #define KG_PER_M3_TO_G_PER_CM3(x) (0.001 * x) + +#define ishexa(c) (isdigit(c) || ((c) >= 'A' && (c) <= 'F') || ((c) >= 'a' && (c) <= 'f')) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp index 5e600ca463dd2..8c4b7b70c594d 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp @@ -16,6 +16,8 @@ #if AP_RANGEFINDER_LWI2C_ENABLED +#include + #include #include @@ -431,9 +433,7 @@ bool AP_RangeFinder_LightWareI2C::sf20_parse_stream(uint8_t *stream_buf, bool number_found = false; uint16_t accumulator = 0; uint16_t digit_u16 = (uint16_t)stream_buf[*p_num_processed_chars]; - while ((((digit_u16 <= '9') && - (digit_u16 >= '0')) || - (digit_u16 == '.')) && + while ((isdigit(digit_u16) || (digit_u16 == '.')) && (*p_num_processed_chars < lx20_max_reply_len_bytes)) { (*p_num_processed_chars)++; if (decrement_multiplier) { diff --git a/libraries/AP_Winch/AP_Winch_Daiwa.cpp b/libraries/AP_Winch/AP_Winch_Daiwa.cpp index 88f6184472631..713548468291e 100644 --- a/libraries/AP_Winch/AP_Winch_Daiwa.cpp +++ b/libraries/AP_Winch/AP_Winch_Daiwa.cpp @@ -118,7 +118,7 @@ void AP_Winch_Daiwa::read_data_from_winch() while (nbytes-- > 0) { int16_t b = uart->read(); - if ((b >= '0' && b <= '9') || (b >= 'A' && b <= 'F') || (b >= 'a' && b <= 'f')) { + if (ishexa(b)) { // add digits to buffer buff[buff_len] = b; buff_len++;