Commit 393f1533 authored by Don Gagne's avatar Don Gagne

Show mavlink sequence number packet loss in UI

parent 0f884579
...@@ -63,7 +63,11 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app) ...@@ -63,7 +63,11 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app)
, _linkMgr(NULL) , _linkMgr(NULL)
, _multiVehicleManager(NULL) , _multiVehicleManager(NULL)
{ {
memset(&totalReceiveCounter, 0, sizeof(totalReceiveCounter));
memset(&totalLossCounter, 0, sizeof(totalLossCounter));
memset(&totalErrorCounter, 0, sizeof(totalErrorCounter));
memset(&currReceiveCounter, 0, sizeof(currReceiveCounter));
memset(&currLossCounter, 0, sizeof(currLossCounter));
} }
MAVLinkProtocol::~MAVLinkProtocol() MAVLinkProtocol::~MAVLinkProtocol()
...@@ -357,11 +361,12 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) ...@@ -357,11 +361,12 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
{ {
// Calculate new loss ratio // Calculate new loss ratio
// Receive loss // Receive loss
float receiveLoss = (double)currLossCounter[mavlinkChannel]/(double)(currReceiveCounter[mavlinkChannel]+currLossCounter[mavlinkChannel]); float receiveLossPercent = (double)currLossCounter[mavlinkChannel]/(double)(currReceiveCounter[mavlinkChannel]+currLossCounter[mavlinkChannel]);
receiveLoss *= 100.0f; receiveLossPercent *= 100.0f;
currLossCounter[mavlinkChannel] = 0; currLossCounter[mavlinkChannel] = 0;
currReceiveCounter[mavlinkChannel] = 0; currReceiveCounter[mavlinkChannel] = 0;
emit receiveLossChanged(message.sysid, receiveLoss); emit receiveLossPercentChanged(message.sysid, receiveLossPercent);
emit receiveLossTotalChanged(message.sysid, totalLossCounter[mavlinkChannel]);
} }
// The packet is emitted as a whole, as it is only 255 - 261 bytes short // The packet is emitted as a whole, as it is only 255 - 261 bytes short
......
...@@ -242,8 +242,9 @@ signals: ...@@ -242,8 +242,9 @@ signals:
void actionGuardChanged(bool enabled); void actionGuardChanged(bool enabled);
/** @brief Emitted if action request timeout changed */ /** @brief Emitted if action request timeout changed */
void actionRetransmissionTimeoutChanged(int ms); void actionRetransmissionTimeoutChanged(int ms);
/** @brief Update the packet loss from one system */
void receiveLossChanged(int uasId, float loss); void receiveLossPercentChanged(int uasId, float lossPercent);
void receiveLossTotalChanged(int uasId, int totalLoss);
/** /**
* @brief Emitted if a new radio status packet received * @brief Emitted if a new radio status packet received
......
This diff is collapsed.
...@@ -46,10 +46,12 @@ This file is part of the PIXHAWK project ...@@ -46,10 +46,12 @@ This file is part of the PIXHAWK project
UASInfoWidget::UASInfoWidget(const QString& title, QAction* action, QWidget *parent, QString name) UASInfoWidget::UASInfoWidget(const QString& title, QAction* action, QWidget *parent, QString name)
: QGCDockWidget(title, action, parent) : QGCDockWidget(title, action, parent)
, _activeUAS(NULL)
, _seqLossPercent(0)
, _seqLossTotal(0)
{ {
ui.setupUi(this); ui.setupUi(this);
this->name = name; this->name = name;
activeUAS = NULL;
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &UASInfoWidget::_activeVehicleChanged); connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &UASInfoWidget::_activeVehicleChanged);
_activeVehicleChanged(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()); _activeVehicleChanged(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle());
...@@ -76,6 +78,9 @@ UASInfoWidget::UASInfoWidget(const QString& title, QAction* action, QWidget *par ...@@ -76,6 +78,9 @@ UASInfoWidget::UASInfoWidget(const QString& title, QAction* action, QWidget *par
this->setVisible(false); this->setVisible(false);
loadSettings(); loadSettings();
connect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::receiveLossPercentChanged, this, &UASInfoWidget::updateSeqLossPercent);
connect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::receiveLossTotalChanged, this, &UASInfoWidget::updateSeqLossTotal);
} }
UASInfoWidget::~UASInfoWidget() UASInfoWidget::~UASInfoWidget()
...@@ -101,20 +106,20 @@ void UASInfoWidget::hideEvent(QHideEvent* event) ...@@ -101,20 +106,20 @@ void UASInfoWidget::hideEvent(QHideEvent* event)
void UASInfoWidget::_activeVehicleChanged(Vehicle* vehicle) void UASInfoWidget::_activeVehicleChanged(Vehicle* vehicle)
{ {
if (activeUAS) { if (_activeUAS) {
disconnect(activeUAS, &UASInterface::batteryChanged, this, &UASInfoWidget::updateBattery); disconnect(_activeUAS, &UASInterface::batteryChanged, this, &UASInfoWidget::updateBattery);
disconnect(activeUAS, &UASInterface::dropRateChanged, this, &UASInfoWidget::updateReceiveLoss); disconnect(_activeUAS, &UASInterface::dropRateChanged, this, &UASInfoWidget::updateReceiveLoss);
disconnect(static_cast<UAS*>(activeUAS), &UAS::loadChanged, this, &UASInfoWidget::updateCPULoad); disconnect(static_cast<UAS*>(_activeUAS), &UAS::loadChanged, this, &UASInfoWidget::updateCPULoad);
disconnect(activeUAS, &UASInterface::errCountChanged, this, &UASInfoWidget::updateErrorCount); disconnect(_activeUAS, &UASInterface::errCountChanged, this, &UASInfoWidget::updateErrorCount);
activeUAS = NULL; _activeUAS = NULL;
} }
if (vehicle) { if (vehicle) {
activeUAS = vehicle->uas(); _activeUAS = vehicle->uas();
connect(activeUAS, &UASInterface::batteryChanged, this, &UASInfoWidget::updateBattery); connect(_activeUAS, &UASInterface::batteryChanged, this, &UASInfoWidget::updateBattery);
connect(activeUAS, &UASInterface::dropRateChanged, this, &UASInfoWidget::updateReceiveLoss); connect(_activeUAS, &UASInterface::dropRateChanged, this, &UASInfoWidget::updateReceiveLoss);
connect(static_cast<UAS*>(activeUAS), &UAS::loadChanged, this, &UASInfoWidget::updateCPULoad); connect(static_cast<UAS*>(_activeUAS), &UAS::loadChanged, this, &UASInfoWidget::updateCPULoad);
connect(activeUAS, &UASInterface::errCountChanged, this, &UASInfoWidget::updateErrorCount); connect(_activeUAS, &UASInterface::errCountChanged, this, &UASInfoWidget::updateErrorCount);
} }
} }
...@@ -128,8 +133,8 @@ void UASInfoWidget::updateBattery(UASInterface* uas, double voltage, double curr ...@@ -128,8 +133,8 @@ void UASInfoWidget::updateBattery(UASInterface* uas, double voltage, double curr
void UASInfoWidget::updateErrorCount(int uasid, QString component, QString device, int count) void UASInfoWidget::updateErrorCount(int uasid, QString component, QString device, int count)
{ {
//qDebug() << __FILE__ << __LINE__ << activeUAS->getUASID() << "=" << uasid; //qDebug() << __FILE__ << __LINE__ << _activeUAS->getUASID() << "=" << uasid;
if (activeUAS->getUASID() == uasid) { if (_activeUAS->getUASID() == uasid) {
errors.remove(component + ":" + device); errors.remove(component + ":" + device);
errors.insert(component + ":" + device, count); errors.insert(component + ":" + device, count);
} }
...@@ -140,7 +145,7 @@ void UASInfoWidget::updateErrorCount(int uasid, QString component, QString devic ...@@ -140,7 +145,7 @@ void UASInfoWidget::updateErrorCount(int uasid, QString component, QString devic
*/ */
void UASInfoWidget::updateCPULoad(UASInterface* uas, double load) void UASInfoWidget::updateCPULoad(UASInterface* uas, double load)
{ {
if (activeUAS == uas) { if (_activeUAS == uas) {
this->load = load; this->load = load;
} }
} }
...@@ -151,6 +156,24 @@ void UASInfoWidget::updateReceiveLoss(int uasId, float receiveLoss) ...@@ -151,6 +156,24 @@ void UASInfoWidget::updateReceiveLoss(int uasId, float receiveLoss)
this->receiveLoss = this->receiveLoss * 0.8f + receiveLoss * 0.2f; this->receiveLoss = this->receiveLoss * 0.8f + receiveLoss * 0.2f;
} }
void UASInfoWidget::updateSeqLossPercent(int uasId, float seqLossPercent)
{
if (_activeUAS && _activeUAS->getUASID() == uasId) {
_seqLossPercent = _seqLossPercent * 0.8f + seqLossPercent * 0.2f;
} else {
_seqLossPercent = 0;
}
}
void UASInfoWidget::updateSeqLossTotal(int uasId, int seqLossTotal)
{
if (_activeUAS && _activeUAS->getUASID() == uasId) {
_seqLossTotal = seqLossTotal;
} else {
_seqLossTotal = 0;
}
}
/** /**
The send loss is typically calculated on the GCS based on packets The send loss is typically calculated on the GCS based on packets
that were received scrambled from the MAV that were received scrambled from the MAV
...@@ -169,14 +192,14 @@ void UASInfoWidget::setVoltage(UASInterface* uas, double voltage) ...@@ -169,14 +192,14 @@ void UASInfoWidget::setVoltage(UASInterface* uas, double voltage)
void UASInfoWidget::setChargeLevel(UASInterface* uas, double chargeLevel) void UASInfoWidget::setChargeLevel(UASInterface* uas, double chargeLevel)
{ {
if (activeUAS == uas) { if (_activeUAS == uas) {
this->chargeLevel = chargeLevel; this->chargeLevel = chargeLevel;
} }
} }
void UASInfoWidget::setTimeRemaining(UASInterface* uas, double seconds) void UASInfoWidget::setTimeRemaining(UASInterface* uas, double seconds)
{ {
if (activeUAS == uas) { if (_activeUAS == uas) {
this->timeRemaining = seconds; this->timeRemaining = seconds;
} }
} }
...@@ -192,6 +215,11 @@ void UASInfoWidget::refresh() ...@@ -192,6 +215,11 @@ void UASInfoWidget::refresh()
ui.receiveLossBar->setValue(qMax(0, qMin(static_cast<int>(receiveLoss), 100))); ui.receiveLossBar->setValue(qMax(0, qMin(static_cast<int>(receiveLoss), 100)));
ui.receiveLossLabel->setText(QString::number(receiveLoss, 'f', 2)); ui.receiveLossLabel->setText(QString::number(receiveLoss, 'f', 2));
ui.seqLossBar->setValue(qMax(0, qMin(static_cast<int>(_seqLossPercent), 100)));
ui.seqLossLabel->setText(QString::number(_seqLossPercent, 'f', 2));
ui.seqcntLossLabel->setText(QString::number(_seqLossTotal));
ui.sendLossBar->setValue(sendLoss); ui.sendLossBar->setValue(sendLoss);
ui.sendLossLabel->setText(QString::number(sendLoss, 'f', 2)); ui.sendLossLabel->setText(QString::number(sendLoss, 'f', 2));
......
...@@ -54,13 +54,16 @@ public: ...@@ -54,13 +54,16 @@ public:
public slots: public slots:
void updateBattery(UASInterface* uas, double voltage, double current, double percent, int seconds); void updateBattery(UASInterface* uas, double voltage, double current, double percent, int seconds);
void updateCPULoad(UASInterface* uas, double load); 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 uasId UNUSED
* @param receiveLoss A percentage value (0-100) of how many message the UAS has failed to receive. * @param receiveLoss A percentage value (0-100) of how many message the UAS has failed to receive.
*/ */
void updateReceiveLoss(int uasId, float receiveLoss); void updateReceiveLoss(int uasId, float receiveLoss);
void updateSeqLossPercent(int uasId, float seqLoss);
void updateSeqLossTotal(int uasId, int seqLossTotal);
/** /**
* @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 uasId UNUSED
...@@ -79,7 +82,6 @@ public slots: ...@@ -79,7 +82,6 @@ public slots:
protected: protected:
UASInterface* activeUAS;
// Configuration variables // Configuration variables
int voltageDecimals; int voltageDecimals;
...@@ -110,6 +112,9 @@ private slots: ...@@ -110,6 +112,9 @@ private slots:
private: private:
Ui::uasInfo ui; Ui::uasInfo ui;
UASInterface* _activeUAS;
float _seqLossPercent;
int _seqLossTotal;
}; };
#endif // _UASINFOWIDGET_H_ #endif // _UASINFOWIDGET_H_
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment