From b03070d0d689e21febce14828bc43c4838cc2586 Mon Sep 17 00:00:00 2001 From: Bryant Mairs Date: Wed, 15 Feb 2012 10:12:23 -0800 Subject: [PATCH] Expanded documentation for UASInfoWidget::update*Loss. Changed the drop rate from a SYS_STATUS message to follow the MAVLink specs along with some extra range checking. --- src/uas/UAS.cc | 12 +++++++++--- src/ui/uas/UASInfoWidget.h | 14 ++++++++++++-- 2 files changed, 21 insertions(+), 5 deletions(-) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 3ff07c480..165c2d943 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -428,9 +428,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) stopLowBattAlarm(); } - // COMMUNICATIONS DROP RATE - // FIXME - emit dropRateChanged(this->getUASID(), state.drop_rate_comm/10000.0f); + // Trigger drop rate updates as needed. Here we convert the incoming + // drop_rate_comm value from 1/100 of a percent in a uint16 to a true + // percentage as a float. We also cap the incoming value at 100% as defined + // by the MAVLink specifications. + if (state.drop_rate_comm > 10000) { + emit dropRateChanged(this->getUASID(), 100.0f); + } else { + emit dropRateChanged(this->getUASID(), state.drop_rate_comm/100.0f); + } } break; case MAVLINK_MSG_ID_ATTITUDE: diff --git a/src/ui/uas/UASInfoWidget.h b/src/ui/uas/UASInfoWidget.h index 81a8179e6..ec977c82d 100644 --- a/src/ui/uas/UASInfoWidget.h +++ b/src/ui/uas/UASInfoWidget.h @@ -57,10 +57,20 @@ public slots: void updateBattery(UASInterface* uas, double voltage, double percent, int seconds); void updateCPULoad(UASInterface* uas, double load); - /** @brief Set the loss rate of packets received by the MAV */ + /** + * @brief Set the loss rate of packets received by the MAV. + * @param uasId UNUSED + * @param receiveLoss A percentage value (0-100) of how many message the UAS has failed to receive. + */ void updateReceiveLoss(int uasId, float receiveLoss); - /** @brief Set the loss rate of packets sent from the MAV */ + + /** + * @brief Set the loss rate of packets sent from the MAV + * @param uasId UNUSED + * @param sendLoss A percentage value (0-100) of how many message QGC has failed to receive. + */ void updateSendLoss(int uasId, float sendLoss); + /** @brief Update the error count */ void updateErrorCount(int uasid, QString component, QString device, int count); -- 2.22.0