Commit 5114ff8e authored by Bryant Mairs's avatar Bryant Mairs

Added logging of useful values from the HEARTBEAT and SYS_STATUS messages to the realtime plotter.

Removed some dead code.
Added more valueChanged() signals to account for every data type. This moves the conversion over into the valueChanged receivers, which while it will require more slot-functions, makes it easier to add more code as any necessary conversion is done internally to the slot and so the signaler doesn't need to know the details.
I also added some more details on the types of units expected by valueChanged().
parent 8cf835c3
......@@ -404,8 +404,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_sys_status_t state;
mavlink_msg_sys_status_decode(&message, &state);
// Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present.
quint64 time = getUnixTime();
QString name = QString("M%1:SYS_STATUS.%2").arg(message.sysid);
emit valueChanged(uasId, name.arg("sensors_enabled"), "bits", state.onboard_control_sensors_enabled, time);
emit valueChanged(uasId, name.arg("sensors_health"), "bits", state.onboard_control_sensors_health, time);
emit valueChanged(uasId, name.arg("errors_comm"), "-", state.errors_comm, time);
emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time);
emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time);
emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time);
emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time);
// Process CPU load.
emit loadChanged(this,state.load/10.0f);
emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time);
// Battery charge/time remaining/voltage calculations
currentVoltage = state.voltage_battery/1000.0f;
lpVoltage = filterVoltage(currentVoltage);
......@@ -415,9 +429,16 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
chargeLevel = state.battery_remaining;
}
//qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
emit batteryChanged(this, lpVoltage, getChargeLevel(), timeRemaining);
emit voltageChanged(message.sysid, state.voltage_battery/1000);
emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time);
emit voltageChanged(message.sysid, currentVoltage);
emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time);
// And if the battery current draw is measured, log that also.
if (state.current_battery != -1)
{
emit valueChanged(uasId, name.arg("battery_current"), "A", ((double)state.current_battery) / 100.0f, time);
}
// LOW BATTERY ALARM
if (lpVoltage < warnVoltage)
......@@ -435,12 +456,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// by the MAVLink specifications.
if (state.drop_rate_comm > 10000)
{
emit dropRateChanged(this->getUASID(), 100.0f);
}
else
{
emit dropRateChanged(this->getUASID(), state.drop_rate_comm/100.0f);
state.drop_rate_comm = 10000;
}
emit dropRateChanged(this->getUASID(), state.drop_rate_comm/100.0f);
emit valueChanged(uasId, name.arg("drop_rate_comm"), "%", state.drop_rate_comm/100.0f, time);
}
break;
case MAVLINK_MSG_ID_ATTITUDE:
......
......@@ -417,12 +417,19 @@ signals:
*
* @param uasId ID of this system
* @param name name of the value, e.g. "battery voltage"
* @param unit The units this variable is in as an abbreviation. For system-dependent (such as raw ADC values) use "raw", for unitless values use "none".
* @param unit The units this variable is in as an abbreviation. For system-dependent (such as raw ADC values) use "raw", for bitfields use "bits", for true/false or on/off use "bool", for unitless values use "-".
* @param value the value that changed
* @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 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 int value, const quint64 msec);
void voltageChanged(int uasId, double voltage);
void waypointUpdated(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool active);
......
......@@ -478,16 +478,13 @@ void HDDisplay::renderOverlay()
*/
void HDDisplay::setActiveUAS(UASInterface* uas)
{
// Disconnect any previously connected active UAS
if (this->uas != NULL) {
// Disconnect any previously connected active MAV
disconnect(this->uas, SIGNAL(valueChanged(int,QString,QString,double,quint64)), this, SLOT(updateValue(int,QString,QString,double,quint64)));
disconnect(this->uas, SIGNAL(valueChanged(int,QString,QString,int,quint64)), this, SLOT(updateValue(int,QString,QString,int,quint64)));
removeSource(this->uas);
}
// Now connect the new UAS
// Setup communication
connect(uas, SIGNAL(valueChanged(int,QString,QString,double,quint64)), this, SLOT(updateValue(int,QString,QString,double,quint64)));
connect(uas, SIGNAL(valueChanged(int,QString,QString,int,quint64)), this, SLOT(updateValue(int,QString,QString,int,quint64)));
addSource(uas);
this->uas = uas;
}
......@@ -842,28 +839,75 @@ float HDDisplay::refLineWidthToPen(float line)
return line * 2.50f;
}
// Connect a generic source
void HDDisplay::addSource(QObject* obj)
{
//genericSources.append(obj);
// FIXME XXX HACK
// if (plots.size() > 0)
// {
// Connect generic source
connect(obj, SIGNAL(valueChanged(int,QString,QString,int,quint64)), this, SLOT(updateValue(int,QString,QString,int,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,unsigned int,quint64)), this, SLOT(updateValue(int,QString,QString,unsigned int,quint64)));
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)));
// }
}
void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const int value, const quint64 msec)
// Disconnect a generic source
void HDDisplay::removeSource(QObject* obj)
{
//genericSources.append(obj);
// 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)
{
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 unsigned int value, const quint64 msec)
void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec)
{
if (!intValues.contains(name)) intValues.insert(name, true);
updateValue(uasId, name, unit, (double)value, msec);
......
......@@ -64,18 +64,31 @@ public:
~HDDisplay();
public slots:
/** @brief Update a HDD double value */
void updateValue(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
/** @brief Update a HDD integer value */
void updateValue(const int uasId, const QString& name, const QString& unit, const int value, const quint64 msec);
/** @brief Update a HDD integer value */
void updateValue(const int uasId, const QString& name, const QString& unit, const unsigned int value, const quint64 msec);
/** @brief Update a HDD integer value */
/** @brief Update the HDD with new int8 data */
void updateValue(const int uasId, const QString& name, const QString& unit, const qint8 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 a HDD integer value */
/** @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);
/** @brief Connects a source to the updateValue() signals */
void addSource(QObject* obj);
/** @brief Disconnects a source to the updateValue() signals */
void removeSource(QObject* obj);
/** @brief Removes a plot item by the action data */
void removeItemByAction();
......
......@@ -12,12 +12,16 @@ public:
signals:
void textMessageReceived(int uasid, int componentid, int severity, const QString& text);
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 int value, const quint64 msec);
void valueChanged(const int uasId, const QString& name, const QString& unit, const unsigned int value, const quint64 msec);
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 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);
public slots:
/** @brief Receive one message from the protocol and decode it */
......
......@@ -1167,7 +1167,6 @@ void MainWindow::addLink(LinkInterface *link)
MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
if (sim)
{
//connect(sim, SIGNAL(valueChanged(int,QString,double,quint64)), linechart, SLOT(appendData(int,QString,double,quint64)));
connect(ui.actionSimulate, SIGNAL(triggered(bool)), sim, SLOT(connectLink(bool)));
}
}
......
......@@ -294,40 +294,37 @@ void LinechartWidget::createLayout()
connect(scalingLogButton, SIGNAL(clicked()), activePlot, SLOT(setLogarithmicScaling()));
}
void LinechartWidget::appendData(int uasId, QString curve, double value, quint64 usec)
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, qint8 value, quint64 usec)
{
static const QString unit("-");
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);
}
}
appendData(uasId, curve, unit, static_cast<qint64>(value), usec);
}
// 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;
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, quint8 value, quint64 usec)
{
appendData(uasId, curve, unit, static_cast<quint64>(value), usec);
}
logFile->write(QString(QString::number(time) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value,'g',18) + "\n").toLatin1());
logFile->flush();
}
}
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, double value, quint64 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()))
{
......@@ -338,9 +335,12 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
// Make sure the curve will be created if it does not yet exist
if(!label)
{
//qDebug() << "ADDING CURVE IN APPENDDATE DOUBLE";
intData.insert(curve+unit, 0);
addCurve(curve, unit);
}
// Add int data
intData.insert(curve+unit, value);
}
// Log data
......@@ -353,23 +353,13 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
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->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, int value, quint64 usec)
{
appendData(uasId, curve, unit, static_cast<qint64>(value), usec);
}
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, unsigned int 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)
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, quint64 value, quint64 usec)
{
if ((selectedMAV == -1 && isVisible()) || (selectedMAV == uasId && isVisible()))
{
......@@ -404,7 +394,7 @@ 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)
void LinechartWidget::appendData(int uasId, const QString& curve, const QString& unit, double value, quint64 usec)
{
if ((selectedMAV == -1 && isVisible()) || (selectedMAV == uasId && isVisible()))
{
......@@ -415,12 +405,9 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
// Make sure the curve will be created if it does not yet exist
if(!label)
{
intData.insert(curve+unit, 0);
//qDebug() << "ADDING CURVE IN APPENDDATE DOUBLE";
addCurve(curve, unit);
}
// Add int data
intData.insert(curve+unit, value);
}
// Log data
......@@ -433,7 +420,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
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->write(QString(QString::number(time) + "\t" + QString::number(uasId) + "\t" + curve + "\t" + QString::number(value,'g',18) + "\n").toLatin1());
logFile->flush();
}
}
......
......@@ -77,18 +77,25 @@ public slots:
void recolor();
/** @brief Set short names for curves */
void setShortNames(bool enable);
/** @brief Append data without unit */
void appendData(int uasId, QString curve, double data, quint64 usec);
/** @brief Append data with unit */
void appendData(int uasId, const QString& curve, const QString& unit, double value, quint64 usec);
/** @brief Append data as int with unit */
void appendData(int uasId, const QString& curve, const QString& unit, int value, quint64 usec);
/** @brief Append data as unsigned int with unit */
void appendData(int uasId, const QString& curve, const QString& unit, unsigned int value, quint64 usec);
/** @brief Append data as int64 with unit */
/** @brief Append int8 data to the given curve. */
void appendData(int uasId, const QString& curve, const QString& unit, qint8 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 data as uint64 with unit */
/** @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 takeButtonClick(bool checked);
void setPlotWindowPosition(int scrollBarValue);
void setPlotWindowPosition(quint64 position);
......
......@@ -93,12 +93,17 @@ void Linecharts::addSystem(UASInterface* uas)
LinechartWidget* widget = new LinechartWidget(uas->getUASID(), this);
addWidget(widget);
plots.insert(uas->getUASID(), widget);
// Values without unit
//connect(uas, SIGNAL(valueChanged(int,QString,double,quint64)), widget, SLOT(appendData(int,QString,double,quint64)));
// Values with unit as double
connect(uas, SIGNAL(valueChanged(int,QString,QString,double,quint64)), widget, SLOT(appendData(int,QString,QString,double,quint64)));
// Values with unit as integer
connect(uas, SIGNAL(valueChanged(int,QString,QString,int,quint64)), widget, SLOT(appendData(int,QString,QString,int,quint64)));
// 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,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)));
// Set system active if this is the only system
......@@ -110,11 +115,15 @@ void Linecharts::addSystem(UASInterface* uas)
// Connect generic sources
for (int i = 0; i < genericSources.count(); ++i)
{
connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,int,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,int,quint64)));
connect(genericSources[i], SIGNAL(valueChanged(int,QString,QString,unsigned int,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,unsigned int,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)));
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,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
selectSystem(uas->getUASID());
......@@ -130,10 +139,14 @@ void Linecharts::addSource(QObject* obj)
if (plots.size() > 0)
{
// Connect generic source
connect(obj, SIGNAL(valueChanged(int,QString,QString,int,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,int,quint64)));
connect(obj, SIGNAL(valueChanged(int,QString,QString,unsigned int,quint64)), plots.values().first(), SLOT(appendData(int,QString,QString,unsigned int,quint64)));
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,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)));
}
}
}
\ No newline at end of file
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