Commit 3deb2c26 authored by Lorenz Meier's avatar Lorenz Meier

Merge branch 'master' of github.com:mavlink/qgroundcontrol into sensor_hil

parents 2375b7cb 42e630eb
...@@ -22,6 +22,7 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare ...@@ -22,6 +22,7 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare
binaryBaudRate(57600), binaryBaudRate(57600),
isPlaying(false), isPlaying(false),
currPacketCount(0), currPacketCount(0),
lastLogDirectory(QDesktopServices::storageLocation(QDesktopServices::DesktopLocation)),
ui(new Ui::QGCMAVLinkLogPlayer) ui(new Ui::QGCMAVLinkLogPlayer)
{ {
ui->setupUi(this); ui->setupUi(this);
...@@ -43,10 +44,12 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare ...@@ -43,10 +44,12 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare
setAccelerationFactorInt(49); setAccelerationFactorInt(49);
ui->speedSlider->setValue(49); ui->speedSlider->setValue(49);
ui->positionSlider->setValue(ui->positionSlider->minimum()); ui->positionSlider->setValue(ui->positionSlider->minimum());
loadSettings();
} }
QGCMAVLinkLogPlayer::~QGCMAVLinkLogPlayer() QGCMAVLinkLogPlayer::~QGCMAVLinkLogPlayer()
{ {
storeSettings();
delete ui; delete ui;
} }
...@@ -167,8 +170,35 @@ bool QGCMAVLinkLogPlayer::reset(int packetIndex) ...@@ -167,8 +170,35 @@ bool QGCMAVLinkLogPlayer::reset(int packetIndex)
} }
} }
void QGCMAVLinkLogPlayer::loadSettings()
{
QSettings settings;
settings.beginGroup("QGC_MAVLINKLOGPLAYER");
lastLogDirectory = settings.value("LAST_LOG_DIRECTORY", lastLogDirectory).toString();
settings.endGroup();
}
void QGCMAVLinkLogPlayer::storeSettings()
{
QSettings settings;
settings.beginGroup("QGC_MAVLINKLOGPLAYER");
settings.setValue("LAST_LOG_DIRECTORY", lastLogDirectory);
settings.endGroup();
settings.sync();
}
/**
* @brief Select a log file
* @param startDirectory Directory where the file dialog will be opened
* @return filename of the logFile
*/
bool QGCMAVLinkLogPlayer::selectLogFile()
{
return selectLogFile(lastLogDirectory);
}
/** /**
* @brief QGCMAVLinkLogPlayer::selectLogFile * @brief Select a log file
* @param startDirectory Directory where the file dialog will be opened * @param startDirectory Directory where the file dialog will be opened
* @return filename of the logFile * @return filename of the logFile
*/ */
...@@ -182,6 +212,7 @@ bool QGCMAVLinkLogPlayer::selectLogFile(const QString startDirectory) ...@@ -182,6 +212,7 @@ bool QGCMAVLinkLogPlayer::selectLogFile(const QString startDirectory)
} }
else else
{ {
lastLogDirectory = fileName;
return loadLogFile(fileName); return loadLogFile(fileName);
} }
} }
......
...@@ -50,6 +50,8 @@ public slots: ...@@ -50,6 +50,8 @@ public slots:
bool reset(int packetIndex=0); bool reset(int packetIndex=0);
/** @brief Select logfile */ /** @brief Select logfile */
bool selectLogFile(const QString startDirectory); bool selectLogFile(const QString startDirectory);
/** @brief Select logfile */
bool selectLogFile();
/** @brief Load log file */ /** @brief Load log file */
bool loadLogFile(const QString& file); bool loadLogFile(const QString& file);
/** @brief Jump to a position in the logfile */ /** @brief Jump to a position in the logfile */
...@@ -81,8 +83,12 @@ protected: ...@@ -81,8 +83,12 @@ protected:
unsigned int currPacketCount; unsigned int currPacketCount;
static const int packetLen = MAVLINK_MAX_PACKET_LEN; static const int packetLen = MAVLINK_MAX_PACKET_LEN;
static const int timeLen = sizeof(quint64); static const int timeLen = sizeof(quint64);
QString lastLogDirectory;
void changeEvent(QEvent *e); void changeEvent(QEvent *e);
void loadSettings();
void storeSettings();
private: private:
Ui::QGCMAVLinkLogPlayer *ui; Ui::QGCMAVLinkLogPlayer *ui;
}; };
......
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