diff --git a/QGCApplication.pro b/QGCApplication.pro
index cd24b64..9bf7968 100644
--- a/QGCApplication.pro
+++ b/QGCApplication.pro
@@ -228,7 +228,6 @@ HEADERS += \
     src/Joystick/JoystickManager.h \
     src/LogCompressor.h \
     src/MG.h \
-    src/MissionEditor/MissionEditorController.h \
     src/MissionManager/MissionManager.h \
     src/MissionManager/MissionController.h \
     src/QGC.h \
@@ -347,7 +346,6 @@ SOURCES += \
     src/Joystick/JoystickManager.cc \
     src/LogCompressor.cc \
     src/main.cc \
-    src/MissionEditor/MissionEditorController.cc \
     src/MissionManager/MissionManager.cc \
     src/MissionManager/MissionController.cc \
     src/QGC.cc \
diff --git a/src/FactSystem/FactSystemTestBase.cc b/src/FactSystem/FactSystemTestBase.cc
index 01168f0..cc1b1b2 100644
--- a/src/FactSystem/FactSystemTestBase.cc
+++ b/src/FactSystem/FactSystemTestBase.cc
@@ -45,7 +45,7 @@ void FactSystemTestBase::_init(MAV_AUTOPILOT autopilot)
     UnitTest::init();
     
     MockLink* link = new MockLink();
-    link->setAutopilotType(autopilot);
+    link->setFirmwareType(autopilot);
     LinkManager::instance()->_addLink(link);
     
     LinkManager::instance()->connectLink(link);
diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml
index 2c2faef..2b8a2c0 100644
--- a/src/FlightDisplay/FlightDisplayView.qml
+++ b/src/FlightDisplay/FlightDisplayView.qml
@@ -73,21 +73,26 @@ Item {
 
     readonly property var _flightMap: flightMap
 
-    property real _roll:            _activeVehicle ? (isNaN(_activeVehicle.roll) ? _defaultRoll : _activeVehicle.roll) : _defaultRoll
-    property real _pitch:           _activeVehicle ? (isNaN(_activeVehicle.pitch) ? _defaultPitch : _activeVehicle.pitch) : _defaultPitch
-    property real _heading:         _activeVehicle ? (isNaN(_activeVehicle.heading) ? _defaultHeading : _activeVehicle.heading) : _defaultHeading
+    property real _roll:                _activeVehicle ? (isNaN(_activeVehicle.roll) ? _defaultRoll : _activeVehicle.roll) : _defaultRoll
+    property real _pitch:               _activeVehicle ? (isNaN(_activeVehicle.pitch) ? _defaultPitch : _activeVehicle.pitch) : _defaultPitch
+    property real _heading:             _activeVehicle ? (isNaN(_activeVehicle.heading) ? _defaultHeading : _activeVehicle.heading) : _defaultHeading
 
-    property var  _vehicleCoordinate:   _activeVehicle ? _activeVehicle.coordinate : _defaultVehicleCoordinate
+    property var  _vehicleCoordinate:   _activeVehicle ? (_activeVehicle.satelliteLock >= 2 ? _activeVehicle.coordinate : _defaultVehicleCoordinate) : _defaultVehicleCoordinate
 
-    property real _altitudeWGS84:   _activeVehicle ? _activeVehicle.altitudeWGS84 : _defaultAltitudeWGS84
-    property real _groundSpeed:     _activeVehicle ? _activeVehicle.groundSpeed : _defaultGroundSpeed
-    property real _airSpeed:        _activeVehicle ? _activeVehicle.airSpeed : _defaultAirSpeed
-    property real _climbRate:       _activeVehicle ? _activeVehicle.climbRate : _defaultClimbRate
+    property real _altitudeWGS84:       _activeVehicle ? _activeVehicle.altitudeWGS84 : _defaultAltitudeWGS84
+    property real _groundSpeed:         _activeVehicle ? _activeVehicle.groundSpeed : _defaultGroundSpeed
+    property real _airSpeed:            _activeVehicle ? _activeVehicle.airSpeed : _defaultAirSpeed
+    property real _climbRate:           _activeVehicle ? _activeVehicle.climbRate : _defaultClimbRate
 
     property bool _showMap: getBool(QGroundControl.flightMapSettings.loadMapSetting(flightMap.mapName, _showMapBackgroundKey, "1"))
 
     FlightDisplayViewController { id: _controller }
-    MissionController { id: _missionController }
+
+    MissionController {
+        id: _missionController
+
+        Component.onCompleted: start(false /* editMode */)
+    }
 
     ExclusiveGroup {
         id: _dropButtonsExclusiveGroup
diff --git a/src/MissionEditor/MissionEditor.qml b/src/MissionEditor/MissionEditor.qml
index 0ffbae7..3e20773 100644
--- a/src/MissionEditor/MissionEditor.qml
+++ b/src/MissionEditor/MissionEditor.qml
@@ -54,24 +54,27 @@ QGCView {
     readonly property string    _autoSyncKey:       "AutoSync"
     readonly property string    _showHelpKey:       "ShowHelp"
     readonly property int       _addMissionItemsButtonAutoOffTimeout:   10000
+    readonly property var       _defaultVehicleCoordinate:   QtPositioning.coordinate(37.803784, -122.462276)
 
     property var    _missionItems:              controller.missionItems
 
-    property var    _homePositionManager:       QGroundControl.homePositionManager
-    property string _homePositionName:          _homePositionManager.homePositions.get(0).name
-
+    //property var    _homePositionManager:       QGroundControl.homePositionManager
+    //property string _homePositionName:          _homePositionManager.homePositions.get(0).name
     //property var    offlineHomePosition:        _homePositionManager.homePositions.get(0).coordinate
+
     property var    liveHomePosition:           controller.liveHomePosition
     property var    liveHomePositionAvailable:  controller.liveHomePositionAvailable
-    //property var    homePosition:               offlineHomePosition // live or offline depending on state
+    property var    homePosition:               _defaultVehicleCoordinate
 
     property bool _syncNeeded:                  controller.missionItems.dirty
     property bool _syncInProgress:              _activeVehicle ? _activeVehicle.missionManager.inProgress : false
 
     property bool _showHelp:                    QGroundControl.flightMapSettings.loadBoolMapSetting(editorMap.mapName, _showHelpKey, true)
 
-    MissionEditorController {
+    MissionController {
         id:         controller
+
+        Component.onCompleted: start(true /* editMode */)
 /*
         FIXME: autoSync is temporarily disconnected since it's still buggy
 
@@ -104,6 +107,7 @@ QGCView {
 
     function updateHomePosition() {
         if (liveHomePositionAvailable) {
+            homePosition = liveHomePosition
             _missionItems.get(0).coordinate = liveHomePosition
             _missionItems.get(0).homePositionValid = true
         }
@@ -282,8 +286,8 @@ QGCView {
                     }
                 } // Item - Mission Item editor
 
-/*
-Home Position Manager is commented out for now until a better implementation is completed
+                /*
+                  Home Position Manager temporarily disbled till more work is done on it
 
                 // Home Position Manager
                 Rectangle {
@@ -556,7 +560,7 @@ Home Position Manager is commented out for now until a better implementation is
                         }
                     } // Column - Online view
                 } // Item - Home Position Manager
-*/
+                */
 
                 // Help Panel
                 Rectangle {
@@ -656,7 +660,7 @@ Home Position Manager is commented out for now until a better implementation is
                         }
 
                         /*
-                        Home Position Manager commented until more complete implementation is done
+                          Home Position Manager disabled
 
                         Image {
                             id:                 homePositionManagerHelpIcon
@@ -680,7 +684,7 @@ Home Position Manager is commented out for now until a better implementation is
                                                 "When enabled, allows you to select/add/update flying field locations. " +
                                                 "You can save multiple flying field locations for use while creating missions while you are not connected to your vehicle."
                         }
-*/
+                        */
 
                         Image {
                             id:                 mapCenterHelpIcon
@@ -803,8 +807,7 @@ Home Position Manager is commented out for now until a better implementation is
                 }
 
                 /*
-                Home Position Manager commented until more complete implementation is done
-
+                  Home Position manager temporarily disable
                 RoundButton {
                     id:                 homePositionManagerButton
                     anchors.margins:    _margin
diff --git a/src/MissionEditor/MissionEditorController.cc b/src/MissionEditor/MissionEditorController.cc
deleted file mode 100644
index e1e7522..0000000
--- a/src/MissionEditor/MissionEditorController.cc
+++ /dev/null
@@ -1,493 +0,0 @@
-/*=====================================================================
-
-QGroundControl Open Source Ground Control Station
-
-(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
-
-This file is part of the QGROUNDCONTROL project
-
-    QGROUNDCONTROL is free software: you can redistribute it and/or modify
-    it under the terms of the GNU General Public License as published by
-    the Free Software Foundation, either version 3 of the License, or
-    (at your option) any later version.
-
-    QGROUNDCONTROL is distributed in the hope that it will be useful,
-    but WITHOUT ANY WARRANTY; without even the implied warranty of
-    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-    GNU General Public License for more details.
-
-    You should have received a copy of the GNU General Public License
-    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
-
-======================================================================*/
-
-#include "MissionEditorController.h"
-#include "ScreenToolsController.h"
-#include "MultiVehicleManager.h"
-#include "MissionManager.h"
-#include "QGCFileDialog.h"
-#include "CoordinateVector.h"
-#include "QGCMessageBox.h"
-
-#include <QQmlContext>
-#include <QQmlEngine>
-#include <QSettings>
-
-const char* MissionEditorController::_settingsGroup = "MissionEditorController";
-
-MissionEditorController::MissionEditorController(QObject *parent)
-    : QObject(parent)
-    , _missionItems(NULL)
-    , _canEdit(true)
-    , _activeVehicle(NULL)
-    , _liveHomePositionAvailable(false)
-    , _autoSync(false)
-    , _firstMissionItemSync(false)
-    , _missionItemsRequested(false)
-{
-    MultiVehicleManager* multiVehicleMgr = MultiVehicleManager::instance();
-    
-    connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionEditorController::_activeVehicleChanged);
-    
-    Vehicle* activeVehicle = multiVehicleMgr->activeVehicle();
-    if (activeVehicle) {
-        _activeVehicleChanged(activeVehicle);
-    } else {
-        _missionItemsRequested = true;
-        _newMissionItemsAvailable();
-    }
-}
-
-MissionEditorController::~MissionEditorController()
-{
-}
-
-void MissionEditorController::_newMissionItemsAvailable(void)
-{
-    if (_firstMissionItemSync) {
-        // This is the first time the vehicle is seeing items. We have to be careful of transitioning from offline
-        // to online.
-
-        _firstMissionItemSync = false;
-        if (_missionItems && _missionItems->count() > 1) {
-            QGCMessageBox::StandardButton button = QGCMessageBox::warning("Mission Editing",
-                                                                          "The vehicle has sent a new set of Mission Items. "
-                                                                            "Do you want to discard your current set of unsaved items and use the ones from the vehicle instead?",
-                                                                          QGCMessageBox::Yes | QGCMessageBox::No,
-                                                                          QGCMessageBox::No);
-            if (button == QGCMessageBox::No) {
-                return;
-            }
-        }
-    } else if (!_missionItemsRequested) {
-        // We didn't specifically ask for new mission items. Disregard the new set since it is
-        // the most likely the set we just sent to the vehicle.
-        return;
-    }
-
-    _missionItemsRequested = false;
-
-    if (_missionItems) {
-        _deinitAllMissionItems();
-        _missionItems->deleteLater();
-    }
-    
-    MissionManager* missionManager = NULL;
-    if (_activeVehicle) {
-        missionManager = _activeVehicle->missionManager();
-    }
-
-    if (!missionManager || missionManager->inProgress()) {
-        _canEdit = true;
-        _missionItems = new QmlObjectListModel(this);
-    } else {
-        _canEdit = missionManager->canEdit();
-        _missionItems = missionManager->copyMissionItems();
-    }
-
-    _initAllMissionItems();
-}
-
-void MissionEditorController::getMissionItems(void)
-{
-    Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
-    
-    if (activeVehicle) {
-        _missionItemsRequested = true;
-        MissionManager* missionManager = activeVehicle->missionManager();
-        connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionEditorController::_newMissionItemsAvailable);
-        activeVehicle->missionManager()->requestMissionItems();
-    }
-}
-
-void MissionEditorController::sendMissionItems(void)
-{
-    Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
-    
-    if (activeVehicle) {
-        activeVehicle->missionManager()->writeMissionItems(*_missionItems, true /* skipFirstItem */);
-        _missionItems->setDirty(false);
-    }
-}
-
-int MissionEditorController::addMissionItem(QGeoCoordinate coordinate)
-{
-    if (!_canEdit) {
-        qWarning() << "addMissionItem called with _canEdit == false";
-    }
-
-    // Coordinate will come through without altitude
-    coordinate.setAltitude(MissionItem::defaultAltitude);
-    
-    MissionItem * newItem = new MissionItem(this, _missionItems->count(), coordinate, MAV_CMD_NAV_WAYPOINT);
-    _initMissionItem(newItem);
-    if (_missionItems->count() == 1) {
-        newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
-    }
-    _missionItems->append(newItem);
-    
-    _recalcAll();
-    
-    return _missionItems->count() - 1;
-}
-
-void MissionEditorController::removeMissionItem(int index)
-{
-    if (!_canEdit) {
-        qWarning() << "addMissionItem called with _canEdit == false";
-        return;
-    }
-    
-    MissionItem* item = qobject_cast<MissionItem*>(_missionItems->removeAt(index));
-    
-    _deinitMissionItem(item);
-    
-    _recalcAll();
-
-    // Set the new current item
-
-    if (index >= _missionItems->count()) {
-        index--;
-    }
-    for (int i=0; i<_missionItems->count(); i++) {
-        MissionItem* item =  qobject_cast<MissionItem*>(_missionItems->get(i));
-        item->setIsCurrentItem(i == index);
-    }
-}
-
-void MissionEditorController::loadMissionFromFile(void)
-{
-    QString errorString;
-    QString filename = QGCFileDialog::getOpenFileName(NULL, "Select Mission File to load");
-    
-    if (filename.isEmpty()) {
-        return;
-    }
-    
-    if (_missionItems) {
-        _deinitAllMissionItems();
-        _missionItems->deleteLater();
-    }
-    _missionItems = new QmlObjectListModel(this);
-
-    _canEdit = true;
-    
-    QFile file(filename);
-    
-    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
-        errorString = file.errorString();
-    } else {
-        QTextStream in(&file);
-        
-        const QStringList& version = in.readLine().split(" ");
-        
-        if (!(version.size() == 3 && version[0] == "QGC" && version[1] == "WPL" && version[2] == "120")) {
-            errorString = "The mission file is not compatible with the current version of QGroundControl.";
-        } else {
-            while (!in.atEnd()) {
-                MissionItem* item = new MissionItem();
-                
-                if (item->load(in)) {
-                    _missionItems->append(item);
-                    
-                    if (!item->canEdit()) {
-                        _canEdit = false;
-                    }
-                } else {
-                    errorString = "The mission file is corrupted.";
-                    break;
-                }
-            }
-        }
-        
-    }
-    
-    if (!errorString.isEmpty()) {
-        _missionItems->clear();
-    }
-    
-    _initAllMissionItems();
-}
-
-void MissionEditorController::saveMissionToFile(void)
-{
-    QString errorString;
-    QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save mission to");
-    
-    if (filename.isEmpty()) {
-        return;
-    }
-    
-    QFile file(filename);
-    
-    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
-        errorString = file.errorString();
-    } else {
-        QTextStream out(&file);
-        
-        out << "QGC WPL 120\r\n";   // Version string
-        
-        for (int i=0; i<_missionItems->count(); i++) {
-            qobject_cast<MissionItem*>(_missionItems->get(i))->save(out);
-        }
-    }
-    
-    _missionItems->setDirty(false);
-}
-
-void MissionEditorController::_recalcWaypointLines(void)
-{
-    bool firstCoordinateItem = true;
-    MissionItem* lastCoordinateItem = qobject_cast<MissionItem*>(_missionItems->get(0));
-    
-    _waypointLines.clear();
-    
-    for (int i=1; i<_missionItems->count(); i++) {
-        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));
-        
-        if (item->specifiesCoordinate()) {
-            if (firstCoordinateItem) {
-                if (item->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
-                    // The first coordinate we hit is a takeoff command so link back to home position
-                    _waypointLines.append(new CoordinateVector(qobject_cast<MissionItem*>(_missionItems->get(0))->coordinate(), item->coordinate()));
-                } else {
-                    // First coordiante is not a takeoff command, it does not link backwards to anything
-                }
-                firstCoordinateItem = false;
-            } else {
-                // Subsequent coordinate items link to last coordinate item
-                _waypointLines.append(new CoordinateVector(lastCoordinateItem->coordinate(), item->coordinate()));
-            }
-            lastCoordinateItem = item;
-        }
-    }
-    
-    emit waypointLinesChanged();
-}
-
-// This will update the sequence numbers to be sequential starting from 0
-void MissionEditorController::_recalcSequence(void)
-{
-    for (int i=0; i<_missionItems->count(); i++) {
-        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));
-        
-        // Setup ascending sequence numbers
-        item->setSequenceNumber(i);
-    }
-}
-
-// This will update the child item hierarchy
-void MissionEditorController::_recalcChildItems(void)
-{
-    MissionItem* currentParentItem = qobject_cast<MissionItem*>(_missionItems->get(0));
-    
-    currentParentItem->childItems()->clear();
-    
-    for (int i=1; i<_missionItems->count(); i++) {
-        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));
-        
-        // Set up non-coordinate item child hierarchy
-        if (item->specifiesCoordinate()) {
-            item->childItems()->clear();
-            currentParentItem = item;
-        } else {
-            currentParentItem->childItems()->append(item);
-        }
-    }
-}
-
-void MissionEditorController::_recalcAll(void)
-{
-    _recalcSequence();
-    _recalcChildItems();
-    _recalcWaypointLines();
-}
-
-/// Initializes a new set of mission items which may have come from the vehicle or have been loaded from a file
-void MissionEditorController::_initAllMissionItems(void)
-{
-    // Add the home position item to the front
-    MissionItem* homeItem = new MissionItem(this);
-    homeItem->setHomePositionSpecialCase(true);
-    homeItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
-    _missionItems->insert(0, homeItem);
-    
-    for (int i=0; i<_missionItems->count(); i++) {
-        _initMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i)));
-    }
-    
-    _recalcAll();
-    
-    emit missionItemsChanged();
-    emit canEditChanged(_canEdit);
-    
-    _missionItems->setDirty(false);
-
-    connect(_missionItems, &QmlObjectListModel::dirtyChanged, this, &MissionEditorController::_dirtyChanged);
-}
-
-void MissionEditorController::_deinitAllMissionItems(void)
-{
-    for (int i=0; i<_missionItems->count(); i++) {
-        _deinitMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i)));
-    }
-
-    connect(_missionItems, &QmlObjectListModel::dirtyChanged, this, &MissionEditorController::_dirtyChanged);
-}
-
-void MissionEditorController::_initMissionItem(MissionItem* item)
-{
-    _missionItems->setDirty(false);
-    
-    connect(item, &MissionItem::commandChanged,     this, &MissionEditorController::_itemCommandChanged);
-    connect(item, &MissionItem::coordinateChanged,  this, &MissionEditorController::_itemCoordinateChanged);
-}
-
-void MissionEditorController::_deinitMissionItem(MissionItem* item)
-{
-    disconnect(item, &MissionItem::commandChanged,     this, &MissionEditorController::_itemCommandChanged);
-    disconnect(item, &MissionItem::coordinateChanged,  this, &MissionEditorController::_itemCoordinateChanged);
-}
-
-void MissionEditorController::_itemCoordinateChanged(const QGeoCoordinate& coordinate)
-{
-    Q_UNUSED(coordinate);
-    _recalcWaypointLines();
-}
-
-void MissionEditorController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command)
-{
-    Q_UNUSED(command);;
-    _recalcChildItems();
-    _recalcWaypointLines();
-}
-
-void MissionEditorController::_activeVehicleChanged(Vehicle* activeVehicle)
-{
-    if (_activeVehicle) {
-        MissionManager* missionManager = _activeVehicle->missionManager();
-
-        disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionEditorController::_newMissionItemsAvailable);
-        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionEditorController::_inProgressChanged);
-        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionEditorController::_activeVehicleHomePositionAvailableChanged);
-        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionEditorController::_activeVehicleHomePositionChanged);
-        _activeVehicle = NULL;
-        _newMissionItemsAvailable();
-        _activeVehicleHomePositionAvailableChanged(false);
-    }
-    
-    _activeVehicle = activeVehicle;
-    
-    if (_activeVehicle) {
-        MissionManager* missionManager = activeVehicle->missionManager();
-
-        connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionEditorController::_newMissionItemsAvailable);
-        connect(missionManager, &MissionManager::inProgressChanged,          this, &MissionEditorController::_inProgressChanged);
-        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionEditorController::_activeVehicleHomePositionAvailableChanged);
-        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionEditorController::_activeVehicleHomePositionChanged);
-
-        if (missionManager->inProgress()) {
-            // Vehicle is still in process of requesting mission items
-            _firstMissionItemSync = true;
-        } else {
-            // Vehicle already has mission items
-            _firstMissionItemSync = false;
-        }
-
-        _missionItemsRequested = true;
-        _newMissionItemsAvailable();
-
-        _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
-        _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
-    }
-}
-
-void MissionEditorController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
-{
-    _liveHomePositionAvailable = homePositionAvailable;
-    emit liveHomePositionAvailableChanged(_liveHomePositionAvailable);
-}
-
-void MissionEditorController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
-{
-    _liveHomePosition = homePosition;
-    emit liveHomePositionChanged(_liveHomePosition);
-}
-
-void MissionEditorController::deleteCurrentMissionItem(void)
-{
-    for (int i=0; i<_missionItems->count(); i++) {
-        MissionItem* item =  qobject_cast<MissionItem*>(_missionItems->get(i));
-        if (item->isCurrentItem() && i != 0) {
-            removeMissionItem(i);
-            return;
-        }
-    }
-}
-
-void MissionEditorController::setAutoSync(bool autoSync)
-{
-    _autoSync = autoSync;
-    emit autoSyncChanged(_autoSync);
-
-    if (_autoSync) {
-        _dirtyChanged(true);
-    }
-}
-
-void MissionEditorController::_dirtyChanged(bool dirty)
-{
-    if (dirty && _autoSync) {
-        Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
-
-        if (activeVehicle && !activeVehicle->armed()) {
-            if (_activeVehicle->missionManager()->inProgress()) {
-                _queuedSend = true;
-            } else {
-                _autoSyncSend();
-            }
-        }
-    }
-}
-
-void MissionEditorController::_autoSyncSend(void)
-{
-    qDebug() << "Auto-syncing with vehicle";
-    _queuedSend = false;
-    if (_missionItems) {
-        sendMissionItems();
-        _missionItems->setDirty(false);
-    }
-}
-
-void MissionEditorController::_inProgressChanged(bool inProgress)
-{
-    if (!inProgress && _queuedSend) {
-        _autoSyncSend();
-    }
-}
-
-QmlObjectListModel* MissionEditorController::missionItems(void)
-{
-    return _missionItems;
-}
diff --git a/src/MissionEditor/MissionEditorController.h b/src/MissionEditor/MissionEditorController.h
deleted file mode 100644
index e74e6da..0000000
--- a/src/MissionEditor/MissionEditorController.h
+++ /dev/null
@@ -1,109 +0,0 @@
-/*=====================================================================
-
-QGroundControl Open Source Ground Control Station
-
-(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
-
-This file is part of the QGROUNDCONTROL project
-
-    QGROUNDCONTROL is free software: you can redistribute it and/or modify
-    it under the terms of the GNU General Public License as published by
-    the Free Software Foundation, either version 3 of the License, or
-    (at your option) any later version.
-
-    QGROUNDCONTROL is distributed in the hope that it will be useful,
-    but WITHOUT ANY WARRANTY; without even the implied warranty of
-    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
-    GNU General Public License for more details.
-
-    You should have received a copy of the GNU General Public License
-    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
-
-======================================================================*/
-
-#ifndef MissionEditorController_H
-#define MissionEditorController_H
-
-#include <QObject>
-
-#include "QmlObjectListModel.h"
-#include "Vehicle.h"
-
-class MissionEditorController : public QObject
-{
-    Q_OBJECT
-    
-public:
-    MissionEditorController(QObject* parent = NULL);
-    ~MissionEditorController();
-
-    Q_PROPERTY(QmlObjectListModel*  missionItems                READ missionItems                   NOTIFY missionItemsChanged)
-    Q_PROPERTY(QmlObjectListModel*  waypointLines               READ waypointLines                  NOTIFY waypointLinesChanged)
-    Q_PROPERTY(bool                 canEdit                     READ canEdit                        NOTIFY canEditChanged)
-    Q_PROPERTY(bool                 liveHomePositionAvailable   READ liveHomePositionAvailable      NOTIFY liveHomePositionAvailableChanged)
-    Q_PROPERTY(QGeoCoordinate       liveHomePosition            READ liveHomePosition               NOTIFY liveHomePositionChanged)
-    Q_PROPERTY(bool                 autoSync                    READ autoSync   WRITE setAutoSync   NOTIFY autoSyncChanged)
-    
-    Q_INVOKABLE int addMissionItem(QGeoCoordinate coordinate);
-    Q_INVOKABLE void getMissionItems(void);
-    Q_INVOKABLE void sendMissionItems(void);
-    Q_INVOKABLE void loadMissionFromFile(void);
-    Q_INVOKABLE void saveMissionToFile(void);
-    Q_INVOKABLE void removeMissionItem(int index);
-    Q_INVOKABLE void deleteCurrentMissionItem(void);
-
-    // Property accessors
-    
-    QmlObjectListModel* missionItems(void);
-    QmlObjectListModel* waypointLines(void) { return &_waypointLines; }
-    bool canEdit(void) { return _canEdit; }
-    bool liveHomePositionAvailable(void) { return _liveHomePositionAvailable; }
-    QGeoCoordinate liveHomePosition(void) { return _liveHomePosition; }
-    bool autoSync(void) { return _autoSync; }
-    void setAutoSync(bool autoSync);
-
-signals:
-    void missionItemsChanged(void);
-    void canEditChanged(bool canEdit);
-    void waypointLinesChanged(void);
-    void liveHomePositionAvailableChanged(bool homePositionAvailable);
-    void liveHomePositionChanged(const QGeoCoordinate& homePosition);
-    void autoSyncChanged(bool autoSync);
-    
-private slots:
-    void _newMissionItemsAvailable();
-    void _itemCoordinateChanged(const QGeoCoordinate& coordinate);
-    void _itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
-    void _activeVehicleChanged(Vehicle* activeVehicle);
-    void _activeVehicleHomePositionAvailableChanged(bool homePositionAvailable);
-    void _activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition);
-    void _dirtyChanged(bool dirty);
-    void _inProgressChanged(bool inProgress);
-
-private:
-    void _recalcSequence(void);
-    void _recalcWaypointLines(void);
-    void _recalcChildItems(void);
-    void _recalcAll(void);
-    void _initAllMissionItems(void);
-    void _deinitAllMissionItems(void);
-    void _initMissionItem(MissionItem* item);
-    void _deinitMissionItem(MissionItem* item);
-    void _autoSyncSend(void);
-
-private:
-    QmlObjectListModel* _missionItems;
-    QmlObjectListModel  _waypointLines;
-    bool                _canEdit;           ///< true: UI can edit these items, false: can't edit, can only send to vehicle or save
-    Vehicle*            _activeVehicle;
-    bool                _liveHomePositionAvailable;
-    QGeoCoordinate      _liveHomePosition;
-    bool                _autoSync;
-    bool                _firstMissionItemSync;
-    bool                _missionItemsRequested;
-    bool                _queuedSend;
-
-    static const char* _settingsGroup;
-};
-
-#endif
diff --git a/src/MissionItem.h b/src/MissionItem.h
index 91ef639..11005d2 100644
--- a/src/MissionItem.h
+++ b/src/MissionItem.h
@@ -86,7 +86,7 @@ public:
     Q_PROPERTY(QmlObjectListModel*  childItems          READ childItems                                     CONSTANT)
 
     /// true: this item is being used as a home position indicator
