Browse Source

Merge branch 'v10release' of github.com:pixhawk/qgroundcontrol into v10release

QGC4.4
LM 14 years ago
parent
commit
ba97a1e3d3
  1. 30
      qgroundcontrol.pro
  2. 22
      src/GAudioOutput.cc
  3. 1
      src/comm/MAVLinkSimulationLink.h
  4. 5
      src/comm/SerialLink.cc
  5. 71
      src/ui/HDDisplay.cc
  6. 8
      src/ui/HDDisplay.h
  7. 2
      src/ui/HSIDisplay.cc
  8. 10
      src/ui/MainWindow.cc
  9. 27
      src/ui/QGCMAVLinkInspector.cc
  10. 3
      src/ui/QGCMAVLinkInspector.h
  11. 4
      src/ui/linechart/LinechartWidget.cc

30
qgroundcontrol.pro

@ -542,19 +542,19 @@ TRANSLATIONS += es-MX.ts \
# xbee support # xbee support
# libxbee only supported by linux and windows systems # libxbee only supported by linux and windows systems
win32-msvc2008|win32-msvc2010|linux{ #win32-msvc2008|win32-msvc2010|linux{
HEADERS += src/comm/XbeeLinkInterface.h \ # HEADERS += src/comm/XbeeLinkInterface.h \
src/comm/XbeeLink.h \ # src/comm/XbeeLink.h \
src/comm/HexSpinBox.h \ # src/comm/HexSpinBox.h \
src/ui/XbeeConfigurationWindow.h \ # src/ui/XbeeConfigurationWindow.h \
src/comm/CallConv.h # src/comm/CallConv.h
SOURCES += src/comm/XbeeLink.cpp \ # SOURCES += src/comm/XbeeLink.cpp \
src/comm/HexSpinBox.cpp \ # src/comm/HexSpinBox.cpp \
src/ui/XbeeConfigurationWindow.cpp # src/ui/XbeeConfigurationWindow.cpp
DEFINES += XBEELINK # DEFINES += XBEELINK
INCLUDEPATH += thirdParty/libxbee # INCLUDEPATH += thirdParty/libxbee
# TO DO: build library when it does not exists already # TO DO: build library when it does not exists already
LIBS += -LthirdParty/libxbee/lib \ # LIBS += -LthirdParty/libxbee/lib \
-llibxbee # -llibxbee
#
} #}

22
src/GAudioOutput.cc

@ -119,9 +119,9 @@ GAudioOutput::GAudioOutput(QObject* parent) : QObject(parent),
} }
#endif #endif
// Initialize audio output // Initialize audio output
m_media = new Phonon::MediaObject(this); //m_media = new Phonon::MediaObject(this);
Phonon::AudioOutput *audioOutput = new Phonon::AudioOutput(Phonon::MusicCategory, this); //Phonon::AudioOutput *audioOutput = new Phonon::AudioOutput(Phonon::MusicCategory, this);
createPath(m_media, audioOutput); //createPath(m_media, audioOutput);
// Prepare regular emergency signal, will be fired off on calling startEmergency() // Prepare regular emergency signal, will be fired off on calling startEmergency()
emergencyTimer = new QTimer(); emergencyTimer = new QTimer();
@ -184,8 +184,8 @@ bool GAudioOutput::say(QString text, int severity)
cst_wave* wav = flite_text_to_wave(text.toStdString().c_str(), v); cst_wave* wav = flite_text_to_wave(text.toStdString().c_str(), v);
// file.fileName() returns the unique file name // file.fileName() returns the unique file name
cst_wave_save(wav, file.fileName().toStdString().c_str(), "riff"); cst_wave_save(wav, file.fileName().toStdString().c_str(), "riff");
m_media->setCurrentSource(Phonon::MediaSource(file.fileName().toStdString().c_str())); //m_media->setCurrentSource(Phonon::MediaSource(file.fileName().toStdString().c_str()));
m_media->play(); //m_media->play();
res = true; res = true;
} }
#endif #endif
@ -228,8 +228,8 @@ void GAudioOutput::notifyPositive()
if (!muted) { if (!muted) {
// Use QFile to transform path for all OS // Use QFile to transform path for all OS
QFile f(QCoreApplication::applicationDirPath()+QString("/audio/double_notify.wav")); QFile f(QCoreApplication::applicationDirPath()+QString("/audio/double_notify.wav"));
m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str())); //m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str()));
m_media->play(); //m_media->play();
} }
} }
@ -238,8 +238,8 @@ void GAudioOutput::notifyNegative()
if (!muted) { if (!muted) {
// Use QFile to transform path for all OS // Use QFile to transform path for all OS
QFile f(QCoreApplication::applicationDirPath()+QString("/audio/flat_notify.wav")); QFile f(QCoreApplication::applicationDirPath()+QString("/audio/flat_notify.wav"));
m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str())); //m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str()));
m_media->play(); //m_media->play();
} }
} }
@ -283,8 +283,8 @@ void GAudioOutput::beep()
// Use QFile to transform path for all OS // Use QFile to transform path for all OS
QFile f(QCoreApplication::applicationDirPath()+QString("/audio/alert.wav")); QFile f(QCoreApplication::applicationDirPath()+QString("/audio/alert.wav"));
qDebug() << "FILE:" << f.fileName(); qDebug() << "FILE:" << f.fileName();
m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str())); //m_media->setCurrentSource(Phonon::MediaSource(f.fileName().toStdString().c_str()));
m_media->play(); //m_media->play();
} }
} }

