diff --git a/src/ui/QGCMAVLinkLogPlayer.cc b/src/ui/QGCMAVLinkLogPlayer.cc
index 83f2a786aeb4d3218d777240c983bcd63d93a6ac..e989fc25049f013b5aa5032f8a7ac457567bbff1 100644
--- a/src/ui/QGCMAVLinkLogPlayer.cc
+++ b/src/ui/QGCMAVLinkLogPlayer.cc
@@ -22,6 +22,7 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare
     binaryBaudRate(57600),
     isPlaying(false),
     currPacketCount(0),
+    lastLogDirectory(QDesktopServices::storageLocation(QDesktopServices::DesktopLocation)),
     ui(new Ui::QGCMAVLinkLogPlayer)
 {
     ui->setupUi(this);
@@ -43,10 +44,12 @@ QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(MAVLinkProtocol* mavlink, QWidget *pare
     setAccelerationFactorInt(49);
     ui->speedSlider->setValue(49);
     ui->positionSlider->setValue(ui->positionSlider->minimum());
+    loadSettings();
 }
 
 QGCMAVLinkLogPlayer::~QGCMAVLinkLogPlayer()
 {
+    storeSettings();
     delete ui;
 }
 
@@ -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
  * @return filename of the logFile
  */
@@ -182,6 +212,7 @@ bool QGCMAVLinkLogPlayer::selectLogFile(const QString startDirectory)
     }
     else
     {
+        lastLogDirectory = fileName;
         return loadLogFile(fileName);
     }
 }
diff --git a/src/ui/QGCMAVLinkLogPlayer.h b/src/ui/QGCMAVLinkLogPlayer.h
index 1ea0b798f912aefe3fd9c8088403b314f27b0c41..e4c0e4fd64627e2232b85d1b1b1020dd97f3543d 100644
--- a/src/ui/QGCMAVLinkLogPlayer.h
+++ b/src/ui/QGCMAVLinkLogPlayer.h
@@ -50,6 +50,8 @@ public slots:
     bool reset(int packetIndex=0);
     /** @brief Select logfile */
     bool selectLogFile(const QString startDirectory);
+    /** @brief Select logfile */
+    bool selectLogFile();
     /** @brief Load log file */
     bool loadLogFile(const QString& file);
     /** @brief Jump to a position in the logfile */
@@ -81,8 +83,12 @@ protected:
     unsigned int currPacketCount;
     static const int packetLen = MAVLINK_MAX_PACKET_LEN;
     static const int timeLen = sizeof(quint64);
+    QString lastLogDirectory;
     void changeEvent(QEvent *e);
 
+    void loadSettings();
+    void storeSettings();
+
 private:
     Ui::QGCMAVLinkLogPlayer *ui;
 };