Commit 04deae9f authored by lm's avatar lm

Fixed data plot and log compressor

parent 0e044f6c
...@@ -58,19 +58,23 @@ void LogCompressor::run() ...@@ -58,19 +58,23 @@ void LogCompressor::run()
QStringList* keys = new QStringList(); QStringList* keys = new QStringList();
QList<quint64> times;// = new QList<quint64>(); QList<quint64> times;// = new QList<quint64>();
QList<quint64> finalTimes; QList<quint64> finalTimes;
qDebug() << "LOG COMPRESSOR: Starting" << fileName;
if (!file.exists()) return; if (!file.exists() || !file.open(QIODevice::ReadOnly | QIODevice::Text))
if (!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);
...@@ -132,7 +136,8 @@ void LogCompressor::run() ...@@ -132,7 +136,8 @@ void LogCompressor::run()
QStringList* outLines = new QStringList(); QStringList* outLines = new QStringList();
for (int i = 0; i < times.length(); i++) 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<qint64>(times.at(i)) != lastTime)
{ {
outLines->append(QString("%1").arg(times.at(i)) + separator + spacer); outLines->append(QString("%1").arg(times.at(i)) + separator + spacer);
lastTime = static_cast<qint64>(times.at(i)); lastTime = static_cast<qint64>(times.at(i));
...@@ -197,6 +202,7 @@ void LogCompressor::run() ...@@ -197,6 +202,7 @@ void LogCompressor::run()
if (offset == 0) if (offset == 0)
{ {
emit logProcessingStatusChanged(tr("Log compressor: Timestamp %1 not found in dataset, ignoring log line %2").arg(time).arg(linecounter)); 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; //continue;
failed = true; failed = true;
} }
...@@ -208,16 +214,19 @@ void LogCompressor::run() ...@@ -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 if (!failed)
lastTimeIndex = index; {
QString outLine = outLines->at(index); // When the algorithm reaches here the correct index was found
QStringList outParts = outLine.split(separator); lastTimeIndex = index;
// Replace measurement placeholder with current value QString outLine = outLines->at(index);
outParts.replace(keys->indexOf(field)+1, value); QStringList outParts = outLine.split(separator);
outLine = outParts.join(separator); // Replace measurement placeholder with current value
outLines->replace(index, outLine); outParts.replace(keys->indexOf(field)+1, value);
outLine = outParts.join(separator);
outLines->replace(index, outLine);
}
} }
...@@ -246,7 +255,7 @@ void LogCompressor::run() ...@@ -246,7 +255,7 @@ void LogCompressor::run()
dataLines = 1; dataLines = 1;
delete keys; delete keys;
emit logProcessingStatusChanged(tr("Log compressor: Finished processing file: %1").arg(outfile.fileName())); 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;
} }
......
...@@ -202,6 +202,12 @@ void MainWindow::buildCommonWidgets() ...@@ -202,6 +202,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()
...@@ -742,6 +748,7 @@ void MainWindow::arrangeCommonCenterStack() ...@@ -742,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);
......
...@@ -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
......
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