-    Q_PROPERTY(bool                 homePosition        MEMBER _homePositionSpecialCase                     CONSTANT)
+    Q_PROPERTY(bool                 homePosition        READ homePosition                                   CONSTANT)
     
     /// true: home position should be shown
     Q_PROPERTY(bool                 homePositionValid   READ homePositionValid      WRITE setHomePositionValid NOTIFY homePositionValidChanged)
@@ -131,6 +131,7 @@ public:
     
     QmlObjectListModel* childItems(void) { return &_childItems; }
 
+    bool homePosition(void) { return _homePositionSpecialCase; }
     bool homePositionValid(void) { return _homePositionValid; }
     void setHomePositionValid(bool homePositionValid);
     
diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc
index 41da713..0e05c17 100644
--- a/src/MissionManager/MissionController.cc
+++ b/src/MissionManager/MissionController.cc
@@ -22,109 +22,281 @@ This file is part of the QGROUNDCONTROL project
 ======================================================================*/
 
 #include "MissionController.h"
-#include "ScreenToolsController.h"
 #include "MultiVehicleManager.h"
 #include "MissionManager.h"
+#include "QGCFileDialog.h"
 #include "CoordinateVector.h"
+#include "QGCMessageBox.h"
+#include "FirmwarePlugin.h"
+
+const char* MissionController::_settingsGroup = "MissionController";
 
 MissionController::MissionController(QObject *parent)
     : QObject(parent)
