Unverified Commit 9276e165 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #7872 from DonLakeFlyer/PolygonTools

Polygon tools, Survey changes
parents 2fc9b3fe 39574fe9
......@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build
* New Polygon editing tools ui. Includes ability to trace polygon by clicking.
* ArduCopter/Rover: Follow Me setup page
* More performant flight path display algorithm. Mobile builds no longer show limited path length.
* ArduCopter/Rover: Add support for Follow Me
......
......@@ -85,6 +85,7 @@
<file alias="QGroundControl/Controls/HeightIndicator.qml">src/QmlControls/HeightIndicator.qml</file>
<file alias="QGroundControl/Controls/IndicatorButton.qml">src/QmlControls/IndicatorButton.qml</file>
<file alias="QGroundControl/Controls/JoystickThumbPad.qml">src/QmlControls/JoystickThumbPad.qml</file>
<file alias="QGroundControl/Controls/KMLOrSHPFileDialog.qml">src/QmlControls/KMLOrSHPFileDialog.qml</file>
<file alias="QGroundControl/Controls/LogReplayStatusBar.qml">src/QmlControls/LogReplayStatusBar.qml</file>
<file alias="QGroundControl/Controls/MainWindowSavedState.qml">src/QmlControls/MainWindowSavedState.qml</file>
<file alias="QGroundControl/Controls/MAVLinkMessageButton.qml">src/QmlControls/MAVLinkMessageButton.qml</file>
......
......@@ -23,6 +23,7 @@ Rectangle {
height: _itemIndicatorHeight + (_touchMarginVertical * 2)
color: "transparent"
z: QGroundControl.zOrderMapItems + 1 // Above item icons
visible: itemCoordinate.isValid
// Properties which must be specific by consumer
property var mapControl ///< Map control which contains this item
......
......@@ -24,6 +24,6 @@ MapItemView {
line.color: "#be781c" // Hack, can't get palette to work in here
z: QGroundControl.zOrderWaypointLines
path: object ? [ object.coordinate1, object.coordinate2 ] : [ ]
path: object && object.coordinate1.isValid && object.coordinate2.isValid ? [ object.coordinate1, object.coordinate2 ] : []
}
}
......@@ -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<QGeoCoordinate>& coordinates)
{
QList<QObject*> 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<QGeoCoordinate>());
}
_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();
}
}
......@@ -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
This diff is collapsed.
......@@ -405,10 +405,10 @@ Item {
planView: true
// This is the center rectangle of the map which is not obscured by tools
property rect centerViewport: Qt.rect(_leftToolWidth, 0, editorMap.width - _leftToolWidth - _rightPanelWidth, editorMap.height - _statusHeight)
property rect centerViewport: Qt.rect(_leftToolWidth, 0, editorMap.width - _leftToolWidth - _rightToolWidth, mapScale.y)
property real _leftToolWidth: toolStrip.x + toolStrip.width
property real _statusHeight: waypointValuesDisplay.visible ? editorMap.height - waypointValuesDisplay.y : 0
property real _leftToolWidth: toolStrip.x + toolStrip.width
property real _rightToolWidth: rightPanel.width + rightPanel.anchors.rightMargin
readonly property real animationDuration: 500
......
This diff is collapsed.
......@@ -21,39 +21,4 @@ import QGroundControl.FlightMap 1.0
/// Survey Complex Mission Item visuals
TransectStyleMapVisuals {
polygonInteractive: true
property var _mapPolygon: object.surveyAreaPolygon
/// Add an initial 4 sided polygon if there is none
function _addInitialPolygon() {
if (_mapPolygon.count < 3) {
// 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)
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 */)
// 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)
_mapPolygon.appendVertex(topLeftCoord)
_mapPolygon.appendVertex(topRightCoord)
_mapPolygon.appendVertex(bottomRightCoord)
_mapPolygon.appendVertex(bottomLeftCoord)
}
}
Component.onCompleted: _addInitialPolygon()
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
import QtQuick 2.11
import QGroundControl 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ShapeFileHelper 1.0
QGCFileDialog {
id: kmlOrSHPLoadDialog
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
}
......@@ -9,30 +9,42 @@ import QGroundControl.ScreenTools 1.0
Item {
visible: false
property var rgDynamicObjects: [ ]
property var rgDynamicObjects: [ ]
property bool empty: rgDynamicObjects.length === 0
function createObject(sourceComponent, parentObject, parentObjectIsMap) {
Component.onDestruction: destroyObjects()
function createObject(sourceComponent, parentObject, addMapItem) {
var obj = sourceComponent.createObject(parentObject)
if (obj.status === Component.Error) {
console.log(obj.errorString())
}
rgDynamicObjects.push(obj)
if (arguments.length < 3) {
parentObjectIsMap = false
addMapItem = false
}
if (parentObjectIsMap) {
map.addMapItem(obj)
if (addMapItem) {
parentObject.addMapItem(obj)
}
return obj
}
function createObjects(rgSourceComponents, parentObject, parentObjectIsMap) {
function createObjects(rgSourceComponents, parentObject, addMapItem) {
if (arguments.length < 3) {
parentObjectIsMap = false
addMapItem = false
}
for (var i=0; i<rgSourceComponents.length; i++) {
createObject(rgSourceComponents[i], parentObject, parentObjectIsMap)
createObject(rgSourceComponents[i], parentObject, addMapItem)
}
}
/// Adds the object to the list. If mapControl is specified it will aso be added to the map.
function addObject(object, mapControl) {
rgDynamicObjects.push(object)
if (arguments.length == 2) {
mapControl.addMapItem(object)
}
return object
}
function destroyObjects() {
......
......@@ -23,6 +23,7 @@ HackFileDialog 1.0 HackFileDialog.qml
HeightIndicator 1.0 HeightIndicator.qml
IndicatorButton 1.0 IndicatorButton.qml
JoystickThumbPad 1.0 JoystickThumbPad.qml
KMLOrSHPFileDialog 1.0 KMLOrSHPFileDialog.qml
LogReplayStatusBar 1.0 LogReplayStatusBar.qml
MainWindowSavedState 1.0 MainWindowSavedState.qml
MAVLinkMessageButton 1.0 MAVLinkMessageButton.qml
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment