diff --git a/QGCSetup.pri b/QGCSetup.pri
index 0de0b32..e0242f0 100644
--- a/QGCSetup.pri
+++ b/QGCSetup.pri
@@ -69,7 +69,6 @@ WindowsBuild {
     COPY_FILE_LIST = \
         $$BASEDIR\\libs\\lib\\sdl2\\msvc\\lib\\x86\\SDL2.dll \
         $$BASEDIR\\deploy\\libeay32.dll \
-        $$BASEDIR_WIN\\deploy\\libssl32.dll \
         $$BASEDIR_WIN\\deploy\\ssleay32.dll
 
     for(COPY_FILE, COPY_FILE_LIST) {
diff --git a/deploy/libeay32.dll b/deploy/libeay32.dll
index ffd92b8..e94703c 100644
Binary files a/deploy/libeay32.dll and b/deploy/libeay32.dll differ
diff --git a/deploy/libssl32.dll b/deploy/libssl32.dll
deleted file mode 100644
index 0592244..0000000
Binary files a/deploy/libssl32.dll and /dev/null differ
diff --git a/deploy/ssleay32.dll b/deploy/ssleay32.dll
index 0592244..5c90915 100644
Binary files a/deploy/ssleay32.dll and b/deploy/ssleay32.dll differ
diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 55b0551..f0bcc39 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -56,7 +56,6 @@ iOSBuild {
             error("Error building .plist file. 'ForAppStore' builds are only possible through the official build system.")
         }
         QT               += qml-private
-        CONFIG           += qtquickcompiler
         QMAKE_INFO_PLIST  = $${BASEDIR}/ios/iOSForAppStore-Info.plist
         OTHER_FILES      += $${BASEDIR}/ios/iOSForAppStore-Info.plist
     } else {
@@ -203,6 +202,7 @@ LinuxBuild {
 CONFIG += qt \
     thread \
     c++11 \
+    qtquickcompiler \
 
 contains(DEFINES, ENABLE_VERBOSE_OUTPUT) {
     message("Enable verbose compiler output (manual override from command line)")
diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml
index ac3c442..f9af268 100644
--- a/src/FlightDisplay/FlightDisplayView.qml
+++ b/src/FlightDisplay/FlightDisplayView.qml
@@ -485,12 +485,12 @@ QGCView {
             z:                          _panel.z + 5
             width:                      parent.width  - (_flightVideoPipControl.width / 2)
             height:                     Math.min(ScreenTools.availableHeight * 0.25, ScreenTools.defaultFontPixelWidth * 16)
-            visible:                    (_virtualJoystick ? _virtualJoystick.value : false) && !QGroundControl.videoManager.fullScreen
+            visible:                    (_virtualJoystick ? _virtualJoystick.value : false) && !QGroundControl.videoManager.fullScreen && !(_activeVehicle ? _activeVehicle.highLatencyLink : false)
             anchors.bottom:             _flightVideoPipControl.top
             anchors.bottomMargin:       ScreenTools.defaultFontPixelHeight * 2
             anchors.horizontalCenter:   flightDisplayViewWidgets.horizontalCenter
             source:                     "qrc:/qml/VirtualJoystick.qml"
-            active:                     _virtualJoystick ? _virtualJoystick.value : false
+            active:                     (_virtualJoystick ? _virtualJoystick.value : false) && !(_activeVehicle ? _activeVehicle.highLatencyLink : false)
 
             property bool useLightColors: isBackgroundDark
 
diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc
index 3e94d74..65ad8a7 100644
--- a/src/MissionManager/MissionController.cc
+++ b/src/MissionManager/MissionController.cc
@@ -56,20 +56,21 @@ const char* MissionController::_jsonMavAutopilotKey =           "MAV_AUTOPILOT";
 const int   MissionController::_missionFileVersion =            2;
 
 MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
-    : PlanElementController(masterController, parent)
-    , _missionManager(_managerVehicle->missionManager())
-    , _visualItems(NULL)
-    , _settingsItem(NULL)
-    , _firstItemsFromVehicle(false)
-    , _itemsRequested(false)
-    , _surveyMissionItemName(tr("Survey"))
-    , _fwLandingMissionItemName(tr("Fixed Wing Landing"))
-    , _structureScanMissionItemName(tr("Structure Scan"))
-    , _corridorScanMissionItemName(tr("Corridor Scan"))
-    , _appSettings(qgcApp()->toolbox()->settingsManager()->appSettings())
-    , _progressPct(0)
-    , _currentPlanViewIndex(-1)
-    , _currentPlanViewItem(NULL)
+    : PlanElementController         (masterController, parent)
+    , _missionManager               (_managerVehicle->missionManager())
+    , _visualItems                  (NULL)
+    , _settingsItem                 (NULL)
+    , _firstItemsFromVehicle        (false)
+    , _itemsRequested               (false)
+    , _inRecalcSequence             (false)
+    , _surveyMissionItemName        (tr("Survey"))
+    , _fwLandingMissionItemName     (tr("Fixed Wing Landing"))
+    , _structureScanMissionItemName (tr("Structure Scan"))
+    , _corridorScanMissionItemName  (tr("Corridor Scan"))
+    , _appSettings                  (qgcApp()->toolbox()->settingsManager()->appSettings())
+    , _progressPct                  (0)
+    , _currentPlanViewIndex         (-1)
+    , _currentPlanViewItem          (NULL)
 {
     _resetMissionFlightStatus();
     managerVehicleChanged(_managerVehicle);
@@ -146,17 +147,17 @@ void MissionController::_init(void)
 // Called when new mission items have completed downloading from Vehicle
 void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllRequested)
 {
-    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle";
+    qCDebug(MissionControllerLog) << "_newMissionItemsAvailableFromVehicle flyView:count" << _flyView << _missionManager->missionItems().count();
 
     // Fly view always reloads on _loadComplete
     // Plan view only reloads on _loadComplete if specifically requested
-    if (_flyView || removeAllRequested || _itemsRequested) {
+    if (_flyView || removeAllRequested || _itemsRequested || _visualItems->count() <= 1) {
         // Fly Mode (accept if):
         //      - Always accepts new items from the vehicle so Fly view is kept up to date
         // Edit Mode (accept if):
-        //      - Either a load from vehicle was manually requested or
+        //      - Remove all was requested from Fly view (clear mission on flight end)
+        //      - A load from vehicle was manually requested
         //      - The initial automatic load from a vehicle completed and the current editor is empty
-        //      - Remove all way requested from Fly view (clear mission on flight end)
 
         QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
         const QList<MissionItem*>& newMissionItems = _missionManager->missionItems();
@@ -1490,15 +1491,21 @@ void MissionController::_recalcMissionFlightStatus()
 // This will update the sequence numbers to be sequential starting from 0
 void MissionController::_recalcSequence(void)
 {
+    if (_inRecalcSequence) {
+        // Don't let this call recurse due to signalling
+        return;
+    }
+
     // Setup ascending sequence numbers for all visual items
 
+    _inRecalcSequence = true;
     int sequenceNumber = 0;
     for (int i=0; i<_visualItems->count(); i++) {
         VisualMissionItem* item = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
-
         item->setSequenceNumber(sequenceNumber);
         sequenceNumber = item->lastSequenceNumber() + 1;
-    }
+    }    
+    _inRecalcSequence = false;
 }
 
 // This will update the child item hierarchy
diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h
index bf31ce0..050bebc 100644
--- a/src/MissionManager/MissionController.h
+++ b/src/MissionManager/MissionController.h
@@ -276,6 +276,7 @@ private:
     CoordVectHashTable      _linesTable;
     bool                    _firstItemsFromVehicle;
     bool                    _itemsRequested;
+    bool                    _inRecalcSequence;
     MissionFlightStatus_t   _missionFlightStatus;
     QString                 _surveyMissionItemName;
     QString                 _fwLandingMissionItemName;
diff --git a/src/MissionManager/PlanElementController.h b/src/MissionManager/PlanElementController.h
index 0690c84..078f218 100644
--- a/src/MissionManager/PlanElementController.h
+++ b/src/MissionManager/PlanElementController.h
@@ -63,7 +63,6 @@ signals:
     void containsItemsChanged   (bool containsItems);
     void syncInProgressChanged  (bool syncInProgress);
     void dirtyChanged           (bool dirty);
-    void vehicleChanged         (Vehicle* vehicle);
     void sendComplete           (void);
     void removeAllComplete      (void);
 
diff --git a/src/MissionManager/PlanManager.cc b/src/MissionManager/PlanManager.cc
index e1f9b24..d3cbb82 100644
--- a/src/MissionManager/PlanManager.cc
+++ b/src/MissionManager/PlanManager.cc
@@ -22,17 +22,17 @@
 QGC_LOGGING_CATEGORY(PlanManagerLog, "PlanManagerLog")
 
 PlanManager::PlanManager(Vehicle* vehicle, MAV_MISSION_TYPE planType)
-    : _vehicle(vehicle)
-    , _planType(planType)
-    , _dedicatedLink(NULL)
-    , _ackTimeoutTimer(NULL)
-    , _expectedAck(AckNone)
-    , _transactionInProgress(TransactionNone)
-    , _resumeMission(false)
-    , _lastMissionRequest(-1)
-    , _missionItemCountToRead(-1)
-    , _currentMissionIndex(-1)
-    , _lastCurrentIndex(-1)
+    : _vehicle                  (vehicle)
+    , _planType                 (planType)
+    , _dedicatedLink            (NULL)
+    , _ackTimeoutTimer          (NULL)
+    , _expectedAck              (AckNone)
+    , _transactionInProgress    (TransactionNone)
+    , _resumeMission            (false)
+    , _lastMissionRequest       (-1)
+    , _missionItemCountToRead   (-1)
+    , _currentMissionIndex      (-1)
+    , _lastCurrentIndex         (-1)
 {
     _ackTimeoutTimer = new QTimer(this);
     _ackTimeoutTimer->setSingleShot(true);
@@ -59,9 +59,8 @@ void PlanManager::_writeMissionItemsWorker(void)
         _itemIndicesToWrite << i;
     }
 
-    _transactionInProgress = TransactionWrite;
     _retryCount = 0;
-    emit inProgressChanged(true);
+    _setTransactionInProgress(TransactionWrite);
     _connectToMavlink();
     _writeMissionCount();
 }
@@ -137,8 +136,7 @@ void PlanManager::loadFromVehicle(void)
     }
 
     _retryCount = 0;
-    _transactionInProgress = TransactionRead;
-    emit inProgressChanged(true);
+    _setTransactionInProgress(TransactionRead);
     _connectToMavlink();
     _requestList();
 }
@@ -821,12 +819,7 @@ void PlanManager::_finishTransaction(bool success, bool apmGuidedItemWrite)
 
     // First thing we do is clear the transaction. This way inProgesss is off when we signal transaction complete.
     TransactionType_t currentTransactionType = _transactionInProgress;
-    _transactionInProgress = TransactionNone;
-    if (currentTransactionType != TransactionNone) {
-        _transactionInProgress = TransactionNone;
-        qCDebug(PlanManagerLog) << QStringLiteral("inProgressChanged %1").arg(_planTypeString());
-        emit inProgressChanged(false);
-    }
+    _setTransactionInProgress(TransactionNone);
 
     switch (currentTransactionType) {
     case TransactionRead:
@@ -919,9 +912,8 @@ void PlanManager::removeAll(void)
         emit lastCurrentIndexChanged(-1);
     }
 
-    _transactionInProgress = TransactionRemoveAll;
     _retryCount = 0;
-    emit inProgressChanged(true);
+    _setTransactionInProgress(TransactionRemoveAll);
 
     _removeAllWorker();
 }
@@ -969,3 +961,12 @@ QString PlanManager::_planTypeString(void)
         return QStringLiteral("T:Unknown");
     }
 }
+
+void PlanManager::_setTransactionInProgress(TransactionType_t type)
+{
+    if (_transactionInProgress  != type) {
+        qCDebug(PlanManagerLog) << "_setTransactionInProgress" << _planTypeString() << type;
+        _transactionInProgress = type;
+        emit inProgressChanged(inProgress());
+    }
+}
diff --git a/src/MissionManager/PlanManager.h b/src/MissionManager/PlanManager.h
index b5c53b5..caa6173 100644
--- a/src/MissionManager/PlanManager.h
+++ b/src/MissionManager/PlanManager.h
@@ -153,6 +153,9 @@ protected:
     QList<MissionItem*> _writeMissionItems;     ///< Set of mission items currently being written to vehicle
     int                 _currentMissionIndex;
     int                 _lastCurrentIndex;
+
+private:
+    void _setTransactionInProgress(TransactionType_t type);
 };
 
 #endif
