Skip to content

Commit

Permalink
AP_GPS: Cast enum to int to fix compiler warning when max enum value …
Browse files Browse the repository at this point in the history
…is less than the constant being compared to.
  • Loading branch information
katzfey committed Dec 12, 2024
1 parent a52c375 commit 72b420f
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<int>(chan) >= MAVLINK_COMM_NUM_BUFFERS) {
return false;
}
if (rtcm.parsers[chan] == nullptr) {
Expand Down

0 comments on commit 72b420f

Please sign in to comment.