diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index f9703964ea32d262312a9e89fb0d05bd55578542..29123742495f631ccd259c5e39a31582411c7756 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1031,21 +1031,21 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) const unsigned int portWidth = 8; // XXX magic number emit remoteControlRSSIChanged(channels.rssi/255.0f); - if (channels.chan1_scaled != UINT16_MAX) + if (static_cast(channels.chan1_scaled) != UINT16_MAX) emit remoteControlChannelScaledChanged(channels.port * portWidth + 0, channels.chan1_scaled/10000.0f); - if (channels.chan2_scaled != UINT16_MAX) + if (static_cast(channels.chan2_scaled) != UINT16_MAX) emit remoteControlChannelScaledChanged(channels.port * portWidth + 1, channels.chan2_scaled/10000.0f); - if (channels.chan3_scaled != UINT16_MAX) + if (static_cast(channels.chan3_scaled) != UINT16_MAX) emit remoteControlChannelScaledChanged(channels.port * portWidth + 2, channels.chan3_scaled/10000.0f); - if (channels.chan4_scaled != UINT16_MAX) + if (static_cast(channels.chan4_scaled) != UINT16_MAX) emit remoteControlChannelScaledChanged(channels.port * portWidth + 3, channels.chan4_scaled/10000.0f); - if (channels.chan5_scaled != UINT16_MAX) + if (static_cast(channels.chan5_scaled) != UINT16_MAX) emit remoteControlChannelScaledChanged(channels.port * portWidth + 4, channels.chan5_scaled/10000.0f); - if (channels.chan6_scaled != UINT16_MAX) + if (static_cast(channels.chan6_scaled) != UINT16_MAX) emit remoteControlChannelScaledChanged(channels.port * portWidth + 5, channels.chan6_scaled/10000.0f); - if (channels.chan7_scaled != UINT16_MAX) + if (static_cast(channels.chan7_scaled) != UINT16_MAX) emit remoteControlChannelScaledChanged(channels.port * portWidth + 6, channels.chan7_scaled/10000.0f); - if (channels.chan8_scaled != UINT16_MAX) + if (static_cast(channels.chan8_scaled) != UINT16_MAX) emit remoteControlChannelScaledChanged(channels.port * portWidth + 7, channels.chan8_scaled/10000.0f); } break;