diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 86f0574..1f0eed6 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -65,6 +65,7 @@
src/FlightMap/Images/airplaneOpaque.svg
src/FlightMap/Images/ZoomPlus.svg
src/FlightMap/Images/ZoomMinus.svg
+ src/FlightMap/Images/TrashDelete.svg
src/FlightMap/Images/Help.svg
diff --git a/src/MissionEditor/MissionEditor.qml b/src/MissionEditor/MissionEditor.qml
index 4002f7a..10c6fb7 100644
--- a/src/MissionEditor/MissionEditor.qml
+++ b/src/MissionEditor/MissionEditor.qml
@@ -43,29 +43,41 @@ QGCView {
// zOrder comes from the Loader in MainWindow.qml
z: zOrder
- readonly property int _decimalPlaces: 7
- readonly property real _horizontalMargin: ScreenTools.defaultFontPixelWidth / 2
- readonly property real _margin: ScreenTools.defaultFontPixelHeight / 2
- readonly property var _activeVehicle: multiVehicleManager.activeVehicle
- readonly property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 16
- readonly property real _rightPanelWidth: ScreenTools.defaultFontPixelWidth * 30
- readonly property real _rightPanelOpacity: 0.8
- readonly property int _toolButtonCount: 6
- readonly property int _addMissionItemsButtonAutoOffTimeout: 10000
-
- property var _missionItems: _controller.missionItems
+ readonly property int _decimalPlaces: 8
+ readonly property real _horizontalMargin: ScreenTools.defaultFontPixelWidth / 2
+ readonly property real _margin: ScreenTools.defaultFontPixelHeight / 2
+ readonly property var _activeVehicle: multiVehicleManager.activeVehicle
+ readonly property real _editFieldWidth: ScreenTools.defaultFontPixelWidth * 16
+ readonly property real _rightPanelWidth: ScreenTools.defaultFontPixelWidth * 30
+ readonly property real _rightPanelOpacity: 0.8
+ readonly property int _toolButtonCount: 6
+ readonly property string _autoSyncKey: "AutoSync"
+ readonly property int _addMissionItemsButtonAutoOffTimeout: 10000
+
+ property var _missionItems: controller.missionItems
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 liveHomePosition: controller.liveHomePosition
+ property var liveHomePositionAvailable: controller.liveHomePositionAvailable
property var homePosition: offlineHomePosition // live or offline depending on state
- property bool _syncNeeded: _controller.missionItems.dirty
+ property bool _syncNeeded: controller.missionItems.dirty
+ property bool _syncInProgress: _activeVehicle ? _activeVehicle.missionManager.inProgress : false
- MissionEditorController { id: _controller }
+ MissionEditorController {
+ id: controller
+ autoSync: QGroundControl.flightMapSettings.loadMapSetting(editorMap.mapName, _autoSyncKey, true)
+
+ onAutoSyncChanged: QGroundControl.flightMapSettings.saveMapSetting(editorMap.mapName, _autoSyncKey, autoSync)
+
+ onMissionItemsChanged: {
+ updateHomePosition()
+ itemEditor.clearItem()
+ }
+ }
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
@@ -85,10 +97,7 @@ QGCView {
function updateHomePosition() {
homePosition = liveHomePositionAvailable ? liveHomePosition : offlineHomePosition
- // Changing the coordinate will set the dirty bit, so we save and reset it
- var dirtyBit = _missionItems.dirty
_missionItems.get(0).coordinate = homePosition
- _missionItems.dirty = dirtyBit
}
Component.onCompleted: updateHomePosition()
@@ -96,13 +105,6 @@ QGCView {
onLiveHomePositionAvailableChanged: updateHomePosition()
onLiveHomePositionChanged: updateHomePosition()
- Connections {
- target: _controller
-
- // When the mission items change _missionsItems[0] changes as well so we need to reset it to home
- onMissionItemsChanged: updateHomePosition
- }
-
QGCViewPanel {
id: panel
anchors.fill: parent
@@ -154,7 +156,7 @@ QGCView {
if (homePositionManagerButton.checked) {
offlineHomePosition = coordinate
} else if (addMissionItemsButton.checked) {
- var index = _controller.addMissionItem(coordinate)
+ var index = controller.addMissionItem(coordinate)
addMissionItemsButtonAutoOffTimer.start()
setCurrentItem(index)
} else {
@@ -177,6 +179,12 @@ QGCView {
property var missionItemIndicator
property real heading: missionItem ? missionItem.heading : 0
+ function clearItem() {
+ itemEditor.visible = false
+ itemEditor.missionItem = undefined
+ itemEditor.missionItemIndicator = undefined
+ }
+
Drag.active: itemDrag.drag.active
Drag.hotSpot.x: width / 2
Drag.hotSpot.y: height / 2
@@ -206,7 +214,7 @@ QGCView {
// Add the mission items to the map
MapItemView {
- model: _controller.missionItems
+ model: controller.missionItems
delegate:
MissionItemIndicator {
@@ -230,9 +238,7 @@ QGCView {
itemEditor.missionItem = Qt.binding(function() { return object })
itemEditor.missionItemIndicator = Qt.binding(function() { return itemIndicator })
} else {
- itemEditor.visible = false
- itemEditor.missionItem = undefined
- itemEditor.missionItemIndicator = undefined
+ itemEditor.clearItem()
}
// Zoom the map and move to the new position
@@ -270,7 +276,7 @@ QGCView {
// Add lines between waypoints
MapItemView {
- model: _controller.waypointLines
+ model: controller.waypointLines
delegate:
MapPolyline {
@@ -301,7 +307,7 @@ QGCView {
anchors.fill: parent
spacing: _margin / 2
orientation: ListView.Vertical
- model: _controller.canEdit ? _controller.missionItems : 0
+ model: controller.canEdit ? controller.missionItems : 0
property real _maxItemHeight: 0
@@ -315,7 +321,7 @@ QGCView {
onRemove: {
var newCurrentItem = object.sequenceNumber - 1
- _controller.removeMissionItem(object.sequenceNumber)
+ controller.removeMissionItem(object.sequenceNumber)
if (_missionItems.count > 1) {
newCurrentItem = Math.min(_missionItems.count - 1, newCurrentItem)
setCurrentItem(newCurrentItem)
@@ -326,7 +332,7 @@ QGCView {
QGCLabel {
anchors.fill: parent
- visible: !_controller.canEdit
+ visible: !controller.canEdit
wrapMode: Text.WordWrap
text: "The set of mission items you have loaded cannot be edited by QGroundControl. " +
"You will only be able to save these to a file, or send them to a vehicle."
@@ -750,12 +756,13 @@ QGCView {
} // Item - Help Panel
RoundButton {
- id: addMissionItemsButton
- anchors.margins: _margin
- anchors.left: parent.left
- y: (parent.height - (_toolButtonCount * height) - ((_toolButtonCount - 1) * _margin)) / 2
- buttonImage: "/qmlimages/MapAddMission.svg"
- exclusiveGroup: _dropButtonsExclusiveGroup
+ id: addMissionItemsButton
+ anchors.margins: _margin
+ anchors.left: parent.left
+ y: (parent.height - (_toolButtonCount * height) - ((_toolButtonCount - 1) * _margin)) / 2
+ buttonImage: "/qmlimages/MapAddMission.svg"
+ exclusiveGroup: _dropButtonsExclusiveGroup
+ z: editorMap.zOrderWidgets
onCheckedChanged: {
if (checked) {
@@ -775,10 +782,26 @@ QGCView {
}
RoundButton {
- id: homePositionManagerButton
+ id: deleteMissionItemButton
anchors.margins: _margin
anchors.left: parent.left
anchors.top: addMissionItemsButton.bottom
+ buttonImage: "/qmlimages/TrashDelete.svg"
+ exclusiveGroup: _dropButtonsExclusiveGroup
+ z: editorMap.zOrderWidgets
+
+ onClicked: {
+ itemEditor.clearItem()
+ controller.deleteCurrentMissionItem()
+ checked = false
+ }
+ }
+
+ RoundButton {
+ id: homePositionManagerButton
+ anchors.margins: _margin
+ anchors.left: parent.left
+ anchors.top: deleteMissionItemButton.bottom
buttonImage: "/qmlimages/MapHome.svg"
exclusiveGroup: _dropButtonsExclusiveGroup
z: editorMap.zOrderWidgets
@@ -838,67 +861,8 @@ QGCView {
viewportMargins: ScreenTools.defaultFontPixelWidth / 2
exclusiveGroup: _dropButtonsExclusiveGroup
z: editorMap.zOrderWidgets
-
- dropDownComponent: Component {
- Column {
- id: columnHolder
- spacing: _margin
-
- QGCLabel {
- width: columnHolder.width
- wrapMode: Text.WordWrap
- text: _syncNeeded ?
- "You have unsaved changed to you mission. You should send to your vehicle, or save to a file:" :
- "Sync:"
- }
-
- Row {
- spacing: ScreenTools.defaultFontPixelWidth
-
- QGCButton {
- text: "Send to vehicle"
- enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress
-
- onClicked: {
- syncButton.hideDropDown()
- _controller.setMissionItems()
- }
- }
-
- QGCButton {
- text: "Load from vehicle"
- enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress
-
- onClicked: {
- syncButton.hideDropDown()
- _controller.getMissionItems()
- }
- }
- }
-
- Row {
- spacing: ScreenTools.defaultFontPixelWidth
-
- QGCButton {
- text: "Save to file..."
-
- onClicked: {
- syncButton.hideDropDown()
- _controller.saveMissionToFile()
- }
- }
-
- QGCButton {
- text: "Load from file..."
-
- onClicked: {
- syncButton.hideDropDown()
- _controller.loadMissionFromFile()
- }
- }
- }
- }
- }
+ dropDownComponent: syncDropDownComponent
+ enabled: !_syncInProgress
}
DropButton {
@@ -952,4 +916,83 @@ QGCView {
} // FlightMap
} // Item - split view container
} // QGCViewPanel
+
+ Component {
+ id: syncDropDownComponent
+
+ Column {
+ id: columnHolder
+ spacing: _margin
+
+ QGCLabel {
+ width: columnHolder.width
+ wrapMode: Text.WordWrap
+ text: _syncNeeded && !controller.autoSync ?
+ "You have unsaved changed to you mission. You should send to your vehicle, or save to a file:" :
+ "Sync:"
+ }
+
+ Row {
+ visible: autoSyncCheckBox.enabled && autoSyncCheckBox.checked
+ spacing: ScreenTools.defaultFontPixelWidth
+
+ QGCButton {
+ text: "Send to vehicle"
+ enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress
+
+ onClicked: {
+ syncButton.hideDropDown()
+ controller.sendMissionItems()
+ }
+ }
+
+ QGCButton {
+ text: "Load from vehicle"
+ enabled: _activeVehicle && !_activeVehicle.missionManager.inProgress
+
+ onClicked: {
+ syncButton.hideDropDown()
+ controller.getMissionItems()
+ }
+ }
+ }
+
+ Row {
+ spacing: ScreenTools.defaultFontPixelWidth
+
+ QGCButton {
+ text: "Save to file..."
+
+ onClicked: {
+ syncButton.hideDropDown()
+ controller.saveMissionToFile()
+ }
+ }
+
+ QGCButton {
+ text: "Load from file..."
+
+ onClicked: {
+ syncButton.hideDropDown()
+ controller.loadMissionFromFile()
+ }
+ }
+ }
+
+ QGCLabel {
+ id: autoSyncDisallowedLabel
+ visible: _activeVehicle && _activeVehicle.armed
+ text: "AutoSync is not allowed whie vehicle is armed"
+ }
+
+ QGCCheckBox {
+ id: autoSyncCheckBox
+ checked: controller.autoSync
+ text: "Automatically sync changes with vehicle"
+ enabled: _activeVehicle ? !_activeVehicle.armed : false
+
+ onClicked: controller.autoSync = checked
+ }
+ }
+ }
} // QGCVIew
diff --git a/src/MissionEditor/MissionEditorController.cc b/src/MissionEditor/MissionEditorController.cc
index 0f4691a..53da03d 100644
--- a/src/MissionEditor/MissionEditorController.cc
+++ b/src/MissionEditor/MissionEditorController.cc
@@ -27,6 +27,7 @@ This file is part of the QGROUNDCONTROL project
#include "MissionManager.h"
#include "QGCFileDialog.h"
#include "CoordinateVector.h"
+#include "QGCMessageBox.h"
#include
#include
@@ -40,6 +41,9 @@ MissionEditorController::MissionEditorController(QWidget *parent)
, _canEdit(true)
, _activeVehicle(NULL)
, _liveHomePositionAvailable(false)
+ , _autoSync(false)
+ , _firstMissionItemSync(false)
+ , _expectingNewMissionItems(false)
{
MultiVehicleManager* multiVehicleMgr = MultiVehicleManager::instance();
@@ -47,9 +51,6 @@ MissionEditorController::MissionEditorController(QWidget *parent)
Vehicle* activeVehicle = multiVehicleMgr->activeVehicle();
if (activeVehicle) {
- MissionManager* missionManager = activeVehicle->missionManager();
- connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionEditorController::_newMissionItemsAvailable);
- _newMissionItemsAvailable();
_activeVehicleChanged(activeVehicle);
} else {
_missionItems = new QmlObjectListModel(this);
@@ -63,6 +64,29 @@ MissionEditorController::~MissionEditorController()
void MissionEditorController::_newMissionItemsAvailable(void)
{
+ if (_firstMissionItemSync || !_expectingNewMissionItems) {
+ // This is the first time the vehicle is seeing items. We have to be careful of transitioning from offline
+ // to online. Other case is an unexpected set of new items from the vehicle.
+
+ _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 (_autoSync) {
+ // When we are running autoSync we assume the MissionManager is notifying us about the
+ // items we just sent to it. We keep our own edit list, instead of resetting.
+ return;
+ }
+
+ _expectingNewMissionItems = false;
+
if (_missionItems) {
_deinitAllMissionItems();
_missionItems->deleteLater();
@@ -81,15 +105,15 @@ void MissionEditorController::getMissionItems(void)
Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
if (activeVehicle) {
+ _expectingNewMissionItems = true;
MissionManager* missionManager = activeVehicle->missionManager();
connect(missionManager, &MissionManager::newMissionItemsAvailable, this, &MissionEditorController::_newMissionItemsAvailable);
activeVehicle->missionManager()->requestMissionItems();
}
}
-void MissionEditorController::setMissionItems(void)
+void MissionEditorController::sendMissionItems(void)
{
- // FIXME: Need to pull out home position
Vehicle* activeVehicle = MultiVehicleManager::instance()->activeVehicle();
if (activeVehicle) {
@@ -131,6 +155,16 @@ void MissionEditorController::removeMissionItem(int 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(_missionItems->get(i));
+ item->setIsCurrentItem(i == index);
+ }
}
void MissionEditorController::loadMissionFromFile(void)
@@ -306,6 +340,8 @@ void MissionEditorController::_initAllMissionItems(void)
emit canEditChanged(_canEdit);
_missionItems->setDirty(false);
+
+ connect(_missionItems, &QmlObjectListModel::dirtyChanged, this, &MissionEditorController::_dirtyChanged);
}
void MissionEditorController::_deinitAllMissionItems(void)
@@ -313,6 +349,8 @@ void MissionEditorController::_deinitAllMissionItems(void)
for (int i=0; i<_missionItems->count(); i++) {
_deinitMissionItem(qobject_cast(_missionItems->get(i)));
}
+
+ connect(_missionItems, &QmlObjectListModel::dirtyChanged, this, &MissionEditorController::_dirtyChanged);
}
void MissionEditorController::_initMissionItem(MissionItem* item)
@@ -345,8 +383,12 @@ void MissionEditorController::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_C
void MissionEditorController::_activeVehicleChanged(Vehicle* activeVehicle)
{
if (_activeVehicle) {
- disconnect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionEditorController::_activeVehicleHomePositionAvailableChanged);
- disconnect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionEditorController::_activeVehicleHomePositionChanged);
+ 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;
_activeVehicleHomePositionAvailableChanged(false);
}
@@ -354,10 +396,23 @@ void MissionEditorController::_activeVehicleChanged(Vehicle* activeVehicle)
_activeVehicle = activeVehicle;
if (_activeVehicle) {
- connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionEditorController::_activeVehicleHomePositionAvailableChanged);
- connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionEditorController::_activeVehicleHomePositionChanged);
+ 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);
_activeVehicleHomePositionChanged(_activeVehicle->homePosition());
_activeVehicleHomePositionAvailableChanged(_activeVehicle->homePositionAvailable());
+
+ if (missionManager->inProgress()) {
+ // Vehicle is still in process of requesting mission items
+ _firstMissionItemSync = true;
+ } else {
+ // Vehicle already has mission items
+ _firstMissionItemSync = false;
+ _newMissionItemsAvailable();
+ }
}
}
@@ -372,3 +427,54 @@ void MissionEditorController::_activeVehicleHomePositionChanged(const QGeoCoordi
_liveHomePosition = homePosition;
emit liveHomePositionChanged(_liveHomePosition);
}
+
+void MissionEditorController::deleteCurrentMissionItem(void)
+{
+ for (int i=0; i<_missionItems->count(); i++) {
+ MissionItem* item = qobject_cast(_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;
+ sendMissionItems();
+ _missionItems->setDirty(false);
+}
+
+void MissionEditorController::_inProgressChanged(bool inProgress)
+{
+ if (!inProgress && _queuedSend) {
+ _autoSyncSend();
+ }
+}
diff --git a/src/MissionEditor/MissionEditorController.h b/src/MissionEditor/MissionEditorController.h
index c833045..bbfb5e2 100644
--- a/src/MissionEditor/MissionEditorController.h
+++ b/src/MissionEditor/MissionEditorController.h
@@ -37,18 +37,20 @@ public:
MissionEditorController(QWidget* 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(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 setMissionItems(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
@@ -57,6 +59,8 @@ public:
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);
@@ -64,6 +68,7 @@ signals:
void waypointLinesChanged(void);
void liveHomePositionAvailableChanged(bool homePositionAvailable);
void liveHomePositionChanged(const QGeoCoordinate& homePosition);
+ void autoSyncChanged(bool autoSync);
private slots:
void _newMissionItemsAvailable();
@@ -72,6 +77,8 @@ private slots:
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);
@@ -82,6 +89,7 @@ private:
void _deinitAllMissionItems(void);
void _initMissionItem(MissionItem* item);
void _deinitMissionItem(MissionItem* item);
+ void _autoSyncSend(void);
private:
QmlObjectListModel* _missionItems;
@@ -90,6 +98,10 @@ private:
Vehicle* _activeVehicle;
bool _liveHomePositionAvailable;
QGeoCoordinate _liveHomePosition;
+ bool _autoSync;
+ bool _firstMissionItemSync;
+ bool _expectingNewMissionItems;
+ bool _queuedSend;
static const char* _settingsGroup;
};
diff --git a/src/QmlControls/MissionItemEditor.qml b/src/QmlControls/MissionItemEditor.qml
index 3c7cb04..277063e 100644
--- a/src/QmlControls/MissionItemEditor.qml
+++ b/src/QmlControls/MissionItemEditor.qml
@@ -19,7 +19,7 @@ Rectangle {
signal clicked
signal remove
- height: innerItem.height + (_margin * 2)
+ height: innerItem.height + (_margin * 3)
color: missionItem.isCurrentItem ? qgcPal.buttonHighlight : qgcPal.windowShade
radius: _radius