Browse Source

New editing tools support

QGC4.4
Don Gagne 6 years ago
parent
commit
fc2260ab65
  1. 39
      src/MissionManager/QGCMapPolygon.cc
  2. 18
      src/MissionManager/QGCMapPolygon.h
  3. 450
      src/MissionManager/QGCMapPolygonVisuals.qml

39
src/MissionManager/QGCMapPolygon.cc

@ -29,6 +29,7 @@ QGCMapPolygon::QGCMapPolygon(QObject* parent)
, _centerDrag (false) , _centerDrag (false)
, _ignoreCenterUpdates (false) , _ignoreCenterUpdates (false)
, _interactive (false) , _interactive (false)
, _resetActive (false)
{ {
_init(); _init();
} }
@ -39,6 +40,7 @@ QGCMapPolygon::QGCMapPolygon(const QGCMapPolygon& other, QObject* parent)
, _centerDrag (false) , _centerDrag (false)
, _ignoreCenterUpdates (false) , _ignoreCenterUpdates (false)
, _interactive (false) , _interactive (false)
, _resetActive (false)
{ {
*this = other; *this = other;
@ -265,11 +267,14 @@ void QGCMapPolygon::appendVertices(const QList<QGeoCoordinate>& coordinates)
{ {
QList<QObject*> objects; QList<QObject*> objects;
_beginResetIfNotActive();
for (const QGeoCoordinate& coordinate: coordinates) { for (const QGeoCoordinate& coordinate: coordinates) {
objects.append(new QGCQGeoCoordinate(coordinate, this)); objects.append(new QGCQGeoCoordinate(coordinate, this));
_polygonPath.append(QVariant::fromValue(coordinate)); _polygonPath.append(QVariant::fromValue(coordinate));
} }
_polygonModel.append(objects); _polygonModel.append(objects);
_endResetIfNotActive();
emit pathChanged(); emit pathChanged();
} }
@ -448,8 +453,10 @@ void QGCMapPolygon::offset(double distance)
} }
// Update internals // Update internals
_beginResetIfNotActive();
clear(); clear();
appendVertices(rgNewPolygon); appendVertices(rgNewPolygon);
_endResetIfNotActive();
} }
bool QGCMapPolygon::loadKMLOrSHPFile(const QString& file) bool QGCMapPolygon::loadKMLOrSHPFile(const QString& file)
@ -461,8 +468,10 @@ bool QGCMapPolygon::loadKMLOrSHPFile(const QString& file)
return false; return false;
} }
_beginResetIfNotActive();
clear(); clear();
appendVertices(rgCoords); appendVertices(rgCoords);
_endResetIfNotActive();
return true; return true;
} }
@ -509,7 +518,37 @@ void QGCMapPolygon::verifyClockwiseWinding(void)
rgReversed.prepend(varCoord.value<QGeoCoordinate>()); rgReversed.prepend(varCoord.value<QGeoCoordinate>());
} }
_beginResetIfNotActive();
clear(); clear();
appendVertices(rgReversed); 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();
} }
} }

18
src/MissionManager/QGCMapPolygon.h

