diff --git a/src/MissionManager/QGCMapPolygon.cc b/src/MissionManager/QGCMapPolygon.cc index d3111ac123ba9e758a532a5267865319b10cca15..f1ec6cafc835964a990b054eb4bbe859531b6859 100644 --- a/src/MissionManager/QGCMapPolygon.cc +++ b/src/MissionManager/QGCMapPolygon.cc @@ -29,6 +29,7 @@ QGCMapPolygon::QGCMapPolygon(QObject* parent) , _centerDrag (false) , _ignoreCenterUpdates (false) , _interactive (false) + , _resetActive (false) { _init(); } @@ -39,6 +40,7 @@ QGCMapPolygon::QGCMapPolygon(const QGCMapPolygon& other, QObject* parent) , _centerDrag (false) , _ignoreCenterUpdates (false) , _interactive (false) + , _resetActive (false) { *this = other; @@ -265,11 +267,14 @@ void QGCMapPolygon::appendVertices(const QList& coordinates) { QList objects; + _beginResetIfNotActive(); for (const QGeoCoordinate& coordinate: coordinates) { objects.append(new QGCQGeoCoordinate(coordinate, this)); _polygonPath.append(QVariant::fromValue(coordinate)); } _polygonModel.append(objects); + _endResetIfNotActive(); + emit pathChanged(); } @@ -448,8 +453,10 @@ void QGCMapPolygon::offset(double distance) } // Update internals + _beginResetIfNotActive(); clear(); appendVertices(rgNewPolygon); + _endResetIfNotActive(); } bool QGCMapPolygon::loadKMLOrSHPFile(const QString& file) @@ -461,8 +468,10 @@ bool QGCMapPolygon::loadKMLOrSHPFile(const QString& file) return false; } + _beginResetIfNotActive(); clear(); appendVertices(rgCoords); + _endResetIfNotActive(); return true; } @@ -509,7 +518,37 @@ void QGCMapPolygon::verifyClockwiseWinding(void) rgReversed.prepend(varCoord.value()); } + _beginResetIfNotActive(); clear(); appendVertices(rgReversed); + _endResetIfNotActive(); + } +} + +void QGCMapPolygon::beginReset(void) +{ + _resetActive = true; + _polygonModel.beginReset(); +} + +void QGCMapPolygon::endReset(void) +{ + _resetActive = false; + _polygonModel.endReset(); + emit pathChanged(); + emit centerChanged(_center); +} + +void QGCMapPolygon::_beginResetIfNotActive(void) +{ + if (!_resetActive) { + beginReset(); + } +} + +void QGCMapPolygon::_endResetIfNotActive(void) +{ + if (!_resetActive) { + endReset(); } } diff --git a/src/MissionManager/QGCMapPolygon.h b/src/MissionManager/QGCMapPolygon.h index d112a58d2ef0f86c35ae55783a33a0d1d7a54023..4a023eb4a6ae0d8666abf8ee392a7fd4f5894581 100644 --- a/src/MissionManager/QGCMapPolygon.h +++ b/src/MissionManager/QGCMapPolygon.h @@ -36,6 +36,8 @@ public: Q_PROPERTY(QGeoCoordinate center READ center WRITE setCenter NOTIFY centerChanged) Q_PROPERTY(bool centerDrag READ centerDrag WRITE setCenterDrag NOTIFY centerDragChanged) Q_PROPERTY(bool interactive READ interactive WRITE setInteractive NOTIFY interactiveChanged) + Q_PROPERTY(bool isValid READ isValid NOTIFY countChanged) + Q_PROPERTY(bool empty READ empty NOTIFY countChanged) Q_INVOKABLE void clear(void); Q_INVOKABLE void appendVertex(const QGeoCoordinate& coordinate); @@ -69,6 +71,9 @@ public: /// Adjust polygon winding order to be clockwise (if needed) Q_INVOKABLE void verifyClockwiseWinding(void); + Q_INVOKABLE void beginReset (void); + Q_INVOKABLE void endReset (void); + /// Saves the polygon to the json object. /// @param json Json object to save to void saveToJson(QJsonObject& json); @@ -94,6 +99,8 @@ public: QGeoCoordinate center (void) const { return _center; } bool centerDrag (void) const { return _centerDrag; } bool interactive (void) const { return _interactive; } + bool isValid (void) const { return _polygonModel.count() >= 3; } + bool empty (void) const { return _polygonModel.count() == 0; } QVariantList path (void) const { return _polygonPath; } QmlObjectListModel* qmlPathModel(void) { return &_polygonModel; } @@ -122,10 +129,12 @@ private slots: void _updateCenter(void); private: - void _init(void); - QPolygonF _toPolygonF(void) const; - QGeoCoordinate _coordFromPointF(const QPointF& point) const; - QPointF _pointFFromCoord(const QGeoCoordinate& coordinate) const; + void _init (void); + QPolygonF _toPolygonF (void) const; + QGeoCoordinate _coordFromPointF (const QPointF& point) const; + QPointF _pointFFromCoord (const QGeoCoordinate& coordinate) const; + void _beginResetIfNotActive (void); + void _endResetIfNotActive (void); QVariantList _polygonPath; QmlObjectListModel _polygonModel; @@ -134,6 +143,7 @@ private: bool _centerDrag; bool _ignoreCenterUpdates; bool _interactive; + bool _resetActive; }; #endif diff --git a/src/MissionManager/QGCMapPolygonVisuals.qml b/src/MissionManager/QGCMapPolygonVisuals.qml index 898d146fceaabf23152b7a7bd4fe652018408a22..3841bec8a2ed78e7ef8b63753b5f2194bdb14ec8 100644 --- a/src/MissionManager/QGCMapPolygonVisuals.qml +++ b/src/MissionManager/QGCMapPolygonVisuals.qml @@ -7,11 +7,12 @@ * ****************************************************************************/ -import QtQuick 2.11 -import QtQuick.Controls 2.4 -import QtLocation 5.3 -import QtPositioning 5.3 -import QtQuick.Dialogs 1.2 +import QtQuick 2.11 +import QtQuick.Controls 2.4 +import QtLocation 5.3 +import QtPositioning 5.3 +import QtQuick.Dialogs 1.2 +import QtQuick.Layouts 1.11 import QGroundControl 1.0 import QGroundControl.ScreenTools 1.0 @@ -32,64 +33,74 @@ Item { property int borderWidth: 0 property color borderColor: "black" - property var _polygonComponent - property var _dragHandlesComponent - property var _splitHandlesComponent - property var _centerDragHandleComponent - property bool _circle: false + property bool _circleMode: false property real _circleRadius + property bool _circleRadiusDrag: false + property var _circleRadiusDragCoord: QtPositioning.coordinate() property bool _editCircleRadius: false + property bool _traceMode: false + property string _instructionText: _polygonToolsText + property var _savedVertices: [ ] + property bool _savedCircleMode property real _zorderDragHandle: QGroundControl.zOrderMapItems + 3 // Highest to prevent splitting when items overlap property real _zorderSplitHandle: QGroundControl.zOrderMapItems + 2 property real _zorderCenterHandle: QGroundControl.zOrderMapItems + 1 // Lowest such that drag or split takes precedence - function addVisuals() { - _polygonComponent = polygonComponent.createObject(mapControl) - mapControl.addMapItem(_polygonComponent) + readonly property string _polygonToolsText: qsTr("Polygon Tools") + readonly property string _traceText: qsTr("Click in the map to add vertices. Click 'Done Tracing' when finished.") + + function addCommonVisuals() { + if (_objMgrCommonVisuals.empty) { + _objMgrCommonVisuals.createObject(polygonComponent, mapControl, true) + } } - function removeVisuals() { - _polygonComponent.destroy() + function removeCommonVisuals() { + _objMgrCommonVisuals.destroyObjects() } - function addHandles() { - if (!_dragHandlesComponent) { - _dragHandlesComponent = dragHandlesComponent.createObject(mapControl) - _splitHandlesComponent = splitHandlesComponent.createObject(mapControl) - _centerDragHandleComponent = centerDragHandleComponent.createObject(mapControl) + function addEditingVisuals() { + if (_objMgrEditingVisuals.empty) { + _objMgrEditingVisuals.createObjects([ dragHandlesComponent, splitHandlesComponent, centerDragHandleComponent ], mapControl, false /* addToMap */) } } - function removeHandles() { - if (_dragHandlesComponent) { - _dragHandlesComponent.destroy() - _dragHandlesComponent = undefined - } - if (_splitHandlesComponent) { - _splitHandlesComponent.destroy() - _splitHandlesComponent = undefined + function removeEditingVisuals() { + _objMgrEditingVisuals.destroyObjects() + } + + + function addToolVisuals() { + if (_objMgrToolVisuals.empty) { + _objMgrToolVisuals.createObject(editHeaderComponent, mapControl) } - if (_centerDragHandleComponent) { - _centerDragHandleComponent.destroy() - _centerDragHandleComponent = undefined + } + + function removeToolVisuals() { + _objMgrToolVisuals.destroyObjects() + } + + function addCircleVisuals() { + if (_objMgrCircleVisuals.empty) { + _objMgrCircleVisuals.createObject(radiusVisualsComponent, mapControl) } } /// Calculate the default/initial 4 sided polygon function defaultPolygonVertices() { // Initial polygon is inset to take 2/3rds space - var rect = Qt.rect(map.centerViewport.x, map.centerViewport.y, map.centerViewport.width, map.centerViewport.height) + var rect = Qt.rect(mapControl.centerViewport.x, mapControl.centerViewport.y, mapControl.centerViewport.width, mapControl.centerViewport.height) rect.x += (rect.width * 0.25) / 2 rect.y += (rect.height * 0.25) / 2 rect.width *= 0.75 rect.height *= 0.75 - var centerCoord = map.toCoordinate(Qt.point(rect.x + (rect.width / 2), rect.y + (rect.height / 2)), false /* clipToViewPort */) - var topLeftCoord = map.toCoordinate(Qt.point(rect.x, rect.y), false /* clipToViewPort */) - var topRightCoord = map.toCoordinate(Qt.point(rect.x + rect.width, rect.y), false /* clipToViewPort */) - var bottomLeftCoord = map.toCoordinate(Qt.point(rect.x, rect.y + rect.height), false /* clipToViewPort */) - var bottomRightCoord = map.toCoordinate(Qt.point(rect.x + rect.width, rect.y + rect.height), false /* clipToViewPort */) + var centerCoord = mapControl.toCoordinate(Qt.point(rect.x + (rect.width / 2), rect.y + (rect.height / 2)), false /* clipToViewPort */) + var topLeftCoord = mapControl.toCoordinate(Qt.point(rect.x, rect.y), false /* clipToViewPort */) + var topRightCoord = mapControl.toCoordinate(Qt.point(rect.x + rect.width, rect.y), false /* clipToViewPort */) + var bottomLeftCoord = mapControl.toCoordinate(Qt.point(rect.x, rect.y + rect.height), false /* clipToViewPort */) + var bottomRightCoord = mapControl.toCoordinate(Qt.point(rect.x + rect.width, rect.y + rect.height), false /* clipToViewPort */) // Initial polygon has max width and height of 3000 meters var halfWidthMeters = Math.min(topLeftCoord.distanceTo(topRightCoord), 3000) / 2 @@ -102,82 +113,111 @@ Item { return [ topLeftCoord, topRightCoord, bottomRightCoord, bottomLeftCoord, centerCoord ] } - /// Add an initial 4 sided polygon - function addInitialPolygon() { - if (mapPolygon.count < 3) { - initialVertices = defaultPolygonVertices() - mapPolygon.appendVertex(initialVertices[0]) - mapPolygon.appendVertex(initialVertices[1]) - mapPolygon.appendVertex(initialVertices[2]) - mapPolygon.appendVertex(initialVertices[3]) - } - } - /// Reset polygon back to initial default - function resetPolygon() { - var initialVertices = defaultPolygonVertices() + function _resetPolygon() { + mapPolygon.beginReset() mapPolygon.clear() + var initialVertices = defaultPolygonVertices() for (var i=0; i<4; i++) { mapPolygon.appendVertex(initialVertices[i]) } - _circle = false + mapPolygon.endReset() + _circleMode = false } - function setCircleRadius(center, radius) { + function _createCircularPolygon(center, radius) { var unboundCenter = center.atDistanceAndAzimuth(0, 0) - _circleRadius = radius var segments = 16 var angleIncrement = 360 / segments var angle = 0 + mapPolygon.beginReset() mapPolygon.clear() + _circleRadius = radius for (var i=0; i= 0) { @@ -216,38 +256,23 @@ Item { visible: removeVertexItem.visible } - QGCMenuItem { - text: qsTr("Circle" ) - onTriggered: resetCircle() - } - - QGCMenuItem { - text: qsTr("Polygon") - onTriggered: resetPolygon() - } - QGCMenuItem { text: qsTr("Set radius..." ) - visible: _circle + visible: _circleMode onTriggered: _editCircleRadius = true } QGCMenuItem { text: qsTr("Edit position..." ) - visible: _circle + visible: _circleMode onTriggered: mainWindow.showComponentDialog(editCenterPositionDialog, qsTr("Edit Center Position"), mainWindow.showDialogDefaultWidth, StandardButton.Close) } QGCMenuItem { text: qsTr("Edit position..." ) - visible: !_circle && menu._editingVertexIndex >= 0 + visible: !_circleMode && menu._editingVertexIndex >= 0 onTriggered: mainWindow.showComponentDialog(editVertexPositionDialog, qsTr("Edit Vertex Position"), mainWindow.showDialogDefaultWidth, StandardButton.Close) } - - QGCMenuItem { - text: qsTr("Load KML/SHP...") - onTriggered: kmlOrSHPLoadDialog.openForLoad() - } } Component { @@ -269,7 +294,7 @@ Item { id: mapQuickItem anchorPoint.x: sourceItem.width / 2 anchorPoint.y: sourceItem.height / 2 - visible: !_circle + visible: !_circleMode property int vertexIndex @@ -323,7 +348,7 @@ Item { id: dragArea mapControl: _root.mapControl z: _zorderDragHandle - visible: !_circle + visible: !_circleMode onDragStop: mapPolygon.verifyClockwiseWinding() property int polygonVertex @@ -380,7 +405,7 @@ Item { anchorPoint.x: dragHandle.width / 2 anchorPoint.y: dragHandle.height / 2 z: _zorderDragHandle - visible: !_circle + visible: !_circleMode property int polygonVertex @@ -463,74 +488,219 @@ Item { onItemCoordinateChanged: mapPolygon.center = itemCoordinate onDragStart: mapPolygon.centerDrag = true onDragStop: mapPolygon.centerDrag = false + } + } - onClicked: menu.popupCenter() + Component { + id: centerDragHandleComponent - function setRadiusFromDialog() { - var radius = QGroundControl.appSettingsDistanceUnitsToMeters(radiusField.text) - setCircleRadius(mapPolygon.center, radius) - _editCircleRadius = false + Item { + property var dragHandle + property var dragArea + + Component.onCompleted: { + dragHandle = centerDragHandle.createObject(mapControl) + dragHandle.coordinate = Qt.binding(function() { return mapPolygon.center }) + mapControl.addMapItem(dragHandle) + dragArea = centerDragAreaComponent.createObject(mapControl, { "itemIndicator": dragHandle, "itemCoordinate": mapPolygon.center }) + } + + Component.onDestruction: { + dragHandle.destroy() + dragArea.destroy() } + } + } + + Component { + id: editHeaderComponent + + Item { + x: mapControl.centerViewport.left + _viewportMargins + y: mapControl.centerViewport.top + _viewportMargins + width: mapControl.centerViewport.width - (_viewportMargins * 2) + height: editHeaderRowLayout.y + editHeaderRowLayout.height + _viewportMargins + z: QGroundControl.zOrderMapItems + 2 + + property real _radius: ScreenTools.defaultFontPixelWidth / 2 + property real _viewportMargins: ScreenTools.defaultFontPixelWidth Rectangle { - anchors.margins: _margin - anchors.left: parent.right - width: radiusColumn.width + (_margin *2) - height: radiusColumn.height + (_margin *2) - color: qgcPal.window - border.color: qgcPal.text - visible: _editCircleRadius - - Column { - id: radiusColumn - anchors.margins: _margin - anchors.left: parent.left - anchors.top: parent.top - spacing: _margin - - QGCLabel { text: qsTr("Radius:") } - - QGCTextField { - id: radiusField - showUnits: true - unitsLabel: QGroundControl.appSettingsDistanceUnitsString - text: QGroundControl.metersToAppSettingsDistanceUnits(_circleRadius).toFixed(2) - onEditingFinished: setRadiusFromDialog() - inputMethodHints: Qt.ImhFormattedNumbersOnly + anchors.fill: parent + radius: _radius + color: "white" + opacity: 0.75 + } + + RowLayout { + id: editHeaderRowLayout + anchors.margins: _viewportMargins + anchors.top: parent.top + anchors.left: parent.left + anchors.right: parent.right + + QGCButton { + text: qsTr("Basic Polygon") + visible: !_traceMode + onClicked: _resetPolygon() + } + + QGCButton { + text: qsTr("Circular Polygon") + visible: !_traceMode + onClicked: _resetCircle() + } + + QGCButton { + text: _traceMode ? qsTr("Done Tracing") : qsTr("Trace Polygon") + onClicked: { + if (_traceMode) { + if (mapPolygon.count < 3) { + _restorePreviousVertices() + } + _traceMode = false + } else { + _saveCurrentVertices() + _circleMode = false + _traceMode = true + mapPolygon.clear(); + } } } + QGCButton { + text: qsTr("Load KML/SHP...") + onClicked: kmlOrSHPLoadDialog.openForLoad() + visible: !_traceMode + } + QGCLabel { - anchors.right: radiusColumn.right - anchors.top: radiusColumn.top - text: "X" + id: instructionLabel + color: "black" + text: _instructionText + Layout.fillWidth: true + } + } + } + } + + // Mouse area to capture clicks for tracing a polygon + Component { + id: traceMouseAreaComponent + + MouseArea { + anchors.fill: map + preventStealing: true + z: QGroundControl.zOrderMapItems + 1 // Over item indicators + + onClicked: { + if (mouse.button === Qt.LeftButton) { + mapPolygon.appendVertex(mapControl.toCoordinate(Qt.point(mouse.x, mouse.y), false /* clipToViewPort */)) + } + } + } + } + + Component { + id: radiusDragHandleComponent + + MapQuickItem { + id: mapQuickItem + anchorPoint.x: dragHandle.width / 2 + anchorPoint.y: dragHandle.height / 2 + z: QGroundControl.zOrderMapItems + 2 + + sourceItem: Rectangle { + id: dragHandle + width: ScreenTools.defaultFontPixelHeight * 1.5 + height: width + radius: width / 2 + color: "white" + opacity: .90 + } + } + } - QGCMouseArea { - fillItem: parent - onClicked: setRadiusFromDialog() + Component { + id: radiusDragAreaComponent + + MissionItemIndicatorDrag { + mapControl: _root.mapControl + + property real _lastRadius + + onItemCoordinateChanged: { + var radius = mapPolygon.center.distanceTo(itemCoordinate) + // Prevent signalling re-entrancy + if (!_circleRadiusDrag && Math.abs(radius - _lastRadius) > 0.1) { + _circleRadiusDrag = true + _createCircularPolygon(mapPolygon.center, radius) + _circleRadiusDragCoord = itemCoordinate + _circleRadiusDrag = false + _lastRadius = radius + } + } + + /* + onItemCoordinateChanged: delayTimer.radius = mapPolygon.center.distanceTo(itemCoordinate) + + onDragStart: delayTimer.start() + onDragStop: { delayTimer.stop(); delayTimer.update() } + + // Use a delayed update to increase performance of redraw while dragging + Timer { + id: delayTimer + interval: 100 + repeat: true + + property real radius + property real _lastRadius + + onRadiusChanged: console.log(radius) + + function update() { + // Prevent signalling re-entrancy + if (!_circleRadiusDrag && radius != _lastRadius) { + _circleRadiusDrag = true + _createCircularPolygon(mapPolygon.center, radius) + _circleRadiusDragCoord = itemCoordinate + _circleRadiusDrag = false + _lastRadius = radius } } + + onTriggered: update() } + */ } } Component { - id: centerDragHandleComponent + id: radiusVisualsComponent Item { - property var dragHandle - property var dragArea + property var circleCenterCoord: mapPolygon.center - Component.onCompleted: { - dragHandle = centerDragHandle.createObject(mapControl) - dragHandle.coordinate = Qt.binding(function() { return mapPolygon.center }) - mapControl.addMapItem(dragHandle) - dragArea = centerDragAreaComponent.createObject(mapControl, { "itemIndicator": dragHandle, "itemCoordinate": mapPolygon.center }) + function _calcRadiusDragCoord() { + _circleRadiusDragCoord = circleCenterCoord.atDistanceAndAzimuth(_circleRadius, 90) } - Component.onDestruction: { - dragHandle.destroy() - dragArea.destroy() + onCircleCenterCoordChanged: { + if (!_circleRadiusDrag) { + _calcRadiusDragCoord() + } + } + + QGCDynamicObjectManager { + id: _objMgr + } + + Component.onCompleted: { + _calcRadiusDragCoord() + var radiusDragHandle = _objMgr.createObject(radiusDragHandleComponent, mapControl, true) + radiusDragHandle.coordinate = Qt.binding(function() { return _circleRadiusDragCoord }) + var radiusDragIndicator = radiusDragAreaComponent.createObject(mapControl, { "itemIndicator": radiusDragHandle, "itemCoordinate": _circleRadiusDragCoord }) + _objMgr.addObject(radiusDragIndicator) } } }