Commit ce66c99f authored by Mariano Lizarraga's avatar Mariano Lizarraga

Merge branch 'experimental' of git@github.com:pixhawk/qgroundcontrol into mergeRemote

parents 05bc98cb 2c92489b
...@@ -126,8 +126,7 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv) ...@@ -126,8 +126,7 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv)
//mainWindow->addLink(simulationLink); //mainWindow->addLink(simulationLink);
mainWindow = MainWindow::instance(); mainWindow = MainWindow::instance();
// Remove splash screen
// Remove splash screen
splashScreen->finish(mainWindow); splashScreen->finish(mainWindow);
// Check if link could be connected // Check if link could be connected
......
/*===================================================================== /*===================================================================
QGroundControl Open Source Ground Control Station QGroundControl Open Source Ground Control Station
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> (c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
...@@ -32,6 +31,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -32,6 +31,7 @@ This file is part of the QGROUNDCONTROL project
#include <QTextStream> #include <QTextStream>
#include <QStringList> #include <QStringList>
#include <QFileInfo> #include <QFileInfo>
#include <QList>
#include "LogCompressor.h" #include "LogCompressor.h"
#include <QDebug> #include <QDebug>
...@@ -56,29 +56,43 @@ void LogCompressor::run() ...@@ -56,29 +56,43 @@ void LogCompressor::run()
QFile file(fileName); QFile file(fileName);
QFile outfile(outFileName); QFile outfile(outFileName);
QStringList* keys = new QStringList(); QStringList* keys = new QStringList();
QStringList* times = new QStringList(); QList<quint64> times;// = new QList<quint64>();
QList<quint64> finalTimes;
if (!file.exists()) return; qDebug() << "LOG COMPRESSOR: Starting" << fileName;
if (!file.open(QIODevice::ReadOnly | QIODevice::Text))
if (!file.exists() || !file.open(QIODevice::ReadOnly | QIODevice::Text))
{
qDebug() << "LOG COMPRESSOR: INPUT FILE DOES NOT EXIST";
emit logProcessingStatusChanged(tr("Log Compressor: Cannot start/compress log file, since input file %1 is not readable").arg(QFileInfo(fileName).absoluteFilePath()));
return; return;
}
if (outFileName != "")
{
// Check if file is writeable // Check if file is writeable
if (!QFileInfo(outfile).isWritable()) if (outFileName == ""/* || !QFileInfo(outfile).isWritable()*/)
{ {
qDebug() << "LOG COMPRESSOR: OUTPUT FILE DOES NOT EXIST" << outFileName;
emit logProcessingStatusChanged(tr("Log Compressor: Cannot start/compress log file, since output file %1 is not writable").arg(QFileInfo(outFileName).absoluteFilePath()));
return; return;
} }
}
// Find all keys // Find all keys
QTextStream in(&file); QTextStream in(&file);
while (!in.atEnd()) {
// Search only a certain region, assuming that not more
// than N dimensions at H Hertz can be send
const unsigned int keySearchLimit = 15000;
// e.g. 500 Hz * 30 values or
// e.g. 100 Hz * 150 values
unsigned int keyCounter = 0;
while (!in.atEnd() && keyCounter < keySearchLimit) {
QString line = in.readLine(); QString line = in.readLine();
// Accumulate map of keys // Accumulate map of keys
// Data field name is at position 2 // Data field name is at position 2
QString key = line.split(separator).at(2); QString key = line.split(separator).at(2);
if (!keys->contains(key)) keys->append(key); if (!keys->contains(key)) keys->append(key);
keyCounter++;
} }
keys->sort(); keys->sort();
...@@ -90,6 +104,8 @@ void LogCompressor::run() ...@@ -90,6 +104,8 @@ void LogCompressor::run()
spacer += " " + separator; spacer += " " + separator;
} }
emit logProcessingStatusChanged(tr("Log compressor: Dataset contains dimension: ") + header);
//qDebug() << header; //qDebug() << header;
//qDebug() << "NOW READING TIMES"; //qDebug() << "NOW READING TIMES";
...@@ -99,33 +115,48 @@ void LogCompressor::run() ...@@ -99,33 +115,48 @@ void LogCompressor::run()
file.reset(); file.reset();
in.reset(); in.reset();
in.resetStatus(); in.resetStatus();
while (!in.atEnd()) { bool ok;
while (!in.atEnd())
{
QString line = in.readLine(); QString line = in.readLine();
// Accumulate map of keys // Accumulate map of keys
// Data field name is at position 2 // Data field name is at position 2b
QString time = line.split(separator).at(0); quint64 time = static_cast<QString>(line.split(separator).at(0)).toLongLong(&ok);
if (!times->contains(time)) if (ok)
{ {
times->append(time); times.append(time);
} }
} }
dataLines = times->length(); qSort(times);
times->sort(); qint64 lastTime = -1;
// Create lines // Create lines
QStringList* outLines = new QStringList(); QStringList* outLines = new QStringList();
for (int i = 0; i < times->length(); i++) for (int i = 0; i < times.length(); i++)
{ {
outLines->append(times->at(i) + separator + spacer); // Cast to signed on purpose, 64 bit timestamp still long enough
if (static_cast<qint64>(times.at(i)) != lastTime)
{
outLines->append(QString("%1").arg(times.at(i)) + separator + spacer);
lastTime = static_cast<qint64>(times.at(i));
finalTimes.append(times.at(i));
//qDebug() << "ADDED:" << outLines->last();
}
} }
dataLines = finalTimes.length();
emit logProcessingStatusChanged(tr("Log compressor: Now processing %1 log lines").arg(finalTimes.length()));
// Fill in the values for all keys // Fill in the values for all keys
file.reset(); file.reset();
QTextStream data(&file); QTextStream data(&file);
int linecounter = 0; int linecounter = 0;
quint64 lastTimeIndex = 0; quint64 lastTimeIndex = 0;
bool failed = false;
while (!data.atEnd()) while (!data.atEnd())
{ {
linecounter++; linecounter++;
...@@ -133,7 +164,7 @@ void LogCompressor::run() ...@@ -133,7 +164,7 @@ void LogCompressor::run()
QString line = data.readLine(); QString line = data.readLine();
QStringList parts = line.split(separator); QStringList parts = line.split(separator);
// Get time // Get time
QString time = parts.first(); quint64 time = static_cast<QString>(parts.first()).toLongLong(&ok);
QString field = parts.at(2); QString field = parts.at(2);
QString value = parts.at(3); QString value = parts.at(3);
// Enforce NaN if no value is present // Enforce NaN if no value is present
...@@ -147,11 +178,14 @@ void LogCompressor::run() ...@@ -147,11 +178,14 @@ void LogCompressor::run()
// but it significantly reduces the time needed for the search // but it significantly reduces the time needed for the search
// setting a window of 1000 entries means that a 1 Hz data point // setting a window of 1000 entries means that a 1 Hz data point
// can still be located // can still be located
int offsetLimit = 200; quint64 offsetLimit = 100;
quint64 offset; quint64 offset;
quint64 index = -1; qint64 index = -1;
// FIXME Lorenz (index is an unsigend int) failed = false;
while (index == -1)
// Search the index until it is valid (!= -1)
// or the start of the list has been reached (failed)
while (index == -1 && !failed)
{ {
if (lastTimeIndex > offsetLimit) if (lastTimeIndex > offsetLimit)
{ {
...@@ -161,15 +195,30 @@ void LogCompressor::run() ...@@ -161,15 +195,30 @@ void LogCompressor::run()
{ {
offset = 0; offset = 0;
} }
quint64 index = times->indexOf(time, offset);
// FIXME Lorenz (index is an unsigend int) index = finalTimes.indexOf(time, offset);
if (index == -1) if (index == -1)
{ {
qDebug() << "INDEX NOT FOUND DURING LOGFILE PROCESSING, RESTARTING SEARCH"; if (offset == 0)
// FIXME Reset and start without offset heuristic again {
offsetLimit+=1000; emit logProcessingStatusChanged(tr("Log compressor: Timestamp %1 not found in dataset, ignoring log line %2").arg(time).arg(linecounter));
qDebug() << "Completely failed finding value";
//continue;
failed = true;
}
else
{
emit logProcessingStatusChanged(tr("Log compressor: Timestamp %1 not found in dataset, restarting search.").arg(time));
offsetLimit*=2;
}
} }
} }
if (index % (dataLines/100) == 0) emit logProcessingStatusChanged(tr("Log compressor: Processed %1% of %2 lines").arg(index/(float)dataLines*100, 0, 'f', 2).arg(dataLines));
if (!failed)
{
// When the algorithm reaches here the correct index was found
lastTimeIndex = index; lastTimeIndex = index;
QString outLine = outLines->at(index); QString outLine = outLines->at(index);
QStringList outParts = outLine.split(separator); QStringList outParts = outLine.split(separator);
...@@ -178,7 +227,7 @@ void LogCompressor::run() ...@@ -178,7 +227,7 @@ void LogCompressor::run()
outLine = outParts.join(separator); outLine = outParts.join(separator);
outLines->replace(index, outLine); outLines->replace(index, outLine);
} }
}
// Add header, write out file // Add header, write out file
...@@ -205,6 +254,7 @@ void LogCompressor::run() ...@@ -205,6 +254,7 @@ void LogCompressor::run()
currentDataLine = 0; currentDataLine = 0;
dataLines = 1; dataLines = 1;
delete keys; delete keys;
emit logProcessingStatusChanged(tr("Log compressor: Finished processing file: %1").arg(outfile.fileName()));
qDebug() << "Done with logfile processing"; qDebug() << "Done with logfile processing";
emit finishedFile(outfile.fileName()); emit finishedFile(outfile.fileName());
running = false; running = false;
......
...@@ -27,6 +27,7 @@ signals: ...@@ -27,6 +27,7 @@ signals:
/** @brief This signal is emitted once a logfile has been finished writing /** @brief This signal is emitted once a logfile has been finished writing
* @param fileName The name out the output (CSV) file * @param fileName The name out the output (CSV) file
*/ */
void logProcessingStatusChanged(QString);
void finishedFile(QString fileName); void finishedFile(QString fileName);
}; };
......
...@@ -59,7 +59,9 @@ MAVLinkProtocol::MAVLinkProtocol() : ...@@ -59,7 +59,9 @@ MAVLinkProtocol::MAVLinkProtocol() :
heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE), heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE),
m_heartbeatsEnabled(false), m_heartbeatsEnabled(false),
m_loggingEnabled(false), m_loggingEnabled(false),
m_logfile(NULL) m_logfile(NULL),
m_enable_version_check(true),
versionMismatchIgnore(false)
{ {
start(QThread::LowPriority); start(QThread::LowPriority);
// Start heartbeat timer, emitting a heartbeat at the configured rate // Start heartbeat timer, emitting a heartbeat at the configured rate
...@@ -76,6 +78,8 @@ MAVLinkProtocol::MAVLinkProtocol() : ...@@ -76,6 +78,8 @@ MAVLinkProtocol::MAVLinkProtocol() :
lastIndex[i][j] = -1; lastIndex[i][j] = -1;
} }
} }
emit versionCheckChanged(m_enable_version_check);
} }
MAVLinkProtocol::~MAVLinkProtocol() MAVLinkProtocol::~MAVLinkProtocol()
...@@ -91,7 +95,6 @@ MAVLinkProtocol::~MAVLinkProtocol() ...@@ -91,7 +95,6 @@ MAVLinkProtocol::~MAVLinkProtocol()
void MAVLinkProtocol::run() void MAVLinkProtocol::run()
{ {
} }
QString MAVLinkProtocol::getLogfileName() QString MAVLinkProtocol::getLogfileName()
...@@ -146,7 +149,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) ...@@ -146,7 +149,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// Check if the UAS has the same id like this system // Check if the UAS has the same id like this system
if (message.sysid == getSystemId()) if (message.sysid == getSystemId())
{ {
qDebug() << "WARNING\nWARNING\nWARNING\nWARNING\nWARNING\nWARNING\nWARNING\n\n RECEIVED MESSAGE FROM THIS SYSTEM WITH ID" << message.msgid << "FROM COMPONENT" << message.compid; emit protocolStatusMessage(tr("SYSTEM ID CONFLICT!"), tr("Warning: A second system is using the same system id (%1)").arg(getSystemId()));
} }
// Create a new UAS based on the heartbeat received // Create a new UAS based on the heartbeat received
...@@ -161,12 +164,15 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) ...@@ -161,12 +164,15 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
mavlink_msg_heartbeat_decode(&message, &heartbeat); mavlink_msg_heartbeat_decode(&message, &heartbeat);
// Check if the UAS has a different protocol version // Check if the UAS has a different protocol version
if (heartbeat.mavlink_version != MAVLINK_VERSION) if (m_enable_version_check && (heartbeat.mavlink_version != MAVLINK_VERSION))
{ {
// Bring up dialog to inform user // Bring up dialog to inform user
MainWindow::instance()->showCriticalMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"), if (!versionMismatchIgnore)
{
emit protocolStatusMessage(tr("The MAVLink protocol version on the MAV and QGroundControl mismatch!"),
tr("It is unsafe to use different MAVLink versions. QGroundControl therefore refuses to connect to system %1, which sends MAVLink version %2 (QGroundControl uses version %3).").arg(message.sysid).arg(heartbeat.mavlink_version).arg(MAVLINK_VERSION)); tr("It is unsafe to use different MAVLink versions. QGroundControl therefore refuses to connect to system %1, which sends MAVLink version %2 (QGroundControl uses version %3).").arg(message.sysid).arg(heartbeat.mavlink_version).arg(MAVLINK_VERSION));
versionMismatchIgnore = true;
}
// Ignore this message and continue gracefully // Ignore this message and continue gracefully
continue; continue;
...@@ -398,6 +404,11 @@ void MAVLinkProtocol::enableLogging(bool enabled) ...@@ -398,6 +404,11 @@ void MAVLinkProtocol::enableLogging(bool enabled)
m_loggingEnabled = enabled; m_loggingEnabled = enabled;
} }
void MAVLinkProtocol::enableVersionCheck(bool enabled)
{
m_enable_version_check = enabled;
}
bool MAVLinkProtocol::heartbeatsEnabled(void) bool MAVLinkProtocol::heartbeatsEnabled(void)
{ {
return m_heartbeatsEnabled; return m_heartbeatsEnabled;
...@@ -408,6 +419,11 @@ bool MAVLinkProtocol::loggingEnabled(void) ...@@ -408,6 +419,11 @@ bool MAVLinkProtocol::loggingEnabled(void)
return m_loggingEnabled; return m_loggingEnabled;
} }
bool MAVLinkProtocol::versionCheckEnabled(void)
{
return m_enable_version_check;
}
/** /**
* The default rate is 1 Hertz. * The default rate is 1 Hertz.
* *
......
...@@ -68,6 +68,8 @@ public: ...@@ -68,6 +68,8 @@ public:
bool heartbeatsEnabled(void); bool heartbeatsEnabled(void);
/** @brief Get logging state */ /** @brief Get logging state */
bool loggingEnabled(void); bool loggingEnabled(void);
/** @brief Get protocol version check state */
bool versionCheckEnabled(void);
/** @brief Get the name of the packet log file */ /** @brief Get the name of the packet log file */
static QString getLogfileName(); static QString getLogfileName();
...@@ -87,6 +89,9 @@ public slots: ...@@ -87,6 +89,9 @@ public slots:
/** @brief Enable/disable binary packet logging */ /** @brief Enable/disable binary packet logging */
void enableLogging(bool enabled); void enableLogging(bool enabled);
/** @brief Enable / disable version check */
void enableVersionCheck(bool enabled);
/** @brief Send an extra heartbeat to all connected units */ /** @brief Send an extra heartbeat to all connected units */
void sendHeartbeat(); void sendHeartbeat();
...@@ -96,12 +101,14 @@ protected: ...@@ -96,12 +101,14 @@ protected:
bool m_heartbeatsEnabled; ///< Enabled/disable heartbeat emission bool m_heartbeatsEnabled; ///< Enabled/disable heartbeat emission
bool m_loggingEnabled; ///< Enable/disable packet logging bool m_loggingEnabled; ///< Enable/disable packet logging
QFile* m_logfile; ///< Logfile QFile* m_logfile; ///< Logfile
bool m_enable_version_check; ///< Enable checking of version match of MAV and QGC
QMutex receiveMutex; ///< Mutex to protect receiveBytes function QMutex receiveMutex; ///< Mutex to protect receiveBytes function
int lastIndex[256][256]; int lastIndex[256][256];
int totalReceiveCounter; int totalReceiveCounter;
int totalLossCounter; int totalLossCounter;
int currReceiveCounter; int currReceiveCounter;
int currLossCounter; int currLossCounter;
bool versionMismatchIgnore;
signals: signals:
/** @brief Message received and directly copied via signal */ /** @brief Message received and directly copied via signal */
...@@ -110,6 +117,10 @@ signals: ...@@ -110,6 +117,10 @@ signals:
void heartbeatChanged(bool heartbeats); void heartbeatChanged(bool heartbeats);
/** @brief Emitted if logging is started / stopped */ /** @brief Emitted if logging is started / stopped */
void loggingChanged(bool enabled); void loggingChanged(bool enabled);
/** @brief Emitted if version check is enabled / disabled */
void versionCheckChanged(bool enabled);
/** @brief Emitted if a message from the protocol should reach the user */
void protocolStatusMessage(const QString& title, const QString& message);
}; };
#endif // MAVLINKPROTOCOL_H_ #endif // MAVLINKPROTOCOL_H_
...@@ -85,6 +85,8 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P ...@@ -85,6 +85,8 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P
#endif #endif
loadSettings();
// Link is setup, register it with link manager // Link is setup, register it with link manager
LinkManager::instance()->add(this); LinkManager::instance()->add(this);
} }
......
...@@ -118,6 +118,21 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) ...@@ -118,6 +118,21 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit valueChanged(uasId, "vis. z", pos.z, time); emit valueChanged(uasId, "vis. z", pos.z, time);
} }
break; break;
case MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE:
{
mavlink_vicon_position_estimate_t pos;
mavlink_msg_vicon_position_estimate_decode(&message, &pos);
quint64 time = getUnixTime(pos.usec);
//emit valueChanged(uasId, "vis. time", pos.usec, time);
emit valueChanged(uasId, "vicon roll", pos.roll, time);
emit valueChanged(uasId, "vicon pitch", pos.pitch, time);
emit valueChanged(uasId, "vicon yaw", pos.yaw, time);
emit valueChanged(uasId, "vicon x", pos.x, time);
emit valueChanged(uasId, "vicon y", pos.y, time);
emit valueChanged(uasId, "vicon z", pos.z, time);
emit localPositionChanged(this, pos.x, pos.y, pos.z, time);
}
break;
case MAVLINK_MSG_ID_AUX_STATUS: case MAVLINK_MSG_ID_AUX_STATUS:
{ {
mavlink_aux_status_t status; mavlink_aux_status_t status;
......
...@@ -37,15 +37,19 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget ...@@ -37,15 +37,19 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget
{ {
m_ui->setupUi(this); m_ui->setupUi(this);
// Initialize state
m_ui->heartbeatCheckBox->setChecked(protocol->heartbeatsEnabled());
m_ui->loggingCheckBox->setChecked(protocol->loggingEnabled());
m_ui->versionCheckBox->setChecked(protocol->versionCheckEnabled());
// Connect actions // Connect actions
connect(protocol, SIGNAL(heartbeatChanged(bool)), m_ui->heartbeatCheckBox, SLOT(setChecked(bool))); connect(protocol, SIGNAL(heartbeatChanged(bool)), m_ui->heartbeatCheckBox, SLOT(setChecked(bool)));
connect(m_ui->heartbeatCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableHeartbeats(bool))); connect(m_ui->heartbeatCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableHeartbeats(bool)));
connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->loggingCheckBox, SLOT(setChecked(bool))); connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->loggingCheckBox, SLOT(setChecked(bool)));
connect(m_ui->loggingCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableLogging(bool))); connect(m_ui->loggingCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableLogging(bool)));
connect(protocol, SIGNAL(versionCheckChanged(bool)), m_ui->versionCheckBox, SLOT(setChecked(bool)));
connect(m_ui->versionCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableVersionCheck(bool)));
// Initialize state
m_ui->heartbeatCheckBox->setChecked(protocol->heartbeatsEnabled());
m_ui->loggingCheckBox->setChecked(protocol->loggingEnabled());
} }
MAVLinkSettingsWidget::~MAVLinkSettingsWidget() MAVLinkSettingsWidget::~MAVLinkSettingsWidget()
......
...@@ -31,6 +31,13 @@ ...@@ -31,6 +31,13 @@
</property> </property>
</widget> </widget>
</item> </item>
<item>
<widget class="QCheckBox" name="versionCheckBox">
<property name="text">
<string>Only accept MAVs with same protocol version</string>
</property>
</widget>
</item>
<item> <item>
<spacer name="verticalSpacer"> <spacer name="verticalSpacer">
<property name="orientation"> <property name="orientation">
......
...@@ -120,6 +120,8 @@ MainWindow::MainWindow(QWidget *parent): ...@@ -120,6 +120,8 @@ MainWindow::MainWindow(QWidget *parent):
// Load mavlink view as default widget set // Load mavlink view as default widget set
//loadMAVLinkView(); //loadMAVLinkView();
statusBar()->setSizeGripEnabled(true);
if (settings.contains("geometry")) if (settings.contains("geometry"))
{ {
// Restore the window geometry // Restore the window geometry
...@@ -144,14 +146,14 @@ MainWindow::MainWindow(QWidget *parent): ...@@ -144,14 +146,14 @@ MainWindow::MainWindow(QWidget *parent):
MainWindow::~MainWindow() MainWindow::~MainWindow()
{ {
delete statusBar;
statusBar = NULL;
} }
void MainWindow::buildCommonWidgets() void MainWindow::buildCommonWidgets()
{ {
//TODO: move protocol outside UI //TODO: move protocol outside UI
mavlink = new MAVLinkProtocol(); mavlink = new MAVLinkProtocol();
connect(mavlink, SIGNAL(protocolStatusMessage(QString,QString)), this, SLOT(showCriticalMessage(QString,QString)), Qt::QueuedConnection);
// Dock widgets // Dock widgets
if (!controlDockWidget) if (!controlDockWidget)
...@@ -201,6 +203,12 @@ void MainWindow::buildCommonWidgets() ...@@ -201,6 +203,12 @@ void MainWindow::buildCommonWidgets()
protocolWidget = new XMLCommProtocolWidget(this); protocolWidget = new XMLCommProtocolWidget(this);
addToCentralWidgetsMenu (protocolWidget, "Mavlink Generator", SLOT(showCentralWidget()),CENTRAL_PROTOCOL); addToCentralWidgetsMenu (protocolWidget, "Mavlink Generator", SLOT(showCentralWidget()),CENTRAL_PROTOCOL);
} }
if (!dataplotWidget)
{
dataplotWidget = new QGCDataPlot2D(this);
addToCentralWidgetsMenu (dataplotWidget, "Data Plot", SLOT(showCentralWidget()),CENTRAL_DATA_PLOT);
}
} }
void MainWindow::buildPxWidgets() void MainWindow::buildPxWidgets()
...@@ -740,6 +748,7 @@ void MainWindow::arrangeCommonCenterStack() ...@@ -740,6 +748,7 @@ void MainWindow::arrangeCommonCenterStack()
if (!centerStack) return; if (!centerStack) return;
if (mapWidget && (centerStack->indexOf(mapWidget) == -1)) centerStack->addWidget(mapWidget); if (mapWidget && (centerStack->indexOf(mapWidget) == -1)) centerStack->addWidget(mapWidget);
if (dataplotWidget && (centerStack->indexOf(dataplotWidget) == -1)) centerStack->addWidget(dataplotWidget);
if (protocolWidget && (centerStack->indexOf(protocolWidget) == -1)) centerStack->addWidget(protocolWidget); if (protocolWidget && (centerStack->indexOf(protocolWidget) == -1)) centerStack->addWidget(protocolWidget);
setCentralWidget(centerStack); setCentralWidget(centerStack);
...@@ -810,15 +819,6 @@ void MainWindow::configureWindowName() ...@@ -810,15 +819,6 @@ void MainWindow::configureWindowName()
#endif #endif
} }
QStatusBar* MainWindow::createStatusBar()
{
QStatusBar* bar = new QStatusBar();
/* Add status fields and messages */
/* Enable resize grip in the bottom right corner */
bar->setSizeGripEnabled(true);
return bar;
}
void MainWindow::startVideoCapture() void MainWindow::startVideoCapture()
{ {
QString format = "bmp"; QString format = "bmp";
...@@ -889,7 +889,7 @@ void MainWindow::reloadStylesheet() ...@@ -889,7 +889,7 @@ void MainWindow::reloadStylesheet()
*/ */
void MainWindow::showStatusMessage(const QString& status, int timeout) void MainWindow::showStatusMessage(const QString& status, int timeout)
{ {
statusBar->showMessage(status, timeout); statusBar()->showMessage(status, timeout);
} }
/** /**
...@@ -900,7 +900,7 @@ void MainWindow::showStatusMessage(const QString& status, int timeout) ...@@ -900,7 +900,7 @@ void MainWindow::showStatusMessage(const QString& status, int timeout)
*/ */
void MainWindow::showStatusMessage(const QString& status) void MainWindow::showStatusMessage(const QString& status)
{ {
statusBar->showMessage(status, 5); statusBar()->showMessage(status, 20000);
} }
void MainWindow::showCriticalMessage(const QString& title, const QString& message) void MainWindow::showCriticalMessage(const QString& title, const QString& message)
...@@ -914,6 +914,17 @@ void MainWindow::showCriticalMessage(const QString& title, const QString& messag ...@@ -914,6 +914,17 @@ void MainWindow::showCriticalMessage(const QString& title, const QString& messag
msgBox.exec(); msgBox.exec();
} }
void MainWindow::showInfoMessage(const QString& title, const QString& message)
{
QMessageBox msgBox(MainWindow::instance());
msgBox.setIcon(QMessageBox::Information);
msgBox.setText(title);
msgBox.setInformativeText(message);
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
msgBox.exec();
}
/** /**
* @brief Create all actions associated to the main window * @brief Create all actions associated to the main window
* *
......
...@@ -98,6 +98,8 @@ public slots: ...@@ -98,6 +98,8 @@ public slots:
void showStatusMessage(const QString& status); void showStatusMessage(const QString& status);
/** @brief Shows a critical message as popup or as widget */ /** @brief Shows a critical message as popup or as widget */
void showCriticalMessage(const QString& title, const QString& message); void showCriticalMessage(const QString& title, const QString& message);
/** @brief Shows an info message as popup or as widget */
void showInfoMessage(const QString& title, const QString& message);
void addLink(); void addLink();
void addLink(LinkInterface* link); void addLink(LinkInterface* link);
...@@ -296,10 +298,6 @@ protected: ...@@ -296,10 +298,6 @@ protected:
VIEW_SECTIONS currentView; VIEW_SECTIONS currentView;
bool aboutToCloseFlag; bool aboutToCloseFlag;
QStatusBar* statusBar;
QStatusBar* createStatusBar();
void clearView(); void clearView();
void buildCommonWidgets(); void buildCommonWidgets();
......
...@@ -40,6 +40,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -40,6 +40,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGCDataPlot2D.h" #include "QGCDataPlot2D.h"
#include "ui_QGCDataPlot2D.h" #include "ui_QGCDataPlot2D.h"
#include "MG.h" #include "MG.h"
#include "MainWindow.h"
#include <cmath> #include <cmath>
#include <QDebug> #include <QDebug>
...@@ -75,7 +76,7 @@ void QGCDataPlot2D::reloadFile() ...@@ -75,7 +76,7 @@ void QGCDataPlot2D::reloadFile()
{ {
if (QFileInfo(fileName).isReadable()) if (QFileInfo(fileName).isReadable())
{ {
if (ui->inputFileType->currentText().contains("pxIMU")) if (ui->inputFileType->currentText().contains("pxIMU") || ui->inputFileType->currentText().contains("RAW"))
{ {
loadRawLog(fileName, ui->xAxis->currentText(), ui->yAxis->text()); loadRawLog(fileName, ui->xAxis->currentText(), ui->yAxis->text());
} }
...@@ -88,9 +89,10 @@ void QGCDataPlot2D::reloadFile() ...@@ -88,9 +89,10 @@ void QGCDataPlot2D::reloadFile()
void QGCDataPlot2D::loadFile() void QGCDataPlot2D::loadFile()
{ {
qDebug() << "DATA PLOT: Loading file:" << fileName;
if (QFileInfo(fileName).isReadable()) if (QFileInfo(fileName).isReadable())
{ {
if (ui->inputFileType->currentText().contains("pxIMU")) if (ui->inputFileType->currentText().contains("pxIMU") || ui->inputFileType->currentText().contains("RAW"))
{ {
loadRawLog(fileName); loadRawLog(fileName);
} }
...@@ -110,7 +112,7 @@ void QGCDataPlot2D::loadFile(QString file) ...@@ -110,7 +112,7 @@ void QGCDataPlot2D::loadFile(QString file)
{ {
loadRawLog(fileName); loadRawLog(fileName);
} }
else if (fileName.contains(".txt") || fileName.contains(".csv")) else if (fileName.contains(".txt") || fileName.contains(".csv") || fileName.contains(".csv"))
{ {
loadCsvLog(fileName); loadCsvLog(fileName);
} }
...@@ -129,7 +131,7 @@ void QGCDataPlot2D::savePlot() ...@@ -129,7 +131,7 @@ void QGCDataPlot2D::savePlot()
if (!fileName.contains(".")) if (!fileName.contains("."))
{ {
// .csv is default extension // .pdf is default extension
fileName.append(".pdf"); fileName.append(".pdf");
} }
...@@ -269,7 +271,16 @@ void QGCDataPlot2D::selectFile() ...@@ -269,7 +271,16 @@ void QGCDataPlot2D::selectFile()
// Let user select the log file name // Let user select the log file name
//QDate date(QDate::currentDate()); //QDate date(QDate::currentDate());
// QString("./pixhawk-log-" + date.toString("yyyy-MM-dd") + "-" + QString::number(logindex) + ".log") // QString("./pixhawk-log-" + date.toString("yyyy-MM-dd") + "-" + QString::number(logindex) + ".log")
fileName = QFileDialog::getOpenFileName(this, tr("Specify log file name"), QString(), "Logfile (*.csv *.txt *.log)");
if (ui->inputFileType->currentText().contains("pxIMU") || ui->inputFileType->currentText().contains("RAW"))
{
fileName = QFileDialog::getOpenFileName(this, tr("Specify log file name"), QString(), "Logfile (*.imu *.raw)");
}
else
{
fileName = QFileDialog::getOpenFileName(this, tr("Specify log file name"), QString(), "Logfile (*.csv *.txt *.log)");
}
// Store reference to file // Store reference to file
QFileInfo fileInfo(fileName); QFileInfo fileInfo(fileName);
...@@ -296,32 +307,36 @@ void QGCDataPlot2D::selectFile() ...@@ -296,32 +307,36 @@ void QGCDataPlot2D::selectFile()
void QGCDataPlot2D::loadRawLog(QString file, QString xAxisName, QString yAxisFilter) void QGCDataPlot2D::loadRawLog(QString file, QString xAxisName, QString yAxisFilter)
{ {
qDebug() << "LOADING RAW LOG!";
if (logFile != NULL) if (logFile != NULL)
{ {
logFile->close(); logFile->close();
delete logFile; delete logFile;
} }
// Postprocess log file // Postprocess log file
logFile = new QTemporaryFile(); logFile = new QTemporaryFile("qt_qgc_temp_log.XXXXXX.csv");
compressor = new LogCompressor(file, logFile->fileName()); compressor = new LogCompressor(file, logFile->fileName());
connect(compressor, SIGNAL(logProcessingStatusChanged(QString)), MainWindow::instance(), SLOT(showStatusMessage(QString)));
connect(compressor, SIGNAL(finishedFile(QString)), this, SLOT(loadFile(QString)));
compressor->startCompression(); compressor->startCompression();
// Block UI // // Block UI
QProgressDialog progress("Transforming RAW log file to CSV", "Abort Transformation", 0, 1, this); // QProgressDialog progress("Transforming RAW log file to CSV", "Abort Transformation", 0, 1, this);
progress.setWindowModality(Qt::WindowModal); // progress.setWindowModality(Qt::WindowModal);
while (!compressor->isFinished()) // while (!compressor->isFinished())
{ // {
MG::SLEEP::usleep(100000); // MG::SLEEP::usleep(100000);
progress.setMaximum(compressor->getDataLines()); //// progress.setMaximum(compressor->getDataLines());
progress.setValue(compressor->getCurrentLine()); //// progress.setValue(compressor->getCurrentLine());
} // }
// Enforce end // // Enforce end
progress.setMaximum(compressor->getDataLines()); // progress.setMaximum(compressor->getDataLines());
progress.setValue(compressor->getDataLines()); // progress.setValue(compressor->getDataLines());
// Done with preprocessing - now load csv log // Done with preprocessing - now load csv log
loadCsvLog(logFile->fileName(), xAxisName, yAxisFilter); //loadFile(logFile->fileName());
} }
/** /**
...@@ -654,6 +669,13 @@ void QGCDataPlot2D::saveCsvLog() ...@@ -654,6 +669,13 @@ void QGCDataPlot2D::saveCsvLog()
fileName = QFileDialog::getSaveFileName( fileName = QFileDialog::getSaveFileName(
this, "Export CSV File Name", QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), this, "Export CSV File Name", QDesktopServices::storageLocation(QDesktopServices::DesktopLocation),
"CSV file (*.csv);;Text file (*.txt)"); "CSV file (*.csv);;Text file (*.txt)");
if (!fileName.contains("."))
{
// .csv is default extension
fileName.append(".csv");
}
// QFileInfo fileInfo(fileName); // QFileInfo fileInfo(fileName);
// //
// // Check if we could create a new file in this directory // // Check if we could create a new file in this directory
......
...@@ -48,6 +48,7 @@ This file is part of the PIXHAWK project ...@@ -48,6 +48,7 @@ This file is part of the PIXHAWK project
#include "LinechartWidget.h" #include "LinechartWidget.h"
#include "LinechartPlot.h" #include "LinechartPlot.h"
#include "LogCompressor.h" #include "LogCompressor.h"
#include "MainWindow.h"
#include "QGC.h" #include "QGC.h"
#include "MG.h" #include "MG.h"
...@@ -348,7 +349,7 @@ void LinechartWidget::startLogging() ...@@ -348,7 +349,7 @@ void LinechartWidget::startLogging()
// Let user select the log file name // Let user select the log file name
QDate date(QDate::currentDate()); QDate date(QDate::currentDate());
// QString("./pixhawk-log-" + date.toString("yyyy-MM-dd") + "-" + QString::number(logindex) + ".log") // QString("./pixhawk-log-" + date.toString("yyyy-MM-dd") + "-" + QString::number(logindex) + ".log")
QString fileName = QFileDialog::getSaveFileName(this, tr("Specify log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("Logfile (*.csv, *.txt);;")); QString fileName = QFileDialog::getSaveFileName(this, tr("Specify log file name"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("Logfile (*.csv *.txt);;"));
if (!fileName.contains(".")) if (!fileName.contains("."))
{ {
...@@ -399,6 +400,8 @@ void LinechartWidget::stopLogging() ...@@ -399,6 +400,8 @@ void LinechartWidget::stopLogging()
// Postprocess log file // Postprocess log file
compressor = new LogCompressor(logFile->fileName()); compressor = new LogCompressor(logFile->fileName());
connect(compressor, SIGNAL(finishedFile(QString)), this, SIGNAL(logfileWritten(QString))); connect(compressor, SIGNAL(finishedFile(QString)), this, SIGNAL(logfileWritten(QString)));
connect(compressor, SIGNAL(logProcessingStatusChanged(QString)), MainWindow::instance(), SLOT(showStatusMessage(QString)));
MainWindow::instance()->showInfoMessage("Logging ended", "QGroundControl is now compressing the logfile in a consistent CVS file. This may take a while, you can continue to use QGroundControl. Status updates appear at the bottom of the window.");
compressor->startCompression(); compressor->startCompression();
} }
logButton->setText(tr("Start logging")); logButton->setText(tr("Start logging"));
......
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