Commit 3ad581bd authored by Don Gagne's avatar Don Gagne

Add support for mission item insert

parent 94c26ac4
...@@ -200,7 +200,7 @@ QGCView { ...@@ -200,7 +200,7 @@ QGCView {
if (false /*homePositionManagerButton.checked*/) { if (false /*homePositionManagerButton.checked*/) {
//offlineHomePosition = coordinate //offlineHomePosition = coordinate
} else if (addMissionItemsButton.checked) { } else if (addMissionItemsButton.checked) {
var index = controller.addMissionItem(coordinate) var index = controller.insertMissionItem(coordinate, controller.missionItems.count)
setCurrentItem(index) setCurrentItem(index)
} else { } else {
editorMap.zoomLevel = editorMap.maxZoomLevel - 2 editorMap.zoomLevel = editorMap.maxZoomLevel - 2
...@@ -288,10 +288,6 @@ QGCView { ...@@ -288,10 +288,6 @@ QGCView {
} else { } else {
itemDragger.clearItem() itemDragger.clearItem()
} }
// Move to the new position
editorMap.latitude = object.coordinate.latitude
editorMap.longitude = object.coordinate.longitude
} }
} }
} }
...@@ -374,6 +370,11 @@ QGCView { ...@@ -374,6 +370,11 @@ QGCView {
itemDragger.clearItem() itemDragger.clearItem()
controller.removeAllMissionItems() controller.removeAllMissionItems()
} }
onInsert: {
controller.insertMissionItem(editorMap.center, i)
setCurrentItem(i)
}
} }
} // ListView } // ListView
} // Item - Mission Item editor } // Item - Mission Item editor
......
...@@ -158,7 +158,7 @@ void MissionController::sendMissionItems(void) ...@@ -158,7 +158,7 @@ void MissionController::sendMissionItems(void)
} }
} }
int MissionController::addMissionItem(QGeoCoordinate coordinate) int MissionController::insertMissionItem(QGeoCoordinate coordinate, int i)
{ {
MissionItem * newItem = new MissionItem(this); MissionItem * newItem = new MissionItem(this);
newItem->setSequenceNumber(_missionItems->count()); newItem->setSequenceNumber(_missionItems->count());
...@@ -179,7 +179,7 @@ int MissionController::addMissionItem(QGeoCoordinate coordinate) ...@@ -179,7 +179,7 @@ int MissionController::addMissionItem(QGeoCoordinate coordinate)
newItem->setParam7(lastValue); newItem->setParam7(lastValue);
} }
} }
_missionItems->append(newItem); _missionItems->insert(i, newItem);
_recalcAll(); _recalcAll();
......
...@@ -46,8 +46,7 @@ public: ...@@ -46,8 +46,7 @@ public:
Q_PROPERTY(QGeoCoordinate liveHomePosition READ liveHomePosition NOTIFY liveHomePositionChanged) Q_PROPERTY(QGeoCoordinate liveHomePosition READ liveHomePosition NOTIFY liveHomePositionChanged)
Q_PROPERTY(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged) Q_PROPERTY(bool autoSync READ autoSync WRITE setAutoSync NOTIFY autoSyncChanged)
Q_INVOKABLE void start(bool editMode) ; Q_INVOKABLE void start(bool editMode);
Q_INVOKABLE int addMissionItem(QGeoCoordinate coordinate);
Q_INVOKABLE void getMissionItems(void); Q_INVOKABLE void getMissionItems(void);
Q_INVOKABLE void sendMissionItems(void); Q_INVOKABLE void sendMissionItems(void);
Q_INVOKABLE void loadMissionFromFile(void); Q_INVOKABLE void loadMissionFromFile(void);
...@@ -55,6 +54,9 @@ public: ...@@ -55,6 +54,9 @@ public:
Q_INVOKABLE void removeMissionItem(int index); Q_INVOKABLE void removeMissionItem(int index);
Q_INVOKABLE void removeAllMissionItems(void); Q_INVOKABLE void removeAllMissionItems(void);
/// @param i: index to insert at
Q_INVOKABLE int insertMissionItem(QGeoCoordinate coordinate, int i);
// Property accessors // Property accessors
QmlObjectListModel* missionItems(void); QmlObjectListModel* missionItems(void);
......
...@@ -176,7 +176,7 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType) ...@@ -176,7 +176,7 @@ void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
QGeoCoordinate coordinate(37.803784, -122.462276); QGeoCoordinate coordinate(37.803784, -122.462276);
_missionController->addMissionItem(coordinate); _missionController->insertMissionItem(coordinate, _missionController->missionItems()->count());
QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(waypointLinesChangedSignalMask), true); QCOMPARE(_multiSpyMissionController->checkOnlySignalsByMask(waypointLinesChangedSignalMask), true);
...@@ -223,7 +223,7 @@ void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareTyp ...@@ -223,7 +223,7 @@ void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareTyp
_missionController = new MissionController(); _missionController = new MissionController();
Q_CHECK_PTR(_missionController); Q_CHECK_PTR(_missionController);
_missionController->start(true /* editMode */); _missionController->start(true /* editMode */);
_missionController->addMissionItem(QGeoCoordinate(37.803784, -122.462276)); _missionController->insertMissionItem(QGeoCoordinate(37.803784, -122.462276), _missionController->missionItems()->count());
// Go online to empty vehicle // Go online to empty vehicle
MissionControllerManagerTest::_initForFirmwareType(firmwareType); MissionControllerManagerTest::_initForFirmwareType(firmwareType);
......
...@@ -21,6 +21,7 @@ Rectangle { ...@@ -21,6 +21,7 @@ Rectangle {
signal clicked signal clicked
signal remove signal remove
signal removeAll signal removeAll
signal insert(int i)
height: innerItem.height + (_margin * 3) height: innerItem.height + (_margin * 3)
color: missionItem.isCurrentItem ? qgcPal.buttonHighlight : qgcPal.windowShade color: missionItem.isCurrentItem ? qgcPal.buttonHighlight : qgcPal.windowShade
...@@ -87,6 +88,11 @@ Rectangle { ...@@ -87,6 +88,11 @@ Rectangle {
Menu { Menu {
id: hamburgerMenu id: hamburgerMenu
MenuItem {
text: "Insert"
onTriggered: insert(missionItem.sequenceNumber)
}
MenuItem { MenuItem {
text: "Delete" text: "Delete"
onTriggered: remove() onTriggered: remove()
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment