From 464e2f14c19f207d5da77dcdae76e095abb2a2e5 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 19 May 2016 12:24:19 -0400 Subject: [PATCH] mavlink remove clang warning/error --- src/modules/mavlink/mavlink_receiver.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index f5ec194177..5ee0312fdc 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -1109,7 +1109,7 @@ void MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg) { /* telemetry status supported only on first ORB_MULTI_MAX_INSTANCES mavlink channels */ - if (_mavlink->get_channel() < ORB_MULTI_MAX_INSTANCES) { + if (_mavlink->get_channel() < (mavlink_channel_t)ORB_MULTI_MAX_INSTANCES) { mavlink_radio_status_t rstatus; mavlink_msg_radio_status_decode(msg, &rstatus); @@ -1319,7 +1319,7 @@ void MavlinkReceiver::handle_message_heartbeat(mavlink_message_t *msg) { /* telemetry status supported only on first TELEMETRY_STATUS_ORB_ID_NUM mavlink channels */ - if (_mavlink->get_channel() < ORB_MULTI_MAX_INSTANCES) { + if (_mavlink->get_channel() < (mavlink_channel_t)ORB_MULTI_MAX_INSTANCES) { mavlink_heartbeat_t hb; mavlink_msg_heartbeat_decode(msg, &hb);