Commit 27f2a93b authored by Lorenz Meier's avatar Lorenz Meier

Merge pull request #84 from Susurrus/datalogger_refactoring

Datalogger refactoring
parents 33b2346e 6ba5787c
/*=================================================================== /*===================================================================
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>
This file is part of the QGROUNDCONTROL project This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or the Free Software Foundation, either version 3 of the License, or
(at your option) any later version. (at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful, QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details. GNU General Public License for more details.
You should have received a copy of the GNU General Public License You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/ ======================================================================*/
/** /**
* @file * @file
* @brief Implementation of class LogCompressor * @brief Implementation of class LogCompressor. This class reads in a file containing messages and translates it into a tab-delimited CSV file.
* @author Lorenz Meier <mavteam@student.ethz.ch> * @author Lorenz Meier <mavteam@student.ethz.ch>
* *
*/ */
#include <QFile> #include <QFile>
#include <QTextStream> #include <QTemporaryFile>
#include <QStringList> #include <QTextStream>
#include <QFileInfo> #include <QStringList>
#include <QList> #include <QFileInfo>
#include "LogCompressor.h" #include <QList>
#include "LogCompressor.h"
#include <QDebug>
#include <QDebug>
/**
* It will only get active upon calling startCompression() /**
*/ * Initializes all the variables necessary for a compression run. This won't actually happen
LogCompressor::LogCompressor(QString logFileName, QString outFileName, int uasid) : * until startCompression(...) is called.
logFileName(logFileName), */
outFileName(outFileName), LogCompressor::LogCompressor(QString logFileName, QString outFileName, QString delimiter) :
running(true), logFileName(logFileName),
currentDataLine(0), outFileName(outFileName),
dataLines(1), running(true),
uasid(uasid), currentDataLine(0),
holeFillingEnabled(true) holeFillingEnabled(true),
{ delimiter(delimiter)
} {
}
void LogCompressor::run()
{ void LogCompressor::run()
QString separator = "\t"; {
QString fileName = logFileName; // Verify that the input file is useable
QFile file(fileName); QFile infile(logFileName);
QFile outfile(outFileName); if (!infile.exists() || !infile.open(QIODevice::ReadOnly | QIODevice::Text)) {
QStringList* keys = new QStringList(); emit logProcessingStatusChanged(tr("Log Compressor: Cannot start/compress log file, since input file %1 is not readable").arg(QFileInfo(infile.fileName()).absoluteFilePath()));
QList<quint64> times;// = new QList<quint64>(); return;
QList<quint64> finalTimes; }
//qDebug() << "LOG COMPRESSOR: Starting" << fileName; // Verify that the output file is useable
QTemporaryFile outTmpFile;
if (!file.exists() || !file.open(QIODevice::ReadOnly | QIODevice::Text)) { if (!outTmpFile.open()) {
//qDebug() << "LOG COMPRESSOR: INPUT FILE DOES NOT EXIST"; emit logProcessingStatusChanged(tr("Log Compressor: Cannot start/compress log file, since output file %1 is not writable").arg(QFileInfo(outTmpFile.fileName()).absoluteFilePath()));
emit logProcessingStatusChanged(tr("Log Compressor: Cannot start/compress log file, since input file %1 is not readable").arg(QFileInfo(fileName).absoluteFilePath())); return;
return; }
}
// Check if file is writeable // First we search the input file through keySearchLimit number of lines
if (outFileName == ""/* || !QFileInfo(outfile).isWritable()*/) { // looking for variables. This is neccessary before CSV files require
//qDebug() << "LOG COMPRESSOR: OUTPUT FILE DOES NOT EXIST" << outFileName; // the same number of fields for every line.
emit logProcessingStatusChanged(tr("Log Compressor: Cannot start/compress log file, since output file %1 is not writable").arg(QFileInfo(outFileName).absoluteFilePath())); const unsigned int keySearchLimit = 15000;
return; unsigned int keyCounter = 0;
} QTextStream in(&infile);
QMap<QString, int> messageMap;
// Find all keys while (!in.atEnd() && keyCounter < keySearchLimit) {
QTextStream in(&file); QString messageName = in.readLine().split(delimiter).at(2);
messageMap.insert(messageName, 0);
// Search only a certain region, assuming that not more ++keyCounter;
// than N dimensions at H Hertz can be send }
const unsigned int keySearchLimit = 15000;
// e.g. 500 Hz * 30 values or // Now update each key with its index in the output string. These are
// e.g. 100 Hz * 150 values // all offset by one to account for the first field: timestamp_ms.
QMap<QString, int>::iterator i = messageMap.constBegin();
unsigned int keyCounter = 0; int j;
while (!in.atEnd() && keyCounter < keySearchLimit) { for (i = messageMap.begin(), j = 1; i != messageMap.end(); ++i, ++j) {
QString line = in.readLine(); i.value() = j;
// Accumulate map of keys }
// Data field name is at position 2
QString key = line.split(separator).at(2); // Open the output file and write the header line to it
if (!keys->contains(key)) QStringList headerList(messageMap.keys());
{ QString headerLine = "timestamp_ms" + delimiter + headerList.join(delimiter) + "\n";
keys->append(key); outTmpFile.write(headerLine.toLocal8Bit());
}
keyCounter++; emit logProcessingStatusChanged(tr("Log compressor: Dataset contains dimension: ") + headerLine);
}
keys->sort(); // Reset our position in the input file before we start the main processing loop.
infile.reset();
QString header = ""; in.reset();
QString spacer = ""; in.resetStatus();
for (int i = 0; i < keys->length(); i++) {
header += keys->at(i) + separator; // Template list stores a list for populating with data as it's parsed from messages.
spacer += separator; QStringList templateList;
} for (int i = 0; i < headerList.size() + 1; ++i) {
templateList << (holeFillingEnabled?"NaN":"");
emit logProcessingStatusChanged(tr("Log compressor: Dataset contains dimension: ") + header); }
QStringList filledList(templateList);
// Find all times QStringList currentLine = in.readLine().split(delimiter);
//in.reset(); currentDataLine = 1;
file.reset(); while (!in.atEnd()) {
in.reset(); // We only overwrite data from the last time set if we aren't doing a zero-order hold
in.resetStatus(); if (!holeFillingEnabled) {
bool ok; filledList = templateList;
while (!in.atEnd()) { }
QString line = in.readLine(); // Populate this time set with the data from this first message
// Accumulate map of keys filledList.replace(0, currentLine.at(0));
// Data field name is at position 2b filledList.replace(messageMap.value(currentLine.at(2)), currentLine.at(3));
quint64 time = static_cast<QString>(line.split(separator).at(0)).toLongLong(&ok);
if (ok) { // Continue searching for messages in the same time set and adding that data
times.append(time); // to the current time set if appropriate.
} while (!in.atEnd()) {
} QStringList newLine = in.readLine().split(delimiter);
++currentDataLine;
qSort(times);
if (newLine.at(0) == currentLine.at(0)) {
qint64 lastTime = -1; QString currentDataName = newLine.at(2);
QString currentDataValue = newLine.at(3);
// Create lines filledList.replace(messageMap.value(currentDataName), currentDataValue);
QStringList* outLines = new QStringList(); } else {
for (int i = 0; i < times.length(); i++) { currentLine = newLine;
// Cast to signed on purpose, 64 bit timestamp still long enough break;
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)); // Write this current time set out to the file
//qDebug() << "ADDED:" << outLines->last(); QString output = filledList.join(delimiter) + "\n";
} outTmpFile.write(output.toLocal8Bit());
} }
dataLines = finalTimes.length(); // We're now done with the source file
infile.close();
emit logProcessingStatusChanged(tr("Log compressor: Now processing %1 log lines").arg(finalTimes.length()));
// Make sure we remove the source file before replacing it.
// Fill in the values for all keys QFile::remove(outFileName);
file.reset(); outTmpFile.copy(outFileName);
QTextStream data(&file); outTmpFile.close();
int linecounter = 0; emit logProcessingStatusChanged(tr("Log Compressor: Writing output to file %1").arg(QFileInfo(outFileName).absoluteFilePath()));
quint64 lastTimeIndex = 0;
bool failed = false; // Clean up and update the status before we return.
currentDataLine = 0;
while (!data.atEnd()) { emit logProcessingStatusChanged(tr("Log compressor: Finished processing file: %1").arg(outFileName));
linecounter++; emit finishedFile(outFileName);
currentDataLine = linecounter; qDebug() << "Done with logfile processing";
QString line = data.readLine(); running = false;
QStringList parts = line.split(separator); }
// Get time
quint64 time = static_cast<QString>(parts.first()).toLongLong(&ok); /**
QString field = parts.at(2); * @param holeFilling If hole filling is enabled, the compressor tries to fill empty data fields with previous
int fieldIndex = keys->indexOf(field); * values from the same variable (or NaN, if no previous value existed)
QString value = parts.at(3); */
// // Enforce NaN if no value is present void LogCompressor::startCompression(bool holeFilling)
// if (value.length() == 0 || value == "" || value == " " || value == "\t" || value == "\n") { {
// // Hole filling disabled, fill with NaN holeFillingEnabled = holeFilling;
// value = "NaN"; start();
// } }
// Get matching output line
bool LogCompressor::isFinished()
// Constraining the search area might result in not finding a key, {
// but it significantly reduces the time needed for the search return !running;
// setting a window of 100 entries means that a 1 Hz data point }
// can still be located
quint64 offsetLimit = 100; int LogCompressor::getCurrentLine()
quint64 offset; {
qint64 index = -1; return currentDataLine;
failed = false; }
\ No newline at end of file
// 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) {
offset = lastTimeIndex - offsetLimit;
} else {
offset = 0;
}
index = finalTimes.indexOf(time, offset);
if (index == -1) {
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 (dataLines > 100) 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);
// Replace measurement placeholder with current value
outParts.replace(fieldIndex+1, value);
outLine = outParts.join(separator);
outLines->replace(index, outLine);
}
}
///////////////////////////
// HOLE FILLING
// If hole filling is enabled, run again through the whole file and replace holes
if (holeFillingEnabled)
{
// Build up the fill values - initialize to NaN
QStringList fillValues;
int fillCount = keys->count();
for (int i = 0; i< fillCount; ++i)
{
fillValues.append("NaN");
}
// Run through all lines and replace with fill values
for (int index = 0; index < outLines->count(); ++index)
{
QString line = outLines->at(index);
//qDebug() << "LINE" << line;
QStringList fields = line.split(separator, QString::SkipEmptyParts);
// The fields line contains the timestamp
// index of the data fields therefore runs from 1 to n-1
int fieldCount = fields.count();
for (int i = 1; i < fillCount+1; ++i)
{
if (fieldCount <= i) fields.append("");
// Allow input data to be screwed up
if (fields.at(i) == "\t" || fields.at(i) == " " || fields.at(i) == "\n")
{
// Remove invalid data
if (fieldCount > fillCount+1)
{
// This field has a seperator value and is too much
//qDebug() << "REMOVED INVALID INPUT DATA";
fields.removeAt(i);
}
// Continue on invalid data
continue;
}
// Check if this is NaN
if (fields.at(i) == 0 || fields.at(i) == "")
{
// Value was empty, replace it
fields.replace(i, fillValues[i-1]);
//qDebug() << "FILL" << fillValues.at(i-1);
}
else
{
// Value was not NaN, use it as
// new fill value
fillValues.replace(i-1, fields[i]);
}
}
outLines->replace(index, fields.join(separator));
}
}
// Add header, write out file
file.close();
if (outFileName == logFileName) {
QFile::remove(file.fileName());
outfile.setFileName(file.fileName());
}
if (!outfile.open(QIODevice::WriteOnly | QIODevice::Text))
return;
outfile.write(QString(QString("timestamp_ms") + separator + header.replace(" ", "_") + QString("\n")).toLatin1());
emit logProcessingStatusChanged(tr("Log Compressor: Writing output to file %1").arg(QFileInfo(outFileName).absoluteFilePath()));
// File output
for (int i = 0; i < outLines->length(); i++) {
//qDebug() << outLines->at(i);
outfile.write(QString(outLines->at(i) + "\n").toLatin1());
}
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;
}
/**
* @param holeFilling If hole filling is enabled, the compressor tries to fill empty data fields with previous
* values from the same variable (or NaN, if no previous value existed)
*/
void LogCompressor::startCompression(bool holeFilling)
{
// Set hole filling
holeFillingEnabled = holeFilling;
start();
}
bool LogCompressor::isFinished()
{
return !running;
}
int LogCompressor::getCurrentLine()
{
return currentDataLine;
}
int LogCompressor::getDataLines()
{
return dataLines;
}
...@@ -8,29 +8,31 @@ class LogCompressor : public QThread ...@@ -8,29 +8,31 @@ class LogCompressor : public QThread
Q_OBJECT Q_OBJECT
public: public:
/** @brief Create the log compressor. It will only get active upon calling startCompression() */ /** @brief Create the log compressor. It will only get active upon calling startCompression() */
LogCompressor(QString logFileName, QString outFileName="", int uasid = 0); LogCompressor(QString logFileName, QString outFileName="", QString delimiter="\t");
/** @brief Start the compression of a raw, line-based logfile into a CSV file */ /** @brief Start the compression of a raw, line-based logfile into a CSV file */
void startCompression(bool holeFilling=false); void startCompression(bool holeFilling=false);
bool isFinished(); bool isFinished();
int getDataLines();
int getCurrentLine(); int getCurrentLine();
protected: protected:
void run(); void run(); ///< This function actually performs the compression. It's an overloaded function from QThread
QString logFileName; QString logFileName; ///< The input file name.
QString outFileName; QString outFileName; ///< The output file name. If blank defaults to logFileName
bool running; bool running; ///< True when the startCompression() function is operating.
int currentDataLine; int currentDataLine; ///< The current line of data that is being processed. Only relevant when running==true
int dataLines; QString delimiter; ///< Delimiter between fields in the output file. Defaults to tab ('\t')
int uasid; bool holeFillingEnabled; ///< Enables the filling of holes in the dataset with the previous value (or NaN if none exists)
bool holeFillingEnabled; ///< Enables the filling of holes in the dataset with the previous value (or NaN if none exists)
signals: signals:
/** @brief This signal is emitted when there is a change in the status of the parsing algorithm. For instance if an error is encountered.
* @param status A status message
*/
void logProcessingStatusChanged(QString status);
/** @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 of the output (CSV) file
*/ */
void logProcessingStatusChanged(QString);
void finishedFile(QString fileName); void finishedFile(QString fileName);
}; };
#endif // LOGCOMPRESSOR_H #endif // LOGCOMPRESSOR_H
\ No newline at end of file
...@@ -145,7 +145,7 @@ ...@@ -145,7 +145,7 @@
<string>Display only variable names in curve list</string> <string>Display only variable names in curve list</string>
</property> </property>
<property name="text"> <property name="text">
<string>Short Names</string> <string>Short names</string>
</property> </property>
</widget> </widget>
</item> </item>
......
...@@ -12,10 +12,10 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) : ...@@ -12,10 +12,10 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
componentID[i] = -1; componentID[i] = -1;
componentMulti[i] = false; componentMulti[i] = false;
onboardTimeOffset[i] = 0; onboardTimeOffset[i] = 0;
onboardToGCSUnixTimeOffsetAndDelay[i] = 0;
firstOnboardTime[i] = 0;
} }
// Fill filter // Fill filter
messageFilter.insert(MAVLINK_MSG_ID_HEARTBEAT, false); messageFilter.insert(MAVLINK_MSG_ID_HEARTBEAT, false);
messageFilter.insert(MAVLINK_MSG_ID_SYS_STATUS, false); messageFilter.insert(MAVLINK_MSG_ID_SYS_STATUS, false);
......
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