From 93ba994eb1d763351222351d559a5a2d56ca0a60 Mon Sep 17 00:00:00 2001 From: Eric Katzfey Date: Thu, 14 Nov 2024 11:57:25 -0800 Subject: [PATCH] AP_GPS: Cast enum to int to fix compiler warning when max enum value is less than the constant being compared to. --- libraries/AP_GPS/AP_GPS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index 79a69b88b2..4d6f1e164c 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) {