diff --git a/src/MissionManager/MissionControllerManagerTest.cc b/src/MissionManager/MissionControllerManagerTest.cc
index 7e04e44..a379130 100644
--- a/src/MissionManager/MissionControllerManagerTest.cc
+++ b/src/MissionManager/MissionControllerManagerTest.cc
@@ -47,8 +47,6 @@ void MissionControllerManagerTest::cleanup(void)
 
 void MissionControllerManagerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
 {
-    UnitTest::init();
-    
     LinkManager* linkMgr = LinkManager::instance();
     Q_CHECK_PTR(linkMgr);
     
diff --git a/src/MissionManager/MissionControllerTest.cc b/src/MissionManager/MissionControllerTest.cc
index 535d08d..7cd925b 100644
--- a/src/MissionManager/MissionControllerTest.cc
+++ b/src/MissionManager/MissionControllerTest.cc
@@ -36,12 +36,15 @@ MissionControllerTest::MissionControllerTest(void)
 void MissionControllerTest::cleanup(void)
 {
     delete _missionController;
+    _missionController = NULL;
 
     MissionControllerManagerTest::cleanup();
 }
 
 void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
 {
+    bool startController = false;
+
     MissionControllerManagerTest::_initForFirmwareType(firmwareType);
 
     _rgSignals[missionItemsChangedSignalIndex] =                SIGNAL(missionItemsChanged());
@@ -49,17 +52,22 @@ void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
     _rgSignals[liveHomePositionAvailableChangedSignalIndex] =   SIGNAL(liveHomePositionAvailableChanged(bool));
     _rgSignals[liveHomePositionChangedSignalIndex] =            SIGNAL(liveHomePositionChanged(const QGeoCoordinate&));
 
-    _missionController = new MissionController();
-    Q_CHECK_PTR(_missionController);
+    if (!_missionController) {
+        startController = true;
+        _missionController = new MissionController();
+        Q_CHECK_PTR(_missionController);
+    }
 
     _multiSpy = new MultiSignalSpy();
     Q_CHECK_PTR(_multiSpy);
     QCOMPARE(_multiSpy->init(_missionController, _rgSignals, _cSignals), true);
 
-    _missionController->start(false /* editMode */);
+    if (startController) {
+        _missionController->start(false /* editMode */);
+    }
 
     // All signals should some through on start
-    QCOMPARE(_multiSpy->checkOnlySignalByMask(missionItemsChangedSignalMask | waypointLinesChangedSignalMask | liveHomePositionAvailableChangedSignalMask | liveHomePositionChangedSignalMask), true);
+    QCOMPARE(_multiSpy->checkOnlySignalsByMask(missionItemsChangedSignalMask | waypointLinesChangedSignalMask | liveHomePositionAvailableChangedSignalMask | liveHomePositionChangedSignalMask), true);
     _multiSpy->clearAllSignals();
 
     QmlObjectListModel* missionItems = _missionController->missionItems();
@@ -183,3 +191,28 @@ void MissionControllerTest::_testAddWayppointPX4(void)
 {
     _testAddWaypointWorker(MAV_AUTOPILOT_PX4);
 }
+
+void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareType)
+{
+    // Start offline and add item
+    _missionController = new MissionController();
+    Q_CHECK_PTR(_missionController);
+    _missionController->start(true /* editMode */);
+    _missionController->addMissionItem(QGeoCoordinate(37.803784, -122.462276));
+
+    // Go online to empty vehicle
+    MissionControllerManagerTest::_initForFirmwareType(firmwareType);
+
+    // Make sure our offline mission items are still there
+    QCOMPARE(_missionController->missionItems()->count(), 2);
+}
+
+void MissionControllerTest::_testOfflineToOnlineAPM(void)
+{
+    _testOfflineToOnlineWorker(MAV_AUTOPILOT_ARDUPILOTMEGA);
+}
+
+void MissionControllerTest::_testOfflineToOnlinePX4(void)
+{
+    _testOfflineToOnlineWorker(MAV_AUTOPILOT_PX4);
+}
diff --git a/src/MissionManager/MissionControllerTest.h b/src/MissionManager/MissionControllerTest.h
index 8ac9b63..9d3043e 100644
--- a/src/MissionManager/MissionControllerTest.h
+++ b/src/MissionManager/MissionControllerTest.h
@@ -43,15 +43,19 @@ public:
 private slots:
     void cleanup(void);
 
-    void _testEmptyVehicleAPM(void);
-    void _testEmptyVehiclePX4(void);
-    void _testAddWayppointAPM(void);
-    void _testAddWayppointPX4(void);
+    void _testOfflineToOnlineAPM(void);
+    void _testOfflineToOnlinePX4(void);
 
 private:
     void _initForFirmwareType(MAV_AUTOPILOT firmwareType);
     void _testEmptyVehicleWorker(MAV_AUTOPILOT firmwareType);
     void _testAddWaypointWorker(MAV_AUTOPILOT firmwareType);
+    void _testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareType);
+
+    void _testEmptyVehicleAPM(void);
+    void _testEmptyVehiclePX4(void);
+    void _testAddWayppointAPM(void);
+    void _testAddWayppointPX4(void);
 
     enum {
         missionItemsChangedSignalIndex = 0,