+    , _editMode(false)
     , _missionItems(NULL)
+    , _canEdit(true)
     , _activeVehicle(NULL)
+    , _liveHomePositionAvailable(false)
+    , _autoSync(false)
+    , _firstMissionItemSync(false)
+    , _missionItemsRequested(false)
+    , _queuedSend(false)
 {
+
+}
+
+MissionController::~MissionController()
+{
+}
+
+void MissionController::start(bool editMode)
+{
+    _editMode = editMode;
+
     MultiVehicleManager* multiVehicleMgr = MultiVehicleManager::instance();
-    
+
     connect(multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &MissionController::_activeVehicleChanged);
-    
+
     Vehicle* activeVehicle = multiVehicleMgr->activeVehicle();
     if (activeVehicle) {
         _activeVehicleChanged(activeVehicle);
     } else {
+        _missionItemsRequested = true;
         _newMissionItemsAvailable();
     }
 }
 
-MissionController::~MissionController()
-{
-}
-
 void MissionController::_newMissionItemsAvailable(void)
 {
+    if (_editMode) {
+        if (_firstMissionItemSync) {
+            // This is the first time the vehicle is seeing items. We have to be careful of transitioning from offline
+            // to online.
+
+            _firstMissionItemSync = false;
+            if (_missionItems && _missionItems->count() > 1) {
+                QGCMessageBox::StandardButton button = QGCMessageBox::warning("Mission Editing",
+                                                                              "The vehicle has sent a new set of Mission Items. "
+                                                                              "Do you want to discard your current set of unsaved items and use the ones from the vehicle instead?",
+                                                                              QGCMessageBox::Yes | QGCMessageBox::No,
+                                                                              QGCMessageBox::No);
+                if (button == QGCMessageBox::No) {
+                    return;
+                }
+            }
+        } else if (!_missionItemsRequested) {
+            // We didn't specifically ask for new mission items. Disregard the new set since it is
+            // the most likely the set we just sent to the vehicle.
+            return;
+        }
+    }
+
+    _missionItemsRequested = false;
+
     if (_missionItems) {
+        _deinitAllMissionItems();
         _missionItems->deleteLater();
     }
-    
+
     MissionManager* missionManager = NULL;
-    Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
-    if (activeVehicle) {
-        missionManager = activeVehicle->missionManager();
+    if (_activeVehicle) {
+        missionManager = _activeVehicle->missionManager();
     }
 
     if (!missionManager || missionManager->inProgress()) {
+        _canEdit = true;
         _missionItems = new QmlObjectListModel(this);
     } else {
+        _canEdit = missionManager->canEdit();
         _missionItems = missionManager->copyMissionItems();
     }
 
     _initAllMissionItems();
 }
 
-void MissionController::_recalcWaypointLines(void)
+void MissionController::getMissionItems(void)
 {
-    int firstIndex = _homePositionValid  ? 0 : 1;
+    Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
 
-    _waypointLines.clear();
+    if (activeVehicle) {
+        _missionItemsRequested = true;
+        MissionManager* missionManager = activeVehicle->missionManager();
+        connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionController::_newMissionItemsAvailable);
+        activeVehicle->missionManager()->requestMissionItems();
+    }
+}
+
+void MissionController::sendMissionItems(void)
+{
+    Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
 
-    if (firstIndex < _missionItems->count()) {
-        bool firstCoordinateItem = true;
-        MissionItem* lastCoordinateItem = qobject_cast<MissionItem*>(_missionItems->get(firstIndex));
+    if (activeVehicle) {
+        activeVehicle->missionManager()->writeMissionItems(*_missionItems);
+        _missionItems->setDirty(false);
+    }
+}
 
-        for (int i=firstIndex; i<_missionItems->count(); i++) {
-            MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));
+int MissionController::addMissionItem(QGeoCoordinate coordinate)
+{
+    if (!_canEdit) {
+        qWarning() << "addMissionItem called with _canEdit == false";
+    }
 
-            if (item->specifiesCoordinate()) {
-                if (firstCoordinateItem) {
-                    if (item->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF && _homePositionValid) {
-                        // The first coordinate we hit is a takeoff command so link back to home position if we have one
-                        _waypointLines.append(new CoordinateVector(qobject_cast<MissionItem*>(_missionItems->get(0))->coordinate(), item->coordinate()));
-                    } else {
-                        // First coordiante is not a takeoff command, it does not link backwards to anything
+    // Coordinate will come through without altitude
+    coordinate.setAltitude(MissionItem::defaultAltitude);
+
+    MissionItem * newItem = new MissionItem(this, _missionItems->count(), coordinate, MAV_CMD_NAV_WAYPOINT);
+    _initMissionItem(newItem);
+    if (_missionItems->count() == 1) {
+        newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
+    }
+    _missionItems->append(newItem);
+
+    _recalcAll();
+
+    return _missionItems->count() - 1;
+}
+
+void MissionController::removeMissionItem(int index)
+{
+    if (!_canEdit) {
+        qWarning() << "addMissionItem called with _canEdit == false";
+        return;
+    }
+
+    MissionItem* item = qobject_cast<MissionItem*>(_missionItems->removeAt(index));
+
+    _deinitMissionItem(item);
+
+    _recalcAll();
+
+    // Set the new current item
+
+    if (index >= _missionItems->count()) {
+        index--;
+    }
+    for (int i=0; i<_missionItems->count(); i++) {
+        MissionItem* item =  qobject_cast<MissionItem*>(_missionItems->get(i));
+        item->setIsCurrentItem(i == index);
+    }
+}
+
+void MissionController::loadMissionFromFile(void)
+{
+    QString errorString;
+    QString filename = QGCFileDialog::getOpenFileName(NULL, "Select Mission File to load");
+
+    if (filename.isEmpty()) {
+        return;
+    }
+
+    if (_missionItems) {
+        _deinitAllMissionItems();
+        _missionItems->deleteLater();
+    }
+    _missionItems = new QmlObjectListModel(this);
+
+    _canEdit = true;
+
+    // FIXME: This needs to handle APM files which have WP 0 in them
+
+    QFile file(filename);
+
+    if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
+        errorString = file.errorString();
+    } else {
+        QTextStream in(&file);
+
+        const QStringList& version = in.readLine().split(" ");
+
+        if (!(version.size() == 3 && version[0] == "QGC" && version[1] == "WPL" && version[2] == "120")) {
+            errorString = "The mission file is not compatible with the current version of QGroundControl.";
+        } else {
+            while (!in.atEnd()) {
+                MissionItem* item = new MissionItem();
+
+                if (item->load(in)) {
+                    _missionItems->append(item);
+
+                    if (!item->canEdit()) {
+                        _canEdit = false;
                     }
-                    firstCoordinateItem = false;
                 } else {
-                    // Subsequent coordinate items link to last coordinate item
-                    _waypointLines.append(new CoordinateVector(lastCoordinateItem->coordinate(), item->coordinate()));
+                    errorString = "The mission file is corrupted.";
+                    break;
                 }
-                lastCoordinateItem = item;
             }
         }
+
     }
-    
-    emit waypointLinesChanged();
+
+    if (!errorString.isEmpty()) {
+        _missionItems->clear();
+    }
+
+    _initAllMissionItems();
 }
 
-// This will update the child item hierarchy
-void MissionController::_recalcChildItems(void)
+void MissionController::saveMissionToFile(void)
 {
-    int firstIndex = _homePositionValid  ? 0 : 1;
+    QString errorString;
+    QString filename = QGCFileDialog::getSaveFileName(NULL, "Select file to save mission to");
+
+    if (filename.isEmpty()) {
+        return;
+    }
 
-    if (_missionItems->count() > firstIndex) {
-        MissionItem* currentParentItem = qobject_cast<MissionItem*>(_missionItems->get(firstIndex));
+    QFile file(filename);
 
-        currentParentItem->childItems()->clear();
+    if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
+        errorString = file.errorString();
+    } else {
+        QTextStream out(&file);
 
-        for (int i=firstIndex+1; i<_missionItems->count(); i++) {
-            MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));
+        out << "QGC WPL 120\r\n";   // Version string
 
-            // Set up non-coordinate item child hierarchy
-            if (item->specifiesCoordinate()) {
-                item->childItems()->clear();
-                currentParentItem = item;
-            } else {
-                currentParentItem->childItems()->append(item);
+        for (int i=1; i<_missionItems->count(); i++) {
+            qobject_cast<MissionItem*>(_missionItems->get(i))->save(out);
+        }
+    }
+
+    _missionItems->setDirty(false);
+}
+
+void MissionController::_recalcWaypointLines(void)
+{
+    MissionItem*    lastCoordinateItem =    qobject_cast<MissionItem*>(_missionItems->get(0));
+    bool            firstCoordinateItem =   true;
+
+    _waypointLines.clear();
+
+    for (int i=1; i<_missionItems->count(); i++) {
+        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));
+
+        if (item->specifiesCoordinate()) {
+            if (firstCoordinateItem) {
+                if (item->command() == MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF) {
+                    MissionItem* homeItem = qobject_cast<MissionItem*>(_missionItems->get(0));
+
+                    // The first coordinate we hit is a takeoff command so link back to home position if valid
+                    if (homeItem->homePositionValid()) {
+                        _waypointLines.append(new CoordinateVector(qobject_cast<MissionItem*>(_missionItems->get(0))->coordinate(), item->coordinate()));
+                    }
+                } else {
+                    // First coordiante is not a takeoff command, it does not link backwards to anything
+                }
+                firstCoordinateItem = false;
+            } else if (!lastCoordinateItem->homePosition() || lastCoordinateItem->homePositionValid()) {
+                // Subsequent coordinate items link to last coordinate item. If the last coordinate item
+                // is an invalid home position we skip the line
+                _waypointLines.append(new CoordinateVector(lastCoordinateItem->coordinate(), item->coordinate()));
             }
+            lastCoordinateItem = item;
         }
     }
+
+    emit waypointLinesChanged();
 }
 
 // This will update the sequence numbers to be sequential starting from 0
