diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index a927410dfc3e1c8186a9a8f41366581f86449ca4..14e815b24f2e53ccac1c1b3dd2db811ab8b89c20 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -1345,4 +1345,4 @@ contains (CONFIG, QGC_DISABLE_INSTALLER_SETUP) {
}
DISTFILES += \
- src/WimaView/WimaMeasurementAreaEditor.qml
+ src/WimaView/WimaMeasurementAreaEditor.qml \
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index c5cdea2278235b56166698c651dfed17fe922757..192af4aabbe41ef0893c829370114828877a83f9 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -277,6 +277,7 @@
src/Wima/WimaMeasurementArea.SettingsGroup.json
src/Wima/CircularSurvey.SettingsGroup.json
src/Wima/WimaArea.SettingsGroup.json
+ src/Wima/WimaController.SettingsGroup.json
src/comm/APMArduCopterMockLink.params
diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml
index edd47a0f8fee53f8b486d6a465ba3663e1f29a2c..a538e34c5b9655c485d71cd303865cae553506e8 100644
--- a/src/FlightDisplay/FlightDisplayView.qml
+++ b/src/FlightDisplay/FlightDisplayView.qml
@@ -402,7 +402,8 @@ QGCView {
script: {
// Stop video, restart it again with Timer
// Avoiding crashs if ParentChange is not yet done
- QGroundControl.videoManager.stopVideo()
+ QGroundControl.video
+ visible: _splitConcave.visibleManager.stopVideo()
videoPopUpTimer.running = true
}
}
@@ -512,22 +513,6 @@ QGCView {
FlightDisplayViewWidgets {
id: flightDisplayViewWidgets
-<<<<<<< HEAD
-=======
- z: _panel.z + 4
- height: ScreenTools.availableHeight - (singleMultiSelector.visible ? singleMultiSelector.height + _margins : 0)
- anchors.left: parent.left
- anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
- anchors.bottom: parent.bottom
- qgcView: root
- useLightColors: isBackgroundDark
- missionController: _missionController
- visible: singleVehicleView.checked && !QGroundControl.videoManager.fullScreen
- }
-
- FlightDisplayWimaMenu {
- id: wimaMenu
->>>>>>> ea04fc44a33fa7111877cdbdc2644ae4a9db9d2c
z: _panel.z + 4
height: ScreenTools.availableHeight - (singleMultiSelector.visible ? singleMultiSelector.height + _margins : 0)
anchors.left: parent.left
@@ -546,8 +531,6 @@ QGCView {
anchors.bottom: parent.bottom
anchors.leftMargin: ScreenTools.defaultFontPixelHeight * 0.25
anchors.bottomMargin: ScreenTools.defaultFontPixelHeight * 0.25
- height: 300
- width: 300
wimaController: wimaController
diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml
index 6dfa0590ba60a4671726fb24fd8a6d720d5b88a6..e03b8dc394127c6e64877fe9f1d8e44b92f79ae0 100644
--- a/src/FlightDisplay/FlightDisplayViewMap.qml
+++ b/src/FlightDisplay/FlightDisplayViewMap.qml
@@ -193,6 +193,13 @@ FlightMap {
property real leftToolWidth: toolStrip.x + toolStrip.width
}
+ // Add mission items generated by wima planer to the map
+ WimaPlanMapItems {
+ map: flightMap
+ largeMapView: _mainIsMap
+ wimaController: flightMap.wimaController
+ }
+
// Add wima Areas to the Map
MapItemView {
model: wimaController.visualItems
@@ -205,18 +212,10 @@ FlightMap {
: object.type === "WimaMeasurementAreaData" ? "green"
: "transparent"
opacity: 0.25
- z: QGroundControl.zOrderTrajectoryLines-2
+ z: QGroundControl.zOrderWaypointLines-2
}
}
- // Add mission items generated by wima planer to the map
- WimaPlanMapItems {
- map: flightMap
- largeMapView: _mainIsMap
- wimaController: flightMap.wimaController
- z: QGroundControl.zOrderTrajectoryLines-1
- }
-
// Add trajectory points to the map
MapItemView {
model: _mainIsMap ? _activeVehicle ? _activeVehicle.trajectoryPoints : 0 : 0
diff --git a/src/FlightDisplay/FlightDisplayWimaMenu.qml b/src/FlightDisplay/FlightDisplayWimaMenu.qml
index 776a28ef8172f96b14944ac54c32666b10675bcc..3e4c04370928136a86f4c6860f876d9ad79f85c6 100644
--- a/src/FlightDisplay/FlightDisplayWimaMenu.qml
+++ b/src/FlightDisplay/FlightDisplayWimaMenu.qml
@@ -14,9 +14,13 @@ import QGroundControl.Vehicle 1.0
import QGroundControl.FlightMap 1.0
import QGroundControl.Airspace 1.0
import QGroundControl.Airmap 1.0
+import QGroundControl.FactSystem 1.0
+import QGroundControl.FactControls 1.0
Item {
- id: _root
+ id: _root
+ height: 400
+ width: 250
property var wimaController // must be provided by the user
@@ -24,61 +28,131 @@ Item {
Rectangle {
anchors.left: parent.left
anchors.bottom: parent.bottom
- height: enableWima.checked ? parent.height : enableWima.height
- width: enableWima.checked ? parent.width : enableWima.width
- color: "black"
+ height: enableWima.enableWimaBoolean ? parent.height : enableWima.height
+ width: enableWima.enableWimaBoolean ? parent.width : enableWima.width
+ color: enableWima.enableWimaBoolean ? qgcPal.window : "transparent"
+ radius: ScreenTools.defaultFontPixelHeight / 4
+ anchors.topMargin: ScreenTools.defaultFontPixelHeight * 0.5
+ anchors.bottomMargin: ScreenTools.defaultFontPixelHeight * 0.5
+ anchors.rightMargin: ScreenTools.defaultFontPixelHeight * 0.5
+ anchors.leftMargin: ScreenTools.defaultFontPixelHeight * 0.5
// checkbox to enable/ disable wima
- QGCCheckBox {
+ SliderSwitch {
id: enableWima
- checked: true
anchors.horizontalCenter: parent.horizontalCenter
+ anchors.topMargin: ScreenTools.defaultFontPixelHeight * 0.25
anchors.top: parent.top
- text: qsTr("WiMA")
- }
+ confirmText: enableWimaBoolean ? qsTr("disable WiMA") : qsTr("enable WiMA")
- // horizonal line
- Rectangle {
- id: horizontalLine
- anchors.left: parent.left
- anchors.right: parent.right
- anchors.top: enableWima.bottom
- anchors.leftMargin: ScreenTools.defaultFontPixelHeight * 0.5
- anchors.rightMargin: ScreenTools.defaultFontPixelHeight * 0.5
- anchors.topMargin: ScreenTools.defaultFontPixelHeight * 0.25
- height: 1
+ property var enableWimaFact: wimaController.enableWimaController
+ property bool enableWimaBoolean: enableWimaFact.value
- color: "white"
+ onAccept: {
+ if (enableWimaBoolean) {
+ enableWimaFact.value = false
+ } else {
+ enableWimaFact.value = true
+ }
+ }
}
- ColumnLayout {
- id : mainColumn
- anchors.left: parent.left
- anchors.right: parent.right
- anchors.top: horizontalLine.bottom
- anchors.bottom: parent.bottom
- anchors.topMargin: ScreenTools.defaultFontPixelHeight * 0.5
- anchors.bottomMargin: ScreenTools.defaultFontPixelHeight * 0.5
- anchors.rightMargin: ScreenTools.defaultFontPixelHeight * 0.5
- anchors.leftMargin: ScreenTools.defaultFontPixelHeight * 0.5
- spacing: ScreenTools.defaultFontPixelHeight * 0.5
-
- QGCButton {
- id: buttonNextMissionPhase
- text: "Next Phase"
- onClicked: wimaController.nextPhase();
+ Column {
+ id: mainColumn
+ anchors.top: enableWima.bottom
+ anchors.left: parent.left
+ anchors.right: parent.right
+ anchors.bottom: parent.bottom
+ anchors.margins: ScreenTools.defaultFontPixelHeight * 0.4
+ spacing: ScreenTools.defaultFontPixelHeight * 0.25
+
+
+ SectionHeader {
+ id: settingsHeader
+ text: qsTr("Settings")
}
+ GridLayout {
+ columns: 2
+ rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5
+ anchors.topMargin: ScreenTools.defaultFontPixelHeight * 0.25
+ visible: settingsHeader.checked
+
+ // Settings
+ QGCLabel { text: qsTr("Next Waypoint") }
+ FactTextField {
+ fact: wimaController.startWaypointIndex
+ Layout.fillWidth: true
+ }
+
+ QGCLabel { text: qsTr("Max Waypoints") }
+ FactTextField {
+ fact: wimaController.maxWaypointsPerPhase
+ Layout.fillWidth: true
+ }
+
+ QGCLabel { text: qsTr("Overlap") }
+ FactTextField {
+ fact: wimaController.overlapWaypoints
+ Layout.fillWidth: true
+ }
- QGCButton {
- id: buttonResetPhase
- text: "Reset Phase"
- onClicked: wimaController.resetPhase();
+ FactCheckBox {
+ text: qsTr("Show All")
+ fact: wimaController.showAllMissionItems
+ }
+
+ FactCheckBox {
+ text: qsTr("Show Current")
+ fact: wimaController.showCurrentMissionItems
+ }
+
+ }
+
+ SectionHeader{
+ id: commandHeader
+ text: qsTr("Commands")
}
+ GridLayout {
+ columns: 2
+ rowSpacing: ScreenTools.defaultFontPixelHeight * 0.5
+ anchors.topMargin: ScreenTools.defaultFontPixelHeight * 0.25
+ visible: commandHeader.checked
+
+ // Buttons
+ QGCButton {
+ id: buttonNextMissionPhase
+ text: qsTr("Next Phase")
+ onClicked: wimaController.nextPhase();
+ Layout.fillWidth: true
+ }
+
+ QGCButton {
+ id: buttonPreviousMissionPhase
+ text: qsTr("Previous Phase")
+ onClicked: wimaController.previousPhase();
+ Layout.fillWidth: true
+ }
+
+ QGCButton {
+ id: buttonResetPhase
+ text: qsTr("Reset Phase")
+ onClicked: wimaController.resetPhase();
+ Layout.fillWidth: true
+ }
+
+ QGCButton {
+ id: buttonUpload
+ text: qsTr("Upload")
+ onClicked: wimaController.uploadToVehicle();
+ Layout.fillWidth: true
+ }
- QGCButton {
- id: buttonUpload
- text: "Upload"
- onClicked: wimaController.uploadToVehicle();
+ QGCButton {
+ id: buttonRemoveFromVehicle
+ text: qsTr("Remove")
+ onClicked: wimaController.removeFromVehicle();
+ Layout.fillWidth: true
+ }
}
}
diff --git a/src/FlightMap/MapItems/WimaPlanMapItems.qml b/src/FlightMap/MapItems/WimaPlanMapItems.qml
index 7c9f1ec66ba260e3e60cfa03d504f0e7b8c4d518..db882ccc1243dd5fafaa7b08008172a233aa7daa 100644
--- a/src/FlightMap/MapItems/WimaPlanMapItems.qml
+++ b/src/FlightMap/MapItems/WimaPlanMapItems.qml
@@ -31,9 +31,13 @@ Item {
property var _missionLineViewComponent
property var _currentMissionLineViewComponent
+ property bool _showAllItems: wimaController.showAllMissionItems.value
+ property bool _showCurrentItems: wimaController.showCurrentMissionItems.value
+
// Add the mission item visuals to the map
- Repeater {
- model: largeMapView ? wimaController.missionItems : 0
+ Repeater {
+ model: largeMapView ? (_showAllItems ? wimaController.missionItems : 0) : 0
+ z: QGroundControl.zOrderWaypointIndicators-2
delegate: WimaMissionItemMapVisual {
map: _map
@@ -45,19 +49,12 @@ Item {
// }
// }
}
-
- /*onItemAdded: {
- console.log(wimaController.missionItems.count)
- }
-
- onItemRemoved: {
- console.log(wimaController.missionItems.count)
- }*/
}
// Add the current mission item visuals to the map
Repeater {
- model: largeMapView ? wimaController.currentMissionItems : 0
+ model: largeMapView ? (_showCurrentItems ? wimaController.currentMissionItems : 0) : 0
+ z: QGroundControl.zOrderWaypointIndicators-1
delegate: WimaMissionItemMapVisual {
map: _map
@@ -88,8 +85,8 @@ Item {
MapPolyline {
line.width: 3
- line.color: mIlineColor
- z: QGroundControl.zOrderWaypointLines
+ line.color: _showAllItems ? mIlineColor : "transparent"
+ z: QGroundControl.zOrderWaypointLines-2
path: wimaController.waypointPath
}
}
@@ -99,8 +96,8 @@ Item {
MapPolyline {
line.width: 3
- line.color: cMIlineColor
- z: QGroundControl.zOrderWaypointLines
+ line.color: _showCurrentItems ? cMIlineColor : "transparent"
+ z: QGroundControl.zOrderWaypointLines-1
path: wimaController.currentWaypointPath
}
}
diff --git a/src/PlanView/CircularSurveyItemEditor.qml b/src/PlanView/CircularSurveyItemEditor.qml
index a5e30c37aaf42520de2186fc2a3881d8dda723c0..8f30522660bc1e9e176b5d30aeabcbcc1e059982 100644
--- a/src/PlanView/CircularSurveyItemEditor.qml
+++ b/src/PlanView/CircularSurveyItemEditor.qml
@@ -129,20 +129,6 @@ Rectangle {
Layout.fillWidth: true
//onUpdated: angleSlider.value = missionItem.deltaAlpha.value
}
-
- /*QGCSlider {
- id: angleSlider
- minimumValue: 0.3
- maximumValue: 10
- stepSize: 0.1
- tickmarksEnabled: false
- Layout.fillWidth: true
- Layout.columnSpan: 2
- Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5
- Component.onCompleted: value = missionItem.deltaAlpha.value
- onValueChanged: missionItem.deltaAlpha.value = value
- updateValueWhileDragging: false
- }*/
}
ColumnLayout {
@@ -151,14 +137,36 @@ Rectangle {
spacing: _margin
visible: transectsHeader.checked
+ FactCheckBox {
+ text: qsTr("Snake Path")
+ fact: missionItem.isSnakePath
+ }
+
+ QGCCheckBox {
+ id: relAlt
+ Layout.alignment: Qt.AlignLeft
+ text: qsTr("Relative altitude")
+ checked: missionItem.cameraCalc.distanceToSurfaceRelative
+ enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain
+ visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!missionItem.cameraCalc.distanceToSurfaceRelative && !missionItem.followTerrain)
+ onClicked: missionItem.cameraCalc.distanceToSurfaceRelative = checked
+
+ Connections {
+ target: missionItem.cameraCalc
+ onDistanceToSurfaceRelativeChanged: relAlt.checked = missionItem.cameraCalc.distanceToSurfaceRelative
+ }
+ }
+
QGCButton {
text: qsTr("Reset Reference")
onClicked: missionItem.resetReference();
+ Layout.fillWidth: true
}
QGCButton {
text: qsTr("Rotate Entry Point")
onClicked: missionItem.rotateEntryPoint();
+ Layout.fillWidth: true
}
/*
@@ -170,22 +178,6 @@ Rectangle {
property Fact _splitConcave: missionItem.splitConcavePolygons
}
*/
-
-
- QGCCheckBox {
- id: relAlt
- Layout.alignment: Qt.AlignLeft
- text: qsTr("Relative altitude")
- checked: missionItem.cameraCalc.distanceToSurfaceRelative
- enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain
- visible: QGroundControl.corePlugin.options.showMissionAbsoluteAltitude || (!missionItem.cameraCalc.distanceToSurfaceRelative && !missionItem.followTerrain)
- onClicked: missionItem.cameraCalc.distanceToSurfaceRelative = checked
-
- Connections {
- target: missionItem.cameraCalc
- onDistanceToSurfaceRelativeChanged: relAlt.checked = missionItem.cameraCalc.distanceToSurfaceRelative
- }
- }
}
SectionHeader {
diff --git a/src/QmlControls/QGroundControlQmlGlobal.h b/src/QmlControls/QGroundControlQmlGlobal.h
index 26c3631e564200356b488dd0344c509f0fad6995..7ec8538cf24ba83292cab8b746fa9442ba926e78 100644
--- a/src/QmlControls/QGroundControlQmlGlobal.h
+++ b/src/QmlControls/QGroundControlQmlGlobal.h
@@ -173,10 +173,10 @@ public:
qreal zOrderTopMost () { return 1000; }
qreal zOrderWidgets () { return 100; }
qreal zOrderMapItems () { return 50; }
- qreal zOrderWaypointIndicators () { return 50; }
- qreal zOrderVehicles () { return 49; }
- qreal zOrderTrajectoryLines () { return 48; }
- qreal zOrderWaypointLines () { return 47; }
+ qreal zOrderWaypointIndicators () { return 40; }
+ qreal zOrderVehicles () { return 30; }
+ qreal zOrderTrajectoryLines () { return 20; }
+ qreal zOrderWaypointLines () { return 10; }
bool isVersionCheckEnabled () { return _toolbox->mavlinkProtocol()->versionCheckEnabled(); }
int mavlinkSystemID () { return _toolbox->mavlinkProtocol()->getSystemId(); }
diff --git a/src/Wima/CircularSurvey.SettingsGroup.json b/src/Wima/CircularSurvey.SettingsGroup.json
index e70d3b0e70957ec2e9582b3eec6867ea081e26b2..68c83f6114adf449ef753dabc4892edf37f101e1 100644
--- a/src/Wima/CircularSurvey.SettingsGroup.json
+++ b/src/Wima/CircularSurvey.SettingsGroup.json
@@ -26,5 +26,11 @@
"min": 0.3,
"decimalPlaces": 1,
"defaultValue": 5.0
+},
+{
+ "name": "IsSnakePath",
+ "shortDescription": "Determines whether the transects are arranged in a snake or a zig-zag manner.",
+ "type": "bool",
+ "defaultValue": 1
}
]
diff --git a/src/Wima/CircularSurveyComplexItem.cc b/src/Wima/CircularSurveyComplexItem.cc
index c8a6616fdb54d5e629dd9551a12872cd38216b2b..20e105cacbb76f48a778ef1390fc248e17229b8a 100644
--- a/src/Wima/CircularSurveyComplexItem.cc
+++ b/src/Wima/CircularSurveyComplexItem.cc
@@ -7,12 +7,14 @@ const char* CircularSurveyComplexItem::settingsGroup = "CircularSur
const char* CircularSurveyComplexItem::deltaRName = "DeltaR";
const char* CircularSurveyComplexItem::deltaAlphaName = "DeltaAlpha";
const char* CircularSurveyComplexItem::transectMinLengthName = "TransectMinLength";
+const char* CircularSurveyComplexItem::isSnakePathName = "IsSnakePath";
const char* CircularSurveyComplexItem::jsonComplexItemTypeValue = "circularSurvey";
const char* CircularSurveyComplexItem::jsonDeltaRKey = "deltaR";
const char* CircularSurveyComplexItem::jsonDeltaAlphaKey = "deltaAlpha";
const char* CircularSurveyComplexItem::jsonTransectMinLengthKey = "transectMinLength";
+const char* CircularSurveyComplexItem::jsonIsSnakePathKey = "isSnakePath";
const char* CircularSurveyComplexItem::jsonReferencePointLatKey = "referencePointLat";
const char* CircularSurveyComplexItem::jsonReferencePointLongKey = "referencePointLong";
const char* CircularSurveyComplexItem::jsonReferencePointAltKey = "referencePointAlt";
@@ -24,12 +26,14 @@ CircularSurveyComplexItem::CircularSurveyComplexItem(Vehicle *vehicle, bool flyV
, _deltaR (settingsGroup, _metaDataMap[deltaRName])
, _deltaAlpha (settingsGroup, _metaDataMap[deltaAlphaName])
, _transectMinLength (settingsGroup, _metaDataMap[transectMinLengthName])
+ , _isSnakePath (settingsGroup, _metaDataMap[isSnakePathName])
, _autoGenerated (false)
{
_editorQml = "qrc:/qml/CircularSurveyItemEditor.qml";
connect(&_deltaR, &Fact::valueChanged, this, &CircularSurveyComplexItem::_rebuildTransects);
connect(&_deltaAlpha, &Fact::valueChanged, this, &CircularSurveyComplexItem::_rebuildTransects);
connect(&_transectMinLength, &Fact::valueChanged, this, &CircularSurveyComplexItem::_rebuildTransects);
+ connect(&_isSnakePath, &Fact::valueChanged, this, &CircularSurveyComplexItem::_rebuildTransects);
connect(this, &CircularSurveyComplexItem::refPointChanged, this, &CircularSurveyComplexItem::_rebuildTransects);
}
@@ -99,12 +103,12 @@ bool CircularSurveyComplexItem::load(const QJsonObject &complexObject, int seque
{ jsonDeltaRKey, QJsonValue::Double, true },
{ jsonDeltaAlphaKey, QJsonValue::Double, true },
{ jsonTransectMinLengthKey, QJsonValue::Double, true },
+ { jsonIsSnakePathKey, QJsonValue::Bool, true },
{ jsonReferencePointLatKey, QJsonValue::Double, true },
{ jsonReferencePointLongKey, QJsonValue::Double, true },
{ jsonReferencePointAltKey, QJsonValue::Double, true },
};
-
if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
return false;
}
@@ -136,6 +140,7 @@ bool CircularSurveyComplexItem::load(const QJsonObject &complexObject, int seque
_referencePoint.setLongitude (complexObject[jsonReferencePointLongKey].toDouble());
_referencePoint.setLatitude (complexObject[jsonReferencePointLatKey].toDouble());
_referencePoint.setAltitude (complexObject[jsonReferencePointAltKey].toDouble());
+ _isSnakePath.setRawValue (complexObject[jsonIsSnakePathKey].toBool());
_autoGenerated = true;
_ignoreRecalc = false;
@@ -160,8 +165,9 @@ void CircularSurveyComplexItem::save(QJsonArray &planItems)
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
saveObject[jsonDeltaRKey] = _deltaR.rawValue().toDouble();
- saveObject[jsonDeltaAlphaKey] = _deltaAlpha.rawValue().toDouble();
+ saveObject[jsonDeltaAlphaKey] = _deltaAlpha.rawValue().toDouble();
saveObject[jsonTransectMinLengthKey] = _transectMinLength.rawValue().toDouble();
+ saveObject[jsonIsSnakePathKey] = _isSnakePath.rawValue().toBool();
saveObject[jsonReferencePointLongKey] = _referencePoint.longitude();
saveObject[jsonReferencePointLatKey] = _referencePoint.latitude();
saveObject[jsonReferencePointAltKey] = _referencePoint.altitude();
@@ -510,7 +516,8 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
return;
- // optimize path to lawn pattern
+ // optimize path to snake or zig-zag pattern
+ bool isSnakePattern = _isSnakePath.rawValue().toBool();
QList currentSection = fullPath.takeFirst();
if ( currentSection.isEmpty() )
return;
@@ -539,7 +546,7 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
}
}
currentSection = fullPath.takeAt(index);
- if (reversePath) {
+ if (reversePath && isSnakePattern) {
PolygonCalculus::reversePath(currentSection);
}
}
@@ -582,6 +589,11 @@ Fact *CircularSurveyComplexItem::transectMinLength()
return &_transectMinLength;
}
+Fact *CircularSurveyComplexItem::isSnakePath()
+{
+ return &_isSnakePath;
+}
+
diff --git a/src/Wima/CircularSurveyComplexItem.h b/src/Wima/CircularSurveyComplexItem.h
index 920b172f6b8ca466acd05d8c604a9fe049012c17..b075390e7dc6c2eeffa69ed51f6bc9101f2a55f3 100644
--- a/src/Wima/CircularSurveyComplexItem.h
+++ b/src/Wima/CircularSurveyComplexItem.h
@@ -18,11 +18,12 @@ public:
/// @param kmlOrShpFile Polygon comes from this file, empty for default polygon
CircularSurveyComplexItem(Vehicle* vehicle, bool flyView, const QString& kmlOrShpFile, QObject* parent);
- Q_PROPERTY(QGeoCoordinate refPoint READ refPoint WRITE setRefPoint NOTIFY refPointChanged)
- Q_PROPERTY(Fact* deltaR READ deltaR CONSTANT)
- Q_PROPERTY(Fact* deltaAlpha READ deltaAlpha CONSTANT)
- Q_PROPERTY(Fact* transectMinLength READ transectMinLength CONSTANT)
- Q_PROPERTY(bool autoGenerated READ autoGenerated NOTIFY autoGeneratedChanged)
+ Q_PROPERTY(QGeoCoordinate refPoint READ refPoint WRITE setRefPoint NOTIFY refPointChanged)
+ Q_PROPERTY(Fact* deltaR READ deltaR CONSTANT)
+ Q_PROPERTY(Fact* deltaAlpha READ deltaAlpha CONSTANT)
+ Q_PROPERTY(Fact* transectMinLength READ transectMinLength CONSTANT)
+ Q_PROPERTY(Fact* isSnakePath READ isSnakePath CONSTANT)
+ Q_PROPERTY(bool autoGenerated READ autoGenerated NOTIFY autoGeneratedChanged)
Q_INVOKABLE void resetReference(void);
@@ -34,8 +35,9 @@ public:
// Property getters
QGeoCoordinate refPoint() const;
Fact *deltaR();
- Fact *deltaAlpha();
+ Fact *deltaAlpha();
Fact *transectMinLength();
+ Fact *isSnakePath();
// Is true if survey was automatically generated, prevents initialisation from gui.
bool autoGenerated();
@@ -61,11 +63,13 @@ public:
static const char* deltaRName;
static const char* deltaAlphaName;
static const char* transectMinLengthName;
+ static const char* isSnakePathName;
static const char* jsonComplexItemTypeValue;
static const char* jsonDeltaRKey;
static const char* jsonDeltaAlphaKey;
- static const char* jsonTransectMinLengthKey;
+ static const char* jsonTransectMinLengthKey;
+ static const char* jsonIsSnakePathKey;
static const char* jsonReferencePointLongKey;
static const char* jsonReferencePointLatKey;
static const char* jsonReferencePointAltKey;
@@ -92,9 +96,10 @@ private:
QMap _metaDataMap;
- SettingsFact _deltaR;
- SettingsFact _deltaAlpha;
- SettingsFact _transectMinLength;
+ SettingsFact _deltaR; // distance between two neighbour circles
+ SettingsFact _deltaAlpha; // angle discretisation of the circles
+ SettingsFact _transectMinLength; // minimal transect lenght, transects are rejected if they are shorter than this value
+ SettingsFact _isSnakePath; // bool value, determining if transects are connected in a snake like or zig zag like manner
QTimer _updateTimer;
diff --git a/src/Wima/WimaController.SettingsGroup.json b/src/Wima/WimaController.SettingsGroup.json
new file mode 100644
index 0000000000000000000000000000000000000000..c9b11b3484b82b27c51bc2bcaac43db351341f7d
--- /dev/null
+++ b/src/Wima/WimaController.SettingsGroup.json
@@ -0,0 +1,38 @@
+[
+{
+ "name": "EnableWimaController",
+ "shortDescription": "Enables or disables the WimaController, which performes different tasks inside the flight view window.",
+ "type": "bool",
+ "defaultValue": 1
+},
+{
+ "name": "OverlapWaypoints",
+ "shortDescription": "Determines the number of overlapping waypoints between two consecutive mission phases.",
+ "type": "uint32",
+ "defaultValue": 2
+},
+{
+ "name": "MaxWaypointsPerPhase",
+ "shortDescription": "Determines the maximum number of waypoints per phase.",
+ "type": "uint32",
+ "defaultValue": 30
+},
+{
+ "name": "StartWaypointIndex",
+ "shortDescription": "The index of the start waypoint for the next mission phase.",
+ "type": "uint32",
+ "defaultValue": 1
+},
+{
+ "name": "ShowAllMissionItems",
+ "shortDescription": "Determines whether the mission items of the overall mission are displayed or not.",
+ "type": "bool",
+ "defaultValue": 1
+},
+{
+ "name": "ShowCurrentMissionItems",
+ "shortDescription": "Determines whether the mission items of the current mission phase are displayed or not.",
+ "type": "bool",
+ "defaultValue": 1
+}
+]
diff --git a/src/Wima/WimaController.cc b/src/Wima/WimaController.cc
index f5da60a8c1e988ff6c5218318d8e9fc097ae6334..81c3c09b3fe8b65f54e4f1559dd3efb5b61b829a 100644
--- a/src/Wima/WimaController.cc
+++ b/src/Wima/WimaController.cc
@@ -1,21 +1,38 @@
#include "WimaController.h"
-const char* WimaController::wimaFileExtension = "wima";
-const char* WimaController::areaItemsName = "AreaItems";
-const char* WimaController::missionItemsName = "MissionItems";
+const char* WimaController::wimaFileExtension = "wima";
+const char* WimaController::areaItemsName = "AreaItems";
+const char* WimaController::missionItemsName = "MissionItems";
+const char* WimaController::settingsGroup = "WimaController";
+const char* WimaController::enableWimaControllerName = "EnableWimaController";
+const char* WimaController::overlapWaypointsName = "OverlapWaypoints";
+const char* WimaController::maxWaypointsPerPhaseName = "MaxWaypointsPerPhase";
+const char* WimaController::startWaypointIndexName = "StartWaypointIndex";
+const char* WimaController::showAllMissionItemsName = "ShowAllMissionItems";
+const char* WimaController::showCurrentMissionItemsName = "ShowCurrentMissionItems";
WimaController::WimaController(QObject *parent)
- : QObject (parent)
- , _container (nullptr)
- , _joinedArea (this)
- , _measurementArea (this)
- , _serviceArea (this)
- , _corridor (this)
- , _localPlanDataValid (false)
- , _startWaypointIndex (1)
- , _endWaypointIndex (1)
-{
-
+ : QObject (parent)
+ , _container (nullptr)
+ , _joinedArea (this)
+ , _measurementArea (this)
+ , _serviceArea (this)
+ , _corridor (this)
+ , _localPlanDataValid (false)
+ , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/WimaController.SettingsGroup.json"), this))
+ , _enableWimaController (settingsGroup, _metaDataMap[enableWimaControllerName])
+ , _overlapWaypoints (settingsGroup, _metaDataMap[overlapWaypointsName])
+ , _maxWaypointsPerPhase (settingsGroup, _metaDataMap[maxWaypointsPerPhaseName])
+ , _startWaypointIndex (settingsGroup, _metaDataMap[startWaypointIndexName])
+ , _showAllMissionItems (settingsGroup, _metaDataMap[showAllMissionItemsName])
+ , _showCurrentMissionItems (settingsGroup, _metaDataMap[showCurrentMissionItemsName])
+{
+ _startWaypointIndex.setRawValue(int(1));
+ _showAllMissionItems.setRawValue(true);
+ _showCurrentMissionItems.setRawValue(true);
+ connect(&_overlapWaypoints, &Fact::rawValueChanged, this, &WimaController::updateNextWaypoint);
+ connect(&_maxWaypointsPerPhase, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
+ connect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
}
QmlObjectListModel* WimaController::visualItems()
@@ -65,6 +82,36 @@ QVariantList WimaController::currentWaypointPath()
return _currentWaypointPath;
}
+Fact *WimaController::enableWimaController()
+{
+ return &_enableWimaController;
+}
+
+Fact *WimaController::overlapWaypoints()
+{
+ return &_overlapWaypoints;
+}
+
+Fact *WimaController::maxWaypointsPerPhase()
+{
+ return &_maxWaypointsPerPhase;
+}
+
+Fact *WimaController::showAllMissionItems()
+{
+ return &_showAllMissionItems;
+}
+
+Fact *WimaController::showCurrentMissionItems()
+{
+ return &_showCurrentMissionItems;
+}
+
+Fact *WimaController::startWaypointIndex()
+{
+ return &_startWaypointIndex;
+}
+
void WimaController::setMasterController(PlanMasterController *masterC)
{
_masterController = masterC;
@@ -100,23 +147,31 @@ void WimaController::setDataContainer(WimaDataContainer *container)
void WimaController::nextPhase()
{
updateCurrentMissionItems();
- updateCurrentPath();
}
void WimaController::previousPhase()
{
+ if (_startWaypointIndex.rawValue().toInt() > 0) {
+ _startWaypointIndex.setRawValue( _startWaypointIndex.rawValue().toInt() - _maxWaypointsPerPhase.rawValue().toInt()
+ + _overlapWaypoints.rawValue().toInt());
+
+ }
}
void WimaController::resetPhase()
{
- _startWaypointIndex = 1;
- nextPhase();
+ _startWaypointIndex.setRawValue(int(1));
}
void WimaController::uploadToVehicle()
{
+ _masterController->sendToVehicle();
+}
+void WimaController::removeFromVehicle()
+{
+ _masterController->removeAllFromVehicle();
}
void WimaController::startMission()
@@ -299,12 +354,6 @@ void WimaController::containerDataValidChanged(bool valid)
if (areaCounter >= numAreas)
break;
}
-
-#ifdef QT_DEBUG
- //qWarning("containerDataValidChanged(): count:");
- //qWarning() << planData.missionItems().count();
-#endif
-
QList tempMissionItems = planData.missionItems();
// create mission items
@@ -343,26 +392,10 @@ void WimaController::containerDataValidChanged(bool valid)
_missionController->insertSimpleMissionItem(*missionItem, missionControllerVisualItems->count());
if ( missionItem->command() == MAV_CMD_NAV_VTOL_LAND
-<<<<<<< HEAD
- || missionItem->command() == MAV_CMD_NAV_LAND)
- break;
-
-=======
|| missionItem->command() == MAV_CMD_NAV_LAND)
- _missionController->insertSimpleMissionItem(*missionItem, missionControllerVisualItems->count());
- break;
->>>>>>> ea04fc44a33fa7111877cdbdc2644ae4a9db9d2c
+ break;
}
-
- // copy mission items to _missionItems
-// MissionSettingsItem *settingsItem = qobject_cast((*missionControllerVisualItems)[0]);
-// if (settingsItem == nullptr) {
-// qWarning("WimaController::containerDataValidChanged(): Nullptr at MissionSettingsItem!");
-// return;
-// }
-// _missionItems.append(settingsItem);
-
for ( int i = 1; i < missionControllerVisualItems->count(); i++) {
SimpleMissionItem *visualItem = qobject_cast((*missionControllerVisualItems)[i]);
if (visualItem == nullptr) {
@@ -377,9 +410,8 @@ void WimaController::containerDataValidChanged(bool valid)
_localPlanDataValid = true;
updateWaypointPath();
- _startWaypointIndex = 1;
+ _startWaypointIndex.setRawValue(int(1));
updateCurrentMissionItems();
- updateCurrentPath();
} else {
_localPlanDataValid = false;
@@ -398,25 +430,37 @@ void WimaController::containerDataValidChanged(bool valid)
void WimaController::updateCurrentMissionItems()
{
-<<<<<<< HEAD
- if (_missionItems.count() < 1 || !_localPlanDataValid)
+ int startWaypointIndexInt = _startWaypointIndex.rawValue().toInt()-1;
+ // check if data was fetched and mission end is not reached yet
+ if (_missionItems.count() < 1 || !_localPlanDataValid || startWaypointIndexInt >= _missionItems.count()-2)
return;
-=======
- if (_missionItems.count() < 0 || !_localPlanDataValid)
- return;
->>>>>>> ea04fc44a33fa7111877cdbdc2644ae4a9db9d2c
- int numberWaypoints = 30; // the number of waypoints currentMissionItems must not exceed
- int overlapping = 2; // number of overlapping waypoints of consecutive mission phases
+ int maxWaypointsPerPhaseInt = _maxWaypointsPerPhase.rawValue().toInt();
+
+ // determine end waypoint index
+ _endWaypointIndex = std::min(startWaypointIndexInt + maxWaypointsPerPhaseInt - 1, _missionItems.count()-2); // -2 -> last item is land item
+ // extract waypoints
QList geoCoordinateList; // list with potential waypoints (from _missionItems), for _currentMissionItems
- _endWaypointIndex = std::min(_startWaypointIndex + numberWaypoints - 1, _missionItems.count()-2); // -2 -> last item is land item
- if (!extractCoordinateList(_missionItems, geoCoordinateList, _startWaypointIndex, _endWaypointIndex)) {
+ if (!extractCoordinateList(_missionItems, geoCoordinateList, startWaypointIndexInt, _endWaypointIndex)) {
qWarning("WimaController::updateCurrentMissionItems(): error on waypoint extraction.");
_currentMissionItems.clear();
return;
}
- _startWaypointIndex = _endWaypointIndex + 1 - overlapping;
+
+ // set start waypoint index for next phase
+ if (_endWaypointIndex < _missionItems.count()-2) {
+ _startWaypointIndexList.append(_startWaypointIndex.rawValue().toInt());
+
+ disconnect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
+ _startWaypointIndex.setRawValue(std::max(_endWaypointIndex + 2 - _overlapWaypoints.rawValue().toInt(), 1));
+ connect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
+ }
+ else {
+ disconnect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
+ _startWaypointIndex.setRawValue(_missionItems.count()-1); // marks that end of mission is reached
+ connect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
+ }
// calculate path from home to first waypoint
QList path;
@@ -498,6 +542,7 @@ void WimaController::updateCurrentMissionItems()
_currentMissionItems.append(visualItemCopy);
}
+ updateCurrentPath();
emit currentMissionItemsChanged();
}
@@ -516,5 +561,14 @@ void WimaController::updateCurrentPath()
emit currentWaypointPathChanged();
}
+void WimaController::updateNextWaypoint()
+{
+ if (_endWaypointIndex < _missionItems.count()-2) {
+ disconnect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
+ _startWaypointIndex.setRawValue(_endWaypointIndex + 2 - _overlapWaypoints.rawValue().toInt());
+ connect(&_startWaypointIndex, &Fact::rawValueChanged, this, &WimaController::updateCurrentMissionItems);
+ }
+}
+
diff --git a/src/Wima/WimaController.h b/src/Wima/WimaController.h
index 39c4321a544b249f1cf37b4c1f6b4e669e119d5c..b7839563347d3d539a502eb9a4b07eeb577430d3 100644
--- a/src/Wima/WimaController.h
+++ b/src/Wima/WimaController.h
@@ -20,6 +20,7 @@
#include "MissionSettingsItem.h"
#include "JsonHelper.h"
#include "QGCApplication.h"
+#include "SettingsFact.h"
class WimaController : public QObject
@@ -32,18 +33,25 @@ public:
WimaController(QObject *parent = nullptr);
- Q_PROPERTY(PlanMasterController* masterController READ masterController WRITE setMasterController NOTIFY masterControllerChanged)
- Q_PROPERTY(MissionController* missionController READ missionController WRITE setMissionController NOTIFY missionControllerChanged)
- Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
- Q_PROPERTY(QString currentFile READ currentFile NOTIFY currentFileChanged)
- Q_PROPERTY(QStringList loadNameFilters READ loadNameFilters CONSTANT)
- Q_PROPERTY(QStringList saveNameFilters READ saveNameFilters CONSTANT)
- Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT)
- Q_PROPERTY(WimaDataContainer* dataContainer READ dataContainer WRITE setDataContainer NOTIFY dataContainerChanged)
- Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged)
- Q_PROPERTY(QmlObjectListModel* currentMissionItems READ currentMissionItems NOTIFY currentMissionItemsChanged)
- Q_PROPERTY(QVariantList waypointPath READ waypointPath NOTIFY waypointPathChanged)
- Q_PROPERTY(QVariantList currentWaypointPath READ currentWaypointPath NOTIFY currentWaypointPathChanged)
+ Q_PROPERTY(PlanMasterController* masterController READ masterController WRITE setMasterController NOTIFY masterControllerChanged)
+ Q_PROPERTY(MissionController* missionController READ missionController WRITE setMissionController NOTIFY missionControllerChanged)
+ Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
+ Q_PROPERTY(QString currentFile READ currentFile NOTIFY currentFileChanged)
+ Q_PROPERTY(QStringList loadNameFilters READ loadNameFilters CONSTANT)
+ Q_PROPERTY(QStringList saveNameFilters READ saveNameFilters CONSTANT)
+ Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT)
+ Q_PROPERTY(WimaDataContainer* dataContainer READ dataContainer WRITE setDataContainer NOTIFY dataContainerChanged)
+ Q_PROPERTY(QmlObjectListModel* missionItems READ missionItems NOTIFY missionItemsChanged)
+ Q_PROPERTY(QmlObjectListModel* currentMissionItems READ currentMissionItems NOTIFY currentMissionItemsChanged)
+ Q_PROPERTY(QVariantList waypointPath READ waypointPath NOTIFY waypointPathChanged)
+ Q_PROPERTY(QVariantList currentWaypointPath READ currentWaypointPath NOTIFY currentWaypointPathChanged)
+ Q_PROPERTY(Fact* enableWimaController READ enableWimaController CONSTANT)
+ Q_PROPERTY(Fact* overlapWaypoints READ overlapWaypoints CONSTANT)
+ Q_PROPERTY(Fact* maxWaypointsPerPhase READ maxWaypointsPerPhase CONSTANT)
+ Q_PROPERTY(Fact* startWaypointIndex READ startWaypointIndex CONSTANT)
+ Q_PROPERTY(Fact* showAllMissionItems READ showAllMissionItems CONSTANT)
+ Q_PROPERTY(Fact* showCurrentMissionItems READ showCurrentMissionItems CONSTANT)
+
// Property accessors
@@ -60,6 +68,12 @@ public:
QmlObjectListModel* currentMissionItems (void);
QVariantList waypointPath (void);
QVariantList currentWaypointPath (void);
+ Fact* enableWimaController (void);
+ Fact* overlapWaypoints (void);
+ Fact* maxWaypointsPerPhase (void);
+ Fact* startWaypointIndex (void);
+ Fact* showAllMissionItems (void);
+ Fact* showCurrentMissionItems (void);
// Property setters
@@ -71,7 +85,8 @@ public:
Q_INVOKABLE void nextPhase();
Q_INVOKABLE void previousPhase();
Q_INVOKABLE void resetPhase();
- Q_INVOKABLE void uploadToVehicle();
+ Q_INVOKABLE void uploadToVehicle();
+ Q_INVOKABLE void removeFromVehicle();
Q_INVOKABLE void startMission();
Q_INVOKABLE void abortMission();
Q_INVOKABLE void pauseMission();
@@ -86,7 +101,15 @@ public:
// static Members
static const char* wimaFileExtension;
static const char* areaItemsName;
- static const char* missionItemsName;
+ static const char* missionItemsName;
+ static const char* settingsGroup;
+ static const char* endWaypointIndexName;
+ static const char* enableWimaControllerName;
+ static const char* overlapWaypointsName;
+ static const char* maxWaypointsPerPhaseName;
+ static const char* startWaypointIndexName;
+ static const char* showAllMissionItemsName;
+ static const char* showCurrentMissionItemsName;
// Member Methodes
QJsonDocument saveToJson(FileType fileType);
@@ -118,6 +141,7 @@ private slots:
void updateCurrentMissionItems (void);
void updateWaypointPath (void);
void updateCurrentPath (void);
+ void updateNextWaypoint (void);
private:
@@ -136,10 +160,20 @@ private:
// _currentMissionItems contains a number of mission items which can be worked off with a single battery chrage
QVariantList _waypointPath; // path connecting the items in _missionItems
QVariantList _currentWaypointPath; // path connecting the items in _currentMissionItems
- int _startWaypointIndex; // index to the mission item stored in _missionItems defining the first element of _currentMissionItems
- QList _startWaypointIndexList;
- int _endWaypointIndex; // index to the mission item stored in _missionItems defining the last element of _currentMissionItems
+ QList _startWaypointIndexList; // list containing the last start waypoint indices, used by previosPhase
QGeoCoordinate _takeoffLandPostion;
-};
+
+ QMap _metaDataMap;
+ SettingsFact _enableWimaController; // enables or disables the wimaControler
+ SettingsFact _overlapWaypoints; // determines the number of overlapping waypoints between two consecutive mission phases
+ SettingsFact _maxWaypointsPerPhase; // determines the maximum number waypoints per phase
+ SettingsFact _startWaypointIndex; // index (displayed on the map, -1 to get index of item in _missionItems) of the mission item
+ //stored in _missionItems defining the first element of _currentMissionItems
+ SettingsFact _showAllMissionItems; // bool value, Determines whether the mission items of the overall mission are displayed or not.
+ SettingsFact _showCurrentMissionItems; // bool value, Determines whether the mission items of the current mission phase are displayed or not.
+
+ int _endWaypointIndex; // indes of the mission item stored in _missionItems defining the last element
+ // (which is not part of the return path) of _currentMissionItem
+};
diff --git a/src/WimaView/SphericalSurveyMapVisual.qml b/src/WimaView/SphericalSurveyMapVisual.qml
index 55f70acff908cc081f20cf1735e49879f2ee68e4..8c6683fab927e244277ab26cda046c5310fca6a4 100644
--- a/src/WimaView/SphericalSurveyMapVisual.qml
+++ b/src/WimaView/SphericalSurveyMapVisual.qml
@@ -86,7 +86,7 @@ Item {
}
function _setRefPoint() {
- _missionItem.refPoint = map.toCoordinate(map.centerViewport.x, map.centerViewport.y, false /* clipToViewPort */)
+ _missionItem.resetReference();
}
Component.onCompleted: {