diff --git a/ChangeLog.md b/ChangeLog.md
index 9933569..571e5a3 100644
--- a/ChangeLog.md
+++ b/ChangeLog.md
@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 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.
* ArduCopter/Rover: Follow Me setup page
* More performant flight path display algorithm. Mobile builds no longer show limited path length.
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 9972eda..fb2a636 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -101,6 +101,7 @@
src/QmlControls/ParameterEditor.qml
src/QmlControls/ParameterEditorDialog.qml
src/QmlControls/PIDTuning.qml
+ src/PlanView/PlanEditToolbar.qml
src/QmlControls/PreFlightCheckButton.qml
src/QmlControls/PreFlightCheckGroup.qml
src/QmlControls/PreFlightCheckModel.qml
diff --git a/src/MissionManager/QGCMapPolygonVisuals.qml b/src/MissionManager/QGCMapPolygonVisuals.qml
index 3841bec..df35680 100644
--- a/src/MissionManager/QGCMapPolygonVisuals.qml
+++ b/src/MissionManager/QGCMapPolygonVisuals.qml
@@ -71,9 +71,9 @@ Item {
}
- function addToolVisuals() {
+ function addToolbarVisuals() {
if (_objMgrToolVisuals.empty) {
- _objMgrToolVisuals.createObject(editHeaderComponent, mapControl)
+ _objMgrToolVisuals.createObject(toolbarComponent, mapControl)
}
}
@@ -155,7 +155,7 @@ Item {
function _handleInteractiveChanged() {
if (interactive) {
addEditingVisuals()
- addToolVisuals()
+ addToolbarVisuals()
} else {
_traceMode = false
removeEditingVisuals()
@@ -513,73 +513,53 @@ Item {
}
Component {
- id: editHeaderComponent
+ id: toolbarComponent
- Item {
- x: mapControl.centerViewport.left + _viewportMargins
- y: mapControl.centerViewport.top + _viewportMargins
- width: mapControl.centerViewport.width - (_viewportMargins * 2)
- height: editHeaderRowLayout.y + editHeaderRowLayout.height + _viewportMargins
+ PlanEditToolbar {
+ x: mapControl.centerViewport.left + _margins
+ y: mapControl.centerViewport.top + _margins
+ width: mapControl.centerViewport.width - (_margins * 2)
z: QGroundControl.zOrderMapItems + 2
- property real _radius: ScreenTools.defaultFontPixelWidth / 2
- property real _viewportMargins: ScreenTools.defaultFontPixelWidth
+ property real _margins: ScreenTools.defaultFontPixelWidth
- Rectangle {
- anchors.fill: parent
- radius: _radius
- color: "white"
- opacity: 0.75
+ QGCButton {
+ _horizontalPadding: 0
+ text: qsTr("Basic Polygon")
+ visible: !_traceMode
+ onClicked: _resetPolygon()
}
- RowLayout {
- id: editHeaderRowLayout
- anchors.margins: _viewportMargins
- anchors.top: parent.top
- anchors.left: parent.left
- anchors.right: parent.right
-
- QGCButton {
- text: qsTr("Basic Polygon")
- visible: !_traceMode
- onClicked: _resetPolygon()
- }
-
- QGCButton {
- text: qsTr("Circular Polygon")
- visible: !_traceMode
- onClicked: _resetCircle()
- }
+ QGCButton {
+ _horizontalPadding: 0
+ text: qsTr("Circular Polygon")
+ visible: !_traceMode
+ onClicked: _resetCircle()
+ }
- 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 {
+ _horizontalPadding: 0
+ 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 {
- id: instructionLabel
- color: "black"
- text: _instructionText
- Layout.fillWidth: true
- }
+ QGCButton {
+ _horizontalPadding: 0
+ text: qsTr("Load KML/SHP...")
+ onClicked: kmlOrSHPLoadDialog.openForLoad()
+ visible: !_traceMode
}
}
}
@@ -589,7 +569,7 @@ Item {
id: traceMouseAreaComponent
MouseArea {
- anchors.fill: map
+ anchors.fill: mapControl
preventStealing: true
z: QGroundControl.zOrderMapItems + 1 // Over item indicators
@@ -640,38 +620,6 @@ Item {
_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()
- }
- */
}
}
diff --git a/src/MissionManager/QGCMapPolyline.cc b/src/MissionManager/QGCMapPolyline.cc
index c4a3085..16ddf12 100644
--- a/src/MissionManager/QGCMapPolyline.cc
+++ b/src/MissionManager/QGCMapPolyline.cc
@@ -27,6 +27,7 @@ QGCMapPolyline::QGCMapPolyline(QObject* parent)
: QObject (parent)
, _dirty (false)
, _interactive (false)
+ , _resetActive (false)
{
_init();
}
@@ -35,6 +36,7 @@ QGCMapPolyline::QGCMapPolyline(const QGCMapPolyline& other, QObject* parent)
: QObject (parent)
, _dirty (false)
, _interactive (false)
+ , _resetActive (false)
{
*this = other;
@@ -118,6 +120,8 @@ QPointF QGCMapPolyline::_pointFFromCoord(const QGeoCoordinate& coordinate) const
void QGCMapPolyline::setPath(const QList& path)
{
+ _beginResetIfNotActive();
+
_polylinePath.clear();
_polylineModel.clearAndDeleteContents();
for (const QGeoCoordinate& coord: path) {
@@ -126,20 +130,22 @@ void QGCMapPolyline::setPath(const QList& path)
}
setDirty(true);
- emit pathChanged();
+
+ _endResetIfNotActive();
}
void QGCMapPolyline::setPath(const QVariantList& path)
{
- _polylinePath = path;
+ _beginResetIfNotActive();
+ _polylinePath = path;
_polylineModel.clearAndDeleteContents();
for (int i=0; i<_polylinePath.count(); i++) {
_polylineModel.append(new QGCQGeoCoordinate(_polylinePath[i].value(), this));
}
-
setDirty(true);
- emit pathChanged();
+
+ _endResetIfNotActive();
}
@@ -339,6 +345,8 @@ QList QGCMapPolyline::offsetPolyline(double distance)
bool QGCMapPolyline::loadKMLFile(const QString& kmlFile)
{
+ _beginResetIfNotActive();
+
QString errorString;
QList rgCoords;
if (!KMLFileHelper::loadPolylineFromFile(kmlFile, rgCoords, errorString)) {
@@ -349,6 +357,8 @@ bool QGCMapPolyline::loadKMLFile(const QString& kmlFile)
clear();
appendVertices(rgCoords);
+ _endResetIfNotActive();
+
return true;
}
@@ -380,12 +390,41 @@ double QGCMapPolyline::length(void) const
void QGCMapPolyline::appendVertices(const QList& coordinates)
{
- QList objects;
+ _beginResetIfNotActive();
+ QList objects;
for (const QGeoCoordinate& coordinate: coordinates) {
objects.append(new QGCQGeoCoordinate(coordinate, this));
_polylinePath.append(QVariant::fromValue(coordinate));
}
_polylineModel.append(objects);
+
+ _endResetIfNotActive();
+}
+
+void QGCMapPolyline::beginReset(void)
+{
+ _resetActive = true;
+ _polylineModel.beginReset();
+}
+
+void QGCMapPolyline::endReset(void)
+{
+ _resetActive = false;
+ _polylineModel.endReset();
emit pathChanged();
}
+
+void QGCMapPolyline::_beginResetIfNotActive(void)
+{
+ if (!_resetActive) {
+ beginReset();
+ }
+}
+
+void QGCMapPolyline::_endResetIfNotActive(void)
+{
+ if (!_resetActive) {
+ endReset();
+ }
+}
diff --git a/src/MissionManager/QGCMapPolyline.h b/src/MissionManager/QGCMapPolyline.h
index 78254c7..5f16f8e 100644
--- a/src/MissionManager/QGCMapPolyline.h
+++ b/src/MissionManager/QGCMapPolyline.h
@@ -30,6 +30,8 @@ public:
Q_PROPERTY(QmlObjectListModel* pathModel READ qmlPathModel CONSTANT)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
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);
@@ -52,11 +54,14 @@ public:
/// @return true: success
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
QList coordinateList(void) const;
/// 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.
/// @param json Json object to save to
@@ -76,12 +81,13 @@ public:
double length(void) const;
// Property methods
-
int count (void) const { return _polylinePath.count(); }
bool dirty (void) const { return _dirty; }
void setDirty (bool dirty);
bool interactive (void) const { return _interactive; }
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& pathModel (void) { return _polylineModel; }
@@ -104,12 +110,15 @@ private slots:
void _polylineModelDirtyChanged(bool dirty);
private:
- void _init(void);
- QGeoCoordinate _coordFromPointF(const QPointF& point) const;
- QPointF _pointFFromCoord(const QGeoCoordinate& coordinate) const;
+ void _init (void);
+ QGeoCoordinate _coordFromPointF (const QPointF& point) const;
+ QPointF _pointFFromCoord (const QGeoCoordinate& coordinate) const;
+ void _beginResetIfNotActive (void);
+ void _endResetIfNotActive (void);
QVariantList _polylinePath;
QmlObjectListModel _polylineModel;
bool _dirty;
bool _interactive;
+ bool _resetActive;
};
diff --git a/src/MissionManager/QGCMapPolylineVisuals.qml b/src/MissionManager/QGCMapPolylineVisuals.qml
index 57010c1..fe34080 100644
--- a/src/MissionManager/QGCMapPolylineVisuals.qml
+++ b/src/MissionManager/QGCMapPolylineVisuals.qml
@@ -30,85 +30,92 @@ Item {
property int lineWidth: 3
property color lineColor: "#be781c"
-
- property var _polylineComponent
property var _dragHandlesComponent
property var _splitHandlesComponent
-
- property real _zorderDragHandle: QGroundControl.zOrderMapItems + 3 // Highest to prevent splitting when items overlap
- property real _zorderSplitHandle: QGroundControl.zOrderMapItems + 2
-
- function addVisuals() {
- _polylineComponent = polylineComponent.createObject(mapControl)
- mapControl.addMapItem(_polylineComponent)
- }
-
- function removeVisuals() {
- _polylineComponent.destroy()
- }
-
- function addHandles() {
- if (!_dragHandlesComponent) {
- _dragHandlesComponent = dragHandlesComponent.createObject(mapControl)
- _splitHandlesComponent = splitHandlesComponent.createObject(mapControl)
+ property bool _traceMode: false
+ property string _instructionText: _corridorToolsText
+ property real _zorderDragHandle: QGroundControl.zOrderMapItems + 3 // Highest to prevent splitting when items overlap
+ property real _zorderSplitHandle: QGroundControl.zOrderMapItems + 2
+ property var _savedVertices: [ ]
+
+ 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 _addCommonVisuals() {
+ if (_objMgrCommonVisuals.empty) {
+ _objMgrCommonVisuals.createObject(polylineComponent, mapControl, true)
}
}
- function removeHandles() {
- if (_dragHandlesComponent) {
- _dragHandlesComponent.destroy()
- _dragHandlesComponent = undefined
- }
- if (_splitHandlesComponent) {
- _splitHandlesComponent.destroy()
- _splitHandlesComponent = undefined
+ function _addInteractiveVisuals() {
+ if (_objMgrInteractiveVisuals.empty) {
+ _objMgrInteractiveVisuals.createObjects([ dragHandlesComponent, splitHandlesComponent, toolbarComponent ], mapControl)
}
}
/// Calculate the default/initial polyline
- function defaultPolylineVertices() {
- var x = map.centerViewport.x + (map.centerViewport.width / 2)
- var yInset = map.centerViewport.height / 4
- var topPointCoord = map.toCoordinate(Qt.point(x, map.centerViewport.y + yInset), false /* clipToViewPort */)
- var bottomPointCoord = map.toCoordinate(Qt.point(x, map.centerViewport.y + map.centerViewport.height - yInset), false /* clipToViewPort */)
+ function _defaultPolylineVertices() {
+ var x = mapControl.centerViewport.x + (mapControl.centerViewport.width / 2)
+ var yInset = mapControl.centerViewport.height / 4
+ var topPointCoord = mapControl.toCoordinate(Qt.point(x, mapControl.centerViewport.y + yInset), false /* clipToViewPort */)
+ var bottomPointCoord = mapControl.toCoordinate(Qt.point(x, mapControl.centerViewport.y + mapControl.centerViewport.height - yInset), false /* clipToViewPort */)
return [ topPointCoord, bottomPointCoord ]
}
- /// Add an initial 2 point polyline
- function addInitialPolyline() {
- if (mapPolyline.count < 2) {
- mapPolyline.clear()
- var initialVertices = defaultPolylineVertices()
- mapPolyline.appendVertex(initialVertices[0])
- mapPolyline.appendVertex(initialVertices[1])
+ /// Reset polyline back to initial default
+ function _resetPolyline() {
+ mapPolyline.beginReset()
+ mapPolyline.clear()
+ var initialVertices = _defaultPolylineVertices()
+ mapPolyline.appendVertex(initialVertices[0])
+ mapPolyline.appendVertex(initialVertices[1])
+ mapPolyline.endReset()
+ }
+
+ function _saveCurrentVertices() {
+ _savedVertices = [ ]
+ for (var i=0; i 0 && _cameraMinTriggerInterval !== 0 && _cameraMinTriggerInterval > missionItem.timeBetweenShots
- }
+ Component.onCompleted: currentIndex = 0
- CameraCalcGrid {
- cameraCalc: missionItem.cameraCalc
- vehicleFlightIsFrontal: true
- distanceToSurfaceLabel: qsTr("Altitude")
- distanceToSurfaceAltitudeMode: missionItem.followTerrain ?
- QGroundControl.AltitudeModeAboveTerrain :
- missionItem.cameraCalc.distanceToSurfaceRelative
- frontalDistanceLabel: qsTr("Trigger Dist")
- sideDistanceLabel: qsTr("Spacing")
+ QGCTabButton { text: qsTr("Grid") }
+ QGCTabButton { text: qsTr("Camera") }
}
- SectionHeader {
- id: corridorHeader
- text: qsTr("Corridor")
- }
+ Column {
+ anchors.left: parent.left
+ anchors.right: parent.right
+ spacing: _margin
+ visible: tabBar.currentIndex == 0
+
+ QGCLabel {
+ anchors.left: parent.left
+ 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
+ }
- GridLayout {
- anchors.left: parent.left
- anchors.right: parent.right
- columnSpacing: _margin
- rowSpacing: _margin
- columns: 2
- visible: corridorHeader.checked
-
- QGCLabel { text: qsTr("Width") }
- FactTextField {
- fact: missionItem.corridorWidth
- Layout.fillWidth: true
+
+ CameraCalcGrid {
+ cameraCalc: missionItem.cameraCalc
+ vehicleFlightIsFrontal: true
+ distanceToSurfaceLabel: qsTr("Altitude")
+ distanceToSurfaceAltitudeMode: missionItem.followTerrain ?
+ QGroundControl.AltitudeModeAboveTerrain :
+ missionItem.cameraCalc.distanceToSurfaceRelative
+ frontalDistanceLabel: qsTr("Trigger Dist")
+ sideDistanceLabel: qsTr("Spacing")
}
- QGCLabel { text: qsTr("Turnaround dist") }
- FactTextField {
- fact: missionItem.turnAroundDistance
- Layout.fillWidth: true
+ SectionHeader {
+ id: corridorHeader
+ text: qsTr("Corridor")
}
- QGCOptionsComboBox {
- Layout.columnSpan: 2
- Layout.fillWidth: true
-
- model: [
- {
- text: qsTr("Images in turnarounds"),
- fact: missionItem.cameraTriggerInTurnAround,
- enabled: missionItem.hoverAndCaptureAllowed ? !missionItem.hoverAndCapture.rawValue : true,
- visible: true
- },
- {
- text: qsTr("Relative altitude"),
- enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain,
- visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!missionItem.cameraCalc.distanceToSurfaceRelative && !missionItem.followTerrain),
- checked: missionItem.cameraCalc.distanceToSurfaceRelative
- }
- ]
+ GridLayout {
+ anchors.left: parent.left
+ anchors.right: parent.right
+ columnSpacing: _margin
+ rowSpacing: _margin
+ columns: 2
+ visible: corridorHeader.checked
+
+ QGCLabel { text: qsTr("Width") }
+ FactTextField {
+ fact: missionItem.corridorWidth
+ Layout.fillWidth: true
+ }
- onItemClicked: {
- if (index == 1) {
- missionItem.cameraCalc.distanceToSurfaceRelative = !missionItem.cameraCalc.distanceToSurfaceRelative
- console.log(missionItem.cameraCalc.distanceToSurfaceRelative)
- }
+ QGCLabel { text: qsTr("Turnaround dist") }
+ FactTextField {
+ fact: missionItem.turnAroundDistance
+ Layout.fillWidth: true
}
- }
- }
- QGCButton {
- text: qsTr("Rotate Entry Point")
- onClicked: missionItem.rotateEntryPoint()
- }
+ QGCOptionsComboBox {
+ Layout.columnSpan: 2
+ Layout.fillWidth: true
- SectionHeader {
- id: terrainHeader
- text: qsTr("Terrain")
- checked: missionItem.followTerrain
- }
+ model: [
+ {
+ text: qsTr("Images in turnarounds"),
+ fact: missionItem.cameraTriggerInTurnAround,
+ enabled: missionItem.hoverAndCaptureAllowed ? !missionItem.hoverAndCapture.rawValue : true,
+ visible: true
+ },
+ {
+ text: qsTr("Relative altitude"),
+ enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain,
+ visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!missionItem.cameraCalc.distanceToSurfaceRelative && !missionItem.followTerrain),
+ checked: missionItem.cameraCalc.distanceToSurfaceRelative
+ }
+ ]
+
+ onItemClicked: {
+ if (index == 1) {
+ missionItem.cameraCalc.distanceToSurfaceRelative = !missionItem.cameraCalc.distanceToSurfaceRelative
+ console.log(missionItem.cameraCalc.distanceToSurfaceRelative)
+ }
+ }
+ }
+ }
- ColumnLayout {
- anchors.left: parent.left
- anchors.right: parent.right
- spacing: _margin
- visible: terrainHeader.checked
+ QGCButton {
+ text: qsTr("Rotate Entry Point")
+ onClicked: missionItem.rotateEntryPoint()
+ }
- QGCCheckBox {
- id: followsTerrainCheckBox
- text: qsTr("Vehicle follows terrain")
+ SectionHeader {
+ id: terrainHeader
+ text: qsTr("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
+ 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
}
- QGCLabel { text: qsTr("Max Climb Rate") }
- FactTextField {
- fact: missionItem.terrainAdjustMaxClimbRate
+ 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 Descent Rate") }
- FactTextField {
- fact: missionItem.terrainAdjustMaxDescentRate
- 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 {
- id: statsHeader
- text: qsTr("Statistics")
- }
-
- TransectStyleComplexItemStats { }
- } // Grid Column
+ SectionHeader {
+ id: statsHeader
+ text: qsTr("Statistics")
+ }
- 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")
+ TransectStyleComplexItemStats { }
+ } // 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
+ }
}
-} // Rectangle
+}
diff --git a/src/PlanView/CorridorScanMapVisual.qml b/src/PlanView/CorridorScanMapVisual.qml
index 22a98a0..025034a 100644
--- a/src/PlanView/CorridorScanMapVisual.qml
+++ b/src/PlanView/CorridorScanMapVisual.qml
@@ -21,8 +21,6 @@ TransectStyleMapVisuals {
property bool _currentItem: object.isCurrentItem
- Component.onCompleted: mapPolylineVisuals.addInitialPolyline()
-
QGCMapPolylineVisuals {
id: mapPolylineVisuals
mapControl: map
diff --git a/src/PlanView/PlanEditToolbar.qml b/src/PlanView/PlanEditToolbar.qml
new file mode 100644
index 0000000..f3a837c
--- /dev/null
+++ b/src/PlanView/PlanEditToolbar.qml
@@ -0,0 +1,73 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+import QtQuick 2.3
+import QtQuick.Controls 2.11
+import QtQuick.Layouts 1.2
+
+import QGroundControl 1.0
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.Controls 1.0
+
+/// Toolbar used for things like Polygon editing tools
+Item {
+ height: toolsFlickable.y + toolsFlickable.height + _margins
+ z: QGroundControl.zOrderMapItems + 2
+
+ property real _radius: ScreenTools.defaultFontPixelWidth / 2
+ property real _margins: ScreenTools.defaultFontPixelWidth / 2
+
+ Component.onCompleted: {
+ // Move the child controls from consumer into the layout control
+ var moveList = []
+ var i
+ for (i = 2; i < children.length; i++) {
+ moveList.push(children[i])
+ }
+ for (i = 0; i < moveList.length; i++) {
+ moveList[i].parent = toolsRowLayout
+ }
+ instructionComponent.createObject(toolsRowLayout)
+ }
+
+ Rectangle {
+ anchors.fill: parent
+ radius: _radius
+ color: "white"
+ opacity: 0.75
+ }
+
+ QGCFlickable {
+ id: toolsFlickable
+ anchors.margins: _margins
+ anchors.top: parent.top
+ anchors.left: parent.left
+ anchors.right: parent.right
+ height: toolsRowLayout.height
+ clip: true
+ flickableDirection: Flickable.HorizontalFlick
+ contentWidth: toolsRowLayout.width
+
+ RowLayout {
+ id: toolsRowLayout
+ spacing: _margins
+ }
+ }
+
+ Component {
+ id: instructionComponent
+
+ QGCLabel {
+ id: instructionLabel
+ color: "black"
+ text: _instructionText
+ Layout.fillWidth: true
+ }
+ }
+}
diff --git a/src/QmlControls/QGroundControl/Controls/qmldir b/src/QmlControls/QGroundControl/Controls/qmldir
index 44e56cf..fae59ca 100644
--- a/src/QmlControls/QGroundControl/Controls/qmldir
+++ b/src/QmlControls/QGroundControl/Controls/qmldir
@@ -39,6 +39,7 @@ PageView 1.0 PageView.qml
ParameterEditor 1.0 ParameterEditor.qml
ParameterEditorDialog 1.0 ParameterEditorDialog.qml
PIDTuning 1.0 PIDTuning.qml
+PlanEditToolbar 1.0 PlanEditToolbar.qml
PreFlightCheckButton 1.0 PreFlightCheckButton.qml
PreFlightCheckGroup 1.0 PreFlightCheckGroup.qml
PreFlightCheckModel 1.0 PreFlightCheckModel.qml