@@ -138,6 +310,26 @@ void MissionController::_recalcSequence(void)
     }
 }
 
+// This will update the child item hierarchy
+void MissionController::_recalcChildItems(void)
+{
+    MissionItem* currentParentItem = qobject_cast<MissionItem*>(_missionItems->get(0));
+
+    currentParentItem->childItems()->clear();
+
+    for (int i=1; i<_missionItems->count(); i++) {
+        MissionItem* item = qobject_cast<MissionItem*>(_missionItems->get(i));
+
+        // Set up non-coordinate item child hierarchy
+        if (item->specifiesCoordinate()) {
+            item->childItems()->clear();
+            currentParentItem = item;
+        } else {
+            currentParentItem->childItems()->append(item);
+        }
+    }
+}
+
 void MissionController::_recalcAll(void)
 {
     _recalcSequence();
@@ -148,41 +340,181 @@ void MissionController::_recalcAll(void)
 /// Initializes a new set of mission items which may have come from the vehicle or have been loaded from a file
 void MissionController::_initAllMissionItems(void)
 {
-    // Add the home position item to the front
-    MissionItem* homeItem = new MissionItem(this);
-    homeItem->setHomePositionSpecialCase(true);
+    MissionItem* homeItem = NULL;
+
+    if (_activeVehicle && _activeVehicle->firmwarePlugin()->sendHomePositionToVehicle() && _missionItems->count() != 0) {
+        homeItem = qobject_cast<MissionItem*>(_missionItems->get(0));
+        homeItem->setHomePositionSpecialCase(true);
+    } else {
+        // Add the home position item to the front
+        homeItem = new MissionItem(this);
+        homeItem->setHomePositionSpecialCase(true);
+        homeItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
+        _missionItems->insert(0, homeItem);
+    }
     homeItem->setHomePositionValid(false);
-    homeItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT);
-    homeItem->setLatitude(47.3769);
-    homeItem->setLongitude(8.549444);
-    _missionItems->insert(0, homeItem);
-    
+
+    for (int i=0; i<_missionItems->count(); i++) {
+        _initMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i)));
+    }
+
     _recalcAll();
-    
+
     emit missionItemsChanged();
+    emit canEditChanged(_canEdit);
+
+    _missionItems->setDirty(false);
+
+    connect(_missionItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
+}
+
+void MissionController::_deinitAllMissionItems(void)
+{
+    for (int i=0; i<_missionItems->count(); i++) {
+        _deinitMissionItem(qobject_cast<MissionItem*>(_missionItems->get(i)));
+    }
+
+    connect(_missionItems, &QmlObjectListModel::dirtyChanged, this, &MissionController::_dirtyChanged);
+}
+
+void MissionController::_initMissionItem(MissionItem* item)
+{
+    _missionItems->setDirty(false);
+
+    connect(item, &MissionItem::commandChanged,     this, &MissionController::_itemCommandChanged);
+    connect(item, &MissionItem::coordinateChanged,  this, &MissionController::_itemCoordinateChanged);
+}
+
+void MissionController::_deinitMissionItem(MissionItem* item)
+{
+    disconnect(item, &MissionItem::commandChanged,     this, &MissionController::_itemCommandChanged);
+    disconnect(item, &MissionItem::coordinateChanged,  this, &MissionController::_itemCoordinateChanged);
+}
+
+void MissionController::_itemCoordinateChanged(const QGeoCoordinate& coordinate)
+{
+    Q_UNUSED(coordinate);
+    _recalcWaypointLines();
+}
+
+void MissionController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command)
+{
+    Q_UNUSED(command);;
+    _recalcChildItems();
+    _recalcWaypointLines();
 }
 
 void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
 {
     if (_activeVehicle) {
         MissionManager* missionManager = _activeVehicle->missionManager();
+
         disconnect(missionManager, &MissionManager::newMissionItemsAvailable,   this, &MissionController::_newMissionItemsAvailable);
+        disconnect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
+        disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged,      this, &MissionController::_activeVehicleHomePositionAvailableChanged);
+        disconnect(_activeVehicle, &Vehicle::homePositionChanged,               this, &MissionController::_activeVehicleHomePositionChanged);
         _activeVehicle = NULL;
+        _newMissionItemsAvailable();
+        _activeVehicleHomePositionAvailableChanged(false);
     }
-    
+
     _activeVehicle = activeVehicle;
