Commit b9847eb0 authored by Lorenz Meier's avatar Lorenz Meier

Removed a lot of verbose debug output, added connection indication to main...

Removed a lot of verbose debug output, added connection indication to main menu bar to improve situational awareness of operator
parent b2a051df
...@@ -69,6 +69,8 @@ const QColor colorRed(154, 20, 20); ...@@ -69,6 +69,8 @@ const QColor colorRed(154, 20, 20);
const QColor colorGreen(20, 200, 20); const QColor colorGreen(20, 200, 20);
const QColor colorYellow(255, 255, 0); const QColor colorYellow(255, 255, 0);
const QColor colorOrange(255, 140, 0); const QColor colorOrange(255, 140, 0);
const QColor colorMagenta(255, 0, 65);
const QColor colorDarkWhite(240, 240, 240);
const QColor colorDarkYellow(180, 180, 0); const QColor colorDarkYellow(180, 180, 0);
const QColor colorBackground("#050508"); const QColor colorBackground("#050508");
const QColor colorBlack(0, 0, 0); const QColor colorBlack(0, 0, 0);
......
...@@ -9,7 +9,7 @@ QGCUASParamManager::QGCUASParamManager(UASInterface* uas, QWidget *parent) : ...@@ -9,7 +9,7 @@ QGCUASParamManager::QGCUASParamManager(UASInterface* uas, QWidget *parent) :
transmissionTimeout(0), transmissionTimeout(0),
retransmissionTimeout(350), retransmissionTimeout(350),
rewriteTimeout(500), rewriteTimeout(500),
retransmissionBurstRequestSize(2) retransmissionBurstRequestSize(5)
{ {
uas->setParamManager(this); uas->setParamManager(this);
} }
......
...@@ -203,8 +203,6 @@ void UAS::updateState() ...@@ -203,8 +203,6 @@ void UAS::updateState()
quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat; quint64 heartbeatInterval = QGC::groundTimeUsecs() - lastHeartbeat;
if (!connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat)) if (!connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat))
{ {
emit heartbeatTimeout(heartbeatInterval);
emit heartbeatTimeout();
connectionLost = true; connectionLost = true;
QString audiostring = QString("Link lost to system %1").arg(this->getUASID()); QString audiostring = QString("Link lost to system %1").arg(this->getUASID());
GAudioOutput::instance()->say(audiostring.toLower()); GAudioOutput::instance()->say(audiostring.toLower());
...@@ -214,6 +212,7 @@ void UAS::updateState() ...@@ -214,6 +212,7 @@ void UAS::updateState()
if (connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat)) if (connectionLost && (heartbeatInterval > timeoutIntervalHeartbeat))
{ {
connectionLossTime = heartbeatInterval; connectionLossTime = heartbeatInterval;
emit heartbeatTimeout(true, heartbeatInterval/1000);
} }
// Connection gained // Connection gained
...@@ -223,6 +222,7 @@ void UAS::updateState() ...@@ -223,6 +222,7 @@ void UAS::updateState()
GAudioOutput::instance()->say(audiostring.toLower()); GAudioOutput::instance()->say(audiostring.toLower());
connectionLost = false; connectionLost = false;
connectionLossTime = 0; connectionLossTime = 0;
emit heartbeatTimeout(false, 0);
} }
// Position lock is set by the MAVLink message handler // Position lock is set by the MAVLink message handler
...@@ -855,7 +855,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -855,7 +855,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// Emit change // Emit change
emit parameterChanged(uasId, message.compid, parameterName, param); emit parameterChanged(uasId, message.compid, parameterName, param);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param); emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
qDebug() << "RECEIVED PARAM:" << param; // qDebug() << "RECEIVED PARAM:" << param;
} }
break; break;
case MAV_PARAM_TYPE_UINT32: case MAV_PARAM_TYPE_UINT32:
...@@ -866,7 +866,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -866,7 +866,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// Emit change // Emit change
emit parameterChanged(uasId, message.compid, parameterName, param); emit parameterChanged(uasId, message.compid, parameterName, param);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param); emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
qDebug() << "RECEIVED PARAM:" << param; // qDebug() << "RECEIVED PARAM:" << param;
} }
break; break;
case MAV_PARAM_TYPE_INT32: case MAV_PARAM_TYPE_INT32:
...@@ -877,7 +877,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -877,7 +877,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// Emit change // Emit change
emit parameterChanged(uasId, message.compid, parameterName, param); emit parameterChanged(uasId, message.compid, parameterName, param);
emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param); emit parameterChanged(uasId, message.compid, value.param_count, value.param_index, parameterName, param);
qDebug() << "RECEIVED PARAM:" << param; // qDebug() << "RECEIVED PARAM:" << param;
} }
break; break;
default: default:
...@@ -1629,11 +1629,11 @@ void UAS::sendMessage(mavlink_message_t message) ...@@ -1629,11 +1629,11 @@ void UAS::sendMessage(mavlink_message_t message)
// Emit message on all links that are currently connected // Emit message on all links that are currently connected
foreach (LinkInterface* link, *links) foreach (LinkInterface* link, *links)
{ {
qDebug() << "ITERATING THROUGH LINKS"; //qDebug() << "ITERATING THROUGH LINKS";
if (link) if (link)
{ {
sendMessage(link, message); sendMessage(link, message);
qDebug() << "SENT MESSAGE"; //qDebug() << "SENT MESSAGE";
} }
else else
{ {
...@@ -2192,7 +2192,7 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v ...@@ -2192,7 +2192,7 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v
p.target_system = (uint8_t)uasId; p.target_system = (uint8_t)uasId;
p.target_component = (uint8_t)component; p.target_component = (uint8_t)component;
qDebug() << "SENT PARAM:" << value; //qDebug() << "SENT PARAM:" << value;
// Copy string into buffer, ensuring not to exceed the buffer size // Copy string into buffer, ensuring not to exceed the buffer size
for (unsigned int i = 0; i < sizeof(p.param_id); i++) for (unsigned int i = 0; i < sizeof(p.param_id); i++)
...@@ -2232,7 +2232,7 @@ void UAS::requestParameter(int component, int id) ...@@ -2232,7 +2232,7 @@ void UAS::requestParameter(int component, int id)
read.target_component = component; read.target_component = component;
mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read); mavlink_msg_param_request_read_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &read);
sendMessage(msg); sendMessage(msg);
qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM ID" << id; //qDebug() << __FILE__ << __LINE__ << "REQUESTING PARAM RETRANSMISSION FROM COMPONENT" << component << "FOR PARAM ID" << id;
} }
/** /**
......
...@@ -527,10 +527,8 @@ signals: ...@@ -527,10 +527,8 @@ signals:
void irUltraSoundLocalizationChanged(UASInterface* uas, int fix); void irUltraSoundLocalizationChanged(UASInterface* uas, int fix);
// ERROR AND STATUS SIGNALS // ERROR AND STATUS SIGNALS
/** @brief Heartbeat timed out */ /** @brief Heartbeat timed out or was regained */
void heartbeatTimeout(); void heartbeatTimeout(bool timeout, unsigned int ms);
/** @brief Heartbeat timed out */
void heartbeatTimeout(unsigned int ms);
/** @brief Name of system changed */ /** @brief Name of system changed */
void nameChanged(QString newName); void nameChanged(QString newName);
/** @brief System has been selected as focused system */ /** @brief System has been selected as focused system */
......
...@@ -170,7 +170,7 @@ void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QStrin ...@@ -170,7 +170,7 @@ void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QStrin
// Load CSV data // Load CSV data
if (!paramMetaFile.open(QIODevice::ReadOnly | QIODevice::Text)) if (!paramMetaFile.open(QIODevice::ReadOnly | QIODevice::Text))
{ {
qDebug() << "COULD NOT OPEN PARAM META INFO FILE:" << fileName; //qDebug() << "COULD NOT OPEN PARAM META INFO FILE:" << fileName;
return; return;
} }
...@@ -235,7 +235,7 @@ void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QStrin ...@@ -235,7 +235,7 @@ void QGCParamWidget::loadParameterInfoCSV(const QString& autopilot, const QStrin
QString out = separator; QString out = separator;
out.replace("\t", "<tab>"); out.replace("\t", "<tab>");
qDebug() << " Separator: \"" << out << "\""; //qDebug() << " Separator: \"" << out << "\"";
//qDebug() << "READING CSV:" << header; //qDebug() << "READING CSV:" << header;
...@@ -470,7 +470,7 @@ void QGCParamWidget::addParameter(int uas, int component, int paramCount, int pa ...@@ -470,7 +470,7 @@ void QGCParamWidget::addParameter(int uas, int component, int paramCount, int pa
*/ */
void QGCParamWidget::addParameter(int uas, int component, QString parameterName, QVariant value) void QGCParamWidget::addParameter(int uas, int component, QString parameterName, QVariant value)
{ {
qDebug() << "PARAM WIDGET GOT PARAM:" << value; //qDebug() << "PARAM WIDGET GOT PARAM:" << value;
Q_UNUSED(uas); Q_UNUSED(uas);
// Reference to item in tree // Reference to item in tree
QTreeWidgetItem* parameterItem = NULL; QTreeWidgetItem* parameterItem = NULL;
...@@ -800,7 +800,7 @@ void QGCParamWidget::loadParameters() ...@@ -800,7 +800,7 @@ void QGCParamWidget::loadParameters()
break; break;
} }
qDebug() << "MARKING COMP" << wpParams.at(1).toInt() << "PARAM" << wpParams.at(2) << "VALUE" << (float)wpParams.at(3).toDouble() << "AS CHANGED"; //qDebug() << "MARKING COMP" << wpParams.at(1).toInt() << "PARAM" << wpParams.at(2) << "VALUE" << (float)wpParams.at(3).toDouble() << "AS CHANGED";
// Mark in UI // Mark in UI
...@@ -833,7 +833,7 @@ void QGCParamWidget::setRetransmissionGuardEnabled(bool enabled) ...@@ -833,7 +833,7 @@ void QGCParamWidget::setRetransmissionGuardEnabled(bool enabled)
void QGCParamWidget::retransmissionGuardTick() void QGCParamWidget::retransmissionGuardTick()
{ {
if (transmissionActive) { if (transmissionActive) {
qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD ACTIVE, CHECKING FOR DROPS.."; //qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD ACTIVE, CHECKING FOR DROPS..";
// Check for timeout // Check for timeout
// stop retransmission attempts on timeout // stop retransmission attempts on timeout
...@@ -872,7 +872,7 @@ void QGCParamWidget::retransmissionGuardTick() ...@@ -872,7 +872,7 @@ void QGCParamWidget::retransmissionGuardTick()
int count = 0; int count = 0;
foreach (int id, *paramList) { foreach (int id, *paramList) {
if (count < retransmissionBurstRequestSize) { if (count < retransmissionBurstRequestSize) {
qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD REQUESTS RETRANSMISSION OF PARAM #" << id << "FROM COMPONENT #" << component; //qDebug() << __FILE__ << __LINE__ << "RETRANSMISSION GUARD REQUESTS RETRANSMISSION OF PARAM #" << id << "FROM COMPONENT #" << component;
emit requestParameter(component, id); emit requestParameter(component, id);
statusLabel->setText(tr("Requested retransmission of #%1").arg(id+1)); statusLabel->setText(tr("Requested retransmission of #%1").arg(id+1));
count++; count++;
...@@ -915,7 +915,7 @@ void QGCParamWidget::retransmissionGuardTick() ...@@ -915,7 +915,7 @@ void QGCParamWidget::retransmissionGuardTick()
} }
break; break;
default: default:
qCritical() << "ABORTED PARAM RETRANSMISSION, NO VALID QVARIANT TYPE"; //qCritical() << "ABORTED PARAM RETRANSMISSION, NO VALID QVARIANT TYPE";
return; return;
} }
statusLabel->setText(tr("Requested rewrite of: %1: %2").arg(key).arg(missingParams->value(key).toDouble())); statusLabel->setText(tr("Requested rewrite of: %1: %2").arg(key).arg(missingParams->value(key).toDouble()));
...@@ -926,7 +926,7 @@ void QGCParamWidget::retransmissionGuardTick() ...@@ -926,7 +926,7 @@ void QGCParamWidget::retransmissionGuardTick()
} }
} }
} else { } else {
qDebug() << __FILE__ << __LINE__ << "STOPPING RETRANSMISSION GUARD GRACEFULLY"; //qDebug() << __FILE__ << __LINE__ << "STOPPING RETRANSMISSION GUARD GRACEFULLY";
setRetransmissionGuardEnabled(false); setRetransmissionGuardEnabled(false);
} }
} }
...@@ -965,21 +965,21 @@ void QGCParamWidget::setParameter(int component, QString parameterName, QVariant ...@@ -965,21 +965,21 @@ void QGCParamWidget::setParameter(int component, QString parameterName, QVariant
{ {
QVariant fixedValue(value.toInt()); QVariant fixedValue(value.toInt());
emit parameterChanged(component, parameterName, fixedValue); emit parameterChanged(component, parameterName, fixedValue);
qDebug() << "PARAM WIDGET SENT:" << fixedValue; //qDebug() << "PARAM WIDGET SENT:" << fixedValue;
} }
break; break;
case QVariant::UInt: case QVariant::UInt:
{ {
QVariant fixedValue(value.toUInt()); QVariant fixedValue(value.toUInt());
emit parameterChanged(component, parameterName, fixedValue); emit parameterChanged(component, parameterName, fixedValue);
qDebug() << "PARAM WIDGET SENT:" << fixedValue; //qDebug() << "PARAM WIDGET SENT:" << fixedValue;
} }
break; break;
case QMetaType::Float: case QMetaType::Float:
{ {
QVariant fixedValue(value.toFloat()); QVariant fixedValue(value.toFloat());
emit parameterChanged(component, parameterName, fixedValue); emit parameterChanged(component, parameterName, fixedValue);
qDebug() << "PARAM WIDGET SENT:" << fixedValue; //qDebug() << "PARAM WIDGET SENT:" << fixedValue;
} }
break; break;
default: default:
......
...@@ -61,6 +61,11 @@ QGCToolBar::QGCToolBar(QWidget *parent) : ...@@ -61,6 +61,11 @@ QGCToolBar::QGCToolBar(QWidget *parent) :
toolBarNameLabel->setToolTip(tr("Currently controlled vehicle")); toolBarNameLabel->setToolTip(tr("Currently controlled vehicle"));
addWidget(toolBarNameLabel); addWidget(toolBarNameLabel);
toolBarTimeoutLabel = new QLabel("UNCONNECTED", this);
toolBarTimeoutLabel->setToolTip(tr("System timed out, interval since last message"));
toolBarTimeoutLabel->setStyleSheet(QString("QLabel { margin: 0px 2px; font: 14px; color: %1; background-color: %2; }").arg(QGC::colorDarkWhite.name()).arg(QGC::colorMagenta.name()));
addWidget(toolBarTimeoutLabel);
toolBarSafetyLabel = new QLabel("SAFE", this); toolBarSafetyLabel = new QLabel("SAFE", this);
toolBarSafetyLabel->setStyleSheet("QLabel { margin: 0px 2px; font: 14px; color: #14C814; }"); toolBarSafetyLabel->setStyleSheet("QLabel { margin: 0px 2px; font: 14px; color: #14C814; }");
toolBarSafetyLabel->setToolTip(tr("Vehicle safety state")); toolBarSafetyLabel->setToolTip(tr("Vehicle safety state"));
...@@ -110,11 +115,38 @@ QGCToolBar::QGCToolBar(QWidget *parent) : ...@@ -110,11 +115,38 @@ QGCToolBar::QGCToolBar(QWidget *parent) :
setActiveUAS(UASManager::instance()->getActiveUAS()); setActiveUAS(UASManager::instance()->getActiveUAS());
connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
// Set the toolbar to be updated every 2s // Set the toolbar to be updated every 2s
connect(&updateViewTimer, SIGNAL(timeout()), this, SLOT(updateView())); connect(&updateViewTimer, SIGNAL(timeout()), this, SLOT(updateView()));
updateViewTimer.start(2000); updateViewTimer.start(2000);
} }
void QGCToolBar::heartbeatTimeout(bool timeout, unsigned int ms)
{
// set timeout label visible
if (timeout)
{
// Alternate colors to increase visibility
if ((ms / 1000) % 2 == 0)
{
toolBarTimeoutLabel->setStyleSheet(QString("QLabel { margin: 0px 2px; font: 14px; color: %1; background-color: %2; }").arg(QGC::colorDarkWhite.name()).arg(QGC::colorMagenta.name()));
}
else
{
toolBarTimeoutLabel->setStyleSheet(QString("QLabel { margin: 0px 2px; font: 14px; color: %1; background-color: %2; }").arg(QGC::colorDarkWhite.name()).arg(QGC::colorMagenta.dark(250).name()));
}
toolBarTimeoutLabel->setText(tr("CONNECTION LOST: %1 s").arg((ms / 1000.0f), 2, 'f', 1));
}
else
{
// Check if loss text is present, reset once
if (toolBarTimeoutLabel->text() != "")
{
toolBarTimeoutLabel->setText("");
toolBarTimeoutLabel->setStyleSheet(QString(""));
}
}
}
void QGCToolBar::setLogPlayer(QGCMAVLinkLogPlayer* player) void QGCToolBar::setLogPlayer(QGCMAVLinkLogPlayer* player)
{ {
this->player = player; this->player = player;
...@@ -244,6 +276,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active) ...@@ -244,6 +276,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
disconnect(mav, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(receiveTextMessage(int,int,int,QString))); disconnect(mav, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(receiveTextMessage(int,int,int,QString)));
disconnect(mav, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBatteryRemaining(UASInterface*,double,double,int))); disconnect(mav, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBatteryRemaining(UASInterface*,double,double,int)));
disconnect(mav, SIGNAL(armingChanged(bool)), this, SLOT(updateArmingState(bool))); disconnect(mav, SIGNAL(armingChanged(bool)), this, SLOT(updateArmingState(bool)));
disconnect(mav, SIGNAL(heartbeatTimeout(bool, unsigned int)), this, SLOT(heartbeatTimeout(bool,unsigned int)));
if (mav->getWaypointManager()) if (mav->getWaypointManager())
{ {
disconnect(mav->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(updateCurrentWaypoint(quint16))); disconnect(mav->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(updateCurrentWaypoint(quint16)));
...@@ -260,6 +293,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active) ...@@ -260,6 +293,7 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
connect(active, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(receiveTextMessage(int,int,int,QString))); connect(active, SIGNAL(textMessageReceived(int,int,int,QString)), this, SLOT(receiveTextMessage(int,int,int,QString)));
connect(active, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBatteryRemaining(UASInterface*,double,double,int))); connect(active, SIGNAL(batteryChanged(UASInterface*,double,double,int)), this, SLOT(updateBatteryRemaining(UASInterface*,double,double,int)));
connect(active, SIGNAL(armingChanged(bool)), this, SLOT(updateArmingState(bool))); connect(active, SIGNAL(armingChanged(bool)), this, SLOT(updateArmingState(bool)));
connect(active, SIGNAL(heartbeatTimeout(bool, unsigned int)), this, SLOT(heartbeatTimeout(bool,unsigned int)));
if (active->getWaypointManager()) if (active->getWaypointManager())
{ {
connect(active->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(updateCurrentWaypoint(quint16))); connect(active->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(updateCurrentWaypoint(quint16)));
...@@ -274,6 +308,8 @@ void QGCToolBar::setActiveUAS(UASInterface* active) ...@@ -274,6 +308,8 @@ void QGCToolBar::setActiveUAS(UASInterface* active)
symbolButton->setStyleSheet(QString("QWidget { background-color: %1; color: #DDDDDF; background-clip: border; } QToolButton { font-weight: bold; font-size: 12px; border: 0px solid #999999; border-radius: 5px; min-width:22px; max-width: 22px; min-height: 22px; max-height: 22px; padding: 0px; margin: 0px 4px 0px 20px; background-color: none; }").arg(mav->getColor().name())); symbolButton->setStyleSheet(QString("QWidget { background-color: %1; color: #DDDDDF; background-clip: border; } QToolButton { font-weight: bold; font-size: 12px; border: 0px solid #999999; border-radius: 5px; min-width:22px; max-width: 22px; min-height: 22px; max-height: 22px; padding: 0px; margin: 0px 4px 0px 20px; background-color: none; }").arg(mav->getColor().name()));
toolBarModeLabel->setText(mav->getShortMode()); toolBarModeLabel->setText(mav->getShortMode());
toolBarStateLabel->setText(mav->getShortState()); toolBarStateLabel->setText(mav->getShortState());
toolBarTimeoutLabel->setStyleSheet(QString(""));
toolBarTimeoutLabel->setText("");
setSystemType(mav, mav->getSystemType()); setSystemType(mav, mav->getSystemType());
} }
......
...@@ -70,6 +70,8 @@ public slots: ...@@ -70,6 +70,8 @@ public slots:
void updateArmingState(bool armed); void updateArmingState(bool armed);
/** @brief Repaint widgets */ /** @brief Repaint widgets */
void updateView(); void updateView();
/** @brief Update connection timeout time */
void heartbeatTimeout(bool timeout, unsigned int ms);
protected: protected:
void createCustomWidgets(); void createCustomWidgets();
...@@ -79,6 +81,7 @@ protected: ...@@ -79,6 +81,7 @@ protected:
UASInterface* mav; UASInterface* mav;
QToolButton* symbolButton; QToolButton* symbolButton;
QLabel* toolBarNameLabel; QLabel* toolBarNameLabel;
QLabel* toolBarTimeoutLabel;
QLabel* toolBarSafetyLabel; QLabel* toolBarSafetyLabel;
QLabel* toolBarModeLabel; QLabel* toolBarModeLabel;
QLabel* toolBarStateLabel; QLabel* toolBarStateLabel;
......
...@@ -98,7 +98,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) : ...@@ -98,7 +98,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
connect(uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString,QString))); connect(uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString,QString)));
connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString))); connect(uas, SIGNAL(modeChanged(int,QString,QString)), this, SLOT(updateMode(int,QString,QString)));
connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateLoad(UASInterface*, double))); connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateLoad(UASInterface*, double)));
connect(uas, SIGNAL(heartbeatTimeout()), this, SLOT(heartbeatTimeout())); connect(uas, SIGNAL(heartbeatTimeout(bool, unsigned int)), this, SLOT(heartbeatTimeout(bool, unsigned int)));
connect(uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int,int))); connect(uas, SIGNAL(waypointSelected(int,int)), this, SLOT(selectWaypoint(int,int)));
connect(uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointUpdated(quint16))); connect(uas->getWaypointManager(), SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointUpdated(quint16)));
connect(uas, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint))); connect(uas, SIGNAL(systemTypeSet(UASInterface*,uint)), this, SLOT(setSystemType(UASInterface*,uint)));
...@@ -175,9 +175,10 @@ UASView::~UASView() ...@@ -175,9 +175,10 @@ UASView::~UASView()
delete selectAction; delete selectAction;
} }
void UASView::heartbeatTimeout() void UASView::heartbeatTimeout(bool timeout, unsigned int ms)
{ {
timeout = true; Q_UNUSED(ms);
this->timeout = timeout;
} }
void UASView::updateNavMode(int uasid, int mode, const QString& text) void UASView::updateNavMode(int uasid, int mode, const QString& text)
......
...@@ -78,7 +78,7 @@ public slots: ...@@ -78,7 +78,7 @@ public slots:
/** @brief Update the view if an UAS has been set to active */ /** @brief Update the view if an UAS has been set to active */
void updateActiveUAS(UASInterface* uas, bool active); void updateActiveUAS(UASInterface* uas, bool active);
/** @brief Set the widget into critical mode */ /** @brief Set the widget into critical mode */
void heartbeatTimeout(); void heartbeatTimeout(bool timeout, unsigned int ms);
/** @brief Set the background color for the widget */ /** @brief Set the background color for the widget */
void setBackgroundColor(); void setBackgroundColor();
/** @brief Bring up the dialog to rename the system */ /** @brief Bring up the dialog to rename the system */
......
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