WimaMapPolygonVisuals.qml 21 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
9

10 11 12 13 14 15 16 17 18 19 20 21 22
import QtQuick          2.3
import QtQuick.Controls 1.2
import QtLocation       5.3
import QtPositioning    5.3
import QtQuick.Dialogs  1.2

import QGroundControl                   1.0
import QGroundControl.ScreenTools       1.0
import QGroundControl.Palette           1.0
import QGroundControl.Controls          1.0
import QGroundControl.FlightMap         1.0
import QGroundControl.ShapeFileHelper   1.0

23
/// WimaMapPolygon map visuals
24
Item {
25 26 27 28 29 30 31 32 33 34 35
    id: _root

    property var    qgcView                                     ///< QGCView for popping dialogs
    property var    mapControl                                  ///< Map control to place item in
    property var    mapPolygon                                  ///< QGCMapPolygon object
    property bool   interactive:        mapPolygon.interactive
    property color  interiorColor:      "transparent"
    property real   interiorOpacity:    1
    property int    borderWidth:        0
    property color  borderColor:        "black"
    property bool   initPolygon:        false
36
    property bool   showVertexIndex:    true
37 38 39 40 41 42 43 44

    property var    _polygonComponent
    property var    _dragHandlesComponent
    property var    _splitHandlesComponent
    property var    _centerDragHandleComponent
    property bool   _circle:                    false
    property real   _circleRadius
    property bool   _editCircleRadius:          false
45 46
    property bool   _handelsVisible: false // state tracker
    property bool   _polygonVisible: false // state tracker
47 48 49 50 51

    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

52 53
    signal dragStop // triggered if node or center handle was stopped dragging

54 55 56 57 58
    function addPolygon() {
        if (!_polygonComponent){
            _polygonComponent = polygonComponent.createObject(mapControl)
            mapControl.addMapItem(_polygonComponent)
        }
59 60
    }

61 62 63 64 65
    function removePolygon() {
        if (_polygonComponent){
            _polygonComponent.destroy()
            _polygonComponent = undefined
        }
66 67 68 69 70
    }

    function addHandles() {
        if (!_dragHandlesComponent) {
            _dragHandlesComponent = dragHandlesComponent.createObject(mapControl)
71 72
        }
        if (!_splitHandlesComponent) {
73
            _splitHandlesComponent = splitHandlesComponent.createObject(mapControl)
74 75
        }
        if (!_centerDragHandleComponent) {
76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166
            _centerDragHandleComponent = centerDragHandleComponent.createObject(mapControl)
        }
    }

    function removeHandles() {
        if (_dragHandlesComponent) {
            _dragHandlesComponent.destroy()
            _dragHandlesComponent = undefined
        }
        if (_splitHandlesComponent) {
            _splitHandlesComponent.destroy()
            _splitHandlesComponent = undefined
        }
        if (_centerDragHandleComponent) {
            _centerDragHandleComponent.destroy()
            _centerDragHandleComponent = undefined
        }
    }

    /// Calculate the default/initial 4 sided polygon
    function defaultPolygonVertices() {
        // Initial polygon is inset to take 2/3rds space
        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 =       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
        var halfHeightMeters =  Math.min(topLeftCoord.distanceTo(bottomLeftCoord), 3000) / 2
        topLeftCoord =      centerCoord.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 0)
        topRightCoord =     centerCoord.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 0)
        bottomLeftCoord =   centerCoord.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 180)
        bottomRightCoord =  centerCoord.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 180)

        return [ topLeftCoord, topRightCoord, bottomRightCoord, bottomLeftCoord, centerCoord  ]
    }

    /// Add an initial 4 sided polygon
    function addInitialPolygon() {
        if (mapPolygon.count < 3) {
            var 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()
        mapPolygon.clear()
        for (var i=0; i<4; i++) {
            mapPolygon.appendVertex(initialVertices[i])
        }
        _circle = false
    }

    function setCircleRadius(center, radius) {
        var unboundCenter = center.atDistanceAndAzimuth(0, 0)
        _circleRadius = radius
        var segments = 16
        var angleIncrement = 360 / segments
        var angle = 0
        mapPolygon.clear()
        for (var i=0; i<segments; i++) {
            var vertex = unboundCenter.atDistanceAndAzimuth(_circleRadius, angle)
            mapPolygon.appendVertex(vertex)
            angle += angleIncrement
        }
        _circle = true
    }

    /// Reset polygon to a circle which fits within initial polygon
    function resetCircle() {
        var initialVertices = defaultPolygonVertices()
        var width = initialVertices[0].distanceTo(initialVertices[1])
        var height = initialVertices[1].distanceTo(initialVertices[2])
        var radius = Math.min(width, height) / 2
        var center = initialVertices[4]
        setCircleRadius(center, radius)
    }

167 168 169 170 171 172 173 174 175 176 177 178 179 180 181

    function updateVisibility(){
       if (visible){
          addPolygon()
          if(interactive){
              addHandles()
          }else{
              removeHandles()
          }
       } else {
           removeHandles()
           removePolygon()
       }
    }

182
    onInteractiveChanged: {
183 184 185 186 187
        updateVisibility()
    }

    onVisibleChanged: {
        updateVisibility()
188 189 190 191 192 193
    }

    Component.onCompleted: {
        if(initPolygon){
            addInitialPolygon()
        }
194
        updateVisibility()
195 196 197
    }

    Component.onDestruction: {
198
        removePolygon()
199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322
        removeHandles()
    }

    QGCPalette { id: qgcPal }

    QGCFileDialog {
        id:             kmlOrSHPLoadDialog
        qgcView:        _root.qgcView
        folder:         QGroundControl.settingsManager.appSettings.missionSavePath
        title:          qsTr("Select Polygon File")
        selectExisting: true
        nameFilters:    ShapeFileHelper.fileDialogKMLOrSHPFilters
        fileExtension:  QGroundControl.settingsManager.appSettings.kmlFileExtension
        fileExtension2: QGroundControl.settingsManager.appSettings.shpFileExtension

        onAcceptedForLoad: {
            mapPolygon.loadKMLOrSHPFile(file)
            mapFitFunctions.fitMapViewportToMissionItems()
            close()
        }
    }

    Menu {
        id: menu

        property int _editingVertexIndex: -1

        function popupVertex(curIndex) {
            menu._editingVertexIndex = curIndex
            removeVertexItem.visible = (mapPolygon.count > 3 && menu._editingVertexIndex >= 0)
            menu.popup()
        }

        function popupCenter() {
            menu.popup()
        }

        MenuItem {
            id:             removeVertexItem
            visible:        !_circle
            text:           qsTr("Remove vertex")
            onTriggered: {
                if (menu._editingVertexIndex >= 0) {
                    mapPolygon.removeVertex(menu._editingVertexIndex)
                }
            }
        }

        MenuSeparator {
            visible:        removeVertexItem.visible
        }

        /*MenuItem {
            text:           qsTr("Circle" )
            onTriggered:    resetCircle()
        }*

        /*MenuItem {
            text:           qsTr("Polygon")
            onTriggered:    resetPolygon()
        }*/

        /*MenuItem {
            text:           qsTr("Set radius..." )
            visible:        _circle
            onTriggered:    _editCircleRadius = true
        }*/

        /*MenuItem {
            text:           qsTr("Edit position..." )
            visible:        _circle
            onTriggered:    qgcView.showDialog(editCenterPositionDialog, qsTr("Edit Center Position"), qgcView.showDialogDefaultWidth, StandardButton.Close)
        }*/

        MenuItem {
            text:           qsTr("Edit position..." )
            visible:        !_circle && menu._editingVertexIndex >= 0
            onTriggered:    qgcView.showDialog(editVertexPositionDialog, qsTr("Edit Vertex Position"), qgcView.showDialogDefaultWidth, StandardButton.Close)
        }

        /*MenuItem {
            text:           qsTr("Load KML/SHP...")
            onTriggered:    kmlOrSHPLoadDialog.openForLoad()
        }*/
    }

    Component {
        id: polygonComponent

        MapPolygon {
            color:          interiorColor
            opacity:        interiorOpacity
            border.color:   borderColor
            border.width:   borderWidth
            path:           mapPolygon.path
        }
    }

    Component {
        id: splitHandleComponent

        MapQuickItem {
            id:             mapQuickItem
            anchorPoint.x:  dragHandle.width / 2
            anchorPoint.y:  dragHandle.height / 2
            visible:        !_circle

            property int vertexIndex

            sourceItem: Rectangle {
                id:         dragHandle
                width:      ScreenTools.defaultFontPixelHeight * 1.5
                height:     width
                radius:     width / 2
                border.color:      "white"
                color:      "transparent"
                opacity:    .50
                z:          _zorderSplitHandle

                QGCLabel {
                    anchors.horizontalCenter:   parent.horizontalCenter
                    anchors.verticalCenter:     parent.verticalCenter
                    text:                       "+"
                }
323

324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376
                QGCMouseArea {
                    fillItem:   parent
                    onClicked:  mapPolygon.splitPolygonSegment(mapQuickItem.vertexIndex)
                }
            }
        }
    }

    Component {
        id: splitHandlesComponent

        Repeater {
            model: mapPolygon.path

            delegate: Item {
                property var _splitHandle
                property var _vertices:     mapPolygon.path

                function _setHandlePosition() {
                    var nextIndex = index + 1
                    if (nextIndex > _vertices.length - 1) {
                        nextIndex = 0
                    }
                    var distance = _vertices[index].distanceTo(_vertices[nextIndex])
                    var azimuth = _vertices[index].azimuthTo(_vertices[nextIndex])
                    _splitHandle.coordinate = _vertices[index].atDistanceAndAzimuth(distance / 2, azimuth)
                }

                Component.onCompleted: {
                    _splitHandle = splitHandleComponent.createObject(mapControl)
                    _splitHandle.vertexIndex = index
                    _setHandlePosition()
                    mapControl.addMapItem(_splitHandle)
                }

                Component.onDestruction: {
                    if (_splitHandle) {
                        _splitHandle.destroy()
                    }
                }
            }
        }
    }

    // Control which is used to drag polygon vertices
    Component {
        id: dragAreaComponent

        MissionItemIndicatorDrag {
            id:         dragArea
            mapControl: _root.mapControl
            z:          _zorderDragHandle
            visible:    !_circle
377 378 379 380
            onDragStop: {
               mapPolygon.verifyClockwiseWinding()
               _root.dragStop()
            }
381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447

            property int polygonVertex

            property bool _creationComplete: false

            Component.onCompleted: _creationComplete = true

            onItemCoordinateChanged: {
                if (_creationComplete) {
                    // During component creation some bad coordinate values got through which screws up draw
                    mapPolygon.adjustVertex(polygonVertex, itemCoordinate)
                }
            }

            onClicked: menu.popupVertex(polygonVertex)
        }
    }

    Component {
        id: centerDragHandle
        MapQuickItem {
            id:             mapQuickItem
            anchorPoint.x:  dragHandle.width  * 0.5
            anchorPoint.y:  dragHandle.height * 0.5
            z:              _zorderDragHandle
            sourceItem: Rectangle {
                id:             dragHandle
                width:          ScreenTools.defaultFontPixelHeight * 1.5
                height:         width
                radius:         width * 0.5
                color:          Qt.rgba(1,1,1,0.8)
                border.color:   Qt.rgba(0,0,0,0.25)
                border.width:   1
                QGCColoredImage {
                    width:      parent.width
                    height:     width
                    color:      Qt.rgba(0,0,0,1)
                    mipmap:     true
                    fillMode:   Image.PreserveAspectFit
                    source:     "/qmlimages/MapCenter.svg"
                    sourceSize.height:  height
                    anchors.centerIn:   parent
                }
            }
        }
    }

    Component {
        id: dragHandleComponent

        MapQuickItem {
            id:             mapQuickItem
            anchorPoint.x:  dragHandle.width  / 2
            anchorPoint.y:  dragHandle.height / 2
            z:              _zorderDragHandle
            visible:        !_circle

            property int polygonVertex

            sourceItem: Rectangle {
                id:             dragHandle
                width:          ScreenTools.defaultFontPixelHeight * 1.5
                height:         width
                radius:         width * 0.5
                color:          Qt.rgba(1,1,1,0.8)
                border.color:   Qt.rgba(0,0,0,0.25)
                border.width:   1
448 449 450 451 452 453 454

                QGCLabel {
                    anchors.horizontalCenter:   parent.horizontalCenter
                    anchors.verticalCenter:     parent.verticalCenter
                    color:                      "black"
                    text:                       showVertexIndex ? polygonVertex : ""
                }
455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524
            }
        }
    }

    // Add all polygon vertex drag handles to the map
    Component {
        id: dragHandlesComponent

        Repeater {
            model: mapPolygon.pathModel

            delegate: Item {
                property var _visuals: [ ]

                Component.onCompleted: {
                    var dragHandle = dragHandleComponent.createObject(mapControl)
                    dragHandle.coordinate = Qt.binding(function() { return object.coordinate })
                    dragHandle.polygonVertex = Qt.binding(function() { return index })
                    mapControl.addMapItem(dragHandle)
                    var dragArea = dragAreaComponent.createObject(mapControl, { "itemIndicator": dragHandle, "itemCoordinate": object.coordinate })
                    dragArea.polygonVertex = Qt.binding(function() { return index })
                    _visuals.push(dragHandle)
                    _visuals.push(dragArea)
                }

                Component.onDestruction: {
                    for (var i=0; i<_visuals.length; i++) {
                        _visuals[i].destroy()
                    }
                    _visuals = [ ]
                }
            }
        }
    }

    Component {
        id: editCenterPositionDialog

        EditPositionDialog {
            coordinate: mapPolygon.center
            onCoordinateChanged: {
                // Prevent spamming signals on vertex changes by setting centerDrag = true when changing center position.
                // This also fixes a bug where Qt gets confused by all the signalling and draws a bad visual.
                mapPolygon.centerDrag = true
                mapPolygon.center = coordinate
                mapPolygon.centerDrag = false
            }
        }
    }

    Component {
        id: editVertexPositionDialog

        EditPositionDialog {
            coordinate:             mapPolygon.vertexCoordinate(menu._editingVertexIndex)
            onCoordinateChanged: {
                mapPolygon.adjustVertex(menu._editingVertexIndex, coordinate)
                mapPolygon.verifyClockwiseWinding()
            }
        }
    }

    Component {
        id: centerDragAreaComponent

        MissionItemIndicatorDrag {
            mapControl:                 _root.mapControl
            z:                          _zorderCenterHandle
            onItemCoordinateChanged:    mapPolygon.center = itemCoordinate
            onDragStart:                mapPolygon.centerDrag = true
525 526 527 528
            onDragStop: {
                mapPolygon.centerDrag = false
                _root.dragStop()
            }
529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599

            onClicked: menu.popupCenter()

            function setRadiusFromDialog() {
                var radius = QGroundControl.appSettingsDistanceUnitsToMeters(radiusField.text)
                setCircleRadius(mapPolygon.center, radius)
                _editCircleRadius = false
            }

            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
                    }
                }

                QGCLabel {
                    anchors.right:  radiusColumn.right
                    anchors.top:    radiusColumn.top
                    text:           "X"

                    QGCMouseArea {
                        fillItem:   parent
                        onClicked:  setRadiusFromDialog()
                    }
                }
            }
        }
    }

    Component {
        id: centerDragHandleComponent

        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()
            }
        }
    }
600
}
601