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.

GCS_MAVLink: Remove pragma to disable compiler warning and instead cast enum to int to fix the code.
  • Loading branch information
katzfey committed Dec 12, 2024
1 parent a52c375 commit 3f12d65
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 5 deletions.
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
5 changes: 1 addition & 4 deletions libraries/GCS_MAVLink/GCS_MAVLink.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<int>(chan) < MAVLINK_COMM_NUM_BUFFERS;
}

mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan);
Expand Down

0 comments on commit 3f12d65

Please sign in to comment.