@ -36,6 +36,8 @@ public:
Q_PROPERTY(QGeoCoordinate center READ center WRITE setCenter NOTIFY centerChanged) Q_PROPERTY(QGeoCoordinate center READ center WRITE setCenter NOTIFY centerChanged)
Q_PROPERTY(bool centerDrag READ centerDrag WRITE setCenterDrag NOTIFY centerDragChanged) Q_PROPERTY(bool centerDrag READ centerDrag WRITE setCenterDrag NOTIFY centerDragChanged)
Q_PROPERTY(bool interactive READ interactive WRITE setInteractive NOTIFY interactiveChanged) 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 clear(void);
Q_INVOKABLE void appendVertex(const QGeoCoordinate& coordinate); Q_INVOKABLE void appendVertex(const QGeoCoordinate& coordinate);
@ -69,6 +71,9 @@ public:
/// Adjust polygon winding order to be clockwise (if needed) /// Adjust polygon winding order to be clockwise (if needed)
Q_INVOKABLE void verifyClockwiseWinding(void); Q_INVOKABLE void verifyClockwiseWinding(void);
Q_INVOKABLE void beginReset (void);
Q_INVOKABLE void endReset (void);
/// Saves the polygon to the json object. /// Saves the polygon to the json object.
/// @param json Json object to save to /// @param json Json object to save to
void saveToJson(QJsonObject& json); void saveToJson(QJsonObject& json);
@ -94,6 +99,8 @@ public:
QGeoCoordinate center (void) const { return _center; } QGeoCoordinate center (void) const { return _center; }
bool centerDrag (void) const { return _centerDrag; } bool centerDrag (void) const { return _centerDrag; }
bool interactive (void) const { return _interactive; } 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; } QVariantList path (void) const { return _polygonPath; }
QmlObjectListModel* qmlPathModel(void) { return &_polygonModel; } QmlObjectListModel* qmlPathModel(void) { return &_polygonModel; }
@ -122,10 +129,12 @@ private slots:
void _updateCenter(void); void _updateCenter(void);
private: private:
void _init(void); void _init (void);
QPolygonF _toPolygonF(void) const; QPolygonF _toPolygonF (void) const;
QGeoCoordinate _coordFromPointF(const QPointF& point) const; QGeoCoordinate _coordFromPointF (const QPointF& point) const;
QPointF _pointFFromCoord(const QGeoCoordinate& coordinate) const; QPointF _pointFFromCoord (const QGeoCoordinate& coordinate) const;
void _beginResetIfNotActive (void);
void _endResetIfNotActive (void);
QVariantList _polygonPath; QVariantList _polygonPath;
QmlObjectListModel _polygonModel; QmlObjectListModel _polygonModel;
@ -134,6 +143,7 @@ private:
bool _centerDrag; bool _centerDrag;
bool _ignoreCenterUpdates; bool _ignoreCenterUpdates;
bool _interactive; bool _interactive;
bool _resetActive;
}; };
#endif #endif

450
src/MissionManager/QGCMapPolygonVisuals.qml

@ -7,11 +7,12 @@
* *
****************************************************************************/ ****************************************************************************/
import QtQuick 2.11 import QtQuick 2.11
import QtQuick.Controls 2.4 import QtQuick.Controls 2.4
import QtLocation 5.3 import QtLocation 5.3
import QtPositioning 5.3 import QtPositioning 5.3
import QtQuick.Dialogs 1.2 import QtQuick.Dialogs 1.2
import QtQuick.Layouts 1.11
import QGroundControl 1.0 import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
@ -32,64 +33,74 @@ Item {
property int borderWidth: 0 property int borderWidth: 0
property color borderColor: "black" property color borderColor: "black"
property var _polygonComponent property bool _circleMode: false
property var _dragHandlesComponent
property var _splitHandlesComponent
property var _centerDragHandleComponent
property bool _circle: false
property real _circleRadius property real _circleRadius
property bool _circleRadiusDrag: false
property var _circleRadiusDragCoord: QtPositioning.coordinate()
property bool _editCircleRadius: false 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 _zorderDragHandle: QGroundControl.zOrderMapItems + 3 // Highest to prevent splitting when items overlap
property real _zorderSplitHandle: QGroundControl.zOrderMapItems + 2 property real _zorderSplitHandle: QGroundControl.zOrderMapItems + 2
property real _zorderCenterHandle: QGroundControl.zOrderMapItems + 1 // Lowest such that drag or split takes precedence property real _zorderCenterHandle: QGroundControl.zOrderMapItems + 1 // Lowest such that drag or split takes precedence
function addVisuals() { readonly property string _polygonToolsText: qsTr("Polygon Tools")
_polygonComponent = polygonComponent.createObject(mapControl) readonly property string _traceText: qsTr("Click in the map to add vertices. Click 'Done Tracing' when finished.")
mapControl.addMapItem(_polygonComponent)
function addCommonVisuals() {
if (_objMgrCommonVisuals.empty) {
_objMgrCommonVisuals.createObject(polygonComponent, mapControl, true)
}
} }
function removeVisuals() { function removeCommonVisuals() {
_polygonComponent.destroy() _objMgrCommonVisuals.destroyObjects()
} }
function addHandles() { function addEditingVisuals() {
if (!_dragHandlesComponent) { if (_objMgrEditingVisuals.empty) {
_dragHandlesComponent = dragHandlesComponent.createObject(mapControl) _objMgrEditingVisuals.createObjects([ dragHandlesComponent, splitHandlesComponent, centerDragHandleComponent ], mapControl, false /* addToMap */)
_splitHandlesComponent = splitHandlesComponent.createObject(mapControl)
_centerDragHandleComponent = centerDragHandleComponent.createObject(mapControl)
} }
} }
function removeHandles() { function removeEditingVisuals() {
if (_dragHandlesComponent) { _objMgrEditingVisuals.destroyObjects()
_dragHandlesComponent.destroy() }
_dragHandlesComponent = undefined
}
if (_splitHandlesComponent) { function addToolVisuals() {
_splitHandlesComponent.destroy() if (_objMgrToolVisuals.empty) {
_splitHandlesComponent = undefined _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 /// Calculate the default/initial 4 sided polygon
function defaultPolygonVertices() { function defaultPolygonVertices() {
// Initial polygon is inset to take 2/3rds space // 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.x += (rect.width * 0.25) / 2
rect.y += (rect.height * 0.25) / 2 rect.y += (rect.height * 0.25) / 2
rect.width *= 0.75 rect.width *= 0.75
rect.height *= 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 centerCoord = mapControl.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 topLeftCoord = mapControl.toCoordinate(Qt.point(rect.x, rect.y), false /* clipToViewPort */)
var topRightCoord = map.toCoordinate(Qt.point(rect.x + rect.width, rect.y), false /* clipToViewPort */) var topRightCoord = mapControl.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 bottomLeftCoord = mapControl.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 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 // Initial polygon has max width and height of 3000 meters
var halfWidthMeters = Math.min(topLeftCoord.distanceTo(topRightCoord), 3000) / 2 var halfWidthMeters = Math.min(topLeftCoord.distanceTo(topRightCoord), 3000) / 2
@ -102,82 +113,111 @@ Item {
return [ topLeftCoord, topRightCoord, bottomRightCoord, bottomLeftCoord, centerCoord ] 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 /// Reset polygon back to initial default
function resetPolygon() { function _resetPolygon() {
var initialVertices = defaultPolygonVertices() mapPolygon.beginReset()
mapPolygon.clear() mapPolygon.clear()
var initialVertices = defaultPolygonVertices()
for (var i=0; i<4; i++) { for (var i=0; i<4; i++) {
mapPolygon.appendVertex(initialVertices[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) var unboundCenter = center.atDistanceAndAzimuth(0, 0)
_circleRadius = radius
var segments = 16 var segments = 16
var angleIncrement = 360 / segments var angleIncrement = 360 / segments
var angle = 0 var angle = 0
mapPolygon.beginReset()
mapPolygon.clear() mapPolygon.clear()
_circleRadius = radius
for (var i=0; i<segments; i++) { for (var i=0; i<segments; i++) {
var vertex = unboundCenter.atDistanceAndAzimuth(_circleRadius, angle) var vertex = unboundCenter.atDistanceAndAzimuth(radius, angle)
mapPolygon.appendVertex(vertex) mapPolygon.appendVertex(vertex)
angle += angleIncrement angle += angleIncrement
} }
_circle = true mapPolygon.endReset()
_circleMode = true
} }
/// Reset polygon to a circle which fits within initial polygon /// Reset polygon to a circle which fits within initial polygon
function resetCircle() { function _resetCircle() {
var initialVertices = defaultPolygonVertices() var initialVertices = defaultPolygonVertices()
var width = initialVertices[0].distanceTo(initialVertices[1]) var width = initialVertices[0].distanceTo(initialVertices[1])
var height = initialVertices[1].distanceTo(initialVertices[2]) var height = initialVertices[1].distanceTo(initialVertices[2])
var radius = Math.min(width, height) / 2 var radius = Math.min(width, height) / 2
var center = initialVertices[4] var center = initialVertices[4]
setCircleRadius(center, radius) _createCircularPolygon(center, radius)
} }
onInteractiveChanged: { function _handleInteractiveChanged() {
if (interactive) { if (interactive) {
addHandles() addEditingVisuals()
addToolVisuals()
} else { } else {
removeHandles() _traceMode = false
removeEditingVisuals()
removeToolVisuals()
} }
} }
Component.onCompleted: { function _saveCurrentVertices() {
addVisuals() _savedVertices = [ ]
if (interactive) { _savedCircleMode = _circleMode
addHandles() for (var i=0; i<mapPolygon.count; i++) {
_savedVertices.push(mapPolygon.vertexCoordinate(i))
}
}
function _restorePreviousVertices() {
mapPolygon.beginReset()
mapPolygon.clear()
for (var i=0; i<_savedVertices.length; i++) {
mapPolygon.appendVertex(_savedVertices[i])
}
mapPolygon.endReset()
_circleMode = _savedCircleMode
}
onInteractiveChanged: _handleInteractiveChanged()
on_TraceModeChanged: {
if (_traceMode) {
_instructionText = _traceText
_objMgrTraceVisuals.createObject(traceMouseAreaComponent, mapControl, false)
} else {
_instructionText = _polygonToolsText
_objMgrTraceVisuals.destroyObjects()
}
}
on_CircleModeChanged: {
if (_circleMode) {
addCircleVisuals()
} else {
_objMgrCircleVisuals.destroyObjects()
} }
} }
Component.onDestruction: { Component.onCompleted: {
removeVisuals() addCommonVisuals()
removeHandles() _handleInteractiveChanged()
} }
QGCDynamicObjectManager { id: _objMgrCommonVisuals }
QGCDynamicObjectManager { id: _objMgrToolVisuals }
QGCDynamicObjectManager { id: _objMgrEditingVisuals }
QGCDynamicObjectManager { id: _objMgrTraceVisuals }
QGCDynamicObjectManager { id: _objMgrCircleVisuals }
QGCPalette { id: qgcPal } QGCPalette { id: qgcPal }
QGCFileDialog { KMLOrSHPFileDialog {
id: kmlOrSHPLoadDialog id: kmlOrSHPLoadDialog
folder: QGroundControl.settingsManager.appSettings.missionSavePath
title: qsTr("Select Polygon File") title: qsTr("Select Polygon File")
selectExisting: true selectExisting: true
nameFilters: ShapeFileHelper.fileDialogKMLOrSHPFilters
fileExtension: QGroundControl.settingsManager.appSettings.kmlFileExtension
fileExtension2: QGroundControl.settingsManager.appSettings.shpFileExtension
onAcceptedForLoad: { onAcceptedForLoad: {
mapPolygon.loadKMLOrSHPFile(file) mapPolygon.loadKMLOrSHPFile(file)
@ -203,7 +243,7 @@ Item {
QGCMenuItem { QGCMenuItem {
id: removeVertexItem id: removeVertexItem
visible: !_circle visible: !_circleMode
text: qsTr("Remove vertex") text: qsTr("Remove vertex")
onTriggered: { onTriggered: {
if (menu._editingVertexIndex >= 0) { if (menu._editingVertexIndex >= 0) {
@ -217,37 +257,22 @@ Item {
} }
QGCMenuItem { QGCMenuItem {
text: qsTr("Circle" )
onTriggered: resetCircle()
}
QGCMenuItem {
text: qsTr("Polygon")
onTriggered: resetPolygon()
}
QGCMenuItem {
text: qsTr("Set radius..." ) text: qsTr("Set radius..." )
visible: _circle visible: _circleMode
onTriggered: _editCircleRadius = true onTriggered: _editCircleRadius = true
} }
QGCMenuItem { QGCMenuItem {
text: qsTr("Edit position..." ) text: qsTr("Edit position..." )
visible: _circle visible: _circleMode
onTriggered: mainWindow.showComponentDialog(editCenterPositionDialog, qsTr("Edit Center Position"), mainWindow.showDialogDefaultWidth, StandardButton.Close) onTriggered: mainWindow.showComponentDialog(editCenterPositionDialog, qsTr("Edit Center Position"), mainWindow.showDialogDefaultWidth, StandardButton.Close)
} }
QGCMenuItem { QGCMenuItem {
text: qsTr("Edit position..." ) 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) onTriggered: mainWindow.showComponentDialog(editVertexPositionDialog, qsTr("Edit Vertex Position"), mainWindow.showDialogDefaultWidth, StandardButton.Close)
} }
QGCMenuItem {
text: qsTr("Load KML/SHP...")
onTriggered: kmlOrSHPLoadDialog.openForLoad()
}
} }
Component { Component {
@ -269,7 +294,7 @@ Item {
id: mapQuickItem id: mapQuickItem
anchorPoint.x: sourceItem.width / 2 anchorPoint.x: sourceItem.width / 2
anchorPoint.y: sourceItem.height / 2 anchorPoint.y: sourceItem.height / 2
visible: !_circle visible: !_circleMode
property int vertexIndex property int vertexIndex
@ -323,7 +348,7 @@ Item {
id: dragArea id: dragArea
mapControl: _root.mapControl mapControl: _root.mapControl
z: _zorderDragHandle z: _zorderDragHandle
visible: !_circle visible: !_circleMode
onDragStop: mapPolygon.verifyClockwiseWinding() onDragStop: mapPolygon.verifyClockwiseWinding()
property int polygonVertex property int polygonVertex
@ -380,7 +405,7 @@ Item {
anchorPoint.x: dragHandle.width / 2 anchorPoint.x: dragHandle.width / 2
anchorPoint.y: dragHandle.height / 2 anchorPoint.y: dragHandle.height / 2
z: _zorderDragHandle z: _zorderDragHandle
visible: !_circle visible: !_circleMode
property int polygonVertex property int polygonVertex
@ -463,74 +488,219 @@ Item {
onItemCoordinateChanged: mapPolygon.center = itemCoordinate onItemCoordinateChanged: mapPolygon.center = itemCoordinate
onDragStart: mapPolygon.centerDrag = true onDragStart: mapPolygon.centerDrag = true
onDragStop: mapPolygon.centerDrag = false onDragStop: mapPolygon.centerDrag = false
}
}
onClicked: menu.popupCenter() Component {
id: centerDragHandleComponent
function setRadiusFromDialog() { Item {
var radius = QGroundControl.appSettingsDistanceUnitsToMeters(radiusField.text) property var dragHandle
setCircleRadius(mapPolygon.center, radius) property var dragArea
_editCircleRadius = false
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 { Rectangle {
anchors.margins: _margin anchors.fill: parent
anchors.left: parent.right radius: _radius
width: radiusColumn.width + (_margin *2) color: "white"
height: radiusColumn.height + (_margin *2) opacity: 0.75
color: qgcPal.window }
border.color: qgcPal.text
visible: _editCircleRadius RowLayout {
id: editHeaderRowLayout
Column { anchors.margins: _viewportMargins
id: radiusColumn anchors.top: parent.top
anchors.margins: _margin anchors.left: parent.left
anchors.left: parent.left anchors.right: parent.right
anchors.top: parent.top
spacing: _margin QGCButton {
text: qsTr("Basic Polygon")
QGCLabel { text: qsTr("Radius:") } visible: !_traceMode
onClicked: _resetPolygon()
QGCTextField { }
id: radiusField
showUnits: true QGCButton {
unitsLabel: QGroundControl.appSettingsDistanceUnitsString text: qsTr("Circular Polygon")
text: QGroundControl.metersToAppSettingsDistanceUnits(_circleRadius).toFixed(2) visible: !_traceMode
onEditingFinished: setRadiusFromDialog() onClicked: _resetCircle()
inputMethodHints: Qt.ImhFormattedNumbersOnly }
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 { QGCLabel {
anchors.right: radiusColumn.right id: instructionLabel
anchors.top: radiusColumn.top color: "black"
text: "X" 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 { Component {
fillItem: parent id: radiusDragAreaComponent
onClicked: setRadiusFromDialog()
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 { Component {
id: centerDragHandleComponent id: radiusVisualsComponent
Item { Item {
property var dragHandle property var circleCenterCoord: mapPolygon.center
property var dragArea
Component.onCompleted: { function _calcRadiusDragCoord() {
dragHandle = centerDragHandle.createObject(mapControl) _circleRadiusDragCoord = circleCenterCoord.atDistanceAndAzimuth(_circleRadius, 90)
dragHandle.coordinate = Qt.binding(function() { return mapPolygon.center })
mapControl.addMapItem(dragHandle)
dragArea = centerDragAreaComponent.createObject(mapControl, { "itemIndicator": dragHandle, "itemCoordinate": mapPolygon.center })
} }
Component.onDestruction: { onCircleCenterCoordChanged: {
dragHandle.destroy() if (!_circleRadiusDrag) {
dragArea.destroy() _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)
} }
} }
} }

Loading…
Cancel
Save