diff --git a/src/MissionManager/PlanMasterController.cc b/src/MissionManager/PlanMasterController.cc
index 8da4769..dc10aae 100644
--- a/src/MissionManager/PlanMasterController.cc
+++ b/src/MissionManager/PlanMasterController.cc
@@ -45,7 +45,6 @@ PlanMasterController::PlanMasterController(QObject* parent)
     , _loadRallyPoints      (false)
     , _sendGeoFence         (false)
     , _sendRallyPoints      (false)
-    , _syncInProgress       (false)
 {
     connect(&_missionController,    &MissionController::dirtyChanged,       this, &PlanMasterController::dirtyChanged);
     connect(&_geoFenceController,   &GeoFenceController::dirtyChanged,      this, &PlanMasterController::dirtyChanged);
@@ -143,6 +142,13 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
     _geoFenceController.managerVehicleChanged(_managerVehicle);
     _rallyPointController.managerVehicleChanged(_managerVehicle);
 
+    // Vehicle changed so we need to signal everything
+    _offline = newOffline;
+    emit containsItemsChanged(containsItems());
+    emit syncInProgressChanged();
+    emit dirtyChanged(dirty());
+    emit offlineChanged(offline());
+
     if (!_flyView) {
         if (!offline()) {
             // We are in Plan view and we have a newly connected vehicle:
@@ -180,10 +186,8 @@ void PlanMasterController::loadFromVehicle(void)
     } else if (syncInProgress()) {
         qCWarning(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle called while syncInProgress";
     } else {
-        _loadGeoFence   = true;
-        _syncInProgress = true;
-        emit syncInProgressChanged(true);
-        qCDebug(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle _missionController.loadFromVehicle";
+        _loadGeoFence = true;
+        qCDebug(PlanMasterControllerLog) << "PlanMasterController::loadFromVehicle calling _missionController.loadFromVehicle";
         _missionController.loadFromVehicle();
         setDirty(false);
     }
@@ -196,7 +200,7 @@ void PlanMasterController::_loadMissionComplete(void)
         _loadGeoFence = false;
         _loadRallyPoints = true;
         if (_geoFenceController.supported()) {
-            qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadMissionComplete _geoFenceController.loadFromVehicle";
+            qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadMissionComplete calling _geoFenceController.loadFromVehicle";
             _geoFenceController.loadFromVehicle();
         } else {
             qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadMissionComplete GeoFence not supported skipping";
@@ -212,7 +216,7 @@ void PlanMasterController::_loadGeoFenceComplete(void)
     if (!_flyView && _loadRallyPoints) {
         _loadRallyPoints = false;
         if (_rallyPointController.supported()) {
-            qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadGeoFenceComplete _rallyPointController.loadFromVehicle";
+            qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadGeoFenceComplete calling _rallyPointController.loadFromVehicle";
             _rallyPointController.loadFromVehicle();
         } else {
             qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadMissionComplete Rally Points not supported skipping";
@@ -225,10 +229,7 @@ void PlanMasterController::_loadGeoFenceComplete(void)
 
 void PlanMasterController::_loadRallyPointsComplete(void)
 {
-    if (!_flyView) {
-        _syncInProgress = false;
-        emit syncInProgressChanged(false);
-    }
+    qCDebug(PlanMasterControllerLog) << "PlanMasterController::_loadRallyPointsComplete";
 }
 
 void PlanMasterController::_sendMissionComplete(void)
@@ -263,11 +264,7 @@ void PlanMasterController::_sendGeoFenceComplete(void)
 
 void PlanMasterController::_sendRallyPointsComplete(void)
 {
-    if (_syncInProgress) {
-        qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle Rally Point send complete";
-        _syncInProgress = false;
-        emit syncInProgressChanged(false);
-    }
+    qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle Rally Point send complete";
 }
 
 void PlanMasterController::sendToVehicle(void)
@@ -284,8 +281,6 @@ void PlanMasterController::sendToVehicle(void)
     } else {
         qCDebug(PlanMasterControllerLog) << "PlanMasterController::sendToVehicle start mission sendToVehicle";
         _sendGeoFence = true;
-        _syncInProgress = true;
-        emit syncInProgressChanged(true);
         _missionController.sendToVehicle();
         setDirty(false);
     }
@@ -515,10 +510,7 @@ void PlanMasterController::sendPlanToVehicle(Vehicle* vehicle, const QString& fi
 
 void PlanMasterController::_showPlanFromManagerVehicle(void)
 {
-    if (!_managerVehicle->initialPlanRequestComplete() &&
-            !_missionController.syncInProgress() &&
-            !_geoFenceController.syncInProgress() &&
-            !_rallyPointController.syncInProgress()) {
+    if (!_managerVehicle->initialPlanRequestComplete() && !syncInProgress()) {
         // Something went wrong with initial load. All controllers are idle, so just force it off
         _managerVehicle->forceInitialPlanRequestComplete();
     }
@@ -530,3 +522,10 @@ void PlanMasterController::_showPlanFromManagerVehicle(void)
         }
     }
 }
+
+bool PlanMasterController::syncInProgress(void) const
+{
+    return _missionController.syncInProgress() ||
+            _geoFenceController.syncInProgress() ||
+            _rallyPointController.syncInProgress();
+}
diff --git a/src/MissionManager/PlanMasterController.h b/src/MissionManager/PlanMasterController.h
index d6d454f..8963494 100644
--- a/src/MissionManager/PlanMasterController.h
+++ b/src/MissionManager/PlanMasterController.h
@@ -34,7 +34,7 @@ public:
     Q_PROPERTY(RallyPointController*    rallyPointController    READ rallyPointController   CONSTANT)
 
     Q_PROPERTY(Vehicle*     controllerVehicle   MEMBER _controllerVehicle               CONSTANT)
-    Q_PROPERTY(bool         offline             READ offline                            NOTIFY offlineEditingChanged)   ///< true: controller is not connected to an active vehicle
+    Q_PROPERTY(bool         offline             READ offline                            NOTIFY offlineChanged)          ///< true: controller is not connected to an active vehicle
     Q_PROPERTY(bool         containsItems       READ containsItems                      NOTIFY containsItemsChanged)    ///< true: Elemement is non-empty
     Q_PROPERTY(bool         syncInProgress      READ syncInProgress                     NOTIFY syncInProgressChanged)   ///< true: Information is currently being saved/sent, false: no active save/send in progress
     Q_PROPERTY(bool         dirty               READ dirty              WRITE setDirty  NOTIFY dirtyChanged)            ///< true: Unsaved/sent changes are present, false: no changes since last save/send
@@ -74,7 +74,7 @@ public:
 
     bool        offline         (void) const { return _offline; }
     bool        containsItems   (void) const;
-    bool        syncInProgress  (void) const { return _syncInProgress; }
+    bool        syncInProgress  (void) const;
     bool        dirty           (void) const;
     void        setDirty        (bool dirty);
     QString     fileExtension   (void) const;
@@ -90,10 +90,9 @@ public:
 
 signals:
     void containsItemsChanged   (bool containsItems);
-    void syncInProgressChanged  (bool syncInProgress);
+    void syncInProgressChanged  (void);
     void dirtyChanged           (bool dirty);
-    void vehicleChanged         (Vehicle* vehicle);
-    void offlineEditingChanged  (bool offlineEditing);
+    void offlineChanged  		(bool offlineEditing);
 
 private slots:
     void _activeVehicleChanged(Vehicle* activeVehicle);
@@ -119,7 +118,6 @@ private:
     bool                    _loadRallyPoints;
     bool                    _sendGeoFence;
     bool                    _sendRallyPoints;
-    bool                    _syncInProgress;
 
     static const int    _planFileVersion;
     static const char*  _planFileType;
diff --git a/src/PlanView/PlanToolBar.qml b/src/PlanView/PlanToolBar.qml
index 3487257..e6616f5 100644
--- a/src/PlanView/PlanToolBar.qml
+++ b/src/PlanView/PlanToolBar.qml
@@ -310,6 +310,12 @@ Rectangle {
         width:          _controllerProgressPct * parent.width
         color:          qgcPal.colorGreen
         visible:        false
+
+        onVisibleChanged: {
+            if (visible) {
+                largeProgressBar._userHide = false
+            }
+        }
     }
 
     /*
diff --git a/src/QGCLoggingCategory.cc b/src/QGCLoggingCategory.cc
index 662de9b..fc1670c 100644
--- a/src/QGCLoggingCategory.cc
+++ b/src/QGCLoggingCategory.cc
@@ -66,8 +66,6 @@ void QGCLoggingCategoryRegister::setFilterRulesFromSettings(const QString& comma
     }
     QString filterRules;
 
-    // Turn off bogus ssl warning
-    filterRules += "qt.network.ssl.warning=false\n";
     filterRules += "*Log.debug=false\n";
 
     // Set up filters defined in settings
diff --git a/src/QtLocationPlugin/QMLControl/OfflineMap.qml b/src/QtLocationPlugin/QMLControl/OfflineMap.qml
index e7c8c87..05b80ee 100644
--- a/src/QtLocationPlugin/QMLControl/OfflineMap.qml
+++ b/src/QtLocationPlugin/QMLControl/OfflineMap.qml
@@ -1005,7 +1005,6 @@ QGCView {
                 text:           qsTr("Export")
                 width:          _buttonSize
                 visible:        QGroundControl.corePlugin.options.showOfflineMapExport
-                enabled:        QGroundControl.mapEngineManager.tileSets.count > 1
                 onClicked:      showExport()
             }
             QGCButton {
@@ -1041,8 +1040,13 @@ QGCView {
                     delegate: QGCCheckBox {
                         text:           object.name
                         checked:        object.selected
-                        onClicked: {
-                            object.selected = checked
+                        onClicked:      object.selected = checked
+                        Connections {
+                            // This connection should theoretically not be needed since the `checked: object.selected` binding should work.
+                            // But for some reason when the user clicks the check box taht binding breaks. Which in turns causes
+                            // Select All/None to update the internal state but check box visible state is out of sync
+                            target:             object
+                            onSelectedChanged:  checked = object.selected
                         }
                     }
                 }
diff --git a/src/Terrain/TerrainQuery.cc b/src/Terrain/TerrainQuery.cc
index ec9c96c..27bc6cf 100644
--- a/src/Terrain/TerrainQuery.cc
+++ b/src/Terrain/TerrainQuery.cc
@@ -17,11 +17,13 @@
 #include <QNetworkRequest>
 #include <QNetworkProxy>
 #include <QNetworkReply>
+#include <QSslConfiguration>
 #include <QJsonDocument>
 #include <QJsonObject>
 #include <QJsonArray>
 #include <QTimer>
 #include <QtLocation/private/qgeotilespec_p.h>
+
 #include <cmath>
 
 QGC_LOGGING_CATEGORY(TerrainQueryLog, "TerrainQueryLog")
@@ -33,7 +35,7 @@ Q_GLOBAL_STATIC(TerrainTileManager, _terrainTileManager)
 TerrainAirMapQuery::TerrainAirMapQuery(QObject* parent)
     : TerrainQueryInterface(parent)
 {
-
+    qCDebug(TerrainQueryVerboseLog) << "supportsSsl" << QSslSocket::supportsSsl() << "sslLibraryBuildVersionString" << QSslSocket::sslLibraryBuildVersionString();
 }
 
 void TerrainAirMapQuery::requestCoordinateHeights(const QList<QGeoCoordinate>& coordinates)
@@ -107,18 +109,24 @@ void TerrainAirMapQuery::_sendQuery(const QString& path, const QUrlQuery& urlQue
 
     QNetworkRequest request(url);
 
+    QSslConfiguration sslConf = request.sslConfiguration();
+    sslConf.setPeerVerifyMode(QSslSocket::VerifyNone);
+    request.setSslConfiguration(sslConf);
+
     QNetworkProxy tProxy;
     tProxy.setType(QNetworkProxy::DefaultProxy);
     _networkManager.setProxy(tProxy);
 
     QNetworkReply* networkReply = _networkManager.get(request);
     if (!networkReply) {
-        qCDebug(TerrainQueryLog) << "QNetworkManager::Get did not return QNetworkReply";
+        qCWarning(TerrainQueryLog) << "QNetworkManager::Get did not return QNetworkReply";
         _requestFailed();
         return;
     }
+    networkReply->ignoreSslErrors();
 
     connect(networkReply, &QNetworkReply::finished, this, &TerrainAirMapQuery::_requestFinished);
+    connect(networkReply, &QNetworkReply::sslErrors, this, &TerrainAirMapQuery::_sslErrors);
     connect(networkReply, QOverload<QNetworkReply::NetworkError>::of(&QNetworkReply::error), this, &TerrainAirMapQuery::_requestError);
 }
 
@@ -127,17 +135,29 @@ void TerrainAirMapQuery::_requestError(QNetworkReply::NetworkError code)
     QNetworkReply* reply = qobject_cast<QNetworkReply*>(QObject::sender());
 
     if (code != QNetworkReply::NoError) {
-        qCDebug(TerrainQueryLog) << "_requestError error:url:data" << reply->error() << reply->url() << reply->readAll();
+        qCWarning(TerrainQueryLog) << "_requestError error:url:data" << reply->error() << reply->url() << reply->readAll();
         return;
     }
 }
 
+void TerrainAirMapQuery::_sslErrors(const QList<QSslError> &errors)
+{
+    for (const auto &error : errors) {
+        qCWarning(TerrainQueryLog) << "SSL error: " << error.errorString();
+
+        const auto &certificate = error.certificate();
+        if (!certificate.isNull()) {
+            qCWarning(TerrainQueryLog) << "SSL Certificate problem: " << certificate.toText();
+        }
+    }
+}
+
 void TerrainAirMapQuery::_requestFinished(void)
 {
     QNetworkReply* reply = qobject_cast<QNetworkReply*>(QObject::sender());
 
     if (reply->error() != QNetworkReply::NoError) {
-        qCDebug(TerrainQueryLog) << "_requestFinished error:url:data" << reply->error() << reply->url() << reply->readAll();
+        qCWarning(TerrainQueryLog) << "_requestFinished error:url:data" << reply->error() << reply->url() << reply->readAll();
         reply->deleteLater();
         _requestFailed();
         return;
@@ -150,7 +170,7 @@ void TerrainAirMapQuery::_requestFinished(void)
     QJsonParseError parseError;
     QJsonDocument responseJson = QJsonDocument::fromJson(responseBytes, &parseError);
     if (parseError.error != QJsonParseError::NoError) {
-        qCDebug(TerrainQueryLog) << "_requestFinished unable to parse json:" << parseError.errorString();
+        qCWarning(TerrainQueryLog) << "_requestFinished unable to parse json:" << parseError.errorString();
         _requestFailed();
         return;
     }
@@ -159,7 +179,7 @@ void TerrainAirMapQuery::_requestFinished(void)
     QJsonObject rootObject = responseJson.object();
     QString status = rootObject["status"].toString();
     if (status != "success") {
-        qCDebug(TerrainQueryLog) << "_requestFinished status != success:" << status;
+        qCWarning(TerrainQueryLog) << "_requestFinished status != success:" << status;
         _requestFailed();
         return;
     }
@@ -252,7 +272,7 @@ void TerrainAirMapQuery::_parseCarpetData(const QJsonValue& carpetJson)
 TerrainOfflineAirMapQuery::TerrainOfflineAirMapQuery(QObject* parent)
     : TerrainQueryInterface(parent)
 {
-
+    qCDebug(TerrainQueryVerboseLog) << "supportsSsl" << QSslSocket::supportsSsl() << "sslLibraryBuildVersionString" << QSslSocket::sslLibraryBuildVersionString();
 }
 
 void TerrainOfflineAirMapQuery::requestCoordinateHeights(const QList<QGeoCoordinate>& coordinates)
@@ -385,7 +405,7 @@ bool TerrainTileManager::_getAltitudesForCoordinates(const QList<QGeoCoordinate>
             if (_tiles[tileHash].isIn(coordinate)) {
                 altitudes.push_back(_tiles[tileHash].elevation(coordinate));
             } else {
-                qCDebug(TerrainQueryLog) << "Error: coordinate not in tile region";
+                qCWarning(TerrainQueryLog) << "Error: coordinate not in tile region";
                 altitudes.push_back(-1.0);
             }
         }
@@ -412,7 +432,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N
     _state = State::Idle;
 
     if (!reply) {
-        qCDebug(TerrainQueryLog) << "Elevation tile fetched but invalid reply data type.";
+        qCWarning(TerrainQueryLog) << "Elevation tile fetched but invalid reply data type.";
         return;
     }
 
@@ -422,13 +442,13 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N
 
     // handle potential errors
     if (error != QNetworkReply::NoError) {
-        qCDebug(TerrainQueryLog) << "Elevation tile fetching returned error (" << error << ")";
+        qCWarning(TerrainQueryLog) << "Elevation tile fetching returned error (" << error << ")";
         _tileFailed();
         reply->deleteLater();
         return;
     }
     if (responseBytes.isEmpty()) {
-        qCDebug(TerrainQueryLog) << "Error in fetching elevation tile. Empty response.";
+        qCWarning(TerrainQueryLog) << "Error in fetching elevation tile. Empty response.";
         _tileFailed();
         reply->deleteLater();
         return;
@@ -446,7 +466,7 @@ void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::N
         }
         _tilesMutex.unlock();
     } else {
-        qCDebug(TerrainQueryLog) << "Received invalid tile";
+        qCWarning(TerrainQueryLog) << "Received invalid tile";
     }
     reply->deleteLater();
 
diff --git a/src/Terrain/TerrainQuery.h b/src/Terrain/TerrainQuery.h
index f41c9be..3f53f6c 100644
--- a/src/Terrain/TerrainQuery.h
+++ b/src/Terrain/TerrainQuery.h
@@ -69,7 +69,8 @@ public:
 
 private slots:
     void _requestError              (QNetworkReply::NetworkError code);
-    void _requestFinished           ();
+    void _requestFinished           (void);
+    void _sslErrors                 (const QList<QSslError> &errors);
 
 private:
     void _sendQuery                 (const QString& path, const QUrlQuery& urlQuery);
diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc
index 69cb9d4..b5040c6 100644
--- a/src/Vehicle/Vehicle.cc
+++ b/src/Vehicle/Vehicle.cc
@@ -2494,7 +2494,7 @@ void Vehicle::_remoteControlRSSIChanged(uint8_t rssi)
 void Vehicle::virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust)
 {
     // The following if statement prevents the virtualTabletJoystick from sending values if the standard joystick is enabled
-    if ( !_joystickEnabled ) {
+    if ( !_joystickEnabled && !_highLatencyLink) {
         _uas->setExternalControlSetpoint(roll, pitch, yaw, thrust, 0, JoystickModeRC);
     }
 }
diff --git a/src/comm/HeartbeatTimer.cc b/src/comm/HeartbeatTimer.cc
index 7090b73..ec1843a 100644
--- a/src/comm/HeartbeatTimer.cc
+++ b/src/comm/HeartbeatTimer.cc
@@ -17,7 +17,11 @@ HeartbeatTimer::HeartbeatTimer(int vehicle_id, bool high_latency) :
     _vehicleID(vehicle_id),
     _high_latency(high_latency)
 {
-    if (!high_latency) {
+}
+
+void HeartbeatTimer::init()
+{
+    if (!_high_latency) {
         _timer->setInterval(_heartbeatReceivedTimeoutMSecs);
         _timer->setSingleShot(true);
         _timer->start();
@@ -26,7 +30,9 @@ HeartbeatTimer::HeartbeatTimer(int vehicle_id, bool high_latency) :
     QObject::connect(_timer, &QTimer::timeout, this, &HeartbeatTimer::timerTimeout);
 }
 
-HeartbeatTimer::~HeartbeatTimer() {
+
+HeartbeatTimer::~HeartbeatTimer()
+{
     if (_timer) {
         QObject::disconnect(_timer, &QTimer::timeout, this, &HeartbeatTimer::timerTimeout);
         _timer->stop();
diff --git a/src/comm/HeartbeatTimer.h b/src/comm/HeartbeatTimer.h
index c62a63f..ea16687 100644
--- a/src/comm/HeartbeatTimer.h
+++ b/src/comm/HeartbeatTimer.h
@@ -36,6 +36,13 @@ public:
      */
     HeartbeatTimer(int vehicle_id, bool high_latency);
 
+    /**
+     * @brief init
+     *
+     * Starts the timer and emits the signal that the link is active for this vehicle ID
+     */
+    void init();
+
     ~HeartbeatTimer();
 
     /**
diff --git a/src/comm/LinkInterface.cc b/src/comm/LinkInterface.cc
index 13da6a8..d2c1923 100644
--- a/src/comm/LinkInterface.cc
+++ b/src/comm/LinkInterface.cc
@@ -195,6 +195,7 @@ void LinkInterface::startHeartbeatTimer(int vehicle_id) {
     } else {
         _heartbeatTimers.insert(vehicle_id, new HeartbeatTimer(vehicle_id, _highLatency));
         QObject::connect(_heartbeatTimers.value(vehicle_id), &HeartbeatTimer::activeChanged, this, &LinkInterface::_activeChanged);
+        _heartbeatTimers.value(vehicle_id)->init();
     }
 }