Commit a44dcf3c authored by John Tapsell's avatar John Tapsell

Replace 9 seperate valueChanged() signals with just 1, and remove the...

Replace 9 seperate valueChanged() signals with just 1, and remove the resultant tons of code duplication
parent 0694a2ac
...@@ -488,16 +488,7 @@ signals: ...@@ -488,16 +488,7 @@ signals:
* @param value the value that changed * @param value the value that changed
* @param msec the timestamp of the message, in milliseconds * @param msec the timestamp of the message, in milliseconds
*/ */
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec); void valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant &value,const quint64 msecs);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
void valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant value,const quint64 msecs);
void voltageChanged(int uasId, double voltage); void voltageChanged(int uasId, double voltage);
void waypointUpdated(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool active); void waypointUpdated(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool active);
......
...@@ -865,93 +865,36 @@ float HDDisplay::refLineWidthToPen(float line) ...@@ -865,93 +865,36 @@ float HDDisplay::refLineWidthToPen(float line)
// Connect a generic source // Connect a generic source
void HDDisplay::addSource(QObject* obj) void HDDisplay::addSource(QObject* obj)
{ {
//genericSources.append(obj); connect(obj, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)), this, SLOT(updateValue(int,QString,QString,QVariant,quint64)));
// FIXME XXX HACK
// if (plots.size() > 0)
// {
connect(obj, SIGNAL(valueChanged(int,QString,QString,qint8,quint64)), this, SLOT(updateValue(int,QString,QString,qint8,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,quint8,quint64)), this, SLOT(updateValue(int,QString,QString,quint8,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,qint16,quint64)), this, SLOT(updateValue(int,QString,QString,qint16,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,quint16,quint64)), this, SLOT(updateValue(int,QString,QString,quint16,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,qint32,quint64)), this, SLOT(updateValue(int,QString,QString,qint32,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,quint32,quint64)), this, SLOT(updateValue(int,QString,QString,quint32,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,quint64,quint64)), this, SLOT(updateValue(int,QString,QString,quint64,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,qint64,quint64)), this, SLOT(updateValue(int,QString,QString,qint64,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,double,quint64)), this, SLOT(updateValue(int,QString,QString,double,quint64)));
// }
} }
// Disconnect a generic source // Disconnect a generic source
void HDDisplay::removeSource(QObject* obj) void HDDisplay::removeSource(QObject* obj)
{ {
//genericSources.append(obj); disconnect(obj, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)), this, SLOT(updateValue(int,QString,QString,QVariant,quint64)));
// FIXME XXX HACK
// if (plots.size() > 0)
// {
disconnect(obj, SIGNAL(valueChanged(int,QString,QString,qint8,quint64)), this, SLOT(updateValue(int,QString,QString,qint8,quint64)));
disconnect(obj, SIGNAL(valueChanged(int,QString,QString,quint8,quint64)), this, SLOT(updateValue(int,QString,QString,quint8,quint64)));
disconnect(obj, SIGNAL(valueChanged(int,QString,QString,qint16,quint64)), this, SLOT(updateValue(int,QString,QString,qint16,quint64)));
disconnect(obj, SIGNAL(valueChanged(int,QString,QString,quint16,quint64)), this, SLOT(updateValue(int,QString,QString,quint16,quint64)));
disconnect(obj, SIGNAL(valueChanged(int,QString,QString,qint32,quint64)), this, SLOT(updateValue(int,QString,QString,qint32,quint64)));
disconnect(obj, SIGNAL(valueChanged(int,QString,QString,quint32,quint64)), this, SLOT(updateValue(int,QString,QString,quint32,quint64)));
disconnect(obj, SIGNAL(valueChanged(int,QString,QString,quint64,quint64)), this, SLOT(updateValue(int,QString,QString,quint64,quint64)));
disconnect(obj, SIGNAL(valueChanged(int,QString,QString,qint64,quint64)), this, SLOT(updateValue(int,QString,QString,qint64,quint64)));
disconnect(obj, SIGNAL(valueChanged(int,QString,QString,double,quint64)), this, SLOT(updateValue(int,QString,QString,double,quint64)));
// }
}
void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec)
{
if (!intValues.contains(name)) intValues.insert(name, true);
updateValue(uasId, name, unit, (double)value, msec);
}
void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec)
{
if (!intValues.contains(name)) intValues.insert(name, true);
updateValue(uasId, name, unit, (double)value, msec);
}
void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec)
{
if (!intValues.contains(name)) intValues.insert(name, true);
updateValue(uasId, name, unit, (double)value, msec);
}
void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec)
{
if (!intValues.contains(name)) intValues.insert(name, true);
updateValue(uasId, name, unit, (double)value, msec);
} }
void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec) void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const QVariant &variant, const quint64 msec)
{ {
if (!intValues.contains(name)) intValues.insert(name, true); Q_UNUSED(uasId);
updateValue(uasId, name, unit, (double)value, msec); Q_UNUSED(unit);
}
void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec) QMetaType::Type type = static_cast< QMetaType::Type>(variant.type());
{ if(type == QMetaType::QByteArray || type == QMetaType::QString)
if (!intValues.contains(name)) intValues.insert(name, true); return;
updateValue(uasId, name, unit, (double)value, msec);
}
void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec) bool ok;
{ double value = variant.toDouble(&ok);
if (!intValues.contains(name)) intValues.insert(name, true); if(!ok)
updateValue(uasId, name, unit, (double)value, msec); return;
}
void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec) if(type == QMetaType::Int || type == QMetaType::UInt || type == QMetaType::Long || type == QMetaType::LongLong
{ || type == QMetaType::Short || type == QMetaType::Char || type == QMetaType::ULong || type == QMetaType::ULongLong
if (!intValues.contains(name)) intValues.insert(name, true); || type == QMetaType::UShort || type == QMetaType::UChar || type == QMetaType::Bool ) {
updateValue(uasId, name, unit, (double)value, msec); if (!intValues.contains(name))
} intValues.insert(name, true);
}
void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec)
{
Q_UNUSED(uasId);
Q_UNUSED(unit);
// Update mean // Update mean
const float oldMean = valuesMean.value(name, 0.0f); const float oldMean = valuesMean.value(name, 0.0f);
const int meanCount = valuesCount.value(name, 0); const int meanCount = valuesCount.value(name, 0);
......
...@@ -64,24 +64,8 @@ public: ...@@ -64,24 +64,8 @@ public:
~HDDisplay(); ~HDDisplay();
public slots: public slots:
/** @brief Update the HDD with new int8 data */ /** @brief Update the HDD with new data */
void updateValue(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec); void updateValue(const int uasId, const QString& name, const QString& unit, const QVariant &value, const quint64 msec);
/** @brief Update the HDD with new uint8 data */
void updateValue(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec);
/** @brief Update the HDD with new int16 data */
void updateValue(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec);
/** @brief Update the HDD with new uint16 data */
void updateValue(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec);
/** @brief Update the HDD with new int32 data */
void updateValue(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec);
/** @brief Update the HDD with new uint32 data */
void updateValue(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec);
/** @brief Update the HDD with new int64 data */
void updateValue(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec);
/** @brief Update the HDD with new uint64 data */
void updateValue(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec);
/** @brief Update the HDD with new double data */
void updateValue(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
virtual void setActiveUAS(UASInterface* uas); virtual void setActiveUAS(UASInterface* uas);
......
...@@ -12,17 +12,7 @@ public: ...@@ -12,17 +12,7 @@ public:
signals: signals:
void textMessageReceived(int uasid, int componentid, int severity, const QString& text); void textMessageReceived(int uasid, int componentid, int severity, const QString& text);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec); void valueChanged(const int uasId, const QString& name, const QString& unit, const QVariant& value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
//void valueChanged(const int uasId, const QString& name, const QString& unit, const QVariant value, const quint64 msec);
public slots: public slots:
/** @brief Receive one message from the protocol and decode it */ /** @brief Receive one message from the protocol and decode it */
......
...@@ -20,51 +20,20 @@ UASRawStatusView::UASRawStatusView(QWidget *parent) : QWidget(parent) ...@@ -20,51 +20,20 @@ UASRawStatusView::UASRawStatusView(QWidget *parent) : QWidget(parent)
} }
void UASRawStatusView::addSource(MAVLinkDecoder *decoder) void UASRawStatusView::addSource(MAVLinkDecoder *decoder)
{ {
connect(decoder,SIGNAL(valueChanged(int,QString,QString,double,quint64)),this,SLOT(valueChanged(int,QString,QString,double,quint64))); connect(decoder,SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)),this,SLOT(valueChanged(int,QString,QString,QVariant,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint8,quint64)),this,SLOT(valueChanged(int,QString,QString,qint8,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint16,quint64)),this,SLOT(valueChanged(int,QString,QString,qint16,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint32,quint64)),this,SLOT(valueChanged(int,QString,QString,qint32,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint64,quint64)),this,SLOT(valueChanged(int,QString,QString,qint64,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,quint8,quint64)),this,SLOT(valueChanged(int,QString,QString,quint8,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint16,quint64)),this,SLOT(valueChanged(int,QString,QString,qint16,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,quint32,quint64)),this,SLOT(valueChanged(int,QString,QString,quint32,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,quint64,quint64)),this,SLOT(valueChanged(int,QString,QString,quint64,quint64)));
} }
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec) void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const QVariant &variant, const quint64 msec)
{ {
valueChanged(uasId,name,unit,(double)value,msec); Q_UNUSED(uasId);
} Q_UNUSED(unit);
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec) Q_UNUSED(msec);
{
valueChanged(uasId,name,unit,(double)value,msec); bool ok;
} double value = variant.toDouble(&ok);
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec) QMetaType::Type type = static_cast<QMetaType::Type>(variant.type());
{ if(!ok || type == QMetaType::QString || type == QMetaType::QByteArray)
valueChanged(uasId,name,unit,(double)value,msec); return;
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec)
{
valueMap[name] = value; valueMap[name] = value;
if (nameToUpdateWidgetMap.contains(name)) if (nameToUpdateWidgetMap.contains(name))
{ {
......
...@@ -15,15 +15,7 @@ public: ...@@ -15,15 +15,7 @@ public:
void addSource(MAVLinkDecoder *decoder); void addSource(MAVLinkDecoder *decoder);
private slots: private slots:
void updateTableTimerTick(); void updateTableTimerTick();
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec); void valueChanged(const int uasId, const QString& name, const QString& unit, const QVariant& value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
protected: protected:
void resizeEvent(QResizeEvent *event); void resizeEvent(QResizeEvent *event);
private: private:
......
...@@ -75,8 +75,8 @@ ...@@ -75,8 +75,8 @@
</item> </item>
<item row="1" column="9"> <item row="1" column="9">
<widget class="QLineEdit" name="editNameLabel"> <widget class="QLineEdit" name="editNameLabel">
<property name="text"> <property name="placeholderText">
<string>&lt;Parameter Name / Label&gt;</string> <string>Parameter Name</string>
</property> </property>
</widget> </widget>
</item> </item>
......
...@@ -190,8 +190,8 @@ ...@@ -190,8 +190,8 @@
</item> </item>
<item row="1" column="1" colspan="7"> <item row="1" column="1" colspan="7">
<widget class="QLineEdit" name="editNameLabel"> <widget class="QLineEdit" name="editNameLabel">
<property name="text"> <property name="placeholderText">
<string>&lt;Parameter Name / Label&gt;</string> <string>Parameter Name / Label</string>
</property> </property>
</widget> </widget>
</item> </item>
......
...@@ -318,38 +318,15 @@ void LinechartWidget::toggleLogarithmicScaling(bool checked) ...@@ -318,38 +318,15 @@ void LinechartWidget::toggleLogarithmicScaling(bool checked)
activePlot->setLinearScaling(); activePlot->setLinearScaling();
} }
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, qint8 value, quint64 usec) void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, const QVariant &variant, quint64 usec)
{ {
appendData(uasId, curve, unit, static_cast<qint64>(value), usec); QMetaType::Type type = static_cast<QMetaType::Type>(variant.type());
} bool ok;
double value = variant.toDouble(&ok);
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, quint8 value, quint64 usec) if(!ok || type == QMetaType::QByteArray || type == QMetaType::QString)
{ return;
appendData(uasId, curve, unit, static_cast<quint64>(value), usec); bool isDouble = type == QMetaType::Float || type == QMetaType::Double;
}
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, qint16 value, quint64 usec)
{
appendData(uasId, curve, unit, static_cast<qint64>(value), usec);
}
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, quint16 value, quint64 usec)
{
appendData(uasId, curve, unit, static_cast<quint64>(value), usec);
}
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, qint32 value, quint64 usec)
{
appendData(uasId, curve, unit, static_cast<qint64>(value), usec);
}
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, quint32 value, quint64 usec)
{
appendData(uasId, curve, unit, static_cast<quint64>(value), usec);
}
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, qint64 value, quint64 usec)
{
if ((selectedMAV == -1 && isVisible()) || (selectedMAV == uasId && isVisible())) if ((selectedMAV == -1 && isVisible()) || (selectedMAV == uasId && isVisible()))
{ {
// Order matters here, first append to plot, then update curve list // Order matters here, first append to plot, then update curve list
...@@ -359,12 +336,14 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString& ...@@ -359,12 +336,14 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
// Make sure the curve will be created if it does not yet exist // Make sure the curve will be created if it does not yet exist
if(!label) if(!label)
{ {
intData.insert(curve+unit, 0); if(!isDouble)
intData.insert(curve+unit, 0);
addCurve(curve, unit); addCurve(curve, unit);
} }
// Add int data // Add int data
intData.insert(curve+unit, value); if(!isDouble)
intData.insert(curve+unit, variant.toInt());
} }
if (lastTimestamp == 0 && usec != 0) if (lastTimestamp == 0 && usec != 0)
...@@ -394,96 +373,6 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString& ...@@ -394,96 +373,6 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
} }
} }
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, quint64 value, quint64 usec)
{
if ((selectedMAV == -1 && isVisible()) || (selectedMAV == uasId && isVisible()))
{
// Order matters here, first append to plot, then update curve list
activePlot->appendData(curve+unit, usec, value);
// Store data
QLabel* label = curveLabels->value(curve+unit, NULL);
// Make sure the curve will be created if it does not yet exist
if(!label)
{
intData.insert(curve+unit, 0);
addCurve(curve, unit);
}
// Add int data
intData.insert(curve+unit, value);
}
if (lastTimestamp == 0 && usec != 0)
{
lastTimestamp = usec;
} else if (usec != 0) {
// Difference larger than 5 secs, enforce ground time
if (abs((int)((qint64)usec - (quint64)lastTimestamp)) > 5000)
{
autoGroundTimeSet = true;
if (activePlot) activePlot->groundTime();
}
}
// Log data
if (logging)
{
if (activePlot->isVisible(curve+unit))
{
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime;
if (time < 0) time = 0;
logFile->write(QString(QString::number(time) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value) + "\n").toLatin1());
logFile->flush();
}
}
}
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, double value, quint64 usec)
{
if ((selectedMAV == -1 && isVisible()) || (selectedMAV == uasId && isVisible()))
{
// Order matters here, first append to plot, then update curve list
activePlot->appendData(curve+unit, usec, value);
// Store data
QLabel* label = curveLabels->value(curve+unit, NULL);
// Make sure the curve will be created if it does not yet exist
if(!label)
{
addCurve(curve, unit);
}
}
if (lastTimestamp == 0 && usec != 0)
{
lastTimestamp = usec;
} else if (usec != 0) {
// Difference larger than 1 sec, enforce ground time
if (abs((int)((qint64)usec - (quint64)lastTimestamp)) > 1000)
{
autoGroundTimeSet = true;
if (activePlot) activePlot->groundTime();
}
}
// Log data
if (logging)
{
if (activePlot->isVisible(curve+unit))
{
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime;
if (time < 0) time = 0;
logFile->write(QString(QString::number(time) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value,'g',18) + "\n").toLatin1());
logFile->flush();
}
}
}
void LinechartWidget::refresh() void LinechartWidget::refresh()
{ {
setUpdatesEnabled(false); setUpdatesEnabled(false);
......
...@@ -77,24 +77,8 @@ public slots: ...@@ -77,24 +77,8 @@ public slots:
void recolor(); void recolor();
/** @brief Set short names for curves */ /** @brief Set short names for curves */
void setShortNames(bool enable); void setShortNames(bool enable);
/** @brief Append int8 data to the given curve. */ /** @brief Append data to the given curve. */
void appendData(int uasId, const QString& curve, const QString& unit, qint8 value, quint64 usec); void appendData(int uasId, const QString& curve, const QString& unit, const QVariant& value, quint64 usec);
/** @brief Append uint8 data to the given curve. */
void appendData(int uasId, const QString& curve, const QString& unit, quint8 value, quint64 usec);
/** @brief Append int16 data to the given curve. */
void appendData(int uasId, const QString& curve, const QString& unit, qint16 value, quint64 usec);
/** @brief Append uint16 data to the given curve. */
void appendData(int uasId, const QString& curve, const QString& unit, quint16 value, quint64 usec);
/** @brief Append int32 data to the given curve. */
void appendData(int uasId, const QString& curve, const QString& unit, qint32 value, quint64 usec);
/** @brief Append uint32 data to the given curve. */
void appendData(int uasId, const QString& curve, const QString& unit, quint32 value, quint64 usec);
/** @brief Append int64 data to the given curve. */
void appendData(int uasId, const QString& curve, const QString& unit, qint64 value, quint64 usec);
/** @brief Append uint64 data to the given curve. */
void appendData(int uasId, const QString& curve, const QString& unit, quint64 value, quint64 usec);
/** @brief Append double data to the given curve. */
void appendData(int uasId, const QString& curve, const QString& unit, double value, quint64 usec);
void toggleLogarithmicScaling(bool toggled); void toggleLogarithmicScaling(bool toggled);
void takeButtonClick(bool checked); void takeButtonClick(bool checked);
......
...@@ -100,15 +100,7 @@ void Linecharts::addSystem(UASInterface* uas) ...@@ -100,15 +100,7 @@ void Linecharts::addSystem(UASInterface* uas)
plots.insert(uasid, widget); plots.insert(uasid, widget);
// Connect valueChanged signals // Connect valueChanged signals
connect(uas, SIGNAL(valueChanged(int,QString,QString,quint8,quint64)), widget, SLOT(appendData(int,QString,QString,quint8,quint64))); connect(uas, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)), widget, SLOT(appendData(int,QString,QString,QVariant,quint64)));
connect(uas, SIGNAL(valueChanged(int,QString,QString,qint8,quint64)), widget, SLOT(appendData(int,QString,QString,qint8,quint64)));
connect(uas, SIGNAL(valueChanged(int,QString,QString,quint16,quint64)), widget, SLOT(appendData(int,QString,QString,quint16,quint64)));
connect(uas, SIGNAL(valueChanged(int,QString,QString,qint16,quint64)), widget, SLOT(appendData(int,QString,QString,qint16,quint64)));
connect(uas, SIGNAL(valueChanged(int,QString,QString,quint32,quint64)), widget, SLOT(appendData(int,QString,QString,quint32,quint64)));
connect(uas, SIGNAL(valueChanged(int,QString,QString,qint32,quint64)), widget, SLOT(appendData(int,QString,QString,qint32,quint64)));
connect(uas, SIGNAL(valueChanged(int,QString,QString,quint64,quint64)), widget, SLOT(appendData(int,QString,QString,quint64,quint64)));
connect(uas, SIGNAL(valueChanged(int,QString,QString,qint64,quint64)), widget, SLOT(appendData(int,QString,QString,qint64,quint64)));
connect(uas, SIGNAL(valueChanged(int,QString,QString,double,quint64)), widget, SLOT(appendData(int,QString,QString,double,quint64)));
connect(widget, SIGNAL(logfileWritten(QString)), this, SIGNAL(logfileWritten(QString))); connect(widget, SIGNAL(logfileWritten(QString)), this, SIGNAL(logfileWritten(QString)));
// Set system active if this is the only system // Set system active if this is the only system
...@@ -120,15 +112,7 @@ void Linecharts::addSystem(UASInterface* uas) ...@@ -120,15 +112,7 @@ void Linecharts::addSystem(UASInterface* uas)
// Connect generic sources // Connect generic sources
for (int i = 0; i < genericSources.count(); ++i) for (int i = 0; i < genericSources.count(); ++i)
{ {
connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,quint8,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,quint8,quint64))); connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,QVariant,quint64)));
connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,qint8,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,qint8,quint64)));
connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,quint16,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,quint16,quint64)));
connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,qint16,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,qint16,quint64)));
connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,quint32,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,quint32,quint64)));
connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,qint32,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,qint32,quint64)));
connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,quint64,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,quint64,quint64)));
connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,qint64,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,qint64,quint64)));
connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,double,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,double,quint64)));
} }
// Select system // Select system
widget->setActive(true); widget->setActive(true);
...@@ -145,14 +129,6 @@ void Linecharts::addSource(QObject* obj) ...@@ -145,14 +129,6 @@ void Linecharts::addSource(QObject* obj)
if (plots.size() > 0) if (plots.size() > 0)
{ {
// Connect generic source // Connect generic source
connect(obj, SIGNAL(valueChanged(int,QString,QString,quint8,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,quint8,quint64))); connect(obj, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,QVariant,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,qint8,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,qint8,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,quint16,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,quint16,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,qint16,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,qint16,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,quint32,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,quint32,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,qint32,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,qint32,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,quint64,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,quint64,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,qint64,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,qint64,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,double,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,double,quint64)));
} }
} }
...@@ -267,107 +267,18 @@ void UASQuickView::setActiveUAS(UASInterface* uas) ...@@ -267,107 +267,18 @@ void UASQuickView::setActiveUAS(UASInterface* uas)
} }
void UASQuickView::addSource(MAVLinkDecoder *decoder) void UASQuickView::addSource(MAVLinkDecoder *decoder)
{ {
connect(decoder,SIGNAL(valueChanged(int,QString,QString,double,quint64)),this,SLOT(valueChanged(int,QString,QString,double,quint64))); connect(decoder,SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)),this,SLOT(valueChanged(int,QString,QString,QVariant,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint8,quint64)),this,SLOT(valueChanged(int,QString,QString,qint8,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint16,quint64)),this,SLOT(valueChanged(int,QString,QString,qint16,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint32,quint64)),this,SLOT(valueChanged(int,QString,QString,qint32,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint64,quint64)),this,SLOT(valueChanged(int,QString,QString,qint64,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,quint8,quint64)),this,SLOT(valueChanged(int,QString,QString,quint8,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,quint16,quint64)),this,SLOT(valueChanged(int,QString,QString,quint16,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,quint32,quint64)),this,SLOT(valueChanged(int,QString,QString,quint32,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,quint64,quint64)),this,SLOT(valueChanged(int,QString,QString,quint64,quint64)));
}
void UASQuickView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec)
{
if (!uasPropertyValueMap.contains(name))
{
if (quickViewSelectDialog)
{
quickViewSelectDialog->addItem(name);
}
}
uasPropertyValueMap[name] = value;
} }
void UASQuickView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec) void UASQuickView::valueChanged(const int uasId, const QString& name, const QString& unit, const QVariant &variant, const quint64 msec)
{
if (!uasPropertyValueMap.contains(name))
{
if (quickViewSelectDialog)
{
quickViewSelectDialog->addItem(name);
}
}
uasPropertyValueMap[name] = value;
}
void UASQuickView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec)
{
if (!uasPropertyValueMap.contains(name))
{
if (quickViewSelectDialog)
{
quickViewSelectDialog->addItem(name);
}
}
uasPropertyValueMap[name] = value;
}
void UASQuickView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec)
{
if (!uasPropertyValueMap.contains(name))
{
if (quickViewSelectDialog)
{
quickViewSelectDialog->addItem(name);
}
}
uasPropertyValueMap[name] = value;
}
void UASQuickView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec)
{
if (!uasPropertyValueMap.contains(name))
{
if (quickViewSelectDialog)
{
quickViewSelectDialog->addItem(name);
}
}
uasPropertyValueMap[name] = value;
}
void UASQuickView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec)
{
if (!uasPropertyValueMap.contains(name))
{
if (quickViewSelectDialog)
{
quickViewSelectDialog->addItem(name);
}
}
uasPropertyValueMap[name] = value;
}
void UASQuickView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec)
{
if (!uasPropertyValueMap.contains(name))
{
if (quickViewSelectDialog)
{
quickViewSelectDialog->addItem(name);
}
}
uasPropertyValueMap[name] = value;
}
void UASQuickView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec)
{
if (!uasPropertyValueMap.contains(name))
{
if (quickViewSelectDialog)
{
quickViewSelectDialog->addItem(name);
}
}
uasPropertyValueMap[name] = value;
}
void UASQuickView::valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec)
{ {
Q_UNUSED(uasId);
Q_UNUSED(unit);
bool ok;
double value = variant.toDouble(&ok);
if(!ok || variant.type() == QMetaType::QString || variant.type() == QMetaType::QByteArray)
return;
if (!uasPropertyValueMap.contains(name)) if (!uasPropertyValueMap.contains(name))
{ {
if (quickViewSelectDialog) if (quickViewSelectDialog)
...@@ -410,13 +321,3 @@ void UASQuickView::actionTriggered(bool checked) ...@@ -410,13 +321,3 @@ void UASQuickView::actionTriggered(bool checked)
} }
} }
void UASQuickView::valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant value,const quint64 msecs)
{
uasPropertyValueMap[name] = value.toDouble();
}
void UASQuickView::valChanged(double val,QString type)
{
//qDebug() << "Value changed:" << type << val;
// uasPropertyValueMap[type] = val;
}
...@@ -59,23 +59,12 @@ protected: ...@@ -59,23 +59,12 @@ protected:
signals: signals:
public slots: public slots:
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec); void valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant& value,const quint64 msecs);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
void valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant value,const quint64 msecs);
void actionTriggered(bool checked); void actionTriggered(bool checked);
void actionTriggered(); void actionTriggered();
void updateTimerTick(); void updateTimerTick();
void addUAS(UASInterface* uas); void addUAS(UASInterface* uas);
void setActiveUAS(UASInterface* uas); void setActiveUAS(UASInterface* uas);
void valChanged(double val,QString type);
void selectDialogClosed(); void selectDialogClosed();
void valueEnabled(QString value); void valueEnabled(QString value);
void valueDisabled(QString value); void valueDisabled(QString value);
......
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