diff --git a/src/MissionEditor/MissionEditor.qml b/src/MissionEditor/MissionEditor.qml index e15e66411141a5604ba88e6ba4dd3a93ced94802..c6b79ffec65a9f1a5d0e4024e253de0394e9fb4a 100644 --- a/src/MissionEditor/MissionEditor.qml +++ b/src/MissionEditor/MissionEditor.qml @@ -173,14 +173,15 @@ QGCView { id: _dropButtonsExclusiveGroup } - function setCurrentItem(index) { + function setCurrentItem(sequenceNumber) { _currentMissionItem = undefined for (var i=0; i<_visualItems.count; i++) { - if (i == index) { - _currentMissionItem = _visualItems.get(i) + var visualItem = _visualItems.get(i) + if (visualItem.sequenceNumber == sequenceNumber) { + _currentMissionItem = visualItem _currentMissionItem.isCurrentItem = true } else { - _visualItems.get(i).isCurrentItem = false + visualItem.isCurrentItem = false } } } @@ -306,8 +307,8 @@ QGCView { coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces) coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces) if (addMissionItemsButton.checked) { - var index = controller.insertSimpleMissionItem(coordinate, controller.visualItems.count) - setCurrentItem(index) + var sequenceNumber = controller.insertSimpleMissionItem(coordinate, controller.visualItems.count) + setCurrentItem(sequenceNumber) } else { editorMap.mapClicked(coordinate) } @@ -364,13 +365,7 @@ QGCView { } } - // Add the simple mission items to the map - MapItemView { - model: controller.visualItems - delegate: missionItemComponent - } - - // Add the complex mission items to the map + // Add the complex mission item polygon to the map MapItemView { model: controller.complexVisualItems delegate: polygonItemComponent @@ -386,6 +381,16 @@ QGCView { } } + // Add the complex mission item grid to the map + MapItemView { + model: controller.complexVisualItems + + delegate: MapPolyline { + line.color: "white" + path: object.gridPoints + } + } + // Add the complex mission item exit coordinates MapItemView { model: controller.complexVisualItems @@ -404,6 +409,12 @@ QGCView { } } + // Add the simple mission items to the map + MapItemView { + model: controller.visualItems + delegate: missionItemComponent + } + Component { id: missionItemComponent @@ -417,10 +428,8 @@ QGCView { onClicked: setCurrentItem(object.sequenceNumber) - function updateItemIndicator() - { - if (object.isCurrentItem && itemIndicator.visible && - object.specifiesCoordinate && object.isSimpleItem) { + function updateItemIndicator() { + if (object.isCurrentItem && itemIndicator.visible && object.specifiesCoordinate && object.isSimpleItem) { // Setup our drag item itemDragger.visible = true itemDragger.missionItem = Qt.binding(function() { return object }) @@ -516,8 +525,8 @@ QGCView { } onInsert: { - controller.insertSimpleMissionItem(editorMap.center, i) - setCurrentItem(i) + var sequenceNumber = controller.insertSimpleMissionItem(editorMap.center, i) + setCurrentItem(sequenceNumber) } onMoveHomeToMapCenter: controller.visualItems.get(0).coordinate = editorMap.center @@ -567,8 +576,8 @@ QGCView { coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces) coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces) coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces) - var index = controller.insertComplexMissionItem(coordinate, controller.visualItems.count) - setCurrentItem(index) + var sequenceNumber = controller.insertComplexMissionItem(coordinate, controller.visualItems.count) + setCurrentItem(sequenceNumber) checked = false addMissionItemsButton.checked = false } @@ -775,7 +784,7 @@ QGCView { QGCButton { text: "Send to vehicle" - enabled: !controller.syncInProgress + enabled: _activeVehicle && !controller.syncInProgress onClicked: { syncButton.hideDropDown() @@ -785,7 +794,7 @@ QGCView { QGCButton { text: "Load from vehicle" - enabled: !controller.syncInProgress + enabled: _activeVehicle && !controller.syncInProgress onClicked: { syncButton.hideDropDown() diff --git a/src/MissionEditor/SurveyItemEditor.qml b/src/MissionEditor/SurveyItemEditor.qml index 14d54468034ab00b32543a599d0d81a970c9e873..141b59c21f80b694bf0dda2f1309eb48b89ffdd1 100644 --- a/src/MissionEditor/SurveyItemEditor.qml +++ b/src/MissionEditor/SurveyItemEditor.qml @@ -29,7 +29,7 @@ Rectangle { anchors.margins: _margin anchors.top: parent.top anchors.left: parent.left - width: availableWidth + anchors.right: parent.right spacing: _margin Connections { @@ -47,6 +47,30 @@ Rectangle { wrapMode: Text.WordWrap } + Repeater { + model: [ missionItem.gridAltitude, missionItem.gridAngle, missionItem.gridSpacing ] + + Item { + anchors.left: parent.left + anchors.right: parent.right + height: textField.height + + QGCLabel { + anchors.baseline: textField.baseline + anchors.left: parent.left + text: modelData.name + } + + FactTextField { + id: textField + anchors.right: parent.right + width: _editFieldWidth + showUnits: true + fact: modelData + } + } + } + QGCButton { text: _addPointsMode ? "Finished" : "Draw Polygon" onClicked: { diff --git a/src/MissionManager/ComplexMissionItem.cc b/src/MissionManager/ComplexMissionItem.cc index 16c0c4dfa18fd01037b6f6aeeff9dec979acd73f..eaed174ea84cc274d4c5e017741a9857bea5fa3f 100644 --- a/src/MissionManager/ComplexMissionItem.cc +++ b/src/MissionManager/ComplexMissionItem.cc @@ -23,11 +23,15 @@ This file is part of the QGROUNDCONTROL project #include "ComplexMissionItem.h" #include "JsonHelper.h" #include "MissionController.h" +#include "QGCGeo.h" -const char* ComplexMissionItem::_jsonVersionKey = "version"; -const char* ComplexMissionItem::_jsonTypeKey = "type"; -const char* ComplexMissionItem::_jsonPolygonKey = "polygon"; -const char* ComplexMissionItem::_jsonIdKey = "id"; +const char* ComplexMissionItem::_jsonVersionKey = "version"; +const char* ComplexMissionItem::_jsonTypeKey = "type"; +const char* ComplexMissionItem::_jsonPolygonKey = "polygon"; +const char* ComplexMissionItem::_jsonIdKey = "id"; +const char* ComplexMissionItem::_jsonGridAltitudeKey = "gridAltitude"; +const char* ComplexMissionItem::_jsonGridAngleKey = "gridAngle"; +const char* ComplexMissionItem::_jsonGridSpacingKey = "gridSpacing"; const char* ComplexMissionItem::_complexType = "survey"; @@ -35,12 +39,15 @@ ComplexMissionItem::ComplexMissionItem(Vehicle* vehicle, QObject* parent) : VisualMissionItem(vehicle, parent) , _sequenceNumber(0) , _dirty(false) + , _gridAltitudeFact (0, "Altitude:", FactMetaData::valueTypeDouble) + , _gridAngleFact (0, "Grid angle:", FactMetaData::valueTypeDouble) + , _gridSpacingFact (0, "Grid spacing:", FactMetaData::valueTypeDouble) { - MissionItem missionItem; + _gridAltitudeFact.setRawValue(25); + _gridSpacingFact.setRawValue(5); - // FIXME: Bogus entries for testing - _missionItems += new MissionItem(this); - _missionItems += new MissionItem(this); + connect(&_gridSpacingFact, &Fact::valueChanged, this, &ComplexMissionItem::_generateGrid); + connect(&_gridAngleFact, &Fact::valueChanged, this, &ComplexMissionItem::_generateGrid); } ComplexMissionItem::ComplexMissionItem(const ComplexMissionItem& other, QObject* parent) @@ -61,9 +68,12 @@ void ComplexMissionItem::clearPolygon(void) // Although this code should remove the polygon from the map it doesn't. There appears // to be a bug in MapPolygon which causes it to not be redrawn if the list is empty. So - // we work around it by using the code above to remove all bu the last point which in turn + // we work around it by using the code above to remove all but the last point which in turn // will cause the polygon to go away. _polygonPath.clear(); + + _clearGrid(); + emit specifiesCoordinateChanged(); } @@ -79,11 +89,18 @@ void ComplexMissionItem::addPolygonCoordinate(const QGeoCoordinate coordinate) emit specifiesCoordinateChanged(); } _setExitCoordinate(coordinate); + + _generateGrid(); } int ComplexMissionItem::lastSequenceNumber(void) const { - return _sequenceNumber + _missionItems.count() - 1; + int lastSeq = _sequenceNumber; + + if (_gridPoints.count()) { + lastSeq += _gridPoints.count() - 1; + } + return lastSeq; } void ComplexMissionItem::setCoordinate(const QGeoCoordinate& coordinate) @@ -91,26 +108,26 @@ void ComplexMissionItem::setCoordinate(const QGeoCoordinate& coordinate) if (_coordinate != coordinate) { _coordinate = coordinate; emit coordinateChanged(_coordinate); - _missionItems[0]->setCoordinate(coordinate); - - // FIXME: Hack _setExitCoordinate(coordinate); } } void ComplexMissionItem::setDirty(bool dirty) { - if (_dirty != dirty) { - _dirty = dirty; - emit dirtyChanged(_dirty); - } + if (_dirty != dirty) { + _dirty = dirty; + emit dirtyChanged(_dirty); + } } void ComplexMissionItem::save(QJsonObject& saveObject) const { - saveObject[_jsonVersionKey] = 1; - saveObject[_jsonTypeKey] = _complexType; - saveObject[_jsonIdKey] = sequenceNumber(); + saveObject[_jsonVersionKey] = 1; + saveObject[_jsonTypeKey] = _complexType; + saveObject[_jsonIdKey] = sequenceNumber(); + saveObject[_jsonGridAltitudeKey] = _gridAltitudeFact.rawValue().toDouble(); + saveObject[_jsonGridAngleKey] = _gridAngleFact.rawValue().toDouble(); + saveObject[_jsonGridSpacingKey] = _gridSpacingFact.rawValue().toDouble(); // Polygon shape @@ -125,42 +142,21 @@ void ComplexMissionItem::save(QJsonObject& saveObject) const } saveObject[_jsonPolygonKey] = polygonArray; - - // Base mission items - - QJsonArray simpleItems; - for (int i=0; i<_missionItems.count(); i++) { - MissionItem* missionItem = _missionItems[i]; - - QJsonObject jsonObject; - missionItem->save(jsonObject); - simpleItems.append(jsonObject); - } - saveObject[MissionController::jsonSimpleItemsKey] = simpleItems; } void ComplexMissionItem::setSequenceNumber(int sequenceNumber) { if (_sequenceNumber != sequenceNumber) { _sequenceNumber = sequenceNumber; - - // Update internal mission items to new numbering - for (int i=0; i<_missionItems.count(); i++) { - _missionItems[i]->setSequenceNumber(sequenceNumber++); - } - emit sequenceNumberChanged(sequenceNumber); + emit lastSequenceNumberChanged(lastSequenceNumber()); } } void ComplexMissionItem::_clear(void) { - // Clear old settings - for (int i=0; i<_missionItems.count(); i++) { - _missionItems[i]->deleteLater(); - } - _missionItems.clear(); - _polygonPath.clear(); + clearPolygon(); + _clearGrid(); } @@ -170,7 +166,7 @@ bool ComplexMissionItem::load(const QJsonObject& complexObject, QString& errorSt // Validate requires keys QStringList requiredKeys; - requiredKeys << _jsonVersionKey << _jsonTypeKey << _jsonIdKey << _jsonPolygonKey << MissionController::jsonSimpleItemsKey; + requiredKeys << _jsonVersionKey << _jsonTypeKey << _jsonIdKey << _jsonPolygonKey << _jsonGridAltitudeKey << _jsonGridAngleKey << _jsonGridSpacingKey; if (!JsonHelper::validateRequiredKeys(complexObject, requiredKeys, errorString)) { _clear(); return false; @@ -179,8 +175,8 @@ bool ComplexMissionItem::load(const QJsonObject& complexObject, QString& errorSt // Validate types QStringList keyList; QList typeList; - keyList << _jsonVersionKey << _jsonTypeKey << _jsonIdKey << _jsonPolygonKey << MissionController::jsonSimpleItemsKey; - typeList << QJsonValue::Double << QJsonValue::String << QJsonValue::Double << QJsonValue::Array << QJsonValue::Array; + keyList << _jsonVersionKey << _jsonTypeKey << _jsonIdKey << _jsonPolygonKey << _jsonGridAltitudeKey << _jsonGridAngleKey << _jsonGridSpacingKey; + typeList << QJsonValue::Double << QJsonValue::String << QJsonValue::Double << QJsonValue::Array << QJsonValue::Double << QJsonValue::Double<< QJsonValue::Double; if (!JsonHelper::validateKeyTypes(complexObject, keyList, typeList, errorString)) { _clear(); return false; @@ -200,6 +196,9 @@ bool ComplexMissionItem::load(const QJsonObject& complexObject, QString& errorSt } setSequenceNumber(complexObject[_jsonIdKey].toInt()); + _gridAltitudeFact.setRawValue(complexObject[_jsonGridAltitudeKey].toDouble()); + _gridAngleFact.setRawValue(complexObject[_jsonGridAngleKey].toDouble()); + _gridSpacingFact.setRawValue(complexObject[_jsonGridSpacingKey].toDouble()); // Polygon shape QJsonArray polygonArray(complexObject[_jsonPolygonKey].toArray()); @@ -214,51 +213,149 @@ bool ComplexMissionItem::load(const QJsonObject& complexObject, QString& errorSt _polygonPath << QVariant::fromValue(pointCoord); } - // Internal mission items - QJsonArray itemArray(complexObject[MissionController::jsonSimpleItemsKey].toArray()); - for (int i=0; iload(itemValue.toObject(), errorString)) { - _missionItems.append(item); - } else { - _clear(); - return false; - } +void ComplexMissionItem::_setExitCoordinate(const QGeoCoordinate& coordinate) +{ + if (_exitCoordinate != coordinate) { + _exitCoordinate = coordinate; + emit exitCoordinateChanged(coordinate); } +} - int itemCount = _missionItems.count(); - if (itemCount > 0) { - _coordinate = _missionItems[0]->coordinate(); - _exitCoordinate = _missionItems[itemCount - 1]->coordinate(); +bool ComplexMissionItem::specifiesCoordinate(void) const +{ + return _polygonPath.count() > 2; +} + +void ComplexMissionItem::_clearGrid(void) +{ + // Bug workaround + while (_gridPoints.count() > 1) { + _gridPoints.takeLast(); } + emit gridPointsChanged(); + _gridPoints.clear(); + emit gridPointsChanged(); - qDebug() << coordinate() << exitCoordinate() << _missionItems[0]->coordinate() << _missionItems[1]->coordinate(); +} + +void ComplexMissionItem::_generateGrid(void) +{ + if (_polygonPath.count() < 3) { + _clearGrid(); + return; + } + + _gridPoints.clear(); + + QList polygonPoints; + QList gridPoints; + + // Convert polygon to NED + qDebug() << "Convert polygon"; + QGeoCoordinate tangentOrigin = _polygonPath[0].value(); + for (int i=0; i<_polygonPath.count(); i++) { + double x, y, z; + convertGeoToNed(_polygonPath[i].value(), tangentOrigin, &x, &y, &z); + polygonPoints += Point_t(x, y); + qDebug() << _polygonPath[i].value() << polygonPoints.last().x << polygonPoints.last().y; + } + + // Generate grid + _gridGenerator(polygonPoints, gridPoints); + + // Convert to Geo and set altitude + for (int i=0; i()); + _setExitCoordinate(_gridPoints.last().value()); + } - return true; } -void ComplexMissionItem::_setExitCoordinate(const QGeoCoordinate& coordinate) +void ComplexMissionItem::_gridGenerator(const QList& polygonPoints, QList& gridPoints) { - if (_exitCoordinate != coordinate) { - _exitCoordinate = coordinate; - emit exitCoordinateChanged(coordinate); + // FIXME: Hack implementataion - int itemCount = _missionItems.count(); - if (itemCount > 0) { - _missionItems[itemCount - 1]->setCoordinate(coordinate); + gridPoints.clear(); + + // Convert polygon to bounding square + + Point_t upperLeft = polygonPoints[0]; + Point_t lowerRight = polygonPoints[0]; + for (int i=1; i> lineList; + + double x = upperLeft.x; + double gridSpacing = _gridSpacingFact.rawValue().toDouble(); + while (x < lowerRight.x) { + double yTop = upperLeft.y; + double yBottom = lowerRight.y; + + lineList += qMakePair(Point_t(x, yTop), Point_t(x, yBottom)); + qDebug() << "line" << lineList.last().first.x<< lineList.last().first.y<< lineList.last().second.x<< lineList.last().second.y; + + x += gridSpacing; + } + + // Turn into a path + + for (int i=0; i points = lineList[i]; + + if (i & 1) { + gridPoints << points.second << points.first; + } else { + gridPoints << points.first << points.second; } } } -bool ComplexMissionItem::specifiesCoordinate(void) const +QmlObjectListModel* ComplexMissionItem::getMissionItems(void) const { - return _polygonPath.count() > 2; + QmlObjectListModel* pMissionItems = new QmlObjectListModel; + + int seqNum = _sequenceNumber; + for (int i=0; i<_gridPoints.count(); i++) { + QGeoCoordinate coord = _gridPoints[i].value(); + double altitude = _gridAltitudeFact.rawValue().toDouble(); + + MissionItem* item = new MissionItem(seqNum++, // sequence number + MAV_CMD_NAV_WAYPOINT, // MAV_CMD + MAV_FRAME_GLOBAL_RELATIVE_ALT, // MAV_FRAME + 0.0, 0.0, 0.0, 0.0, // param 1-4 + coord.latitude(), + coord.longitude(), + altitude, + true, // autoContinue + false, // isCurrentItem + pMissionItems); // parent - allow delete on pMissionItems to delete everthing + pMissionItems->append(item); + } + + return pMissionItems; } diff --git a/src/MissionManager/ComplexMissionItem.h b/src/MissionManager/ComplexMissionItem.h index c8bb4b403b6d16a06596127f77101b88191da329..e19e93e31becd9cbb905a6f157f594a22c028b99 100644 --- a/src/MissionManager/ComplexMissionItem.h +++ b/src/MissionManager/ComplexMissionItem.h @@ -26,6 +26,7 @@ #include "VisualMissionItem.h" #include "MissionItem.h" +#include "Fact.h" class ComplexMissionItem : public VisualMissionItem { @@ -35,19 +36,30 @@ public: ComplexMissionItem(Vehicle* vehicle, QObject* parent = NULL); ComplexMissionItem(const ComplexMissionItem& other, QObject* parent = NULL); + Q_PROPERTY(Fact* gridAltitude READ gridAltitude CONSTANT) + Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT) + Q_PROPERTY(Fact* gridSpacing READ gridSpacing CONSTANT) Q_PROPERTY(QVariantList polygonPath READ polygonPath NOTIFY polygonPathChanged) Q_PROPERTY(int lastSequenceNumber READ lastSequenceNumber NOTIFY lastSequenceNumberChanged) + Q_PROPERTY(QVariantList gridPoints READ gridPoints NOTIFY gridPointsChanged) Q_INVOKABLE void clearPolygon(void); Q_INVOKABLE void addPolygonCoordinate(const QGeoCoordinate coordinate); QVariantList polygonPath(void) { return _polygonPath; } + QVariantList gridPoints (void) { return _gridPoints; } - QList& missionItems(void) { return _missionItems; } + Fact* gridAltitude(void) { return &_gridAltitudeFact; } + Fact* gridAngle(void) { return &_gridAngleFact; } + Fact* gridSpacing(void) { return &_gridSpacingFact; } /// @return The last sequence number used by this item. Takes into account child items of the complex item int lastSequenceNumber(void) const; + /// Returns the mission items associated with the complex item. Caller is responsible for freeing. Calling + /// delete on returned QmlObjectListModel will free all memory including internal items. + QmlObjectListModel* getMissionItems(void) const; + /// Load the complex mission item from Json /// @param complexObject Complex mission item json object /// @param[out] errorString Error if load fails @@ -78,22 +90,47 @@ public: signals: void polygonPathChanged(void); void lastSequenceNumberChanged(int lastSequenceNumber); + void altitudeChanged(double altitude); + void gridAngleChanged(double gridAngle); + void gridPointsChanged(void); private: + typedef struct Point_s { + double x; + double y; + + Point_s(double x, double y) { + this->x = x; + this->y = y; + } + } Point_t; + void _clear(void); void _setExitCoordinate(const QGeoCoordinate& coordinate); + void _clearGrid(void); + void _generateGrid(void); + void _gridGenerator(const QList& polygonPoints, QList& gridPoints); int _sequenceNumber; bool _dirty; QVariantList _polygonPath; - QList _missionItems; + QVariantList _gridPoints; QGeoCoordinate _coordinate; QGeoCoordinate _exitCoordinate; + double _altitude; + double _gridAngle; + + Fact _gridAltitudeFact; + Fact _gridAngleFact; + Fact _gridSpacingFact; static const char* _jsonVersionKey; static const char* _jsonTypeKey; static const char* _jsonPolygonKey; static const char* _jsonIdKey; + static const char* _jsonGridAltitudeKey; + static const char* _jsonGridAngleKey; + static const char* _jsonGridSpacingKey; static const char* _complexType; }; diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 29f3f9413dc0e2a4d44374acf9718dc2d3c665d1..12d0c4606f04865d9f69c8b406c712b0a1775e33 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -132,28 +132,28 @@ void MissionController::sendMissionItems(void) { if (_activeVehicle) { // Convert to MissionItems so we can send to vehicle - QList missionItems; - int sequenceNumber = 0; for (int i=0; i<_visualItems->count(); i++) { VisualMissionItem* visualItem = qobject_cast(_visualItems->get(i)); if (visualItem->isSimpleItem()) { - MissionItem& missionItem = qobject_cast(visualItem)->missionItem(); - missionItem.setSequenceNumber(sequenceNumber++); - missionItems.append(&missionItem); + missionItems.append(new MissionItem(qobject_cast(visualItem)->missionItem())); } else { ComplexMissionItem* complexItem = qobject_cast(visualItem); - for (int j=0; jmissionItems().count(); j++) { - MissionItem* missionItem = complexItem->missionItems()[i]; - missionItem->setSequenceNumber(sequenceNumber++); - missionItems.append(missionItem); + QmlObjectListModel* complexMissionItems = complexItem->getMissionItems(); + for (int j=0; jcount(); j++) { + missionItems.append(new MissionItem(*qobject_cast(complexMissionItems->get(j)))); } + delete complexMissionItems; } } _activeVehicle->missionManager()->writeMissionItems(missionItems); _visualItems->setDirty(false); + + for (int i=0; isetSequenceNumber(_nextSequenceNumber()); + newItem->setSequenceNumber(sequenceNumber); newItem->setCoordinate(coordinate); newItem->setCommand(MavlinkQmlSingleton::MAV_CMD_NAV_WAYPOINT); _initVisualItem(newItem); @@ -198,13 +199,14 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i) _recalcAll(); - return _visualItems->count() - 1; + return sequenceNumber; } int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i) { + int sequenceNumber = _nextSequenceNumber(); ComplexMissionItem* newItem = new ComplexMissionItem(_activeVehicle, this); - newItem->setSequenceNumber(_nextSequenceNumber()); + newItem->setSequenceNumber(sequenceNumber); newItem->setCoordinate(coordinate); _initVisualItem(newItem); @@ -213,7 +215,7 @@ int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i _recalcAll(); - return _visualItems->count() - 1; + return sequenceNumber; } void MissionController::removeMissionItem(int index) @@ -771,7 +773,7 @@ void MissionController::_recalcChildItems(void) if (item->specifiesCoordinate()) { item->childItems()->clear(); currentParentItem = item; - } else { + } else if (item->isSimpleItem()) { currentParentItem->childItems()->append(item); } } @@ -860,13 +862,16 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem) if (visualItem->isSimpleItem()) { // We need to track commandChanged on simple item since recalc has special handling for takeoff command - SimpleMissionItem* simpleItem = qobject_cast(visualItem); if (simpleItem) { connect(&simpleItem->missionItem()._commandFact, &Fact::valueChanged, this, &MissionController::_itemCommandChanged); } else { qWarning() << "isSimpleItem == true, yet not SimpleMissionItem"; } + } else { + // We need to track changes of lastSequenceNumber so we can recalc sequence numbers for subsequence items + ComplexMissionItem* complexItem = qobject_cast(visualItem); + connect(complexItem, &ComplexMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence); } } diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h index 05dd1a3e881b331d5a9522a811afd6fb5beb90bf..34956ec9a797311d89335b0e5091bfb94a3853bc 100644 --- a/src/MissionManager/MissionController.h +++ b/src/MissionManager/MissionController.h @@ -59,10 +59,14 @@ public: Q_INVOKABLE void removeAllMissionItems(void); Q_INVOKABLE QStringList getMobileMissionFiles(void); - /// @param i: index to insert at + /// Add a new simple mission item to the list + /// @param i: index to insert at + /// @return Sequence number for new item Q_INVOKABLE int insertSimpleMissionItem(QGeoCoordinate coordinate, int i); - /// @param i: index to insert at + /// Add a new complex mission item to the list + /// @param i: index to insert at + /// @return Sequence number for new item Q_INVOKABLE int insertComplexMissionItem(QGeoCoordinate coordinate, int i); // Property accessors diff --git a/src/MissionManager/SimpleMissionItem.h b/src/MissionManager/SimpleMissionItem.h index 0e6ed0bc8f84c7178a6e6bb99b15b7071c7813d9..88c243fb20888a0d3c298f948fcdb7ee95de2162 100644 --- a/src/MissionManager/SimpleMissionItem.h +++ b/src/MissionManager/SimpleMissionItem.h @@ -117,16 +117,13 @@ public slots: signals: void commandChanged (int command); - void coordinateChanged (const QGeoCoordinate& coordinate); - void exitCoordinateChanged (const QGeoCoordinate& exitCoordinate); - //void dirtyChanged (bool dirty); void frameChanged (int frame); void friendlyEditAllowedChanged (bool friendlyEditAllowed); void headingDegreesChanged (double heading); void rawEditChanged (bool rawEdit); void uiModelChanged (void); void showHomePositionChanged (bool showHomePosition); - + private slots: void _setDirtyFromSignal(void); void _sendCommandChanged(void);