diff --git a/WimaDok/main.tex b/WimaDok/main.tex
index 15efb6802526ff455dfa562f9369f46c6ea7a0de..b569afe1d09ab382026478ef566a24d6a30c6686 100644
--- a/WimaDok/main.tex
+++ b/WimaDok/main.tex
@@ -26,6 +26,8 @@ WiMA is a abbreviation for \textbf{Wi}reless \textbf{M}easurement \textbf{A}ppli
This document was created to explain the functionality of the WiMA-Extension at one hand, and to encourage the reader to find bugs inside the program. As the extension is still being developed the contents demonstrated inside this document may differ from those ones in the program.
The folder "deploy" in the QGroundControl root directory (can be cloned from Gitlab) contains a AppImage of the program. QGroundControl can be launched by double-clicking the AppImage. Currently only a Linux version is available.
+
+A Documentation of the QGroundControl program can be found under \url{https://docs.qgroundcontrol.com/en/}.
\section{Documentation}
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index e669249c141bbfb5703957859c40454cd696fa3e..c5cdea2278235b56166698c651dfed17fe922757 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -227,7 +227,9 @@
src/WimaView/CoordinateIndicator.qml
src/WimaView/WimaJoinedAreaMapVisual.qml
src/WimaView/WimaCorridorEditor.qml
- src/FlightMap/MapItems/WimaPlanMapItems.qml
+ src/FlightMap/MapItems/WimaPlanMapItems.qml
+ src/PlanView/WimaMissionItemMapVisual.qml
+ src/FlightDisplay/FlightDisplayWimaMenu.qml
src/Settings/APMMavlinkStreamRate.SettingsGroup.json
diff --git a/src/FlightDisplay/FlightDisplayView.qml b/src/FlightDisplay/FlightDisplayView.qml
index 673974b02126e0a0fad998ca8e8c38f94a995ad9..6a4e25cebe1f49b76edb3d34b85837ec04366225 100644
--- a/src/FlightDisplay/FlightDisplayView.qml
+++ b/src/FlightDisplay/FlightDisplayView.qml
@@ -510,17 +510,25 @@ QGCView {
}
}
- FlightDisplayViewWidgets {
- id: flightDisplayViewWidgets
+// FlightDisplayViewWidgets {
+// id: flightDisplayViewWidgets
+// 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
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
}
//-------------------------------------------------------------------------
diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml
index c3060d00b0470983741d5b55dca624079a53aba7..6dfa0590ba60a4671726fb24fd8a6d720d5b88a6 100644
--- a/src/FlightDisplay/FlightDisplayViewMap.qml
+++ b/src/FlightDisplay/FlightDisplayViewMap.qml
@@ -205,18 +205,16 @@ FlightMap {
: object.type === "WimaMeasurementAreaData" ? "green"
: "transparent"
opacity: 0.25
- z: QGroundControl.zOrderTrajectoryLines-1
+ z: QGroundControl.zOrderTrajectoryLines-2
}
}
// Add mission items generated by wima planer to the map
- PlanMapItems {
+ WimaPlanMapItems {
map: flightMap
largeMapView: _mainIsMap
- masterController: masterController
- isActiveVehicle: _vehicle.active
-
- property var _vehicle: object
+ wimaController: flightMap.wimaController
+ z: QGroundControl.zOrderTrajectoryLines-1
}
// Add trajectory points to the map
diff --git a/src/FlightDisplay/FlightDisplayWimaMenu.qml b/src/FlightDisplay/FlightDisplayWimaMenu.qml
new file mode 100644
index 0000000000000000000000000000000000000000..1d90c0f09fbaf9eda1158b99d0088d652d016256
--- /dev/null
+++ b/src/FlightDisplay/FlightDisplayWimaMenu.qml
@@ -0,0 +1,32 @@
+import QtQuick 2.3
+import QtQuick.Controls 1.2
+import QtQuick.Controls.Styles 1.4
+import QtQuick.Dialogs 1.2
+import QtLocation 5.3
+import QtPositioning 5.3
+import QtQuick.Layouts 1.2
+
+import QGroundControl 1.0
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.Controls 1.0
+import QGroundControl.Palette 1.0
+import QGroundControl.Vehicle 1.0
+import QGroundControl.FlightMap 1.0
+import QGroundControl.Airspace 1.0
+import QGroundControl.Airmap 1.0
+
+Item {
+ id: _root
+
+ Rectangle {
+ anchors.top: parent.top
+ color: "white"
+ height: 100
+ width: 200
+
+ QGCCheckBox {
+ id: enableWima
+ text: qsTr("WiMA")
+ }
+ }
+}
diff --git a/src/FlightDisplay/qmldir b/src/FlightDisplay/qmldir
index f37894a8b7de3e97cf3a70eb14bd974b818c5000..7eb144dc6d7d5d249e5326e843f4ff58ee59dcb3 100644
--- a/src/FlightDisplay/qmldir
+++ b/src/FlightDisplay/qmldir
@@ -15,4 +15,5 @@ PreFlightGPSCheck 1.0 PreFlightGPSCheck.qml
PreFlightRCCheck 1.0 PreFlightRCCheck.qml
PreFlightSensorsHealthCheck 1.0 PreFlightSensorsHealthCheck.qml
PreFlightSoundCheck 1.0 PreFlightSoundCheck.qml
+FlightDisplayWimaMenu 1.0 FlightDisplayWimaMenu.qml
diff --git a/src/FlightMap/Images/.directory b/src/FlightMap/Images/.directory
new file mode 100644
index 0000000000000000000000000000000000000000..7f2a552800449f3024f021c8c015686c01dc9c61
--- /dev/null
+++ b/src/FlightMap/Images/.directory
@@ -0,0 +1,4 @@
+[Dolphin]
+PreviewsShown=true
+Timestamp=2019,10,13,16,25,8
+Version=4
diff --git a/src/FlightMap/MapItems/MissionItemIndicator.qml b/src/FlightMap/MapItems/MissionItemIndicator.qml
index d4f3f70d47d4885821e206031427fdea8893ead7..d41b286975584e5ee397ff34264dfecf1231b9a3 100644
--- a/src/FlightMap/MapItems/MissionItemIndicator.qml
+++ b/src/FlightMap/MapItems/MissionItemIndicator.qml
@@ -21,6 +21,7 @@ MapQuickItem {
property var missionItem
property int sequenceNumber
+ property var color
signal clicked
@@ -37,6 +38,8 @@ MapQuickItem {
vehicleYaw: missionItem.missionVehicleYaw
showGimbalYaw: !isNaN(missionItem.missionGimbalYaw)
onClicked: _item.clicked()
+ color: _item.color ? _item.color
+ : checked ? "green" : (child ? qgcPal.mapIndicatorChild : qgcPal.mapIndicator)
property bool _isCurrentItem: missionItem ? missionItem.isCurrentItem : false
}
diff --git a/src/FlightMap/MapItems/WimaPlanMapItems.qml b/src/FlightMap/MapItems/WimaPlanMapItems.qml
index e25dcbd1ec2e6421daf40421bbbe7d37964decaa..7c9f1ec66ba260e3e60cfa03d504f0e7b8c4d518 100644
--- a/src/FlightMap/MapItems/WimaPlanMapItems.qml
+++ b/src/FlightMap/MapItems/WimaPlanMapItems.qml
@@ -16,41 +16,71 @@ import QGroundControl.Controls 1.0
import QGroundControl.FlightMap 1.0
// Adds visual items generated by wima planer to the map.
-// Currently only used by Fly View even though it's called PlanMapItems!
Item {
id: _root
- property var map ///< Map control to show items on
- property bool largeMapView ///< true: map takes up entire view, false: map is in small window
- property var wimaController value
+ property var map ///< Map control to show items on
+ property bool largeMapView ///< true: map takes up entire view, false: map is in small window
+ property var wimaController
+ property string mIColor: "#B4808080" // Mission Items Color, gray with alpha 0.7 #AARRGGBB
+ property string mIlineColor: mIColor
+ property string cMIColor: "orangered" // Current Mission Items Color
+ property string cMIlineColor: cMIColor
- property var _map: map
+ property var _map: map
property var _missionLineViewComponent
+ property var _currentMissionLineViewComponent
// Add the mission item visuals to the map
Repeater {
- model: largeMapView ? _missionController.visualItems : 0
+ model: largeMapView ? wimaController.missionItems : 0
- delegate: MissionItemMapVisual {
+ delegate: WimaMissionItemMapVisual {
map: _map
- onClicked: {
- if (isActiveVehicle) {
- // Only active vehicle supports click to change current mission item
- guidedActionsController.confirmAction(guidedActionsController.actionSetWaypoint, Math.max(object.sequenceNumber, 1))
- }
- }
+ color: _root.mIColor
+// onClicked: {
+// if (isActiveVehicle) {
+// // Only active vehicle supports click to change current mission item
+// guidedActionsController.confirmAction(guidedActionsController.actionSetWaypoint, Math.max(object.sequenceNumber, 1))
+// }
+// }
+ }
+
+ /*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
+
+ delegate: WimaMissionItemMapVisual {
+ map: _map
+ color: _root.cMIColor
}
}
+
Component.onCompleted: {
_missionLineViewComponent = missionLineViewComponent.createObject(map)
if (_missionLineViewComponent.status === Component.Error)
console.log(_missionLineViewComponent.errorString())
map.addMapItem(_missionLineViewComponent)
+
+ _currentMissionLineViewComponent = currentMissionLineViewComponent.createObject(map)
+ if (_currentMissionLineViewComponent.status === Component.Error)
+ console.log(_currentMissionLineViewComponent.errorString())
+ map.addMapItem(_currentMissionLineViewComponent)
}
Component.onDestruction: {
_missionLineViewComponent.destroy()
+ _currentMissionLineViewComponent.destroy()
}
Component {
@@ -58,9 +88,20 @@ Item {
MapPolyline {
line.width: 3
- line.color: "#be781c" // Hack, can't get palette to work in here
+ line.color: mIlineColor
+ z: QGroundControl.zOrderWaypointLines
+ path: wimaController.waypointPath
+ }
+ }
+
+ Component {
+ id: currentMissionLineViewComponent
+
+ MapPolyline {
+ line.width: 3
+ line.color: cMIlineColor
z: QGroundControl.zOrderWaypointLines
- path: _missionController.waypointPath
+ path: wimaController.currentWaypointPath
}
}
}
diff --git a/src/FlightMap/qmldir b/src/FlightMap/qmldir
index d7b3ba36b4badb4963e6926fa6f40149c974facf..e28a6d73cc6d13bc4bc2dd4b21958a5ec5d5dbf0 100644
--- a/src/FlightMap/qmldir
+++ b/src/FlightMap/qmldir
@@ -25,5 +25,6 @@ MissionItemIndicatorDrag 1.0 MissionItemIndicatorDrag.qml
MissionItemView 1.0 MissionItemView.qml
MissionLineView 1.0 MissionLineView.qml
PlanMapItems 1.0 PlanMapItems.qml
+WimaPlanMapItems 1.0 WimaPlanMapItems.qml
PolygonEditor 1.0 PolygonEditor.qml
VehicleMapItem 1.0 VehicleMapItem.qml
diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc
index 98177a3962bbaacbbce2d212af4a29e771461a76..ba6f388375d0ef58de35b3431e4a830d46cee88b 100644
--- a/src/MissionManager/MissionController.cc
+++ b/src/MissionManager/MissionController.cc
@@ -386,6 +386,34 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
return newItem->sequenceNumber();
}
+int MissionController::insertSimpleMissionItem(const MissionItem &missionItem, int i)
+{
+ int sequenceNumber = _nextSequenceNumber();
+ SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, missionItem, this);
+ newItem->setSequenceNumber(sequenceNumber);
+ newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
+ _initVisualItem(newItem);
+ MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
+ if (newItem->command() == takeoffCmd) {
+ if (!_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
+ return -1; // can not add this takeoff command for this vehicle
+ }
+ }
+ if (newItem->specifiesAltitude()) {
+ double prevAltitude;
+ int prevAltitudeMode;
+
+ if (_findPreviousAltitude(i, &prevAltitude, &prevAltitudeMode)) {
+ newItem->altitude()->setRawValue(prevAltitude);
+ newItem->setAltitudeMode(static_cast(prevAltitudeMode));
+ }
+ }
+ newItem->setMissionFlightStatus(_missionFlightStatus);
+ _visualItems->insert(i, newItem);
+
+ return newItem->sequenceNumber();
+}
+
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int i)
{
int sequenceNumber = _nextSequenceNumber();
diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h
index 6a0f4eb7fb3e38edf85e241740a1bbd7c3cd205f..6e56a7f4272cdf0f082a88fc096f2fba307956ce 100644
--- a/src/MissionManager/MissionController.h
+++ b/src/MissionManager/MissionController.h
@@ -108,6 +108,11 @@ public:
/// @return Sequence number for new item
Q_INVOKABLE int insertSimpleMissionItem(QGeoCoordinate coordinate, int i);
+ /// Add a new simple mission item to the list
+ /// @param i: index to insert at
+ /// @return Sequence number for new item
+ int insertSimpleMissionItem(const MissionItem &missionItem, int i);
+
/// Add a new ROI mission item to the list
/// @param i: index to insert at
/// @return Sequence number for new item
diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc
index 74a9e7f5b6da288e17aed91e53c8c5485a74dbf6..53cacddef8eeec37d0c9e67784440ad388d15c6d 100644
--- a/src/MissionManager/SimpleMissionItem.cc
+++ b/src/MissionManager/SimpleMissionItem.cc
@@ -148,7 +148,7 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const Missi
SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent)
: VisualMissionItem (other, flyView, parent)
- , _missionItem (other._vehicle)
+ , _missionItem (other._missionItem, this)
, _rawEdit (false)
, _dirty (false)
, _ignoreDirtyChangeSignals (false)
diff --git a/src/MissionManager/VisualMissionItem.cc b/src/MissionManager/VisualMissionItem.cc
index 7d6e566c155a45edf20ab0e9be7f9d0e79f73771..964fc643c83951cf4682c2d1010e36db9d1ca29b 100644
--- a/src/MissionManager/VisualMissionItem.cc
+++ b/src/MissionManager/VisualMissionItem.cc
@@ -79,7 +79,7 @@ const VisualMissionItem& VisualMissionItem::operator=(const VisualMissionItem& o
_vehicle = other._vehicle;
setIsCurrentItem(other._isCurrentItem);
- setDirty(other._dirty);
+ _dirty = other._dirty;
_homePositionSpecialCase = other._homePositionSpecialCase;
_terrainAltitude = other._terrainAltitude;
setAltDifference(other._altDifference);
diff --git a/src/PlanView/WimaMissionItemMapVisual.qml b/src/PlanView/WimaMissionItemMapVisual.qml
new file mode 100644
index 0000000000000000000000000000000000000000..bd26bb902ad34518268b0af8e5c1c8fff6f0dfcc
--- /dev/null
+++ b/src/PlanView/WimaMissionItemMapVisual.qml
@@ -0,0 +1,118 @@
+/****************************************************************************
+ *
+ * (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 1.2
+import QtLocation 5.3
+import QtPositioning 5.3
+
+import QGroundControl 1.0
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.Palette 1.0
+import QGroundControl.Controls 1.0
+import QGroundControl.FlightMap 1.0
+
+/// Simple Mission Item visuals
+Item {
+ id: _root
+
+ property var map ///< Map control to place item in
+ property var qgcView ///< QGCView to use for popping dialogs
+ property var color
+
+ property var _missionItem: object
+ property var _itemVisual
+ property var _dragArea
+ property bool _itemVisualShowing: false
+ property bool _dragAreaShowing: false
+
+ signal clicked(int sequenceNumber)
+
+ function hideItemVisuals() {
+ if (_itemVisualShowing) {
+ _itemVisual.destroy()
+ _itemVisualShowing = false
+ }
+ }
+
+ function showItemVisuals() {
+ if (!_itemVisualShowing) {
+ _itemVisual = indicatorComponent.createObject(map)
+ map.addMapItem(_itemVisual)
+ _itemVisualShowing = true
+ }
+ }
+
+ function hideDragArea() {
+ if (_dragAreaShowing) {
+ _dragArea.destroy()
+ _dragAreaShowing = false
+ }
+ }
+
+ function showDragArea() {
+ if (!_dragAreaShowing && _missionItem.specifiesCoordinate) {
+ _dragArea = dragAreaComponent.createObject(map)
+ _dragAreaShowing = true
+ }
+ }
+
+ Component.onCompleted: {
+ showItemVisuals()
+ if (_missionItem.isCurrentItem && map.planView) {
+ showDragArea()
+ }
+ }
+
+ Component.onDestruction: {
+ hideDragArea()
+ hideItemVisuals()
+ }
+
+
+ Connections {
+ target: _missionItem
+
+ onIsCurrentItemChanged: {
+ if (_missionItem.isCurrentItem) {
+ showDragArea()
+ } else {
+ hideDragArea()
+ }
+ }
+ }
+
+ // Control which is used to drag items
+ Component {
+ id: dragAreaComponent
+
+ MissionItemIndicatorDrag {
+ mapControl: _root.map
+ itemIndicator: _itemVisual
+ itemCoordinate: _missionItem.coordinate
+
+ onItemCoordinateChanged: _missionItem.coordinate = itemCoordinate
+ }
+ }
+
+ Component {
+ id: indicatorComponent
+
+ MissionItemIndicator {
+ coordinate: _missionItem.coordinate
+ visible: _missionItem.specifiesCoordinate
+ z: QGroundControl.zOrderMapItems
+ missionItem: _missionItem
+ sequenceNumber: _missionItem.sequenceNumber
+ color: _root.color
+
+ onClicked: _root.clicked(_missionItem.sequenceNumber)
+ }
+ }
+}
diff --git a/src/Wima/ToDo.txt b/src/Wima/ToDo.txt
deleted file mode 100644
index 9aa7945d050ec483211c2d19e3fb39413855a7f1..0000000000000000000000000000000000000000
--- a/src/Wima/ToDo.txt
+++ /dev/null
@@ -1,4 +0,0 @@
-add refpt gui and edit constructor
-new path optim required for circ survey
-add gui elements for circ survey
-solve bug for cantFindPath.wima on Desktop/WimaPath
diff --git a/src/Wima/WimaAreaData.cc b/src/Wima/WimaAreaData.cc
index e8c8b686f8aa85ba69859391057c97dc00423759..cdf2fbc73e866df194312b49750a50bf55ab8932 100644
--- a/src/Wima/WimaAreaData.cc
+++ b/src/Wima/WimaAreaData.cc
@@ -26,6 +26,16 @@ QVariantList WimaAreaData::path() const
return _path;
}
+QList WimaAreaData::coordinateList() const
+{
+ QList coordinateList;
+
+ for ( auto coorinate : _path)
+ coordinateList.append(coorinate.value());
+
+ return coordinateList;
+}
+
/*!
* \fn void WimaAreaData::setMaxAltitude(double maxAltitude)
*
diff --git a/src/Wima/WimaAreaData.h b/src/Wima/WimaAreaData.h
index 79231757a1701ff5cdcbedf27159954e8fab1995..f3774a73ceae68f2785d83c8eb8bf52487006488 100644
--- a/src/Wima/WimaAreaData.h
+++ b/src/Wima/WimaAreaData.h
@@ -19,8 +19,9 @@ public:
//WimaAreaData(const WimaArea &other, QObject *parent = nullptr);
WimaAreaData& operator=(const WimaAreaData& otherData) = delete; // avoid slicing
- double maxAltitude() const;
- QVariantList path() const;
+ double maxAltitude() const;
+ QVariantList path() const;
+ QList coordinateList() const;
virtual QString type() const = 0;
diff --git a/src/Wima/WimaController.cc b/src/Wima/WimaController.cc
index b8ccf8c8d92e318e5283041b50923e7ce8bae98a..435f93909d6a98173112be857c10aa59362b590c 100644
--- a/src/Wima/WimaController.cc
+++ b/src/Wima/WimaController.cc
@@ -12,6 +12,8 @@ WimaController::WimaController(QObject *parent)
, _serviceArea (this)
, _corridor (this)
, _localPlanDataValid (false)
+ , _startWaypointIndex (1)
+ , _endWaypointIndex (1)
{
}
@@ -38,7 +40,7 @@ QStringList WimaController::saveNameFilters() const
return filters;
}
-WimaDataContainer *WimaController::dataContainer() const
+WimaDataContainer *WimaController::dataContainer()
{
return _container;
}
@@ -48,6 +50,21 @@ QmlObjectListModel *WimaController::missionItems()
return &_missionItems;
}
+QmlObjectListModel *WimaController::currentMissionItems()
+{
+ return &_currentMissionItems;
+}
+
+QVariantList WimaController::waypointPath()
+{
+ return _waypointPath;
+}
+
+QVariantList WimaController::currentWaypointPath()
+{
+ return _currentWaypointPath;
+}
+
void WimaController::setMasterController(PlanMasterController *masterC)
{
_masterController = masterC;
@@ -80,6 +97,12 @@ void WimaController::setDataContainer(WimaDataContainer *container)
}
}
+void WimaController::nextPhase()
+{
+ updateCurrentMissionItems();
+ updateCurrentPath();
+}
+
void WimaController::startMission()
{
@@ -100,11 +123,6 @@ void WimaController::resumeMission()
}
-bool WimaController::updateMission()
-{
- return true;
-}
-
void WimaController::saveToCurrent()
{
}
@@ -136,6 +154,74 @@ QJsonDocument WimaController::saveToJson(FileType fileType)
return QJsonDocument();
}
+bool WimaController::calcShortestPath(const QGeoCoordinate &start, const QGeoCoordinate &destination, QList &path)
+{
+ using namespace GeoUtilities;
+ using namespace PolygonCalculus;
+ QList path2D;
+ bool retVal = PolygonCalculus::shortestPath(
+ toQPolygonF(toCartesian2D(_joinedArea.coordinateList(), /*origin*/ start)),
+ /*start point*/ QPointF(0,0),
+ /*destination*/ toCartesian2D(destination, start),
+ /*shortest path*/ path2D);
+ path.append(toGeo(path2D, /*origin*/ start));
+
+ return retVal;
+}
+
+bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList &coordinateList)
+{
+ return extractCoordinateList(missionItems, coordinateList, 0, missionItems.count()-1);
+}
+
+bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QList &coordinateList, int startIndex, int endIndex)
+{
+ if ( startIndex >= 0
+ && startIndex < missionItems.count()
+ && endIndex >= 0
+ && endIndex < missionItems.count()) {
+ if (startIndex > endIndex) {
+ if (!extractCoordinateList(missionItems, coordinateList, startIndex, missionItems.count()-1))
+ return false;
+ if (!extractCoordinateList(missionItems, coordinateList, 0, endIndex))
+ return false;
+ } else {
+ for (int i = startIndex; i <= endIndex; i++) {
+ SimpleMissionItem *mItem = missionItems.value(i);
+
+ if (mItem == nullptr) {
+ coordinateList.clear();
+ return false;
+ }
+ coordinateList.append(mItem->coordinate());
+ }
+ }
+ } else
+ return false;
+
+ return true;
+}
+
+bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList)
+{
+ return extractCoordinateList(missionItems, coordinateList, 0 , missionItems.count()-1);
+}
+
+bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList, int startIndex, int endIndex)
+{
+ QList geoCoordintateList;
+
+ bool retValue = extractCoordinateList(missionItems, geoCoordintateList, startIndex, endIndex);
+
+ if (!retValue)
+ return false;
+
+ for (auto coordinate : geoCoordintateList)
+ coordinateList.append(QVariant::fromValue(coordinate));
+
+ return true;
+}
+
/*!
* \fn void WimaController::containerDataValidChanged(bool valid)
* Pulls plan data generated by \c WimaPlaner from the \c _container if the data is valid (\a valid equals true).
@@ -159,14 +245,11 @@ void WimaController::containerDataValidChanged(bool valid)
int areaCounter = 0;
int numAreas = 4; // extract only numAreas Areas, if there are more they are invalid and ignored
- qWarning() << QString("List Size: %1").arg(areaList.size());
for (int i = 0; i < areaList.size(); i++) {
const WimaAreaData *areaData = areaList[i];
- qWarning() << areaData->type();
if (areaData->type() == WimaServiceAreaData::typeString) { // is it a service area?
_serviceArea = *qobject_cast(areaData);
-// qWarning("Service area, wuhuuu!");
areaCounter++;
_visualItems.append(&_serviceArea);
@@ -175,7 +258,6 @@ void WimaController::containerDataValidChanged(bool valid)
if (areaData->type() == WimaMeasurementAreaData::typeString) { // is it a measurement area?
_measurementArea = *qobject_cast(areaData);
-// qWarning("Measurement area, wuhuuu!");
areaCounter++;
_visualItems.append(&_measurementArea);
@@ -184,7 +266,6 @@ void WimaController::containerDataValidChanged(bool valid)
if (areaData->type() == WimaCorridorData::typeString) { // is it a corridor?
_corridor = *qobject_cast(areaData);
-// qWarning("WimaCorridorData, wuhuuu!");
areaCounter++;
//_visualItems.append(&_corridor); // not needed
@@ -193,7 +274,6 @@ void WimaController::containerDataValidChanged(bool valid)
if (areaData->type() == WimaJoinedAreaData::typeString) { // is it a corridor?
_joinedArea = *qobject_cast(areaData);
-// qWarning("WimaJoinedAreaData, wuhuuu!");
areaCounter++;
_visualItems.append(&_joinedArea);
@@ -204,10 +284,54 @@ void WimaController::containerDataValidChanged(bool valid)
break;
}
+#ifdef QT_DEBUG
+ //qWarning("containerDataValidChanged(): count:");
+ //qWarning() << planData.missionItems().count();
+#endif
+
QList tempMissionItems = planData.missionItems();
- for (auto missionItem : tempMissionItems)
- _missionItems.append(const_cast(missionItem)); // losing const qualifier here
+ // create mission items
+ _missionController->removeAll();
+ QmlObjectListModel* missionControllerVisualItems = _missionController->visualItems();
+ bool copyON = false;
+ for ( int i = 0; i < tempMissionItems.size(); i++) {
+ const MissionItem *missionItem = tempMissionItems[i];
+ if (copyON || missionItem->command() == MAV_CMD_NAV_VTOL_TAKEOFF
+ || missionItem->command() == MAV_CMD_NAV_TAKEOFF) {
+ _missionController->insertSimpleMissionItem(*missionItem, missionControllerVisualItems->count());
+ copyON = true;
+ }
+
+ if ( missionItem->command() == MAV_CMD_NAV_VTOL_LAND
+ || missionItem->command() == MAV_CMD_NAV_LAND)
+ 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) {
+ qWarning("WimaController::containerDataValidChanged(): Nullptr at SimpleMissionItem!");
+ return;
+ }
+ SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
+ _missionItems.append(visualItemCopy);
+ }
+
+ updateWaypointPath();
+
+ _startWaypointIndex = 1;
+ updateCurrentMissionItems();
+ updateCurrentPath();
if (areaCounter == numAreas)
_localPlanDataValid = true;
@@ -220,11 +344,118 @@ void WimaController::containerDataValidChanged(bool valid)
emit visualItemsChanged();
emit missionItemsChanged();
+
+#ifdef QT_DEBUG
+ //qWarning("Mission Items count: ");
+ //qWarning() << _missionItems.count();
+#endif
}
+void WimaController::updateCurrentMissionItems()
+{
+ int numberWaypoints = 30; // the number of waypoints currentMissionItems must not exceed
+ int overlapping = 2; // number of overlapping waypoints of consecutive mission phases
+
+ SimpleMissionItem *homeItem = _missionItems.value(0);
+ if (homeItem == nullptr) {
+ qWarning("WimaController::updateCurrentMissionItems(): nullptr");
+ _currentMissionItems.clear();
+ return;
+ }
+ QGeoCoordinate homeCoordinate(homeItem->coordinate());
+
+ 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)) {
+ qWarning("WimaController::updateCurrentMissionItems(): error on waypoint extraction.");
+ _currentMissionItems.clear();
+ return;
+ }
+ _startWaypointIndex = _endWaypointIndex + 1 - overlapping;
+
+ // calculate path from home to first waypoint
+ QList path;
+ if ( !calcShortestPath(homeCoordinate, geoCoordinateList[0], path) ) {
+ qWarning("WimaController::updateCurrentMissionItems(): Not able to calc path from home to first waypoint.");
+ _currentMissionItems.clear();
+ return;
+ }
+ // prepend to geoCoordinateList
+ for (int i = path.size()-2; i >= 0; i--) // i = path.size()-2 : last coordinate already in geoCoordinateList
+ geoCoordinateList.prepend(path[i]);
+
+ // calculate path from last waypoint to home
+ path.clear();
+ if ( !calcShortestPath(geoCoordinateList.last(), homeCoordinate, path) ) {
+ qWarning("WimaController::updateCurrentMissionItems(): Not able to calc path from home to first waypoint.");
+ _currentMissionItems.clear();
+ return;
+ }
+ path.removeFirst(); // first coordinate already in geoCoordinateList
+ geoCoordinateList.append(path);
+
+ // create Mission Items
+ _missionController->removeAll();
+ QmlObjectListModel* missionControllerVisuals = _missionController->visualItems();
+ for (auto coordinate : geoCoordinateList)
+ _missionController->insertSimpleMissionItem(coordinate, missionControllerVisuals->count());
+
+ // set land command for last mission item
+ SimpleMissionItem *landItem = missionControllerVisuals->value(missionControllerVisuals->count()-1);
+ if (landItem == nullptr) {
+ qWarning("WimaController::updateCurrentMissionItems(): nullptr");
+ _currentMissionItems.clear();
+ return;
+ }
+ // check vehicle type, before setting land command
+ Vehicle* controllerVehicle = _masterController->controllerVehicle();
+ MAV_CMD landCmd = controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
+ if (controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) {
+ landItem->setCommand(landCmd);
+ } else {
+ _currentMissionItems.clear();
+ return;
+ }
+ // copy mission items to _currentMissionItems
+// MissionSettingsItem *settingsItem = qobject_cast((*missionControllerVisuals)[0]);
+// if (settingsItem == nullptr) {
+// qWarning("WimaController::containerDataValidChanged(): Nullptr at MissionSettingsItem!");
+// return;
+// }
+// _missionItems.append(settingsItem);
+
+ _currentMissionItems.clear();
+ for ( int i = 1; i < missionControllerVisuals->count(); i++) {
+ SimpleMissionItem *visualItem = missionControllerVisuals->value(i);
+ if (visualItem == nullptr) {
+ qWarning("WimaController::updateCurrentMissionItems(): Nullptr at SimpleMissionItem!");
+ _currentMissionItems.clear();
+ return;
+ }
+ SimpleMissionItem *visualItemCopy = new SimpleMissionItem(*visualItem, true, this);
+ _currentMissionItems.append(visualItemCopy);
+ }
+
+ emit currentMissionItemsChanged();
+}
+
+void WimaController::updateWaypointPath()
+{
+ _waypointPath.clear();
+ if (!extractCoordinateList(_missionItems, _waypointPath, 0, _missionItems.count()-1))
+ return;
+ emit waypointPathChanged();
+}
+void WimaController::updateCurrentPath()
+{
+ _currentWaypointPath.clear();
+ if (!extractCoordinateList(_currentMissionItems, _currentWaypointPath, 0, _currentMissionItems.count()-1))
+ return;
+ emit currentWaypointPathChanged();
+}
diff --git a/src/Wima/WimaController.h b/src/Wima/WimaController.h
index 0d7fc5f0d29d6cb32aa7cb221ed594426029299f..28b8c1d42dc97b423b2189cc561f0310c7b01039 100644
--- a/src/Wima/WimaController.h
+++ b/src/Wima/WimaController.h
@@ -39,21 +39,27 @@ public:
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(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)
// Property accessors
PlanMasterController* masterController (void) { return _masterController; }
MissionController* missionController (void) { return _missionController; }
- QmlObjectListModel* visualItems (void) ;
+ QmlObjectListModel* visualItems (void);
QString currentFile (void) const { return _currentFile; }
QStringList loadNameFilters (void) const;
QStringList saveNameFilters (void) const;
QString fileExtension (void) const { return wimaFileExtension; }
QGCMapPolygon joinedArea (void) const;
- WimaDataContainer* dataContainer (void) const;
+ WimaDataContainer* dataContainer (void);
QmlObjectListModel* missionItems (void);
+ QmlObjectListModel* currentMissionItems (void);
+ QVariantList waypointPath (void);
+ QVariantList currentWaypointPath (void);
// Property setters
@@ -62,11 +68,11 @@ public:
void setDataContainer (WimaDataContainer* container);
// Member Methodes
+ Q_INVOKABLE void nextPhase();
Q_INVOKABLE void startMission();
Q_INVOKABLE void abortMission();
Q_INVOKABLE void pauseMission();
Q_INVOKABLE void resumeMission();
- Q_INVOKABLE bool updateMission();
Q_INVOKABLE void saveToCurrent ();
Q_INVOKABLE void saveToFile (const QString& filename);
@@ -82,6 +88,16 @@ public:
// Member Methodes
QJsonDocument saveToJson(FileType fileType);
+ bool calcShortestPath(const QGeoCoordinate &start, const QGeoCoordinate &destination, QList &path);
+ /// extracts the coordinates stored in missionItems (list of MissionItems) and stores them in coordinateList
+ bool extractCoordinateList(QmlObjectListModel &missionItems, QList &coordinateList);
+ /// extracts the coordinates (between startIndex and endIndex) stored in missionItems (list of MissionItems) and stores them in coordinateList.
+ bool extractCoordinateList(QmlObjectListModel &missionItems, QList &coordinateList, int startIndex, int endIndex);
+ /// extracts the coordinates stored in missionItems (list of MissionItems) and stores them in coordinateList
+ bool extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList);
+ /// extracts the coordinates (between startIndex and endIndex) stored in missionItems (list of MissionItems) and stores them in coordinateList.
+ bool extractCoordinateList(QmlObjectListModel &missionItems, QVariantList &coordinateList, int startIndex, int endIndex);
+
signals:
void masterControllerChanged (void);
void missionControllerChanged (void);
@@ -90,9 +106,16 @@ signals:
void dataContainerChanged ();
void readyForSaveSendChanged (bool ready);
void missionItemsChanged (void);
+ void currentMissionItemsChanged (void);
+ void waypointPathChanged (void);
+ void currentWaypointPathChanged (void);
private slots:
void containerDataValidChanged (bool valid);
+ void updateCurrentMissionItems (void);
+ void updateWaypointPath (void);
+ void updateCurrentPath (void);
+
private:
PlanMasterController *_masterController;
@@ -105,6 +128,12 @@ private:
WimaServiceAreaData _serviceArea; // area for supplying
WimaCorridorData _corridor; // corridor connecting opArea and serArea
bool _localPlanDataValid;
- QmlObjectListModel _missionItems;
+ QmlObjectListModel _missionItems; // all mission itmes (Mission Items) generaded by wimaPlaner, displayed in flightView
+ QmlObjectListModel _currentMissionItems; // contains the current mission items, which are a sub set of _missionItems,
+ // _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
+ int _endWaypointIndex; // index to the mission item stored in _missionItems defining the last element of _currentMissionItems
};
diff --git a/src/Wima/WimaPlanData.cc b/src/Wima/WimaPlanData.cc
index 69ffd06c22c0b6cac31e70a18c7117394be81753..b379f4eb573d48bf9c166618f9f2712f71a81518 100644
--- a/src/Wima/WimaPlanData.cc
+++ b/src/Wima/WimaPlanData.cc
@@ -20,10 +20,12 @@ WimaPlanData::WimaPlanData(const WimaPlanData &other, QObject *parent)
*/
WimaPlanData &WimaPlanData::operator=(const WimaPlanData &other)
{
+ // copy wima areas
QList areaList = other.areaList();
_areaList.clear();
for (int i = 0; i < areaList.size(); i++) {
const WimaAreaData *areaData = areaList[i];
+ // determine area type and append
if (areaData->type() == WimaJoinedAreaData::typeString) {
this->append(*qobject_cast(areaData));
}else if (areaData->type() == WimaServiceAreaData::typeString) {
@@ -35,6 +37,9 @@ WimaPlanData &WimaPlanData::operator=(const WimaPlanData &other)
}
}
+ // copy mission items
+ _missionItems = other.missionItems();
+
return *this;
}
diff --git a/src/Wima/WimaPlaner.cc b/src/Wima/WimaPlaner.cc
index 6ff0434e1f44f4757e877a4f999d3ef41b81ac8a..cac04e0644d6e02f8cb676eabf9191e071a5ff0c 100644
--- a/src/Wima/WimaPlaner.cc
+++ b/src/Wima/WimaPlaner.cc
@@ -242,7 +242,6 @@ bool WimaPlaner::updateMission()
qWarning("WimaPlaner::updateMission(): settingsItem == nullptr");
return false;
}
-
// set altitudes, temporary measure to solve bugs
QGeoCoordinate center = _serviceArea.center();
center.setAltitude(0);
@@ -253,15 +252,20 @@ bool WimaPlaner::updateMission()
center = _corridor.center();
center.setAltitude(0);
_corridor.setCenter(center);
-
-
// set HomePos. to serArea center
settingsItem->setCoordinate(_serviceArea.center());
// create take off position item
int sequenceNumber = _missionController->insertSimpleMissionItem(_serviceArea.center(), missionItems->count());
- _missionController->setCurrentPlanViewIndex(sequenceNumber, true);
+ _missionController->setCurrentPlanViewIndex(sequenceNumber, true);
+ SimpleMissionItem* takeOffItem = qobject_cast(missionItems->get(missionItems->count()-1));
+ if (takeOffItem == nullptr){
+ qWarning("WimaPlaner::updateMission(): takeOffItem == nullptr");
+ return false;
+ } else {
+ takeOffItem->setCoordinate(_serviceArea.center()); //necessary, insertSimpleMissionItem does not copy coordinate (why?)
+ }
// create survey item, will be extened with more()-> mission types in the future
_missionController->insertComplexMissionItem(_missionController->circularSurveyComplexItemName(), _measurementArea.center(), missionItems->count());
@@ -280,13 +284,9 @@ bool WimaPlaner::updateMission()
survey->setAutoGenerated(true); // prevents reinitialisation from gui
survey->surveyAreaPolygon()->clear();
survey->surveyAreaPolygon()->appendVertices(_measurementArea.coordinateList());
-
}
-
-
-
// calculate path from take off to opArea
if (survey->visualTransectPoints().size() == 0) {
qWarning("WimaPlaner::updateMission(): survey no points.");
@@ -345,6 +345,8 @@ bool WimaPlaner::updateMission()
MAV_CMD landCmd = controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_LAND : MAV_CMD_NAV_LAND;
if (controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(landCmd)) {
landItem->setCommand(landCmd);
+ } else {
+ return false;
}
}
@@ -588,26 +590,6 @@ bool WimaPlaner::recalcJoinedArea(QString &errorString)
return false; // this happens if all areas are pairwise disjoint
}
// join service area, op area and corridor
-
-
-// // remove if debugging finished
-// WimaServiceArea *test = new WimaServiceArea(this);
-
-// WimaServiceArea *test1 = new WimaServiceArea(this);
-// WimaServiceArea *test2 = new WimaServiceArea(this);
-// WimaServiceArea *test3 = new WimaServiceArea(this);
-// Circle circle(25, this);
-// using namespace GeoUtilities;
-
-// test->setPath(toGeo(circle.approximateSektor(0.5, 1, 3), _joinedArea.center()));
-// _visualItems.append(test);
-// test1->setPath(toGeo(circle.approximateSektor(0.5, 1, -1), _joinedArea.center()));
-// _visualItems.append(test1);
-// test2->setPath(toGeo(circle.approximateSektor(0.5,-1, 3), _joinedArea.center()));
-// _visualItems.append(test2);
-// test3->setPath(toGeo(circle.approximateSektor(0.5, -1, -3), _joinedArea.center()));
-// _visualItems.append(test3);
-
return true;
}
@@ -682,6 +664,21 @@ WimaPlanData WimaPlaner::toPlanData()
// convert mission items to mavlink commands
QList rgMissionItems;
MissionController::convertToMissionItems(_missionController->visualItems(), rgMissionItems, this);
+
+ // remove warnings if you read this
+// qWarning("WimaPlaner::toPlanData(): rgMissionItems");
+// for (auto item : rgMissionItems) {
+// qWarning() << item->command();
+// qWarning() << item->param1();
+// qWarning() << item->param2();
+// qWarning() << item->param3();
+// qWarning() << item->param4();
+// qWarning() << item->param5();
+// qWarning() << item->param6();
+// qWarning() << item->param7();
+// qWarning(" ");
+// }
+
QList rgMissionItemsConst;
for (auto missionItem : rgMissionItems)
rgMissionItemsConst.append(missionItem);
diff --git a/src/Wima/WimaPlaner.h b/src/Wima/WimaPlaner.h
index 69d1b40be710306a437ca380ceb2b048fac6d24b..e06625d084f2bf41fdc6ca41572415da91a475aa 100644
--- a/src/Wima/WimaPlaner.h
+++ b/src/Wima/WimaPlaner.h
@@ -109,6 +109,8 @@ public:
QJsonDocument saveToJson(FileType fileType);
+ bool calcShortestPath(const QGeoCoordinate &start, const QGeoCoordinate &destination, QList &path);
+
// static Members
static const char* wimaFileExtension;
static const char* areaItemsName;
@@ -127,7 +129,6 @@ private slots:
void recalcPolygonInteractivity (int index);
bool recalcJoinedArea (QString &errorString);
void pushToContainer ();
- bool calcShortestPath (const QGeoCoordinate &start, const QGeoCoordinate &destination, QList &path);
private:
// Member Functions
diff --git a/src/Wima/notesOnWpExchange.txt b/src/Wima/notesOnWpExchange.txt
index 29fc445e4cdfd065d19a5d1232d52e4419eb4318..10c055277f0a369204e07e8f9004275ae33e52ab 100644
--- a/src/Wima/notesOnWpExchange.txt
+++ b/src/Wima/notesOnWpExchange.txt
@@ -6,3 +6,6 @@ How to exchange mission between WimaPlaner and WimaController.
4) start/continue mission
5) return vehicle on battery low
6) go to 4) or quit if last waypoint reached
+
+
+investigate load, loadFromVehicle, syncInProgress, _newMissionItemsAvailableFromVehicle