Commit 69ef65c7 authored by Lorenz Meier's avatar Lorenz Meier

Merge pull request #246 from cehberlin/master

Save and store last log file directory
parents 3935c549 72e70e19
......@@ -167,9 +167,14 @@ bool QGCMAVLinkLogPlayer::reset(int packetIndex)
}
}
bool QGCMAVLinkLogPlayer::selectLogFile()
/**
* @brief QGCMAVLinkLogPlayer::selectLogFile
* @param startDirectory Directory where the file dialog will be opened
* @return filename of the logFile
*/
bool QGCMAVLinkLogPlayer::selectLogFile(const QString startDirectory)
{
QString fileName = QFileDialog::getOpenFileName(this, tr("Specify MAVLink log file name to replay"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("MAVLink or Binary Logfile (*.mavlink *.bin *.log)"));
QString fileName = QFileDialog::getOpenFileName(this, tr("Specify MAVLink log file name to replay"), startDirectory, tr("MAVLink or Binary Logfile (*.mavlink *.bin *.log)"));
if (fileName == "")
{
......@@ -370,6 +375,7 @@ void QGCMAVLinkLogPlayer::logLoop()
//qDebug() << "START TIME: " << startTime;
// Check if these bytes could be correctly decoded
// TODO
if (!ok)
{
ui->logStatsLabel->setText(tr("Error decoding first timestamp, aborting."));
......@@ -381,14 +387,15 @@ void QGCMAVLinkLogPlayer::logLoop()
// Initialization seems fine, load next chunk
//this is ok because before we already read the timestamp of this paket before
QByteArray chunk = logFile.read(timeLen+packetLen);
QByteArray packet = chunk.mid(0, packetLen);
QByteArray packet = chunk.left(packetLen);
// Emit this packet
emit bytesReady(logLink, packet);
// Check if reached end of file before reading next timestamp
if (chunk.length() < timeLen+packetLen || logFile.atEnd())
if (chunk.length() < (timeLen + packetLen) || logFile.atEnd())
{
// Reached end of file
reset();
......@@ -400,6 +407,7 @@ void QGCMAVLinkLogPlayer::logLoop()
}
// End of file not reached, read next timestamp
// which is located after current packet
QByteArray rawTime = chunk.mid(packetLen);
// This is the timestamp of the next packet
......
......@@ -49,7 +49,7 @@ public slots:
/** @brief Reset the logfile */
bool reset(int packetIndex=0);
/** @brief Select logfile */
bool selectLogFile();
bool selectLogFile(const QString startDirectory);
/** @brief Load log file */
bool loadLogFile(const QString& file);
/** @brief Jump to a position in the logfile */
......
......@@ -38,7 +38,8 @@ QGCToolBar::QGCToolBar(QWidget *parent) :
batteryVoltage(0),
wpId(0),
wpDistance(0),
systemArmed(false)
systemArmed(false),
lastLogDirectory(QDesktopServices::storageLocation(QDesktopServices::DesktopLocation))
{
setObjectName("QGC_TOOLBAR");
......@@ -123,6 +124,8 @@ QGCToolBar::QGCToolBar(QWidget *parent) :
// Set the toolbar to be updated every 2s
connect(&updateViewTimer, SIGNAL(timeout()), this, SLOT(updateView()));
updateViewTimer.start(2000);
loadSettings();
}
void QGCToolBar::heartbeatTimeout(bool timeout, unsigned int ms)
......@@ -171,13 +174,13 @@ void QGCToolBar::playLogFile(bool checked)
player->playPause(false);
if (checked)
{
if (!player->selectLogFile()) return;
if (!player->selectLogFile(lastLogDirectory)) return;
}
}
// If no replaying happens already, start it
else
{
if (!player->selectLogFile()) return;
if (!player->selectLogFile(lastLogDirectory)) return;
}
player->playPause(checked);
}
......@@ -192,7 +195,7 @@ void QGCToolBar::logging(bool checked)
if (checked)
{
// Prompt the user for a filename/location to save to
QString fileName = QFileDialog::getSaveFileName(this, tr("Specify MAVLink log file to save to"), QDesktopServices::storageLocation(QDesktopServices::DesktopLocation), tr("MAVLink Logfile (*.mavlink *.log *.bin);;"));
QString fileName = QFileDialog::getSaveFileName(this, tr("Specify MAVLink log file to save to"), lastLogDirectory, tr("MAVLink Logfile (*.mavlink *.log *.bin);;"));
// Check that they didn't cancel out
if (fileName.isNull())
......@@ -224,6 +227,7 @@ void QGCToolBar::logging(bool checked)
{
MainWindow::instance()->getMAVLink()->setLogfileName(fileName);
MainWindow::instance()->getMAVLink()->enableLogging(true);
lastLogDirectory = file.absoluteDir().absolutePath(); //save last log directory
}
}
}
......@@ -486,6 +490,24 @@ void QGCToolBar::connectLink(bool connect)
}
void QGCToolBar::loadSettings()
{
QSettings settings;
settings.beginGroup("QGC_TOOLBAR");
lastLogDirectory = settings.value("LAST_LOG_DIRECTORY", lastLogDirectory).toString();
settings.endGroup();
}
void QGCToolBar::storeSettings()
{
QSettings settings;
settings.beginGroup("QGC_TOOLBAR");
settings.setValue("LAST_LOG_DIRECTORY", lastLogDirectory);
settings.endGroup();
settings.sync();
}
void QGCToolBar::clearStatusString()
{
lastSystemMessage = "";
......@@ -494,6 +516,7 @@ void QGCToolBar::clearStatusString()
QGCToolBar::~QGCToolBar()
{
storeSettings();
if (toggleLoggingAction) toggleLoggingAction->deleteLater();
if (logReplayAction) logReplayAction->deleteLater();
}
......@@ -80,6 +80,8 @@ public slots:
protected:
void createCustomWidgets();
void storeSettings();
void loadSettings();
QAction* toggleLoggingAction;
QAction* logReplayAction;
......@@ -109,6 +111,7 @@ protected:
quint64 lastSystemMessageTimeMs;
QTimer updateViewTimer;
bool systemArmed;
QString lastLogDirectory;
};
#endif // QGCTOOLBAR_H
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