Commit 127b6740 authored by Don Gagne's avatar Don Gagne

parent 9276e165
...@@ -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 Corridor editing tools ui. Includes ability to trace polyline by clicking.
* New Polygon editing tools ui. Includes ability to trace polygon by clicking. * 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.
......
...@@ -101,6 +101,7 @@ ...@@ -101,6 +101,7 @@
<file alias="QGroundControl/Controls/ParameterEditor.qml">src/QmlControls/ParameterEditor.qml</file> <file alias="QGroundControl/Controls/ParameterEditor.qml">src/QmlControls/ParameterEditor.qml</file>
<file alias="QGroundControl/Controls/ParameterEditorDialog.qml">src/QmlControls/ParameterEditorDialog.qml</file> <file alias="QGroundControl/Controls/ParameterEditorDialog.qml">src/QmlControls/ParameterEditorDialog.qml</file>
<file alias="QGroundControl/Controls/PIDTuning.qml">src/QmlControls/PIDTuning.qml</file> <file alias="QGroundControl/Controls/PIDTuning.qml">src/QmlControls/PIDTuning.qml</file>
<file alias="QGroundControl/Controls/PlanEditToolbar.qml">src/PlanView/PlanEditToolbar.qml</file>
<file alias="QGroundControl/Controls/PreFlightCheckButton.qml">src/QmlControls/PreFlightCheckButton.qml</file> <file alias="QGroundControl/Controls/PreFlightCheckButton.qml">src/QmlControls/PreFlightCheckButton.qml</file>
<file alias="QGroundControl/Controls/PreFlightCheckGroup.qml">src/QmlControls/PreFlightCheckGroup.qml</file> <file alias="QGroundControl/Controls/PreFlightCheckGroup.qml">src/QmlControls/PreFlightCheckGroup.qml</file>
<file alias="QGroundControl/Controls/PreFlightCheckModel.qml">src/QmlControls/PreFlightCheckModel.qml</file> <file alias="QGroundControl/Controls/PreFlightCheckModel.qml">src/QmlControls/PreFlightCheckModel.qml</file>
......
...@@ -71,9 +71,9 @@ Item { ...@@ -71,9 +71,9 @@ Item {
} }
function addToolVisuals() { function addToolbarVisuals() {
if (_objMgrToolVisuals.empty) { if (_objMgrToolVisuals.empty) {
_objMgrToolVisuals.createObject(editHeaderComponent, mapControl) _objMgrToolVisuals.createObject(toolbarComponent, mapControl)
} }
} }
...@@ -155,7 +155,7 @@ Item { ...@@ -155,7 +155,7 @@ Item {
function _handleInteractiveChanged() { function _handleInteractiveChanged() {
if (interactive) { if (interactive) {
addEditingVisuals() addEditingVisuals()
addToolVisuals() addToolbarVisuals()
} else { } else {
_traceMode = false _traceMode = false
removeEditingVisuals() removeEditingVisuals()
...@@ -513,73 +513,53 @@ Item { ...@@ -513,73 +513,53 @@ Item {
} }
Component { Component {
id: editHeaderComponent id: toolbarComponent
Item { PlanEditToolbar {
x: mapControl.centerViewport.left + _viewportMargins x: mapControl.centerViewport.left + _margins
y: mapControl.centerViewport.top + _viewportMargins y: mapControl.centerViewport.top + _margins
width: mapControl.centerViewport.width - (_viewportMargins * 2) width: mapControl.centerViewport.width - (_margins * 2)
height: editHeaderRowLayout.y + editHeaderRowLayout.height + _viewportMargins
z: QGroundControl.zOrderMapItems + 2 z: QGroundControl.zOrderMapItems + 2
property real _radius: ScreenTools.defaultFontPixelWidth / 2 property real _margins: ScreenTools.defaultFontPixelWidth
property real _viewportMargins: ScreenTools.defaultFontPixelWidth
Rectangle { QGCButton {
anchors.fill: parent _horizontalPadding: 0
radius: _radius text: qsTr("Basic Polygon")
color: "white" visible: !_traceMode
opacity: 0.75 onClicked: _resetPolygon()
} }
RowLayout { QGCButton {
id: editHeaderRowLayout _horizontalPadding: 0
anchors.margins: _viewportMargins text: qsTr("Circular Polygon")
anchors.top: parent.top visible: !_traceMode
anchors.left: parent.left onClicked: _resetCircle()
anchors.right: parent.right }
QGCButton {
text: qsTr("Basic Polygon")
visible: !_traceMode
onClicked: _resetPolygon()
}
QGCButton {
text: qsTr("Circular Polygon")
visible: !_traceMode
onClicked: _resetCircle()
}
QGCButton { QGCButton {
text: _traceMode ? qsTr("Done Tracing") : qsTr("Trace Polygon") _horizontalPadding: 0
onClicked: { text: _traceMode ? qsTr("Done Tracing") : qsTr("Trace Polygon")
if (_traceMode) { onClicked: {
if (mapPolygon.count < 3) { if (_traceMode) {
_restorePreviousVertices() if (mapPolygon.count < 3) {
} _restorePreviousVertices()
_traceMode = false
} else {
_saveCurrentVertices()
_circleMode = false
_traceMode = true
mapPolygon.clear();
} }
_traceMode = false
} else {
_saveCurrentVertices()
_circleMode = false
_traceMode = true
mapPolygon.clear();
} }
} }
}
QGCButton { QGCButton {
text: qsTr("Load KML/SHP...") _horizontalPadding: 0
onClicked: kmlOrSHPLoadDialog.openForLoad() text: qsTr("Load KML/SHP...")
visible: !_traceMode onClicked: kmlOrSHPLoadDialog.openForLoad()
} visible: !_traceMode
QGCLabel {
id: instructionLabel
color: "black"
text: _instructionText
Layout.fillWidth: true
}
} }
} }
} }
...@@ -589,7 +569,7 @@ Item { ...@@ -589,7 +569,7 @@ Item {
id: traceMouseAreaComponent id: traceMouseAreaComponent
MouseArea { MouseArea {
anchors.fill: map anchors.fill: mapControl
preventStealing: true preventStealing: true
z: QGroundControl.zOrderMapItems + 1 // Over item indicators z: QGroundControl.zOrderMapItems + 1 // Over item indicators
...@@ -640,38 +620,6 @@ Item { ...@@ -640,38 +620,6 @@ Item {
_lastRadius = radius _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()
}
*/
} }
} }
......
...@@ -27,6 +27,7 @@ QGCMapPolyline::QGCMapPolyline(QObject* parent) ...@@ -27,6 +27,7 @@ QGCMapPolyline::QGCMapPolyline(QObject* parent)
: QObject (parent) : QObject (parent)
, _dirty (false) , _dirty (false)
, _interactive (false) , _interactive (false)
, _resetActive (false)
{ {
_init(); _init();
} }
...@@ -35,6 +36,7 @@ QGCMapPolyline::QGCMapPolyline(const QGCMapPolyline& other, QObject* parent) ...@@ -35,6 +36,7 @@ QGCMapPolyline::QGCMapPolyline(const QGCMapPolyline& other, QObject* parent)
: QObject (parent) : QObject (parent)
, _dirty (false) , _dirty (false)
, _interactive (false) , _interactive (false)
, _resetActive (false)
{ {
*this = other; *this = other;
...@@ -118,6 +120,8 @@ QPointF QGCMapPolyline::_pointFFromCoord(const QGeoCoordinate& coordinate) const ...@@ -118,6 +120,8 @@ QPointF QGCMapPolyline::_pointFFromCoord(const QGeoCoordinate& coordinate) const
void QGCMapPolyline::setPath(const QList<QGeoCoordinate>& path) void QGCMapPolyline::setPath(const QList<QGeoCoordinate>& path)
{ {
_beginResetIfNotActive();
_polylinePath.clear(); _polylinePath.clear();
_polylineModel.clearAndDeleteContents(); _polylineModel.clearAndDeleteContents();
for (const QGeoCoordinate& coord: path) { for (const QGeoCoordinate& coord: path) {
...@@ -126,20 +130,22 @@ void QGCMapPolyline::setPath(const QList<QGeoCoordinate>& path) ...@@ -126,20 +130,22 @@ void QGCMapPolyline::setPath(const QList<QGeoCoordinate>& path)
} }
setDirty(true); setDirty(true);
emit pathChanged();
_endResetIfNotActive();
} }
void QGCMapPolyline::setPath(const QVariantList& path) void QGCMapPolyline::setPath(const QVariantList& path)
{ {
_polylinePath = path; _beginResetIfNotActive();
_polylinePath = path;
_polylineModel.clearAndDeleteContents(); _polylineModel.clearAndDeleteContents();
for (int i=0; i<_polylinePath.count(); i++) { for (int i=0; i<_polylinePath.count(); i++) {
_polylineModel.append(new QGCQGeoCoordinate(_polylinePath[i].value<QGeoCoordinate>(), this)); _polylineModel.append(new QGCQGeoCoordinate(_polylinePath[i].value<QGeoCoordinate>(), this));
} }
setDirty(true); setDirty(true);
emit pathChanged();
_endResetIfNotActive();
} }
...@@ -339,6 +345,8 @@ QList<QGeoCoordinate> QGCMapPolyline::offsetPolyline(double distance) ...@@ -339,6 +345,8 @@ QList<QGeoCoordinate> QGCMapPolyline::offsetPolyline(double distance)
bool QGCMapPolyline::loadKMLFile(const QString& kmlFile) bool QGCMapPolyline::loadKMLFile(const QString& kmlFile)
{ {
_beginResetIfNotActive();
QString errorString; QString errorString;
QList<QGeoCoordinate> rgCoords; QList<QGeoCoordinate> rgCoords;
if (!KMLFileHelper::loadPolylineFromFile(kmlFile, rgCoords, errorString)) { if (!KMLFileHelper::loadPolylineFromFile(kmlFile, rgCoords, errorString)) {
...@@ -349,6 +357,8 @@ bool QGCMapPolyline::loadKMLFile(const QString& kmlFile) ...@@ -349,6 +357,8 @@ bool QGCMapPolyline::loadKMLFile(const QString& kmlFile)
clear(); clear();
appendVertices(rgCoords); appendVertices(rgCoords);
_endResetIfNotActive();
return true; return true;
} }
...@@ -380,12 +390,41 @@ double QGCMapPolyline::length(void) const ...@@ -380,12 +390,41 @@ double QGCMapPolyline::length(void) const
void QGCMapPolyline::appendVertices(const QList<QGeoCoordinate>& coordinates) void QGCMapPolyline::appendVertices(const QList<QGeoCoordinate>& coordinates)
{ {
QList<QObject*> objects; _beginResetIfNotActive();
QList<QObject*> objects;
for (const QGeoCoordinate& coordinate: coordinates) { for (const QGeoCoordinate& coordinate: coordinates) {
objects.append(new QGCQGeoCoordinate(coordinate, this)); objects.append(new QGCQGeoCoordinate(coordinate, this));
_polylinePath.append(QVariant::fromValue(coordinate)); _polylinePath.append(QVariant::fromValue(coordinate));
} }
_polylineModel.append(objects); _polylineModel.append(objects);
_endResetIfNotActive();
}
void QGCMapPolyline::beginReset(void)
{
_resetActive = true;
_polylineModel.beginReset();
}
void QGCMapPolyline::endReset(void)
{
_resetActive = false;
_polylineModel.endReset();
emit pathChanged(); emit pathChanged();
} }
void QGCMapPolyline::_beginResetIfNotActive(void)
{
if (!_resetActive) {
beginReset();
}
}
void QGCMapPolyline::_endResetIfNotActive(void)
{
if (!_resetActive) {
endReset();
}
}
...@@ -30,6 +30,8 @@ public: ...@@ -30,6 +30,8 @@ public:
Q_PROPERTY(QmlObjectListModel* pathModel READ qmlPathModel CONSTANT) Q_PROPERTY(QmlObjectListModel* pathModel READ qmlPathModel CONSTANT)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
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);
...@@ -52,11 +54,14 @@ public: ...@@ -52,11 +54,14 @@ public:
/// @return true: success /// @return true: success
Q_INVOKABLE bool loadKMLFile(const QString& kmlFile); Q_INVOKABLE bool loadKMLFile(const QString& kmlFile);
Q_INVOKABLE void beginReset (void);
Q_INVOKABLE void endReset (void);
/// Returns the path in a list of QGeoCoordinate's format /// Returns the path in a list of QGeoCoordinate's format
QList<QGeoCoordinate> coordinateList(void) const; QList<QGeoCoordinate> coordinateList(void) const;
/// Returns the QGeoCoordinate for the vertex specified /// Returns the QGeoCoordinate for the vertex specified
QGeoCoordinate vertexCoordinate(int vertex) const; Q_INVOKABLE QGeoCoordinate vertexCoordinate(int vertex) const;
/// Saves the polyline to the json object. /// Saves the polyline to the json object.
/// @param json Json object to save to /// @param json Json object to save to
...@@ -76,12 +81,13 @@ public: ...@@ -76,12 +81,13 @@ public:
double length(void) const; double length(void) const;
// Property methods // Property methods
int count (void) const { return _polylinePath.count(); } int count (void) const { return _polylinePath.count(); }
bool dirty (void) const { return _dirty; } bool dirty (void) const { return _dirty; }
void setDirty (bool dirty); void setDirty (bool dirty);
bool interactive (void) const { return _interactive; } bool interactive (void) const { return _interactive; }
QVariantList path (void) const { return _polylinePath; } QVariantList path (void) const { return _polylinePath; }
bool isValid (void) const { return _polylineModel.count() >= 2; }
bool empty (void) const { return _polylineModel.count() == 0; }
QmlObjectListModel* qmlPathModel(void) { return &_polylineModel; } QmlObjectListModel* qmlPathModel(void) { return &_polylineModel; }
QmlObjectListModel& pathModel (void) { return _polylineModel; } QmlObjectListModel& pathModel (void) { return _polylineModel; }
...@@ -104,12 +110,15 @@ private slots: ...@@ -104,12 +110,15 @@ private slots:
void _polylineModelDirtyChanged(bool dirty); void _polylineModelDirtyChanged(bool dirty);
private: private:
void _init(void); void _init (void);
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 _polylinePath; QVariantList _polylinePath;
QmlObjectListModel _polylineModel; QmlObjectListModel _polylineModel;
bool _dirty; bool _dirty;
bool _interactive; bool _interactive;
bool _resetActive;
}; };
...@@ -30,85 +30,92 @@ Item { ...@@ -30,85 +30,92 @@ Item {
property int lineWidth: 3 property int lineWidth: 3
property color lineColor: "#be781c" property color lineColor: "#be781c"
property var _polylineComponent
property var _dragHandlesComponent property var _dragHandlesComponent
property var _splitHandlesComponent property var _splitHandlesComponent
property bool _traceMode: false
property real _zorderDragHandle: QGroundControl.zOrderMapItems + 3 // Highest to prevent splitting when items overlap property string _instructionText: _corridorToolsText
property real _zorderSplitHandle: QGroundControl.zOrderMapItems + 2 property real _zorderDragHandle: QGroundControl.zOrderMapItems + 3 // Highest to prevent splitting when items overlap
property real _zorderSplitHandle: QGroundControl.zOrderMapItems + 2
function addVisuals() { property var _savedVertices: [ ]
_polylineComponent = polylineComponent.createObject(mapControl)
mapControl.addMapItem(_polylineComponent) readonly property string _corridorToolsText: qsTr("Corridor Tools")
} readonly property string _traceText: qsTr("Click in the map to add vertices. Click 'Done Tracing' when finished.")
function removeVisuals() { function _addCommonVisuals() {
_polylineComponent.destroy() if (_objMgrCommonVisuals.empty) {
} _objMgrCommonVisuals.createObject(polylineComponent, mapControl, true)
function addHandles() {
if (!_dragHandlesComponent) {
_dragHandlesComponent = dragHandlesComponent.createObject(mapControl)
_splitHandlesComponent = splitHandlesComponent.createObject(mapControl)
} }
} }
function removeHandles() { function _addInteractiveVisuals() {
if (_dragHandlesComponent) { if (_objMgrInteractiveVisuals.empty) {
_dragHandlesComponent.destroy() _objMgrInteractiveVisuals.createObjects([ dragHandlesComponent, splitHandlesComponent, toolbarComponent ], mapControl)
_dragHandlesComponent = undefined
}
if (_splitHandlesComponent) {
_splitHandlesComponent.destroy()
_splitHandlesComponent = undefined
} }
} }
/// Calculate the default/initial polyline /// Calculate the default/initial polyline
function defaultPolylineVertices() { function _defaultPolylineVertices() {
var x = map.centerViewport.x + (map.centerViewport.width / 2) var x = mapControl.centerViewport.x + (mapControl.centerViewport.width / 2)
var yInset = map.centerViewport.height / 4 var yInset = mapControl.centerViewport.height / 4
var topPointCoord = map.toCoordinate(Qt.point(x, map.centerViewport.y + yInset), false /* clipToViewPort */) var topPointCoord = mapControl.toCoordinate(Qt.point(x, mapControl.centerViewport.y + yInset), false /* clipToViewPort */)
var bottomPointCoord = map.toCoordinate(Qt.point(x, map.centerViewport.y + map.centerViewport.height - yInset), false /* clipToViewPort */) var bottomPointCoord = mapControl.toCoordinate(Qt.point(x, mapControl.centerViewport.y + mapControl.centerViewport.height - yInset), false /* clipToViewPort */)
return [ topPointCoord, bottomPointCoord ] return [ topPointCoord, bottomPointCoord ]
} }
/// Add an initial 2 point polyline /// Reset polyline back to initial default
function addInitialPolyline() { function _resetPolyline() {
if (mapPolyline.count < 2) { mapPolyline.beginReset()
mapPolyline.clear() mapPolyline.clear()
var initialVertices = defaultPolylineVertices() var initialVertices = _defaultPolylineVertices()
mapPolyline.appendVertex(initialVertices[0]) mapPolyline.appendVertex(initialVertices[0])
mapPolyline.appendVertex(initialVertices[1]) mapPolyline.appendVertex(initialVertices[1])
mapPolyline.endReset()
}
function _saveCurrentVertices() {
_savedVertices = [ ]
for (var i=0; i<mapPolyline.count; i++) {
_savedVertices.push(mapPolyline.vertexCoordinate(i))
} }
} }
/// Reset polyline back to initial default function _restorePreviousVertices() {
function resetPolyline() { mapPolyline.beginReset()
mapPolyline.clear() mapPolyline.clear()
addInitialPolyline() for (var i=0; i<_savedVertices.length; i++) {
mapPolyline.appendVertex(_savedVertices[i])
}
mapPolyline.endReset()
} }
onInteractiveChanged: { onInteractiveChanged: {
if (interactive) { if (interactive) {
addHandles() _addInteractiveVisuals()
} else {
_objMgrInteractiveVisuals.destroyObjects()
}
}
on_TraceModeChanged: {
if (_traceMode) {
_instructionText = _traceText
_objMgrTraceVisuals.createObject(traceMouseAreaComponent, mapControl, false)
} else { } else {
removeHandles() _instructionText = _corridorToolsText
_objMgrTraceVisuals.destroyObjects()
} }
} }
Component.onCompleted: { Component.onCompleted: {
addVisuals() _addCommonVisuals()
if (interactive) { if (interactive) {
addHandles() _addInteractiveVisuals()
} }
} }
Component.onDestruction: { QGCDynamicObjectManager { id: _objMgrCommonVisuals }
removeVisuals() QGCDynamicObjectManager { id: _objMgrInteractiveVisuals }
removeHandles() QGCDynamicObjectManager { id: _objMgrTraceVisuals }
}
QGCPalette { id: qgcPal } QGCPalette { id: qgcPal }
...@@ -142,19 +149,10 @@ Item { ...@@ -142,19 +149,10 @@ Item {
onTriggered: mapPolyline.removeVertex(menu._removeVertexIndex) onTriggered: mapPolyline.removeVertex(menu._removeVertexIndex)
} }
QGCMenuSeparator {
visible: removeVertexItem.visible
}
QGCMenuItem { QGCMenuItem {
text: qsTr("Edit position..." ) text: qsTr("Edit position..." )
onTriggered: mainWindow.showComponentDialog(editPositionDialog, qsTr("Edit Position"), mainWindow.showDialogDefaultWidth, StandardButton.Cancel) onTriggered: mainWindow.showComponentDialog(editPositionDialog, qsTr("Edit Position"), mainWindow.showDialogDefaultWidth, StandardButton.Cancel)
} }
QGCMenuItem {
text: qsTr("Load KML...")
onTriggered: kmlLoadDialog.openForLoad()
}
} }
Component { Component {
...@@ -311,5 +309,66 @@ Item { ...@@ -311,5 +309,66 @@ Item {
} }
} }
} }
Component {
id: toolbarComponent
PlanEditToolbar {
x: mapControl.centerViewport.left + _margins
y: mapControl.centerViewport.top + _margins
width: mapControl.centerViewport.width - (_margins * 2)
z: QGroundControl.zOrderMapItems + 2
property real _margins: ScreenTools.defaultFontPixelWidth
QGCButton {
_horizontalPadding: 0
text: qsTr("Basic Corridor")
visible: !_traceMode
onClicked: _resetPolyline()
}
QGCButton {
_horizontalPadding: 0
text: _traceMode ? qsTr("Done Tracing") : qsTr("Trace Corridor")
onClicked: {
if (_traceMode) {
if (mapPolyline.count < 2) {
_restorePreviousVertices()
}
_traceMode = false
} else {
_saveCurrentVertices()
_traceMode = true
mapPolyline.clear();
}
}
}
QGCButton {
_horizontalPadding: 0
text: qsTr("Load KML...")
onClicked: kmlLoadDialog.openForLoad()
visible: !_traceMode
}
}
}
// Mouse area to capture clicks for tracing a polyline
Component {
id: traceMouseAreaComponent
MouseArea {
anchors.fill: mapControl
preventStealing: true
z: QGroundControl.zOrderMapItems + 1 // Over item indicators