diff --git a/src/Core.cc b/src/Core.cc index b49eed18eab00942c85dadd72ccfd89f98197b69..3e5602704bb8413801254bca0d9ac592e3639df0 100644 --- a/src/Core.cc +++ b/src/Core.cc @@ -126,8 +126,7 @@ Core::Core(int &argc, char* argv[]) : QApplication(argc, argv) //mainWindow->addLink(simulationLink); mainWindow = MainWindow::instance(); - - // Remove splash screen + // Remove splash screen splashScreen->finish(mainWindow); // Check if link could be connected diff --git a/src/LogCompressor.cc b/src/LogCompressor.cc index 444b27a4b68c49c7d7682b1c4aad7b284f7238e9..2aac554ce95764348da3b3528d2b0bdef9785ad4 100644 --- a/src/LogCompressor.cc +++ b/src/LogCompressor.cc @@ -1,5 +1,4 @@ -/*===================================================================== - +/*=================================================================== QGroundControl Open Source Ground Control Station (c) 2009, 2010 QGROUNDCONTROL PROJECT @@ -32,6 +31,7 @@ This file is part of the QGROUNDCONTROL project #include #include #include +#include #include "LogCompressor.h" #include @@ -56,29 +56,43 @@ void LogCompressor::run() QFile file(fileName); QFile outfile(outFileName); QStringList* keys = new QStringList(); - QStringList* times = new QStringList(); + QList times;// = new QList(); + QList finalTimes; - if (!file.exists()) return; - if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) + qDebug() << "LOG COMPRESSOR: Starting" << fileName; + + 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; + } - if (outFileName != "") - { // 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; } - } // Find all keys 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(); // Accumulate map of keys // Data field name is at position 2 QString key = line.split(separator).at(2); if (!keys->contains(key)) keys->append(key); + keyCounter++; } keys->sort(); @@ -90,6 +104,8 @@ void LogCompressor::run() spacer += " " + separator; } + emit logProcessingStatusChanged(tr("Log compressor: Dataset contains dimension: ") + header); + //qDebug() << header; //qDebug() << "NOW READING TIMES"; @@ -99,33 +115,48 @@ void LogCompressor::run() file.reset(); in.reset(); in.resetStatus(); - while (!in.atEnd()) { + bool ok; + while (!in.atEnd()) + { QString line = in.readLine(); // Accumulate map of keys - // Data field name is at position 2 - QString time = line.split(separator).at(0); - if (!times->contains(time)) + // Data field name is at position 2b + quint64 time = static_cast(line.split(separator).at(0)).toLongLong(&ok); + if (ok) { - times->append(time); + times.append(time); } } - dataLines = times->length(); + qSort(times); - times->sort(); + qint64 lastTime = -1; // Create lines 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(times.at(i)) != lastTime) + { + outLines->append(QString("%1").arg(times.at(i)) + separator + spacer); + lastTime = static_cast(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 file.reset(); QTextStream data(&file); int linecounter = 0; quint64 lastTimeIndex = 0; + bool failed = false; + while (!data.atEnd()) { linecounter++; @@ -133,7 +164,7 @@ void LogCompressor::run() QString line = data.readLine(); QStringList parts = line.split(separator); // Get time - QString time = parts.first(); + quint64 time = static_cast(parts.first()).toLongLong(&ok); QString field = parts.at(2); QString value = parts.at(3); // Enforce NaN if no value is present @@ -147,11 +178,14 @@ void LogCompressor::run() // but it significantly reduces the time needed for the search // setting a window of 1000 entries means that a 1 Hz data point // can still be located - int offsetLimit = 200; + quint64 offsetLimit = 100; quint64 offset; - quint64 index = -1; - // FIXME Lorenz (index is an unsigend int) - while (index == -1) + qint64 index = -1; + failed = false; + + // 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) { @@ -161,15 +195,30 @@ void LogCompressor::run() { offset = 0; } - quint64 index = times->indexOf(time, offset); - // FIXME Lorenz (index is an unsigend int) + + index = finalTimes.indexOf(time, offset); if (index == -1) { - qDebug() << "INDEX NOT FOUND DURING LOGFILE PROCESSING, RESTARTING SEARCH"; - // FIXME Reset and start without offset heuristic again - offsetLimit+=1000; + if (offset == 0) + { + 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; QString outLine = outLines->at(index); QStringList outParts = outLine.split(separator); @@ -178,7 +227,7 @@ void LogCompressor::run() outLine = outParts.join(separator); outLines->replace(index, outLine); } - + } // Add header, write out file @@ -205,6 +254,7 @@ void LogCompressor::run() currentDataLine = 0; dataLines = 1; delete keys; + emit logProcessingStatusChanged(tr("Log compressor: Finished processing file: %1").arg(outfile.fileName())); qDebug() << "Done with logfile processing"; emit finishedFile(outfile.fileName()); running = false; diff --git a/src/LogCompressor.h b/src/LogCompressor.h index fff3dee983fe889fe10941b0ef2aaaaeca2bf110..5df91ce47baa6acfcb71d538a04bd42b6293ba62 100644 --- a/src/LogCompressor.h +++ b/src/LogCompressor.h @@ -27,6 +27,7 @@ signals: /** @brief This signal is emitted once a logfile has been finished writing * @param fileName The name out the output (CSV) file */ + void logProcessingStatusChanged(QString); void finishedFile(QString fileName); }; diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 49c3cd2734a85fd59d6c51127a4d1d073a229f56..39bc47bc1d7279c6f3f9e3b56dbd7ff15803f207 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -59,7 +59,9 @@ MAVLinkProtocol::MAVLinkProtocol() : heartbeatRate(MAVLINK_HEARTBEAT_DEFAULT_RATE), m_heartbeatsEnabled(false), m_loggingEnabled(false), - m_logfile(NULL) + m_logfile(NULL), + m_enable_version_check(true), + versionMismatchIgnore(false) { start(QThread::LowPriority); // Start heartbeat timer, emitting a heartbeat at the configured rate @@ -76,6 +78,8 @@ MAVLinkProtocol::MAVLinkProtocol() : lastIndex[i][j] = -1; } } + + emit versionCheckChanged(m_enable_version_check); } MAVLinkProtocol::~MAVLinkProtocol() @@ -91,7 +95,6 @@ MAVLinkProtocol::~MAVLinkProtocol() void MAVLinkProtocol::run() { - } QString MAVLinkProtocol::getLogfileName() @@ -146,7 +149,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) // Check if the UAS has the same id like this system 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 @@ -161,12 +164,15 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) mavlink_msg_heartbeat_decode(&message, &heartbeat); // 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 - 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)); - + versionMismatchIgnore = true; + } // Ignore this message and continue gracefully continue; @@ -398,6 +404,11 @@ void MAVLinkProtocol::enableLogging(bool enabled) m_loggingEnabled = enabled; } +void MAVLinkProtocol::enableVersionCheck(bool enabled) +{ + m_enable_version_check = enabled; +} + bool MAVLinkProtocol::heartbeatsEnabled(void) { return m_heartbeatsEnabled; @@ -408,6 +419,11 @@ bool MAVLinkProtocol::loggingEnabled(void) return m_loggingEnabled; } +bool MAVLinkProtocol::versionCheckEnabled(void) +{ + return m_enable_version_check; +} + /** * The default rate is 1 Hertz. * diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h index d3e436d34b6005f8adb19c3b48a4c8a27f6f9d5c..76171e262d954e9d0f827fe5e87364e0aaeb8a2e 100644 --- a/src/comm/MAVLinkProtocol.h +++ b/src/comm/MAVLinkProtocol.h @@ -68,6 +68,8 @@ public: bool heartbeatsEnabled(void); /** @brief Get logging state */ bool loggingEnabled(void); + /** @brief Get protocol version check state */ + bool versionCheckEnabled(void); /** @brief Get the name of the packet log file */ static QString getLogfileName(); @@ -87,6 +89,9 @@ public slots: /** @brief Enable/disable binary packet logging */ void enableLogging(bool enabled); + /** @brief Enable / disable version check */ + void enableVersionCheck(bool enabled); + /** @brief Send an extra heartbeat to all connected units */ void sendHeartbeat(); @@ -96,12 +101,14 @@ protected: bool m_heartbeatsEnabled; ///< Enabled/disable heartbeat emission bool m_loggingEnabled; ///< Enable/disable packet logging 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 int lastIndex[256][256]; int totalReceiveCounter; int totalLossCounter; int currReceiveCounter; int currLossCounter; + bool versionMismatchIgnore; signals: /** @brief Message received and directly copied via signal */ @@ -110,6 +117,10 @@ signals: void heartbeatChanged(bool heartbeats); /** @brief Emitted if logging is started / stopped */ 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_ diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index afb4da35eb6ec34cbe76e3ab36c6569f81286d67..ee320e7363d3419c8faf027001e1f967de249e65 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -85,6 +85,8 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P #endif + loadSettings(); + // Link is setup, register it with link manager LinkManager::instance()->add(this); } diff --git a/src/uas/PxQuadMAV.cc b/src/uas/PxQuadMAV.cc index 2b9739ee4d9ed5108f0d1029410abc537b3855da..bde4e9e52b6be86f8d5796e961ad7abc535a7999 100644 --- a/src/uas/PxQuadMAV.cc +++ b/src/uas/PxQuadMAV.cc @@ -118,6 +118,21 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message) emit valueChanged(uasId, "vis. z", pos.z, time); } 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: { mavlink_aux_status_t status; diff --git a/src/ui/MAVLinkSettingsWidget.cc b/src/ui/MAVLinkSettingsWidget.cc index d4198389125e5ab9ebb165bafa19bb3b3b662ade..054ff10a5a73ddf40017c24edfc23a00c3aaef2c 100644 --- a/src/ui/MAVLinkSettingsWidget.cc +++ b/src/ui/MAVLinkSettingsWidget.cc @@ -37,15 +37,19 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget { 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(protocol, SIGNAL(heartbeatChanged(bool)), m_ui->heartbeatCheckBox, SLOT(setChecked(bool))); connect(m_ui->heartbeatCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableHeartbeats(bool))); connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->loggingCheckBox, SLOT(setChecked(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() diff --git a/src/ui/MAVLinkSettingsWidget.ui b/src/ui/MAVLinkSettingsWidget.ui index c65627d3b23f6be6fc3292ec183701c2879810d4..c24aaddf2099bd0c80b773b9dc1f8c77c08bd7cb 100644 --- a/src/ui/MAVLinkSettingsWidget.ui +++ b/src/ui/MAVLinkSettingsWidget.ui @@ -31,6 +31,13 @@ + + + + Only accept MAVs with same protocol version + + + diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index bb9cad8151fcbe3580834ed1096ab1fddbcb99ac..d083ea0a013f229d07dbab7a9a388b55b34e51b0 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -120,6 +120,8 @@ MainWindow::MainWindow(QWidget *parent): // Load mavlink view as default widget set //loadMAVLinkView(); + statusBar()->setSizeGripEnabled(true); + if (settings.contains("geometry")) { // Restore the window geometry @@ -144,14 +146,14 @@ MainWindow::MainWindow(QWidget *parent): MainWindow::~MainWindow() { - delete statusBar; - statusBar = NULL; + } void MainWindow::buildCommonWidgets() { //TODO: move protocol outside UI mavlink = new MAVLinkProtocol(); + connect(mavlink, SIGNAL(protocolStatusMessage(QString,QString)), this, SLOT(showCriticalMessage(QString,QString)), Qt::QueuedConnection); // Dock widgets if (!controlDockWidget) @@ -201,6 +203,12 @@ void MainWindow::buildCommonWidgets() protocolWidget = new XMLCommProtocolWidget(this); 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() @@ -740,6 +748,7 @@ void MainWindow::arrangeCommonCenterStack() if (!centerStack) return; 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); setCentralWidget(centerStack); @@ -810,15 +819,6 @@ void MainWindow::configureWindowName() #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() { QString format = "bmp"; @@ -889,7 +889,7 @@ void MainWindow::reloadStylesheet() */ 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) */ void MainWindow::showStatusMessage(const QString& status) { - statusBar->showMessage(status, 5); + statusBar()->showMessage(status, 20000); } void MainWindow::showCriticalMessage(const QString& title, const QString& message) @@ -914,6 +914,17 @@ void MainWindow::showCriticalMessage(const QString& title, const QString& messag 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 * diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 9ff4500de2e7a5942d4dd5955aaef05cd27ddf7a..1d9e61d707cfa1612f82c977745796f8c5aec6cd 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -98,6 +98,8 @@ public slots: void showStatusMessage(const QString& status); /** @brief Shows a critical message as popup or as widget */ 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(LinkInterface* link); @@ -296,10 +298,6 @@ protected: VIEW_SECTIONS currentView; bool aboutToCloseFlag; - QStatusBar* statusBar; - QStatusBar* createStatusBar(); - - void clearView(); void buildCommonWidgets(); diff --git a/src/ui/QGCDataPlot2D.cc b/src/ui/QGCDataPlot2D.cc index 6f71b0ba4bffcef163e9765ea4584919162f5386..5d0e01179dde2d4b7b48db53d5d14d744589906d 100644 --- a/src/ui/QGCDataPlot2D.cc +++ b/src/ui/QGCDataPlot2D.cc @@ -40,6 +40,7 @@ This file is part of the QGROUNDCONTROL project #include "QGCDataPlot2D.h" #include "ui_QGCDataPlot2D.h" #include "MG.h" +#include "MainWindow.h" #include #include @@ -75,7 +76,7 @@ void QGCDataPlot2D::reloadFile() { 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()); } @@ -88,9 +89,10 @@ void QGCDataPlot2D::reloadFile() void QGCDataPlot2D::loadFile() { + qDebug() << "DATA PLOT: Loading file:" << fileName; if (QFileInfo(fileName).isReadable()) { - if (ui->inputFileType->currentText().contains("pxIMU")) + if (ui->inputFileType->currentText().contains("pxIMU") || ui->inputFileType->currentText().contains("RAW")) { loadRawLog(fileName); } @@ -110,7 +112,7 @@ void QGCDataPlot2D::loadFile(QString file) { loadRawLog(fileName); } - else if (fileName.contains(".txt") || fileName.contains(".csv")) + else if (fileName.contains(".txt") || fileName.contains(".csv") || fileName.contains(".csv")) { loadCsvLog(fileName); } @@ -129,7 +131,7 @@ void QGCDataPlot2D::savePlot() if (!fileName.contains(".")) { - // .csv is default extension + // .pdf is default extension fileName.append(".pdf"); } @@ -269,7 +271,16 @@ void QGCDataPlot2D::selectFile() // Let user select the log file name //QDate date(QDate::currentDate()); // 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 QFileInfo fileInfo(fileName); @@ -296,32 +307,36 @@ void QGCDataPlot2D::selectFile() void QGCDataPlot2D::loadRawLog(QString file, QString xAxisName, QString yAxisFilter) { + qDebug() << "LOADING RAW LOG!"; + if (logFile != NULL) { logFile->close(); delete logFile; } // Postprocess log file - logFile = new QTemporaryFile(); + logFile = new QTemporaryFile("qt_qgc_temp_log.XXXXXX.csv"); 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(); - // Block UI - QProgressDialog progress("Transforming RAW log file to CSV", "Abort Transformation", 0, 1, this); - progress.setWindowModality(Qt::WindowModal); +// // Block UI +// QProgressDialog progress("Transforming RAW log file to CSV", "Abort Transformation", 0, 1, this); +// progress.setWindowModality(Qt::WindowModal); - while (!compressor->isFinished()) - { - MG::SLEEP::usleep(100000); - progress.setMaximum(compressor->getDataLines()); - progress.setValue(compressor->getCurrentLine()); - } - // Enforce end - progress.setMaximum(compressor->getDataLines()); - progress.setValue(compressor->getDataLines()); +// while (!compressor->isFinished()) +// { +// MG::SLEEP::usleep(100000); +//// progress.setMaximum(compressor->getDataLines()); +//// progress.setValue(compressor->getCurrentLine()); +// } +// // Enforce end +// progress.setMaximum(compressor->getDataLines()); +// progress.setValue(compressor->getDataLines()); // Done with preprocessing - now load csv log - loadCsvLog(logFile->fileName(), xAxisName, yAxisFilter); + //loadFile(logFile->fileName()); } /** @@ -654,6 +669,13 @@ void QGCDataPlot2D::saveCsvLog() fileName = QFileDialog::getSaveFileName( this, "Export CSV File Name", QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), "CSV file (*.csv);;Text file (*.txt)"); + + if (!fileName.contains(".")) + { + // .csv is default extension + fileName.append(".csv"); + } + // QFileInfo fileInfo(fileName); // // // Check if we could create a new file in this directory diff --git a/src/ui/linechart/LinechartWidget.cc b/src/ui/linechart/LinechartWidget.cc index d1703573e3fc178fa9c7db3b8276e4281aeb21e6..09198bdb2ac2962b1bf9187e2b5ab9f6d1fdabd5 100644 --- a/src/ui/linechart/LinechartWidget.cc +++ b/src/ui/linechart/LinechartWidget.cc @@ -48,6 +48,7 @@ This file is part of the PIXHAWK project #include "LinechartWidget.h" #include "LinechartPlot.h" #include "LogCompressor.h" +#include "MainWindow.h" #include "QGC.h" #include "MG.h" @@ -348,7 +349,7 @@ void LinechartWidget::startLogging() // Let user select the log file name QDate date(QDate::currentDate()); // 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(".")) { @@ -399,6 +400,8 @@ void LinechartWidget::stopLogging() // Postprocess log file compressor = new LogCompressor(logFile->fileName()); 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(); } logButton->setText(tr("Start logging"));