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. ...@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build ### 3.6.0 - Daily Build
* New Polygon editing tools ui. Includes ability to trace polygon by clicking.
* ArduCopter/Rover: Follow Me setup page * ArduCopter/Rover: Follow Me setup page
* More performant flight path display algorithm. Mobile builds no longer show limited path length. * More performant flight path display algorithm. Mobile builds no longer show limited path length.
* ArduCopter/Rover: Add support for Follow Me * ArduCopter/Rover: Add support for Follow Me
......
...@@ -85,6 +85,7 @@ ...@@ -85,6 +85,7 @@
<file alias="QGroundControl/Controls/HeightIndicator.qml">src/QmlControls/HeightIndicator.qml</file> <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/IndicatorButton.qml">src/QmlControls/IndicatorButton.qml</file>
<file alias="QGroundControl/Controls/JoystickThumbPad.qml">src/QmlControls/JoystickThumbPad.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/LogReplayStatusBar.qml">src/QmlControls/LogReplayStatusBar.qml</file>
<file alias="QGroundControl/Controls/MainWindowSavedState.qml">src/QmlControls/MainWindowSavedState.qml</file> <file alias="QGroundControl/Controls/MainWindowSavedState.qml">src/QmlControls/MainWindowSavedState.qml</file>
<file alias="QGroundControl/Controls/MAVLinkMessageButton.qml">src/QmlControls/MAVLinkMessageButton.qml</file> <file alias="QGroundControl/Controls/MAVLinkMessageButton.qml">src/QmlControls/MAVLinkMessageButton.qml</file>
......
...@@ -23,6 +23,7 @@ Rectangle { ...@@ -23,6 +23,7 @@ Rectangle {
height: _itemIndicatorHeight + (_touchMarginVertical * 2) height: _itemIndicatorHeight + (_touchMarginVertical * 2)
color: "transparent" color: "transparent"
z: QGroundControl.zOrderMapItems + 1 // Above item icons z: QGroundControl.zOrderMapItems + 1 // Above item icons
visible: itemCoordinate.isValid
// Properties which must be specific by consumer // Properties which must be specific by consumer
property var mapControl ///< Map control which contains this item property var mapControl ///< Map control which contains this item
......
...@@ -24,6 +24,6 @@ MapItemView { ...@@ -24,6 +24,6 @@ MapItemView {
line.color: "#be781c" // Hack, can't get palette to work in here line.color: "#be781c" // Hack, can't get palette to work in here
z: QGroundControl.zOrderWaypointLines 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) ...@@ -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) ...@@ -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) ...@@ -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) ...@@ -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) ...@@ -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) ...@@ -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();
} }
} }
...@@ -36,6 +36,8 @@ public: ...@@ -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: ...@@ -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: ...@@ -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: ...@@ -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: ...@@ -134,6 +143,7 @@ private:
bool _centerDrag; bool _centerDrag;
bool _ignoreCenterUpdates; bool _ignoreCenterUpdates;
bool _interactive; bool _interactive;
bool _resetActive;
}; };
#endif #endif
...@@ -7,11 +7,12 @@ ...@@ -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 { ...@@ -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 { ...@@ -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 { ...@@ -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) {
...@@ -216,38 +256,23 @@ Item { ...@@ -216,38 +256,23 @@ Item {
visible: removeVertexItem.visible visible: removeVertexItem.visible
} }
QGCMenuItem {
text: qsTr("Circle" )
onTriggered: resetCircle()
}
QGCMenuItem {
text: qsTr("Polygon")
onTriggered: resetPolygon()
}
QGCMenuItem { 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 { ...@@ -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 { ...@@ -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 { ...@@ -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 { ...@@ -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)
} }
} }
} }
......
...@@ -405,10 +405,10 @@ Item { ...@@ -405,10 +405,10 @@ Item {
planView: true planView: true
// This is the center rectangle of the map which is not obscured by tools // 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 _leftToolWidth: toolStrip.x + toolStrip.width
property real _statusHeight: waypointValuesDisplay.visible ? editorMap.height - waypointValuesDisplay.y : 0 property real _rightToolWidth: rightPanel.width + rightPanel.anchors.rightMargin
readonly property real animationDuration: 500 readonly property real animationDuration: 500
......
...@@ -54,101 +54,119 @@ Rectangle { ...@@ -54,101 +54,119 @@ Rectangle {
anchors.top: parent.top anchors.top: parent.top
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin
QGCTabBar { ColumnLayout {
id: tabBar
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin
visible: !missionItem.surveyAreaPolygon.isValid
Component.onCompleted: currentIndex = QGroundControl.settingsManager.planViewSettings.displayPresetsTabFirst.rawValue ? 2 : 0 QGCLabel {
Layout.fillWidth: true
QGCTabButton { text: qsTr("Grid") } wrapMode: Text.WordWrap
QGCTabButton { text: qsTr("Camera") } text: qsTr("Use the Polygon Tools to create the polygon which outlines your survey area.")
QGCTabButton { text: qsTr("Presets") } }
} }
Column { Column {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: tabBar.currentIndex == 0 visible: missionItem.surveyAreaPolygon.isValid
QGCLabel { QGCTabBar {
id: tabBar
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
text: qsTr("WARNING: Photo interval is below minimum interval (%1 secs) supported by camera.").arg(_cameraMinTriggerInterval.toFixed(1))
wrapMode: Text.WordWrap
color: qgcPal.warningText
visible: missionItem.cameraShots > 0 && _cameraMinTriggerInterval !== 0 && _cameraMinTriggerInterval > missionItem.timeBetweenShots
}
CameraCalcGrid { Component.onCompleted: currentIndex = QGroundControl.settingsManager.planViewSettings.displayPresetsTabFirst.rawValue ? 2 : 0
cameraCalc: missionItem.cameraCalc
vehicleFlightIsFrontal: true
distanceToSurfaceLabel: qsTr("Altitude")
distanceToSurfaceAltitudeMode: missionItem.followTerrain ?
QGroundControl.AltitudeModeAboveTerrain :
missionItem.cameraCalc.distanceToSurfaceRelative
frontalDistanceLabel: qsTr("Trigger Dist")
sideDistanceLabel: qsTr("Spacing")
}
SectionHeader { QGCTabButton { text: qsTr("Grid") }
id: transectsHeader QGCTabButton { text: qsTr("Camera") }
text: qsTr("Transects") QGCTabButton { text: qsTr("Presets") }
} }
GridLayout { Column {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
columnSpacing: _margin spacing: _margin
rowSpacing: _margin visible: tabBar.currentIndex == 0
columns: 2
visible: transectsHeader.checked QGCLabel {
anchors.left: parent.left
QGCLabel { text: qsTr("Angle") } anchors.right: parent.right
FactTextField { text: qsTr("WARNING: Photo interval is below minimum interval (%1 secs) supported by camera.").arg(_cameraMinTriggerInterval.toFixed(1))
fact: missionItem.gridAngle wrapMode: Text.WordWrap
Layout.fillWidth: true color: qgcPal.warningText
onUpdated: angleSlider.value = missionItem.gridAngle.value visible: missionItem.cameraShots > 0 && _cameraMinTriggerInterval !== 0 && _cameraMinTriggerInterval > missionItem.timeBetweenShots
} }
QGCSlider { CameraCalcGrid {
id: angleSlider cameraCalc: missionItem.cameraCalc
minimumValue: 0 vehicleFlightIsFrontal: true
maximumValue: 359 distanceToSurfaceLabel: qsTr("Altitude")
stepSize: 1 distanceToSurfaceAltitudeMode: missionItem.followTerrain ?
tickmarksEnabled: false QGroundControl.AltitudeModeAboveTerrain :
Layout.fillWidth: true missionItem.cameraCalc.distanceToSurfaceRelative
Layout.columnSpan: 2 frontalDistanceLabel: qsTr("Trigger Dist")
Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5 sideDistanceLabel: qsTr("Spacing")
onValueChanged: missionItem.gridAngle.value = value
Component.onCompleted: value = missionItem.gridAngle.value
updateValueWhileDragging: true
} }
QGCLabel { SectionHeader {
text: qsTr("Turnaround dist") id: transectsHeader
text: qsTr("Transects")
} }
FactTextField {
fact: missionItem.turnAroundDistance GridLayout {
Layout.fillWidth: true anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: transectsHeader.checked
QGCLabel { text: qsTr("Angle") }
FactTextField {
fact: missionItem.gridAngle
Layout.fillWidth: true
onUpdated: angleSlider.value = missionItem.gridAngle.value
}
QGCSlider {
id: angleSlider
minimumValue: 0
maximumValue: 359
stepSize: 1
tickmarksEnabled: false
Layout.fillWidth: true
Layout.columnSpan: 2
Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5
onValueChanged: missionItem.gridAngle.value = value
Component.onCompleted: value = missionItem.gridAngle.value
updateValueWhileDragging: true
}
QGCLabel {
text: qsTr("Turnaround dist")
}
FactTextField {
fact: missionItem.turnAroundDistance
Layout.fillWidth: true
}
} }
}
QGCButton { QGCButton {
text: qsTr("Rotate Entry Point") text: qsTr("Rotate Entry Point")
onClicked: missionItem.rotateEntryPoint(); onClicked: missionItem.rotateEntryPoint();
} }
ColumnLayout { ColumnLayout {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: transectsHeader.checked visible: transectsHeader.checked
/* /*
Temporarily removed due to bug https://github.com/mavlink/qgroundcontrol/issues/7005 Temporarily removed due to bug https://github.com/mavlink/qgroundcontrol/issues/7005
FactCheckBox { FactCheckBox {
text: qsTr("Split concave polygons") text: qsTr("Split concave polygons")
...@@ -158,231 +176,232 @@ Rectangle { ...@@ -158,231 +176,232 @@ Rectangle {
} }
*/ */
QGCOptionsComboBox { QGCOptionsComboBox {
Layout.fillWidth: true Layout.fillWidth: true
model: [ model: [
{ {
text: qsTr("Hover and capture image"), text: qsTr("Hover and capture image"),
fact: missionItem.hoverAndCapture, fact: missionItem.hoverAndCapture,
enabled: !missionItem.followTerrain, enabled: !missionItem.followTerrain,
visible: missionItem.hoverAndCaptureAllowed visible: missionItem.hoverAndCaptureAllowed
}, },
{ {
text: qsTr("Refly at 90 deg offset"), text: qsTr("Refly at 90 deg offset"),
fact: missionItem.refly90Degrees, fact: missionItem.refly90Degrees,
enabled: !missionItem.followTerrain, enabled: !missionItem.followTerrain,
visible: true visible: true
}, },
{ {
text: qsTr("Images in turnarounds"), text: qsTr("Images in turnarounds"),
fact: missionItem.cameraTriggerInTurnAround, fact: missionItem.cameraTriggerInTurnAround,
enabled: missionItem.hoverAndCaptureAllowed ? !missionItem.hoverAndCapture.rawValue : true, enabled: missionItem.hoverAndCaptureAllowed ? !missionItem.hoverAndCapture.rawValue : true,
visible: true visible: true
}, },
{ {
text: qsTr("Fly alternate transects"), text: qsTr("Fly alternate transects"),
fact: missionItem.flyAlternateTransects, fact: missionItem.flyAlternateTransects,
enabled: true, enabled: true,
visible: _vehicle ? (_vehicle.fixedWing || _vehicle.vtol) : false visible: _vehicle ? (_vehicle.fixedWing || _vehicle.vtol) : false
}, },
{ {
text: qsTr("Relative altitude"), text: qsTr("Relative altitude"),
enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain, enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain,
visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!missionItem.cameraCalc.distanceToSurfaceRelative && !missionItem.followTerrain), visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!missionItem.cameraCalc.distanceToSurfaceRelative && !missionItem.followTerrain),
checked: missionItem.cameraCalc.distanceToSurfaceRelative checked: missionItem.cameraCalc.distanceToSurfaceRelative
}
]
onItemClicked: {
if (index == 4) {
missionItem.cameraCalc.distanceToSurfaceRelative = !missionItem.cameraCalc.distanceToSurfaceRelative
console.log(missionItem.cameraCalc.distanceToSurfaceRelative)
}
} }
] }
}
onItemClicked: { SectionHeader {
if (index == 4) { id: terrainHeader
missionItem.cameraCalc.distanceToSurfaceRelative = !missionItem.cameraCalc.distanceToSurfaceRelative text: qsTr("Terrain")
console.log(missionItem.cameraCalc.distanceToSurfaceRelative) checked: missionItem.followTerrain
}
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: terrainHeader.checked
QGCCheckBox {
id: followsTerrainCheckBox
text: qsTr("Vehicle follows terrain")
checked: missionItem.followTerrain
onClicked: missionItem.followTerrain = checked
}
GridLayout {
Layout.fillWidth: true
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: followsTerrainCheckBox.checked
QGCLabel { text: qsTr("Tolerance") }
FactTextField {
fact: missionItem.terrainAdjustTolerance
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Max Climb Rate") }
FactTextField {
fact: missionItem.terrainAdjustMaxClimbRate
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Max Descent Rate") }
FactTextField {
fact: missionItem.terrainAdjustMaxDescentRate
Layout.fillWidth: true
} }
} }
} }
}
SectionHeader { SectionHeader {
id: terrainHeader id: statsHeader
text: qsTr("Terrain") text: qsTr("Statistics")
checked: missionItem.followTerrain }
}
TransectStyleComplexItemStats {
anchors.left: parent.left
anchors.right: parent.right
visible: statsHeader.checked
}
} // Grid Column
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: tabBar.currentIndex == 1
CameraCalcCamera {
cameraCalc: missionItem.cameraCalc
vehicleFlightIsFrontal: true
distanceToSurfaceLabel: qsTr("Altitude")
distanceToSurfaceAltitudeMode: missionItem.followTerrain ?
QGroundControl.AltitudeModeAboveTerrain :
missionItem.cameraCalc.distanceToSurfaceRelative
frontalDistanceLabel: qsTr("Trigger Dist")
sideDistanceLabel: qsTr("Spacing")
}
} // Camera Column
ColumnLayout { ColumnLayout {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: terrainHeader.checked visible: tabBar.currentIndex == 2
QGCLabel {
Layout.fillWidth: true
text: qsTr("Presets")
wrapMode: Text.WordWrap
}
QGCCheckBox { QGCComboBox {
id: followsTerrainCheckBox id: presetCombo
text: qsTr("Vehicle follows terrain") Layout.fillWidth: true
checked: missionItem.followTerrain model: missionItem.presetNames
onClicked: missionItem.followTerrain = checked
} }
GridLayout { RowLayout {
Layout.fillWidth: true Layout.fillWidth: true
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: followsTerrainCheckBox.checked
QGCLabel { text: qsTr("Tolerance") } QGCButton {
FactTextField {
fact: missionItem.terrainAdjustTolerance
Layout.fillWidth: true Layout.fillWidth: true
text: qsTr("Apply Preset")
enabled: missionItem.presetNames.length != 0
onClicked: missionItem.loadPreset(presetCombo.textAt(presetCombo.currentIndex))
} }
QGCLabel { text: qsTr("Max Climb Rate") } QGCButton {
FactTextField {
fact: missionItem.terrainAdjustMaxClimbRate
Layout.fillWidth: true Layout.fillWidth: true
text: qsTr("Delete Preset")
enabled: missionItem.presetNames.length != 0
onClicked: missionItem.deletePreset(presetCombo.textAt(presetCombo.currentIndex))
} }
QGCLabel { text: qsTr("Max Descent Rate") }
FactTextField {
fact: missionItem.terrainAdjustMaxDescentRate
Layout.fillWidth: true
}
} }
}
SectionHeader {
id: statsHeader
text: qsTr("Statistics")
}
TransectStyleComplexItemStats {
anchors.left: parent.left
anchors.right: parent.right
visible: statsHeader.checked
}
} // Grid Column
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: tabBar.currentIndex == 1
CameraCalcCamera {
cameraCalc: missionItem.cameraCalc
vehicleFlightIsFrontal: true
distanceToSurfaceLabel: qsTr("Altitude")
distanceToSurfaceAltitudeMode: missionItem.followTerrain ?
QGroundControl.AltitudeModeAboveTerrain :
missionItem.cameraCalc.distanceToSurfaceRelative
frontalDistanceLabel: qsTr("Trigger Dist")
sideDistanceLabel: qsTr("Spacing")
}
} // Camera Column
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: tabBar.currentIndex == 2
QGCLabel {
Layout.fillWidth: true
text: qsTr("Presets")
wrapMode: Text.WordWrap
}
QGCComboBox {
id: presetCombo
Layout.fillWidth: true
model: missionItem.presetNames
}
RowLayout { Item { height: ScreenTools.defaultFontPixelHeight; width: 1 }
Layout.fillWidth: true
QGCButton { QGCButton {
Layout.alignment: Qt.AlignCenter
Layout.fillWidth: true Layout.fillWidth: true
text: qsTr("Apply Preset") text: qsTr("Save Settings As New Preset")
enabled: missionItem.presetNames.length != 0 onClicked: mainWindow.showComponentDialog(savePresetDialog, qsTr("Save Preset"), mainWindow.showDialogDefaultWidth, StandardButton.Save | StandardButton.Cancel)
onClicked: missionItem.loadPreset(presetCombo.textAt(presetCombo.currentIndex))
} }
QGCButton { SectionHeader {
id: presectsTransectsHeader
anchors.left: undefined
anchors.right: undefined
Layout.fillWidth: true Layout.fillWidth: true
text: qsTr("Delete Preset") text: qsTr("Transects")
enabled: missionItem.presetNames.length != 0
onClicked: missionItem.deletePreset(presetCombo.textAt(presetCombo.currentIndex))
} }
} GridLayout {
Layout.fillWidth: true
Item { height: ScreenTools.defaultFontPixelHeight; width: 1 } columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: presectsTransectsHeader.checked
QGCButton { QGCLabel { text: qsTr("Angle") }
Layout.alignment: Qt.AlignCenter FactTextField {
Layout.fillWidth: true fact: missionItem.gridAngle
text: qsTr("Save Settings As New Preset") Layout.fillWidth: true
onClicked: mainWindow.showComponentDialog(savePresetDialog, qsTr("Save Preset"), mainWindow.showDialogDefaultWidth, StandardButton.Save | StandardButton.Cancel) onUpdated: presetsAngleSlider.value = missionItem.gridAngle.value
} }
SectionHeader { QGCSlider {
id: presectsTransectsHeader id: presetsAngleSlider
anchors.left: undefined minimumValue: 0
anchors.right: undefined maximumValue: 359
Layout.fillWidth: true stepSize: 1
text: qsTr("Transects") tickmarksEnabled: false
} Layout.fillWidth: true
Layout.columnSpan: 2
Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5
onValueChanged: missionItem.gridAngle.value = value
Component.onCompleted: value = missionItem.gridAngle.value
updateValueWhileDragging: true
}
GridLayout { QGCButton {
Layout.fillWidth: true Layout.columnSpan: 2
columnSpacing: _margin Layout.fillWidth: true
rowSpacing: _margin text: qsTr("Rotate Entry Point")
columns: 2 onClicked: missionItem.rotateEntryPoint();
visible: presectsTransectsHeader.checked }
QGCLabel { text: qsTr("Angle") }
FactTextField {
fact: missionItem.gridAngle
Layout.fillWidth: true
onUpdated: presetsAngleSlider.value = missionItem.gridAngle.value
} }
QGCSlider { SectionHeader {
id: presetsAngleSlider id: presetsStatsHeader
minimumValue: 0 anchors.left: undefined
maximumValue: 359 anchors.right: undefined
stepSize: 1 Layout.fillWidth: true
tickmarksEnabled: false text: qsTr("Statistics")
Layout.fillWidth: true
Layout.columnSpan: 2
Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5
onValueChanged: missionItem.gridAngle.value = value
Component.onCompleted: value = missionItem.gridAngle.value
updateValueWhileDragging: true
} }
QGCButton { TransectStyleComplexItemStats {
Layout.columnSpan: 2
Layout.fillWidth: true Layout.fillWidth: true
text: qsTr("Rotate Entry Point") visible: presetsStatsHeader.checked
onClicked: missionItem.rotateEntryPoint();
} }
} } // Main editing column
} // Top level Column
SectionHeader {
id: presetsStatsHeader
anchors.left: undefined
anchors.right: undefined
Layout.fillWidth: true
text: qsTr("Statistics")
}
TransectStyleComplexItemStats {
Layout.fillWidth: true
visible: presetsStatsHeader.checked
}
} // Camera Column
Component { Component {
id: savePresetDialog id: savePresetDialog
...@@ -418,4 +437,17 @@ Rectangle { ...@@ -418,4 +437,17 @@ Rectangle {
} }
} }
} }
KMLOrSHPFileDialog {
id: kmlOrSHPLoadDialog
title: qsTr("Select Polygon File")
selectExisting: true
onAcceptedForLoad: {
missionItem.surveyAreaPolygon.loadKMLOrSHPFile(file)
missionItem.resetState = false
//editorMap.mapFitFunctions.fitMapViewportToMissionItems()
close()
}
}
} // Rectangle } // Rectangle
...@@ -21,39 +21,4 @@ import QGroundControl.FlightMap 1.0 ...@@ -21,39 +21,4 @@ import QGroundControl.FlightMap 1.0
/// Survey Complex Mission Item visuals /// Survey Complex Mission Item visuals
TransectStyleMapVisuals { TransectStyleMapVisuals {
polygonInteractive: true 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 ...@@ -9,30 +9,42 @@ import QGroundControl.ScreenTools 1.0
Item { Item {
visible: false 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) var obj = sourceComponent.createObject(parentObject)
if (obj.status === Component.Error) { if (obj.status === Component.Error) {
console.log(obj.errorString()) console.log(obj.errorString())
} }
rgDynamicObjects.push(obj) rgDynamicObjects.push(obj)
if (arguments.length < 3) { if (arguments.length < 3) {
parentObjectIsMap = false addMapItem = false
} }
if (parentObjectIsMap) { if (addMapItem) {
map.addMapItem(obj) parentObject.addMapItem(obj)
} }
return obj return obj
} }
function createObjects(rgSourceComponents, parentObject, parentObjectIsMap) { function createObjects(rgSourceComponents, parentObject, addMapItem) {
if (arguments.length < 3) { if (arguments.length < 3) {
parentObjectIsMap = false addMapItem = false
} }
for (var i=0; i<rgSourceComponents.length; i++) { 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() { function destroyObjects() {
......
...@@ -23,6 +23,7 @@ HackFileDialog 1.0 HackFileDialog.qml ...@@ -23,6 +23,7 @@ HackFileDialog 1.0 HackFileDialog.qml
HeightIndicator 1.0 HeightIndicator.qml HeightIndicator 1.0 HeightIndicator.qml
IndicatorButton 1.0 IndicatorButton.qml IndicatorButton 1.0 IndicatorButton.qml
JoystickThumbPad 1.0 JoystickThumbPad.qml JoystickThumbPad 1.0 JoystickThumbPad.qml
KMLOrSHPFileDialog 1.0 KMLOrSHPFileDialog.qml
LogReplayStatusBar 1.0 LogReplayStatusBar.qml LogReplayStatusBar 1.0 LogReplayStatusBar.qml
MainWindowSavedState 1.0 MainWindowSavedState.qml MainWindowSavedState 1.0 MainWindowSavedState.qml
MAVLinkMessageButton 1.0 MAVLinkMessageButton.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