-    
+
     if (_activeVehicle) {
         MissionManager* missionManager = activeVehicle->missionManager();
+
         connect(missionManager, &MissionManager::newMissionItemsAvailable,  this, &MissionController::_newMissionItemsAvailable);
+        connect(missionManager, &MissionManager::inProgressChanged,          this, &MissionController::_inProgressChanged);
+        connect(_activeVehicle, &Vehicle::homePositionAvailableChanged,     this, &MissionController::_activeVehicleHomePositionAvailableChanged);
+        connect(_activeVehicle, &Vehicle::homePositionChanged,              this, &MissionController::_activeVehicleHomePositionChanged);
+
+        if (missionManager->inProgress()) {
+            // Vehicle is still in process of requesting mission items
+            _firstMissionItemSync = true;
+        } else {
+            // Vehicle already has mission items
+            _firstMissionItemSync = false;
+        }
+
+        _missionItemsRequested = true;
         _newMissionItemsAvailable();
+
+        _activeVehicleHomePositionChanged(_activeVehicle->homePosition());
+        _activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
+    }
+}
+
+void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
+{
+    _liveHomePositionAvailable = homePositionAvailable;
+    emit liveHomePositionAvailableChanged(_liveHomePositionAvailable);
+}
+
+void MissionController::_activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
+{
+    _liveHomePosition = homePosition;
+    emit liveHomePositionChanged(_liveHomePosition);
+}
+
+void MissionController::deleteCurrentMissionItem(void)
+{
+    for (int i=0; i<_missionItems->count(); i++) {
+        MissionItem* item =  qobject_cast<MissionItem*>(_missionItems->get(i));
+        if (item->isCurrentItem() && i != 0) {
+            removeMissionItem(i);
+            return;
+        }
+    }
+}
+
+void MissionController::setAutoSync(bool autoSync)
+{
+    // FIXME: AutoSync temporarily turned off
+#if 0
+    _autoSync = autoSync;
+    emit autoSyncChanged(_autoSync);
+
+    if (_autoSync) {
+        _dirtyChanged(true);
+    }
+#else
+    Q_UNUSED(autoSync)
+#endif
+}
+
+void MissionController::_dirtyChanged(bool dirty)
+{
+    if (dirty && _autoSync) {
+        Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
+
+        if (activeVehicle && !activeVehicle->armed()) {
+            if (_activeVehicle->missionManager()->inProgress()) {
+                _queuedSend = true;
+            } else {
+                _autoSyncSend();
+            }
+        }
+    }
+}
+
+void MissionController::_autoSyncSend(void)
+{
+    qDebug() << "Auto-syncing with vehicle";
+    _queuedSend = false;
+    if (_missionItems) {
+        sendMissionItems();
+        _missionItems->setDirty(false);
     }
 }
 
-void MissionController::setHomePositionValid(bool homePositionValid)
+void MissionController::_inProgressChanged(bool inProgress)
 {
-    _homePositionValid = homePositionValid;
-    qobject_cast<MissionItem*>(_missionItems->get(0))->setHomePositionValid(homePositionValid);
+    if (!inProgress && _queuedSend) {
+        _autoSyncSend();
+    }
+}
 
-    emit homePositionValidChanged(_homePositionValid);
+QmlObjectListModel* MissionController::missionItems(void)
+{
+    return _missionItems;
 }
diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h
index 43a96ae..fba66c9 100644
--- a/src/MissionManager/MissionController.h
+++ b/src/MissionManager/MissionController.h
@@ -29,37 +29,57 @@ This file is part of the QGROUNDCONTROL project
 #include "QmlObjectListModel.h"
 #include "Vehicle.h"
 
-/// MissionController is a read only controller for Mission Items
 class MissionController : public QObject
 {
     Q_OBJECT
-    
+
 public:
     MissionController(QObject* parent = NULL);
     ~MissionController();
 
-    Q_PROPERTY(QmlObjectListModel*  missionItems    READ missionItems   NOTIFY missionItemsChanged)
-    Q_PROPERTY(QmlObjectListModel*  waypointLines   READ waypointLines  NOTIFY waypointLinesChanged)
+    Q_PROPERTY(QmlObjectListModel*  missionItems                READ missionItems                   NOTIFY missionItemsChanged)
+    Q_PROPERTY(QmlObjectListModel*  waypointLines               READ waypointLines                  NOTIFY waypointLinesChanged)
+    Q_PROPERTY(bool                 canEdit                     READ canEdit                        NOTIFY canEditChanged)
+    Q_PROPERTY(bool                 liveHomePositionAvailable   READ liveHomePositionAvailable      NOTIFY liveHomePositionAvailableChanged)
+    Q_PROPERTY(QGeoCoordinate       liveHomePosition            READ liveHomePosition               NOTIFY liveHomePositionChanged)
+    Q_PROPERTY(bool                 autoSync                    READ autoSync   WRITE setAutoSync   NOTIFY autoSyncChanged)
+
+    Q_INVOKABLE void start(bool editMode)    ;
+    Q_INVOKABLE int addMissionItem(QGeoCoordinate coordinate);
+    Q_INVOKABLE void getMissionItems(void);
+    Q_INVOKABLE void sendMissionItems(void);
+    Q_INVOKABLE void loadMissionFromFile(void);
+    Q_INVOKABLE void saveMissionToFile(void);
+    Q_INVOKABLE void removeMissionItem(int index);
+    Q_INVOKABLE void deleteCurrentMissionItem(void);
 
-    /// true: home position should be shown on map, false: home position not shown on map
-    Q_PROPERTY(bool homePositionValid READ homePositionValid WRITE setHomePositionValid NOTIFY homePositionValidChanged)
-    
     // Property accessors
-    
-    QmlObjectListModel* missionItems(void) { return _missionItems; }
-    QmlObjectListModel* waypointLines(void) { return &_waypointLines; }
 
-    bool homePositionValid(void) { return _homePositionValid; }
-    void setHomePositionValid(bool homPositionValid);
+    QmlObjectListModel* missionItems(void);
+    QmlObjectListModel* waypointLines(void) { return &_waypointLines; }
+    bool canEdit(void) { return _canEdit; }
+    bool liveHomePositionAvailable(void) { return _liveHomePositionAvailable; }
+    QGeoCoordinate liveHomePosition(void) { return _liveHomePosition; }
+    bool autoSync(void) { return _autoSync; }
+    void setAutoSync(bool autoSync);
 
 signals:
     void missionItemsChanged(void);
+    void canEditChanged(bool canEdit);
     void waypointLinesChanged(void);
-    void homePositionValidChanged(bool homePositionValid);
-    
+    void liveHomePositionAvailableChanged(bool homePositionAvailable);
+    void liveHomePositionChanged(const QGeoCoordinate& homePosition);
+    void autoSyncChanged(bool autoSync);
+
 private slots:
     void _newMissionItemsAvailable();
+    void _itemCoordinateChanged(const QGeoCoordinate& coordinate);
+    void _itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command);
     void _activeVehicleChanged(Vehicle* activeVehicle);
+    void _activeVehicleHomePositionAvailableChanged(bool homePositionAvailable);
+    void _activeVehicleHomePositionChanged(const QGeoCoordinate& homePosition);
+    void _dirtyChanged(bool dirty);
+    void _inProgressChanged(bool inProgress);
 
 private:
     void _recalcSequence(void);
@@ -67,12 +87,25 @@ private:
     void _recalcChildItems(void);
     void _recalcAll(void);
     void _initAllMissionItems(void);
+    void _deinitAllMissionItems(void);
+    void _initMissionItem(MissionItem* item);
+    void _deinitMissionItem(MissionItem* item);
+    void _autoSyncSend(void);
 
 private:
