diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 79a69b88b2962..4d6f1e164ccc9 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -1619,7 +1619,7 @@ void AP_GPS::handle_gps_rtcm_data(mavlink_channel_t chan, const mavlink_message_ */ bool AP_GPS::parse_rtcm_injection(mavlink_channel_t chan, const mavlink_gps_rtcm_data_t &pkt) { - if (chan >= MAVLINK_COMM_NUM_BUFFERS) { + if (static_cast(chan) >= MAVLINK_COMM_NUM_BUFFERS) { return false; } if (rtcm.parsers[chan] == nullptr) { diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.h b/libraries/GCS_MAVLink/GCS_MAVLink.h index b59ba9d93c311..7a7db6a68366a 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.h +++ b/libraries/GCS_MAVLink/GCS_MAVLink.h @@ -55,10 +55,7 @@ extern mavlink_system_t mavlink_system; /// @param chan Channel to send to static inline bool valid_channel(mavlink_channel_t chan) { -#pragma clang diagnostic push -#pragma clang diagnostic ignored "-Wtautological-constant-out-of-range-compare" - return chan < MAVLINK_COMM_NUM_BUFFERS; -#pragma clang diagnostic pop + return static_cast(chan) < MAVLINK_COMM_NUM_BUFFERS; } mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan);