Commit 4348fabe authored by Don Gagne's avatar Don Gagne

Merge pull request #3179 from DonLakeFlyer/SeqLoss

Show mavlink sequence number packet loss in UI
parents 0f884579 393f1533
......@@ -63,7 +63,11 @@ MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app)
, _linkMgr(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()
......@@ -357,11 +361,12 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
{
// Calculate new loss ratio
// Receive loss
float receiveLoss = (double)currLossCounter[mavlinkChannel]/(double)(currReceiveCounter[mavlinkChannel]+currLossCounter[mavlinkChannel]);
receiveLoss *= 100.0f;
float receiveLossPercent = (double)currLossCounter[mavlinkChannel]/(double)(currReceiveCounter[mavlinkChannel]+currLossCounter[mavlinkChannel]);
receiveLossPercent *= 100.0f;
currLossCounter[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
......
......@@ -242,8 +242,9 @@ signals:
void actionGuardChanged(bool enabled);
/** @brief Emitted if action request timeout changed */
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
......
This diff is collapsed.
......@@ -46,10 +46,12 @@ This file is part of the PIXHAWK project
UASInfoWidget::UASInfoWidget(const QString& title, QAction* action, QWidget *parent, QString name)
: QGCDockWidget(title, action, parent)
, _activeUAS(NULL)
, _seqLossPercent(0)
, _seqLossTotal(0)
{
ui.setupUi(this);
this->name = name;
activeUAS = NULL;
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &UASInfoWidget::_activeVehicleChanged);
_activeVehicleChanged(qgcApp()->toolbox()->multiVehicleManager()->activeVehicle());
......@@ -76,6 +78,9 @@ UASInfoWidget::UASInfoWidget(const QString& title, QAction* action, QWidget *par
this->setVisible(false);
loadSettings();
connect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::receiveLossPercentChanged, this, &UASInfoWidget::updateSeqLossPercent);
connect(qgcApp()->toolbox()->mavlinkProtocol(), &MAVLinkProtocol::receiveLossTotalChanged, this, &UASInfoWidget::updateSeqLossTotal);
}
UASInfoWidget::~UASInfoWidget()
......@@ -101,20 +106,20 @@ void UASInfoWidget::hideEvent(QHideEvent* event)
void UASInfoWidget::_activeVehicleChanged(Vehicle* vehicle)
{
if (activeUAS) {
disconnect(activeUAS, &UASInterface::batteryChanged, this, &UASInfoWidget::updateBattery);
disconnect(activeUAS, &UASInterface::dropRateChanged, this, &UASInfoWidget::updateReceiveLoss);
disconnect(static_cast<UAS*>(activeUAS), &UAS::loadChanged, this, &UASInfoWidget::updateCPULoad);
disconnect(activeUAS, &UASInterface::errCountChanged, this, &UASInfoWidget::updateErrorCount);
activeUAS = NULL;
if (_activeUAS) {
disconnect(_activeUAS, &UASInterface::batteryChanged, this, &UASInfoWidget::updateBattery);
disconnect(_activeUAS, &UASInterface::dropRateChanged, this, &UASInfoWidget::updateReceiveLoss);
disconnect(static_cast<UAS*>(_activeUAS), &UAS::loadChanged, this, &UASInfoWidget::updateCPULoad);
disconnect(_activeUAS, &UASInterface::errCountChanged, this, &UASInfoWidget::updateErrorCount);
_activeUAS = NULL;
}
if (vehicle) {
activeUAS = vehicle->uas();
connect(activeUAS, &UASInterface::batteryChanged, this, &UASInfoWidget::updateBattery);
connect(activeUAS, &UASInterface::dropRateChanged, this, &UASInfoWidget::updateReceiveLoss);
connect(static_cast<UAS*>(activeUAS), &UAS::loadChanged, this, &UASInfoWidget::updateCPULoad);
connect(activeUAS, &UASInterface::errCountChanged, this, &UASInfoWidget::updateErrorCount);
_activeUAS = vehicle->uas();
connect(_activeUAS, &UASInterface::batteryChanged, this, &UASInfoWidget::updateBattery);
connect(_activeUAS, &UASInterface::dropRateChanged, this, &UASInfoWidget::updateReceiveLoss);
connect(static_cast<UAS*>(_activeUAS), &UAS::loadChanged, this, &UASInfoWidget::updateCPULoad);
connect(_activeUAS, &UASInterface::errCountChanged, this, &UASInfoWidget::updateErrorCount);
}
}
......@@ -128,8 +133,8 @@ void UASInfoWidget::updateBattery(UASInterface* uas, double voltage, double curr
void UASInfoWidget::updateErrorCount(int uasid, QString component, QString device, int count)
{
//qDebug() << __FILE__ << __LINE__ << activeUAS->getUASID() << "=" << uasid;
if (activeUAS->getUASID() == uasid) {
//qDebug() << __FILE__ << __LINE__ << _activeUAS->getUASID() << "=" << uasid;
if (_activeUAS->getUASID() == uasid) {
errors.remove(component + ":" + device);
errors.insert(component + ":" + device, count);
}
......@@ -140,7 +145,7 @@ void UASInfoWidget::updateErrorCount(int uasid, QString component, QString devic
*/
void UASInfoWidget::updateCPULoad(UASInterface* uas, double load)
{
if (activeUAS == uas) {
if (_activeUAS == uas) {
this->load = load;
}
}
......@@ -151,6 +156,24 @@ void UASInfoWidget::updateReceiveLoss(int uasId, float receiveLoss)
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
that were received scrambled from the MAV
......@@ -169,14 +192,14 @@ void UASInfoWidget::setVoltage(UASInterface* uas, double voltage)
void UASInfoWidget::setChargeLevel(UASInterface* uas, double chargeLevel)
{
if (activeUAS == uas) {
if (_activeUAS == uas) {
this->chargeLevel = chargeLevel;
}
}
void UASInfoWidget::setTimeRemaining(UASInterface* uas, double seconds)
{
if (activeUAS == uas) {
if (_activeUAS == uas) {
this->timeRemaining = seconds;
}
}
......@@ -192,6 +215,11 @@ void UASInfoWidget::refresh()
ui.receiveLossBar->setValue(qMax(0, qMin(static_cast<int>(receiveLoss), 100)));
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.sendLossLabel->setText(QString::number(sendLoss, 'f', 2));
......
......@@ -54,13 +54,16 @@ public:
public slots:
void updateBattery(UASInterface* uas, double voltage, double current, double percent, int seconds);
void updateCPULoad(UASInterface* uas, double load);
/**
* @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.
*/
/**
* @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);
void updateSeqLossPercent(int uasId, float seqLoss);
void updateSeqLossTotal(int uasId, int seqLossTotal);
/**
* @brief Set the loss rate of packets sent from the MAV
* @param uasId UNUSED
......@@ -79,7 +82,6 @@ public slots:
protected:
UASInterface* activeUAS;
// Configuration variables
int voltageDecimals;
......@@ -110,6 +112,9 @@ private slots:
private:
Ui::uasInfo ui;
UASInterface* _activeUAS;
float _seqLossPercent;
int _seqLossTotal;
};
#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