+    bool                _editMode;
     QmlObjectListModel* _missionItems;
     QmlObjectListModel  _waypointLines;
+    bool                _canEdit;           ///< true: UI can edit these items, false: can't edit, can only send to vehicle or save
     Vehicle*            _activeVehicle;
-    bool                _homePositionValid;
+    bool                _liveHomePositionAvailable;
+    QGeoCoordinate      _liveHomePosition;
+    bool                _autoSync;
+    bool                _firstMissionItemSync;
+    bool                _missionItemsRequested;
+    bool                _queuedSend;
+
+    static const char* _settingsGroup;
 };
 
 #endif
diff --git a/src/MissionManager/MissionManager.cc b/src/MissionManager/MissionManager.cc
index 3647744..f17b699 100644
--- a/src/MissionManager/MissionManager.cc
+++ b/src/MissionManager/MissionManager.cc
@@ -26,6 +26,7 @@
 
 #include "MissionManager.h"
 #include "Vehicle.h"
+#include "FirmwarePlugin.h"
 #include "MAVLinkProtocol.h"
 
 QGC_LOGGING_CATEGORY(MissionManagerLog, "MissionManagerLog")
@@ -53,8 +54,10 @@ MissionManager::~MissionManager()
 
 }
 
-void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems, bool skipFirstItem)
+void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems)
 {
+    bool skipFirstItem = !_vehicle->firmwarePlugin()->sendHomePositionToVehicle();
+
     _retryCount = 0;
     _missionItems.clear();
 
@@ -65,10 +68,12 @@ void MissionManager::writeMissionItems(const QmlObjectListModel& missionItems, b
 
         MissionItem* item = qobject_cast<MissionItem*>(_missionItems.get(_missionItems.count() - 1));
 
-        // Editor uses 1-based sequence numbers, adjust them before going out
-        item->setSequenceNumber(item->sequenceNumber() - 1);
-        if (item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
-            item->setParam1((int)item->param1() - 1);
+        if (skipFirstItem) {
+            // Home is in sequence 1, remainder of items start at sequence 1
+            item->setSequenceNumber(item->sequenceNumber() - 1);
+            if (item->command() == MavlinkQmlSingleton::MAV_CMD_DO_JUMP) {
+                item->setParam1((int)item->param1() - 1);
+            }
         }
     }
     emit newMissionItemsAvailable();
@@ -200,9 +205,9 @@ bool MissionManager::_stopAckTimeout(AckType_t expectedAck)
     return success;
 }
 
-void MissionManager::_sendTransactionComplete(void)
+void MissionManager::_readTransactionComplete(void)
 {
-    qCDebug(MissionManagerLog) << "_sendTransactionComplete read sequence complete";
+    qCDebug(MissionManagerLog) << "_readTransactionComplete read sequence complete";
     
     mavlink_message_t       message;
     mavlink_mission_ack_t   missionAck;
@@ -233,8 +238,7 @@ void MissionManager::_handleMissionCount(const mavlink_message_t& message)
     qCDebug(MissionManagerLog) << "_handleMissionCount count:" << _cMissionItems;
     
     if (_cMissionItems == 0) {
-        emit newMissionItemsAvailable();
-        emit inProgressChanged(false);
+        _readTransactionComplete();
     } else {
         _requestNextMissionItem(0);
     }
@@ -304,7 +308,7 @@ void MissionManager::_handleMissionItem(const mavlink_message_t& message)
     
     int nextSequenceNumber = missionItem.seq + 1;
     if (nextSequenceNumber == _cMissionItems) {
-        _sendTransactionComplete();
+        _readTransactionComplete();
     } else {
         _requestNextMissionItem(nextSequenceNumber);
     }
diff --git a/src/MissionManager/MissionManager.h b/src/MissionManager/MissionManager.h
index 964d72a..ab9c83a 100644
--- a/src/MissionManager/MissionManager.h
+++ b/src/MissionManager/MissionManager.h
@@ -63,8 +63,7 @@ public:
     
     /// Writes the specified set of mission items to the vehicle
     ///     @oaram missionItems Items to send to vehicle
-    ///     @param skipFirstItem true: Don't send first item
-    void writeMissionItems(const QmlObjectListModel& missionItems, bool skipFirstItem);
+    void writeMissionItems(const QmlObjectListModel& missionItems);
     
     /// Returns a copy of the current set of mission items. Caller is responsible for
     /// freeing returned object.
@@ -106,7 +105,7 @@ private:
     
     void _startAckTimeout(AckType_t ack);
     bool _stopAckTimeout(AckType_t expectedAck);
-    void _sendTransactionComplete(void);
+    void _readTransactionComplete(void);
     void _handleMissionCount(const mavlink_message_t& message);
     void _handleMissionItem(const mavlink_message_t& message);
     void _handleMissionRequest(const mavlink_message_t& message);
@@ -137,4 +136,4 @@ private:
     QmlObjectListModel  _missionItems;
 };
 
-#endif
\ No newline at end of file
+#endif
diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc
index 51baaad..3f34623 100644
--- a/src/QGCApplication.cc
+++ b/src/QGCApplication.cc
@@ -89,7 +89,6 @@
 #include "CoordinateVector.h"
 #include "MainToolBarController.h"
 #include "MissionController.h"
-#include "MissionEditorController.h"
 #include "FlightDisplayViewController.h"
 #include "VideoSurface.h"
 #include "VideoReceiver.h"
@@ -355,7 +354,6 @@ void QGCApplication::_initCommon(void)
     qmlRegisterType<ScreenToolsController>          ("QGroundControl.Controllers", 1, 0, "ScreenToolsController");
     qmlRegisterType<MainToolBarController>          ("QGroundControl.Controllers", 1, 0, "MainToolBarController");
     qmlRegisterType<MissionController>              ("QGroundControl.Controllers", 1, 0, "MissionController");
-    qmlRegisterType<MissionEditorController>        ("QGroundControl.Controllers", 1, 0, "MissionEditorController");
     qmlRegisterType<FlightDisplayViewController>    ("QGroundControl.Controllers", 1, 0, "FlightDisplayViewController");
 
 #ifndef __mobile__
diff --git a/src/VehicleSetup/SetupViewTest.cc b/src/VehicleSetup/SetupViewTest.cc
index e430316..3891dc4 100644
--- a/src/VehicleSetup/SetupViewTest.cc
+++ b/src/VehicleSetup/SetupViewTest.cc
@@ -60,7 +60,7 @@ void SetupViewTest::_clickThrough_test(void)
     
     MockLink* link = new MockLink();
     Q_CHECK_PTR(link);
-    link->setAutopilotType(MAV_AUTOPILOT_PX4);
+    link->setFirmwareType(MAV_AUTOPILOT_PX4);
     LinkManager::instance()->_addLink(link);
     linkMgr->connectLink(link);
     
diff --git a/src/qgcunittest/MainWindowTest.cc b/src/qgcunittest/MainWindowTest.cc
index 6288292..95d0b0d 100644
--- a/src/qgcunittest/MainWindowTest.cc
+++ b/src/qgcunittest/MainWindowTest.cc
@@ -63,7 +63,7 @@ void MainWindowTest::_connectWindowClose_test(MAV_AUTOPILOT autopilot)
     
     MockLink* link = new MockLink();
     Q_CHECK_PTR(link);
-    link->setAutopilotType(autopilot);
+    link->setFirmwareType(autopilot);
     LinkManager::instance()->_addLink(link);
     
     linkMgr->connectLink(link);