From a47942f54c8f863d55f1903d137b6a7b7bf6d795 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 30 Dec 2013 00:15:33 +0100 Subject: [PATCH] Only emit signals for valid ranges --- src/uas/UAS.cc | 48 ++++++++++++++++++++++++++++++++---------------- 1 file changed, 32 insertions(+), 16 deletions(-) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 80ca3694c..f9703964e 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -1005,14 +1005,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) const unsigned int portWidth = 8; // XXX magic number emit remoteControlRSSIChanged(channels.rssi/255.0f); - emit remoteControlChannelRawChanged(channels.port * portWidth + 0, channels.chan1_raw); - emit remoteControlChannelRawChanged(channels.port * portWidth + 1, channels.chan2_raw); - emit remoteControlChannelRawChanged(channels.port * portWidth + 2, channels.chan3_raw); - emit remoteControlChannelRawChanged(channels.port * portWidth + 3, channels.chan4_raw); - emit remoteControlChannelRawChanged(channels.port * portWidth + 4, channels.chan5_raw); - emit remoteControlChannelRawChanged(channels.port * portWidth + 5, channels.chan6_raw); - emit remoteControlChannelRawChanged(channels.port * portWidth + 6, channels.chan7_raw); - emit remoteControlChannelRawChanged(channels.port * portWidth + 7, channels.chan8_raw); + if (channels.chan1_raw != UINT16_MAX) + emit remoteControlChannelRawChanged(channels.port * portWidth + 0, channels.chan1_raw); + if (channels.chan2_raw != UINT16_MAX) + emit remoteControlChannelRawChanged(channels.port * portWidth + 1, channels.chan2_raw); + if (channels.chan3_raw != UINT16_MAX) + emit remoteControlChannelRawChanged(channels.port * portWidth + 2, channels.chan3_raw); + if (channels.chan4_raw != UINT16_MAX) + emit remoteControlChannelRawChanged(channels.port * portWidth + 3, channels.chan4_raw); + if (channels.chan5_raw != UINT16_MAX) + emit remoteControlChannelRawChanged(channels.port * portWidth + 4, channels.chan5_raw); + if (channels.chan6_raw != UINT16_MAX) + emit remoteControlChannelRawChanged(channels.port * portWidth + 5, channels.chan6_raw); + if (channels.chan7_raw != UINT16_MAX) + emit remoteControlChannelRawChanged(channels.port * portWidth + 6, channels.chan7_raw); + if (channels.chan8_raw != UINT16_MAX) + emit remoteControlChannelRawChanged(channels.port * portWidth + 7, channels.chan8_raw); } break; case MAVLINK_MSG_ID_RC_CHANNELS_SCALED: @@ -1023,14 +1031,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) const unsigned int portWidth = 8; // XXX magic number emit remoteControlRSSIChanged(channels.rssi/255.0f); - emit remoteControlChannelScaledChanged(channels.port * portWidth + 0, channels.chan1_scaled/10000.0f); - emit remoteControlChannelScaledChanged(channels.port * portWidth + 1, channels.chan2_scaled/10000.0f); - emit remoteControlChannelScaledChanged(channels.port * portWidth + 2, channels.chan3_scaled/10000.0f); - emit remoteControlChannelScaledChanged(channels.port * portWidth + 3, channels.chan4_scaled/10000.0f); - emit remoteControlChannelScaledChanged(channels.port * portWidth + 4, channels.chan5_scaled/10000.0f); - emit remoteControlChannelScaledChanged(channels.port * portWidth + 5, channels.chan6_scaled/10000.0f); - emit remoteControlChannelScaledChanged(channels.port * portWidth + 6, channels.chan7_scaled/10000.0f); - emit remoteControlChannelScaledChanged(channels.port * portWidth + 7, channels.chan8_scaled/10000.0f); + if (channels.chan1_scaled != UINT16_MAX) + emit remoteControlChannelScaledChanged(channels.port * portWidth + 0, channels.chan1_scaled/10000.0f); + if (channels.chan2_scaled != UINT16_MAX) + emit remoteControlChannelScaledChanged(channels.port * portWidth + 1, channels.chan2_scaled/10000.0f); + if (channels.chan3_scaled != UINT16_MAX) + emit remoteControlChannelScaledChanged(channels.port * portWidth + 2, channels.chan3_scaled/10000.0f); + if (channels.chan4_scaled != UINT16_MAX) + emit remoteControlChannelScaledChanged(channels.port * portWidth + 3, channels.chan4_scaled/10000.0f); + if (channels.chan5_scaled != UINT16_MAX) + emit remoteControlChannelScaledChanged(channels.port * portWidth + 4, channels.chan5_scaled/10000.0f); + if (channels.chan6_scaled != UINT16_MAX) + emit remoteControlChannelScaledChanged(channels.port * portWidth + 5, channels.chan6_scaled/10000.0f); + if (channels.chan7_scaled != UINT16_MAX) + emit remoteControlChannelScaledChanged(channels.port * portWidth + 6, channels.chan7_scaled/10000.0f); + if (channels.chan8_scaled != UINT16_MAX) + emit remoteControlChannelScaledChanged(channels.port * portWidth + 7, channels.chan8_scaled/10000.0f); } break; case MAVLINK_MSG_ID_PARAM_VALUE: -- 2.22.0