From 6be09149118b21ee07a3a82c81b3277b3940f733 Mon Sep 17 00:00:00 2001 From: lm Date: Fri, 28 May 2010 16:13:48 +0200 Subject: [PATCH] Fixed packet drop counting / handling --- src/uas/UAS.cc | 3 ++- src/uas/UASInterface.h | 5 ++--- src/ui/MainWindow.cc | 10 +--------- src/ui/uas/UASInfoWidget.cc | 4 ++-- src/ui/watchdog/WatchdogControl.cc | 4 ++-- src/ui/watchdog/WatchdogControl.h | 4 ++-- 6 files changed, 11 insertions(+), 19 deletions(-) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index f9792b0af..238ea45f8 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -221,7 +221,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) } // COMMUNICATIONS DROP RATE - emit dropRateChanged(this->getUASID(), this->receiveDropRate, this->sendDropRate); + emit dropRateChanged(this->getUASID(), state.packet_drop); + qDebug() << __FILE__ << __LINE__ << "RCV LOSS: " << state.packet_drop; // AUDIO if (modechanged && statechanged) diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 0002a0028..4758a08a5 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -233,10 +233,9 @@ signals: * @brief Drop rate of communication link updated * * @param systemId id of the air system - * @param receiveDrop drop rate of packets this MAV receives (send from GCS or other MAVs) - * @param sendDrop drop rate of packets this MAV sends (received on GCS) + * @param receiveDrop drop rate of packets this MAV receives (sent from GCS or other MAVs) */ - void dropRateChanged(int systemId, float receiveDrop, float sendDrop); + void dropRateChanged(int systemId, float receiveDrop); /** @brief Robot mode has changed */ void modeChanged(int sysId, QString status, QString description); /** @brief A command has been issued **/ diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index aa01f8870..f6c29bf02 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -166,7 +166,7 @@ settings() adjustSize(); // - connect(mavlink, SIGNAL(receiveLossChanged(float)), info, SLOT(updateReceiveLoss(float))); + connect(mavlink, SIGNAL(receiveLossChanged(float)), info, SLOT(updateSendLoss(float))); } MainWindow::~MainWindow() @@ -377,7 +377,6 @@ void MainWindow::clearView() void MainWindow::loadPilotView() { clearView(); - GAudioOutput::instance()->say("Switched to Pilot View"); // HEAD UP DISPLAY centerStack->setCurrentWidget(hud); @@ -402,8 +401,6 @@ void MainWindow::loadOperatorView() { clearView(); - GAudioOutput::instance()->say("Switched to Operator View"); - // MAP centerStack->setCurrentWidget(map); @@ -448,8 +445,6 @@ void MainWindow::loadSettingsView() { clearView(); - GAudioOutput::instance()->say("Switched to Settings View"); - // LINE CHART linechart->setActive(true); centerStack->setCurrentWidget(linechart); @@ -472,8 +467,6 @@ void MainWindow::loadEngineerView() clearView(); // Engineer view, used in EMAV2009 - GAudioOutput::instance()->say("Switched to Engineer View"); - // LINE CHART linechart->setActive(true); centerStack->setCurrentWidget(linechart); @@ -516,7 +509,6 @@ void MainWindow::loadMAVLinkView() void MainWindow::loadAllView() { clearView(); - GAudioOutput::instance()->say("Loaded complete view"); QDockWidget* containerPFD = new QDockWidget(tr("Primary Flight Display"), this); containerPFD->setWidget(headDown1); diff --git a/src/ui/uas/UASInfoWidget.cc b/src/ui/uas/UASInfoWidget.cc index d1e348f03..989be0d44 100644 --- a/src/ui/uas/UASInfoWidget.cc +++ b/src/ui/uas/UASInfoWidget.cc @@ -23,7 +23,7 @@ This file is part of the PIXHAWK project /** * @file - * @brief Brief Description + * @brief Implementation of class UASInfoWidget * * @author Lorenz Meier * @@ -86,7 +86,7 @@ void UASInfoWidget::addUAS(UASInterface* uas) if (uas != NULL) { connect(uas, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBattery(UASInterface*,double,double,int))); - connect(uas, SIGNAL(dropRateChanged(int,float,float)), this, SLOT(updateDropRate(int,float,float))); + connect(uas, SIGNAL(dropRateChanged(int,float)), this, SLOT(updateReceiveLoss(int,float))); connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateCPULoad(UASInterface*,double))); // Set this UAS as active if it is the first one diff --git a/src/ui/watchdog/WatchdogControl.cc b/src/ui/watchdog/WatchdogControl.cc index 12655dc52..d9ec97d2c 100644 --- a/src/ui/watchdog/WatchdogControl.cc +++ b/src/ui/watchdog/WatchdogControl.cc @@ -14,11 +14,11 @@ WatchdogControl::WatchdogControl(QWidget *parent) : ui->setupUi(this); // UI is initialized, setup layout - listLayout = new QVBoxLayout(m_ui->listWidget); + listLayout = new QVBoxLayout(ui->mainWidget); listLayout->setSpacing(6); listLayout->setMargin(0); listLayout->setAlignment(Qt::AlignTop); - m_ui->listWidget->setLayout(listLayout); + ui->mainWidget->setLayout(listLayout); connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(setUAS(UASInterface*))); } diff --git a/src/ui/watchdog/WatchdogControl.h b/src/ui/watchdog/WatchdogControl.h index 0559d6b50..a91574b0e 100644 --- a/src/ui/watchdog/WatchdogControl.h +++ b/src/ui/watchdog/WatchdogControl.h @@ -5,7 +5,7 @@ #include #include -#include +#include #include #include @@ -115,7 +115,7 @@ protected: void changeEvent(QEvent *e); UASInterface* mav; - QHBoxLayout* mainWidgetLayout; + QVBoxLayout* listLayout; private: Ui::WatchdogControl *ui; -- 2.22.0