1
src/comm/MAVLinkSimulationLink.h

@ -38,6 +38,7 @@ This file is part of the QGROUNDCONTROL project
#include <QQueue> #include <QQueue>
#include <QMutex> #include <QMutex>
#include <QMap> #include <QMap>
#include <qmath.h>
#include <inttypes.h> #include <inttypes.h>
#include "QGCMAVLink.h" #include "QGCMAVLink.h"

5
src/comm/SerialLink.cc

@ -211,8 +211,9 @@ using namespace TNX;
SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl, bool parity, SerialLink::SerialLink(QString portname, int baudRate, bool hardwareFlowControl, bool parity,
int dataBits, int stopBits) : int dataBits, int stopBits) :
port(NULL), m_stopp(false), port(NULL),
ports(new QVector<QString>()) ports(new QVector<QString>()),
m_stopp(false)
{ {
// Setup settings // Setup settings
this->porthandle = portname.trimmed(); this->porthandle = portname.trimmed();

71
src/ui/HDDisplay.cc

@ -216,7 +216,7 @@ void HDDisplay::saveState()
// Restore instrument settings // Restore instrument settings
for (int i = 0; i < acceptList->count(); i++) { for (int i = 0; i < acceptList->count(); i++) {
QString key = acceptList->at(i); QString key = acceptList->at(i);
instruments += "|" + QString::number(minValues.value(key, -1.0))+","+key+","+acceptUnitList->at(i)+","+QString::number(maxValues.value(key, +1.0))+","+((symmetric.value(key, false)) ? "s" : ""); instruments += "|" + QString::number(minValues.value(key, -1.0))+","+key+","+acceptUnitList->at(i)+","+QString::number(maxValues.value(key, +1.0))+","+customNames.value(key, "")+","+((symmetric.value(key, false)) ? "s" : "");
} }
// qDebug() << "Saving" << instruments; // qDebug() << "Saving" << instruments;
@ -271,16 +271,23 @@ void HDDisplay::addGauge()
QStringList items; QStringList items;
for (int i = 0; i < values.count(); ++i) { for (int i = 0; i < values.count(); ++i) {
QString key = values.keys().at(i); QString key = values.keys().at(i);
QString label = key;
QStringList keySplit = key.split(".");
if (keySplit.size() > 1)
{
keySplit.removeFirst();
label = keySplit.join(".");
}
QString unit = units.value(key); QString unit = units.value(key);
if (unit.contains("deg") || unit.contains("rad")) { if (unit.contains("deg") || unit.contains("rad")) {
items.append(QString("%1,%2,%3,%4,s").arg("-180").arg(key).arg(unit).arg("+180")); items.append(QString("%1,%2,%3,%4,%5,s").arg("-180").arg(key).arg(unit).arg("+180").arg(label));
} else { } else {
items.append(QString("%1,%2,%3,%4").arg("0").arg(key).arg(unit).arg("+100")); items.append(QString("%1,%2,%3,%4,%5").arg("0").arg(key).arg(unit).arg("+100").arg(label));
} }
} }
bool ok; bool ok;
QString item = QInputDialog::getItem(this, tr("Add Gauge Instrument"), QString item = QInputDialog::getItem(this, tr("Add Gauge Instrument"),
tr("Format: min, curve name, unit, max[,s]"), items, 0, true, &ok); tr("Format: min, data name, unit, max, label [,s]"), items, 0, true, &ok);
if (ok && !item.isEmpty()) { if (ok && !item.isEmpty()) {
addGauge(item); addGauge(item);
} }
@ -307,9 +314,19 @@ void HDDisplay::addGauge(const QString& gauge)
val = parts.at(3).toDouble(&ok); val = parts.at(3).toDouble(&ok);
success &= ok; success &= ok;
if (ok) maxValues.insert(key, val); if (ok) maxValues.insert(key, val);
// Convert name
if (parts.length() >= 5)
{
if (parts.at(4).length() > 0)
{
customNames.insert(key, parts.at(4));
}
}
// Convert symmetric flag // Convert symmetric flag
if (parts.length() >= 5) { if (parts.length() >= 6)
if (parts.at(4).contains("s")) { {
if (parts.at(5).contains("s"))
{
symmetric.insert(key, true); symmetric.insert(key, true);
} }
} }
@ -425,12 +442,15 @@ void HDDisplay::renderOverlay()
float topSpacing = leftSpacing; float topSpacing = leftSpacing;
float yCoord = topSpacing + gaugeWidth/2.0f; float yCoord = topSpacing + gaugeWidth/2.0f;
for (int i = 0; i < acceptList->size(); ++i) { for (int i = 0; i < acceptList->size(); ++i)
{
QString value = acceptList->at(i); QString value = acceptList->at(i);
drawGauge(xCoord, yCoord, gaugeWidth/2.0f, minValues.value(value, -1.0f), maxValues.value(value, 1.0f), value, values.value(value, minValues.value(value, 0.0f)), gaugeColor, &painter, symmetric.value(value, false), goodRanges.value(value, qMakePair(0.0f, 0.5f)), critRanges.value(value, qMakePair(0.7f, 1.0f)), true); QString label = customNames.value(value);
drawGauge(xCoord, yCoord, gaugeWidth/2.0f, minValues.value(value, -1.0f), maxValues.value(value, 1.0f), label, values.value(value, minValues.value(value, 0.0f)), gaugeColor, &painter, symmetric.value(value, false), goodRanges.value(value, qMakePair(0.0f, 0.5f)), critRanges.value(value, qMakePair(0.7f, 1.0f)), true);
xCoord += gaugeWidth + leftSpacing; xCoord += gaugeWidth + leftSpacing;
// Move one row down if necessary // Move one row down if necessary
if (xCoord + gaugeWidth*0.9f > vwidth) { if (xCoord + gaugeWidth*0.9f > vwidth)
{
yCoord += topSpacing + gaugeWidth; yCoord += topSpacing + gaugeWidth;
xCoord = leftSpacing + gaugeWidth/2.0f; xCoord = leftSpacing + gaugeWidth/2.0f;
} }
@ -807,12 +827,45 @@ float HDDisplay::refLineWidthToPen(float line)
return line * 2.50f; return line * 2.50f;
} }
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,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) void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const int value, const quint64 msec)
{ {
if (!intValues.contains(name)) intValues.insert(name, true); if (!intValues.contains(name)) intValues.insert(name, true);
updateValue(uasId, name, unit, (double)value, msec); 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)
{
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 qint64 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 quint64 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 double value, const quint64 msec) void HDDisplay::updateValue(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec)
{ {
Q_UNUSED(uasId); Q_UNUSED(uasId);

8
src/ui/HDDisplay.h

@ -68,7 +68,14 @@ public slots:
void updateValue(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec); void updateValue(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
/** @brief Update a HDD integer value */ /** @brief Update a HDD integer value */
void updateValue(const int uasId, const QString& name, const QString& unit, const int value, const quint64 msec); 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 */
void updateValue(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec);
/** @brief Update a HDD integer value */
void updateValue(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec);
virtual void setActiveUAS(UASInterface* uas); virtual void setActiveUAS(UASInterface* uas);
void addSource(QObject* obj);
/** @brief Removes a plot item by the action data */ /** @brief Removes a plot item by the action data */
void removeItemByAction(); void removeItemByAction();
@ -149,6 +156,7 @@ protected:
QMap<QString, float> maxValues; ///< The maximum value this variable is assumed to have QMap<QString, float> maxValues; ///< The maximum value this variable is assumed to have
QMap<QString, bool> symmetric; ///< Draw the gauge / dial symmetric bool = yes QMap<QString, bool> symmetric; ///< Draw the gauge / dial symmetric bool = yes
QMap<QString, bool> intValues; ///< Is the gauge value an integer? QMap<QString, bool> intValues; ///< Is the gauge value an integer?
QMap<QString, QString> customNames; ///< Custom names for the data names
QMap<QString, QPair<float, float> > goodRanges; ///< The range of good values QMap<QString, QPair<float, float> > goodRanges; ///< The range of good values
QMap<QString, QPair<float, float> > critRanges; ///< The range of critical values QMap<QString, QPair<float, float> > critRanges; ///< The range of critical values
double scalingFactor; ///< Factor used to scale all absolute values to screen coordinates double scalingFactor; ///< Factor used to scale all absolute values to screen coordinates

2
src/ui/HSIDisplay.cc

@ -99,8 +99,8 @@ HSIDisplay::HSIDisplay(QWidget *parent) :
laserFix(0), laserFix(0),
mavInitialized(false), mavInitialized(false),
bottomMargin(10.0f), bottomMargin(10.0f),
topMargin(12.0f),
dragStarted(false), dragStarted(false),
topMargin(12.0f),
leftDragStarted(false), leftDragStarted(false),
mouseHasMoved(false), mouseHasMoved(false),
actionPending(false), actionPending(false),

10
src/ui/MainWindow.cc

@ -91,9 +91,9 @@ MainWindow::MainWindow(QWidget *parent):
currentStyle(QGC_MAINWINDOW_STYLE_INDOOR), currentStyle(QGC_MAINWINDOW_STYLE_INDOOR),
aboutToCloseFlag(false), aboutToCloseFlag(false),
changingViewsFlag(false), changingViewsFlag(false),
centerStackActionGroup(this),
styleFileName(QCoreApplication::applicationDirPath() + "/style-indoor.css"), styleFileName(QCoreApplication::applicationDirPath() + "/style-indoor.css"),
autoReconnect(false), autoReconnect(false),
centerStackActionGroup(this),
lowPowerMode(false) lowPowerMode(false)
{ {
hide(); hide();
@ -427,14 +427,18 @@ void MainWindow::buildCommonWidgets()
if (!headDown1DockWidget) { if (!headDown1DockWidget) {
headDown1DockWidget = new QDockWidget(tr("Flight Display"), this); headDown1DockWidget = new QDockWidget(tr("Flight Display"), this);
headDown1DockWidget->setWidget( new HDDisplay(acceptList, "Flight Display", this) ); HDDisplay* hdDisplay = new HDDisplay(acceptList, "Flight Display", this);
hdDisplay->addSource(mavlinkDecoder);
headDown1DockWidget->setWidget(hdDisplay);
headDown1DockWidget->setObjectName("HEAD_DOWN_DISPLAY_1_DOCK_WIDGET"); headDown1DockWidget->setObjectName("HEAD_DOWN_DISPLAY_1_DOCK_WIDGET");
addTool(headDown1DockWidget, tr("Flight Display"), Qt::RightDockWidgetArea); addTool(headDown1DockWidget, tr("Flight Display"), Qt::RightDockWidgetArea);
} }
if (!headDown2DockWidget) { if (!headDown2DockWidget) {
headDown2DockWidget = new QDockWidget(tr("Actuator Status"), this); headDown2DockWidget = new QDockWidget(tr("Actuator Status"), this);
headDown2DockWidget->setWidget( new HDDisplay(acceptList2, "Actuator Status", this) ); HDDisplay* hdDisplay = new HDDisplay(acceptList2, "Actuator Status", this);
hdDisplay->addSource(mavlinkDecoder);
headDown2DockWidget->setWidget(hdDisplay);
headDown2DockWidget->setObjectName("HEAD_DOWN_DISPLAY_2_DOCK_WIDGET"); headDown2DockWidget->setObjectName("HEAD_DOWN_DISPLAY_2_DOCK_WIDGET");
addTool(headDown2DockWidget, tr("Actuator Status"), Qt::RightDockWidgetArea); addTool(headDown2DockWidget, tr("Actuator Status"), Qt::RightDockWidgetArea);
} }

27
src/ui/QGCMAVLinkInspector.cc

@ -37,10 +37,11 @@ void QGCMAVLinkInspector::refreshView()
// Ignore NULL values // Ignore NULL values
if (!msg) continue; if (!msg) continue;
// Update the tree view // Update the tree view
QString messageName("%1 (%2 Hz, #%3)");
messageName = messageName.arg(messageInfo[msg->msgid].name).arg(messagesHz.value(msg->msgid, 0), 2, 'f', 0).arg(msg->msgid);
if (!treeWidgetItems.contains(msg->msgid)) if (!treeWidgetItems.contains(msg->msgid))
{ {
QString messageName("%1 (#%2)");
messageName = messageName.arg(messageInfo[msg->msgid].name).arg(msg->msgid);
QStringList fields; QStringList fields;
fields << messageName; fields << messageName;
QTreeWidgetItem* widget = new QTreeWidgetItem(fields); QTreeWidgetItem* widget = new QTreeWidgetItem(fields);
@ -56,7 +57,10 @@ void QGCMAVLinkInspector::refreshView()
ui->treeWidget->addTopLevelItem(widget); ui->treeWidget->addTopLevelItem(widget);
} }
// Set Hz
QTreeWidgetItem* message = treeWidgetItems.value(msg->msgid); QTreeWidgetItem* message = treeWidgetItems.value(msg->msgid);
message->setFirstColumnSpanned(true);
message->setData(0, Qt::DisplayRole, QVariant(messageName));
for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i) for (unsigned int i = 0; i < messageInfo[msg->msgid].num_fields; ++i)
{ {
updateField(msg->msgid, i, message->child(i)); updateField(msg->msgid, i, message->child(i));
@ -71,6 +75,25 @@ void QGCMAVLinkInspector::receiveMessage(LinkInterface* link,mavlink_message_t m
// int filterValue = ui->systemComboBox()->value().toInt(); // int filterValue = ui->systemComboBox()->value().toInt();
// if (filterValue != ) // if (filterValue != )
memcpy(receivedMessages+message.msgid, &message, sizeof(mavlink_message_t)); memcpy(receivedMessages+message.msgid, &message, sizeof(mavlink_message_t));
float msgHz = 0.0f;
quint64 receiveTime = QGC::groundTimeMilliseconds();
if (lastMessageUpdate.contains(message.msgid))
{
msgHz = 1000.0/(double)(receiveTime - lastMessageUpdate.value(message.msgid));
if (isinf(msgHz) || isnan(msgHz) || msgHz < 0.0f)
{
msgHz = 1;
}
//qDebug() << "DIFF:" << receiveTime - lastMessageUpdate.value(message.msgid);
float newHz = 0.001f*msgHz+0.999f*messagesHz.value(message.msgid, 1);
qDebug() << "HZ" << newHz;
messagesHz.insert(message.msgid, newHz);
}
//qDebug() << "MSGHZ:" << messagesHz.value(message.msgid, 1000);
lastMessageUpdate.insert(message.msgid, receiveTime);
} }
QGCMAVLinkInspector::~QGCMAVLinkInspector() QGCMAVLinkInspector::~QGCMAVLinkInspector()

3
src/ui/QGCMAVLinkInspector.h

@ -26,7 +26,8 @@ public slots:
void refreshView(); void refreshView();
protected: protected:
QMap<int, quint64> lastFieldUpdate; ///< Used to switch between highlight and non-highlighting color QMap<int, quint64> lastMessageUpdate; ///< Used to switch between highlight and non-highlighting color
QMap<int, float> messagesHz; ///< Used to store update rate in Hz
mavlink_message_t receivedMessages[256]; ///< Available / known messages mavlink_message_t receivedMessages[256]; ///< Available / known messages
QMap<int, QTreeWidgetItem*> treeWidgetItems; ///< Available tree widget items QMap<int, QTreeWidgetItem*> treeWidgetItems; ///< Available tree widget items
QTimer updateTimer; ///< Only update at 1 Hz to not overload the GUI QTimer updateTimer; ///< Only update at 1 Hz to not overload the GUI

4
src/ui/linechart/LinechartWidget.cc

@ -315,6 +315,7 @@ void LinechartWidget::appendData(int uasId, QString curve, double value, quint64
{ {
if (activePlot->isVisible(curve+unit)) if (activePlot->isVisible(curve+unit))
{ {
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec; if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime; qint64 time = usec - logStartTime;
if (time < 0) time = 0; if (time < 0) time = 0;
@ -347,6 +348,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
{ {
if (activePlot->isVisible(curve+unit)) if (activePlot->isVisible(curve+unit))
{ {
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec; if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime; qint64 time = usec - logStartTime;
if (time < 0) time = 0; if (time < 0) time = 0;
@ -391,6 +393,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
{ {
if (activePlot->isVisible(curve+unit)) if (activePlot->isVisible(curve+unit))
{ {
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec; if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime; qint64 time = usec - logStartTime;
if (time < 0) time = 0; if (time < 0) time = 0;
@ -425,6 +428,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
{ {
if (activePlot->isVisible(curve+unit)) if (activePlot->isVisible(curve+unit))
{ {
if (usec == 0) usec = QGC::groundTimeMilliseconds();
if (logStartTime == 0) logStartTime = usec; if (logStartTime == 0) logStartTime = usec;
qint64 time = usec - logStartTime; qint64 time = usec - logStartTime;
if (time < 0) time = 0; if (time < 0) time = 0;

Loading…
Cancel
Save