diff --git a/src/LogCompressor.cc b/src/LogCompressor.cc index 6ba3136ecfaeea47a8efdf79217eab5ddbeff65b..108535429cd6ecf386cabd90bd104863fad5defa 100644 --- a/src/LogCompressor.cc +++ b/src/LogCompressor.cc @@ -58,19 +58,23 @@ void LogCompressor::run() QStringList* keys = new QStringList(); QList times;// = new QList(); QList finalTimes; + + qDebug() << "LOG COMPRESSOR: Starting" << fileName; - if (!file.exists()) return; - 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; + } - 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); @@ -132,7 +136,8 @@ void LogCompressor::run() QStringList* outLines = new QStringList(); for (int i = 0; i < times.length(); i++) { - if (times.at(i) != lastTime) + // 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)); @@ -197,6 +202,7 @@ void LogCompressor::run() 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; } @@ -208,16 +214,19 @@ void LogCompressor::run() } } - if (index % (dataLines/10) == 0) emit logProcessingStatusChanged(tr("Log compressor: Processed %1%% of %2 lines").arg(index/(float)dataLines).arg(dataLines)); + 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)); - // When the algorithm reaches here the correct index was found - lastTimeIndex = index; - QString outLine = outLines->at(index); - QStringList outParts = outLine.split(separator); - // Replace measurement placeholder with current value - outParts.replace(keys->indexOf(field)+1, value); - outLine = outParts.join(separator); - outLines->replace(index, outLine); + if (!failed) + { + // When the algorithm reaches here the correct index was found + lastTimeIndex = index; + QString outLine = outLines->at(index); + QStringList outParts = outLine.split(separator); + // Replace measurement placeholder with current value + outParts.replace(keys->indexOf(field)+1, value); + outLine = outParts.join(separator); + outLines->replace(index, outLine); + } } @@ -246,7 +255,7 @@ void LogCompressor::run() dataLines = 1; 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()); running = false; } diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 9a3f6682819c0ae74b74bee2ce86352d7fded174..a6d2da50172473486dc4da97edcb8604b5b39bba 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -202,6 +202,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() @@ -742,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); 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