diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index f9202a72bfd39f62460574022a152b5ffa323d22..ea0820229ab0bd25d5eb544dae573dab9a1815e4 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -7,93 +7,146 @@
src/ui/toolbar/BatteryIndicator.qml
src/ui/toolbar/GPSIndicator.qml
src/ui/toolbar/GPSRTKIndicator.qml
+ src/ui/toolbar/JoystickIndicator.qml
+ src/ui/toolbar/LinkIndicator.qml
src/ui/toolbar/MessageIndicator.qml
src/ui/toolbar/ModeIndicator.qml
- src/ui/toolbar/VTOLModeIndicator.qml
src/ui/toolbar/RCRSSIIndicator.qml
src/ui/toolbar/TelemetryRSSIIndicator.qml
- src/ui/toolbar/JoystickIndicator.qml
- src/ui/toolbar/LinkIndicator.qml
+ src/ui/toolbar/VTOLModeIndicator.qml
- src/PlanView/CorridorScanEditor.qml
- src/PlanView/CameraCalc.qml
- src/PlanView/CorridorScanMapVisual.qml
- src/QmlControls/EditPositionDialog.qml
- src/QmlControls/FileButton.qml
- src/MissionManager/QGCMapCircleVisuals.qml
- src/MissionManager/QGCMapPolylineVisuals.qml
- src/PlanView/StructureScanMapVisual.qml
+ src/AnalyzeView/AnalyzePage.qml
src/AnalyzeView/AnalyzeView.qml
- src/ui/AppSettings.qml
- src/ui/preferences/BluetoothSettings.qml
- src/FlightMap/Widgets/CameraPageWidget.qml
- src/ViewWidgets/CustomCommandWidget.qml
- src/ui/preferences/DebugWindow.qml
+ src/AnalyzeView/GeoTagPage.qml
+ src/AnalyzeView/LogDownloadPage.qml
+ src/AnalyzeView/MavlinkConsolePage.qml
src/AutoPilotPlugins/Common/ESP8266Component.qml
src/AutoPilotPlugins/Common/ESP8266ComponentSummary.qml
- src/VehicleSetup/FirmwareUpgrade.qml
+ src/AutoPilotPlugins/Common/MotorComponent.qml
+ src/AutoPilotPlugins/Common/RadioComponent.qml
+ src/AutoPilotPlugins/Common/SetupPage.qml
+ src/AutoPilotPlugins/Common/SyslinkComponent.qml
+ src/FactSystem/FactControls/AltitudeFactTextField.qml
+ src/FactSystem/FactControls/FactBitmask.qml
+ src/FactSystem/FactControls/FactCheckBox.qml
+ src/FactSystem/FactControls/FactComboBox.qml
+ src/FactSystem/FactControls/FactLabel.qml
+ src/FactSystem/FactControls/FactPanel.qml
+ src/FactSystem/FactControls/FactTextField.qml
+ src/FactSystem/FactControls/FactTextFieldGrid.qml
+ src/FactSystem/FactControls/FactTextFieldRow.qml
+ src/FactSystem/FactControls/FactTextFieldSlider.qml
+ src/FactSystem/FactControls/FactValueSlider.qml
+ src/FactSystem/FactControls/qmldir
+ src/FlightDisplay/BuiltInPreFlightCheckModel.qml
+ src/FlightDisplay/FlightDisplayView.qml
src/FlightDisplay/FlightDisplayViewDummy.qml
+ src/FlightDisplay/FlightDisplayViewMap.qml
src/FlightDisplay/FlightDisplayViewUVC.qml
- src/PlanView/FWLandingPatternEditor.qml
- src/ui/preferences/GeneralSettings.qml
- src/AnalyzeView/GeoTagPage.qml
+ src/FlightDisplay/FlightDisplayViewVideo.qml
+ src/FlightDisplay/FlightDisplayViewWidgets.qml
+ src/FlightDisplay/FlightDisplayWimaMenu.qml
+ src/FlightDisplay/GuidedActionConfirm.qml
+ src/FlightDisplay/GuidedActionList.qml
+ src/FlightDisplay/GuidedActionsController.qml
+ src/FlightDisplay/GuidedAltitudeSlider.qml
+ src/FlightDisplay/MultiVehicleList.qml
+ src/FlightDisplay/PreFlightBatteryCheck.qml
+ src/FlightDisplay/PreFlightGPSCheck.qml
+ src/FlightDisplay/PreFlightRCCheck.qml
+ src/FlightDisplay/PreFlightSensorsHealthCheck.qml
+ src/FlightDisplay/PreFlightSoundCheck.qml
+ src/FlightDisplay/SmallValue.qml
+ src/FlightDisplay/VirtualJoystick.qml
+ src/FlightDisplay/qmldir
+ src/FlightMap/FlightMap.qml
+ src/FlightMap/MapItems/CameraTriggerIndicator.qml
+ src/FlightMap/MapItems/CustomMapItems.qml
+ src/FlightMap/MapItems/MissionItemIndicator.qml
+ src/FlightMap/MapItems/MissionItemIndicatorDrag.qml
+ src/FlightMap/MapItems/MissionItemView.qml
+ src/FlightMap/MapItems/MissionLineView.qml
+ src/FlightMap/MapItems/PlanMapItems.qml
+ src/FlightMap/MapItems/PolygonEditor.qml
+ src/FlightMap/MapItems/VehicleMapItem.qml
+ src/FlightMap/MapItems/WimaPlanMapItems.qml
+ src/FlightMap/MapScale.qml
+ src/FlightMap/QGCVideoBackground.qml
+ src/FlightMap/Widgets/CameraPageWidget.qml
+ src/FlightMap/Widgets/CenterMapDropButton.qml
+ src/FlightMap/Widgets/CenterMapDropPanel.qml
+ src/FlightMap/Widgets/CompassRing.qml
src/FlightMap/Widgets/HealthPageWidget.qml
- src/ui/preferences/HelpSettings.qml
- src/VehicleSetup/JoystickConfig.qml
- src/ui/preferences/LinkSettings.qml
- src/AnalyzeView/LogDownloadPage.qml
- src/ui/preferences/LogReplaySettings.qml
- src/ui/MainWindowHybrid.qml
- src/ui/MainWindowInner.qml
- src/ui/MainWindowNative.qml
- src/AnalyzeView/MavlinkConsolePage.qml
- src/ui/preferences/MavlinkSettings.qml
- src/PlanView/MissionSettingsEditor.qml
- src/ui/preferences/MockLink.qml
- src/ui/preferences/MockLinkSettings.qml
- src/AutoPilotPlugins/Common/MotorComponent.qml
- src/QtLocationPlugin/QMLControl/OfflineMap.qml
- src/PlanView/PlanView.qml
- src/VehicleSetup/PX4FlowSensor.qml
+ src/FlightMap/Widgets/InstrumentSwipeView.qml
+ src/FlightMap/Widgets/MapFitFunctions.qml
+ src/FlightMap/Widgets/QGCArtificialHorizon.qml
+ src/FlightMap/Widgets/QGCAttitudeHUD.qml
+ src/FlightMap/Widgets/QGCAttitudeWidget.qml
+ src/FlightMap/Widgets/QGCCompassWidget.qml
src/FlightMap/Widgets/QGCInstrumentWidget.qml
src/FlightMap/Widgets/QGCInstrumentWidgetAlternate.qml
- src/AnalyzeView/AnalyzePage.qml
- src/QmlControls/AppMessages.qml
+ src/FlightMap/Widgets/QGCPitchIndicator.qml
+ src/FlightMap/Widgets/ValuePageWidget.qml
+ src/FlightMap/Widgets/VibrationPageWidget.qml
+ src/FlightMap/Widgets/VideoPageWidget.qml
+ src/FlightMap/qmldir
+ src/MissionManager/QGCMapCircleVisuals.qml
+ src/MissionManager/QGCMapPolygonVisuals.qml
+ src/MissionManager/QGCMapPolylineVisuals.qml
+ src/PlanView/CameraCalc.qml
src/PlanView/CameraSection.qml
+ src/PlanView/CorridorScanEditor.qml
+ src/PlanView/CorridorScanMapVisual.qml
+ src/PlanView/FWLandingPatternEditor.qml
+ src/PlanView/FWLandingPatternMapVisual.qml
+ src/PlanView/GeoFenceEditor.qml
+ src/PlanView/GeoFenceMapVisuals.qml
+ src/PlanView/MissionItemEditor.qml
+ src/PlanView/MissionItemMapVisual.qml
+ src/PlanView/MissionItemStatus.qml
+ src/PlanView/MissionSettingsEditor.qml
+ src/PlanView/PlanToolBar.qml
+ src/PlanView/PlanView.qml
+ src/PlanView/RallyPointEditorHeader.qml
+ src/PlanView/RallyPointItemEditor.qml
+ src/PlanView/RallyPointMapVisuals.qml
+ src/PlanView/SimpleItemEditor.qml
+ src/PlanView/SimpleItemMapVisual.qml
+ src/PlanView/StructureScanEditor.qml
+ src/PlanView/StructureScanMapVisual.qml
+ src/PlanView/SurveyItemEditor.qml
+ src/PlanView/SurveyMapVisual.qml
+ src/PlanView/TransectStyleComplexItemStats.qml
+ src/PlanView/WimaMissionItemMapVisual.qml
+ src/QmlControls/AppMessages.qml
src/QmlControls/ClickableColor.qml
src/QmlControls/DeadMouseArea.qml
src/QmlControls/DropButton.qml
src/QmlControls/DropPanel.qml
+ src/QmlControls/EditPositionDialog.qml
src/QmlControls/ExclusiveGroupItem.qml
src/QmlControls/FactSliderPanel.qml
+ src/QmlControls/FileButton.qml
src/QmlControls/FlightModeDropdown.qml
src/QmlControls/FlightModeMenu.qml
- src/PlanView/FWLandingPatternMapVisual.qml
- src/PlanView/GeoFenceEditor.qml
- src/PlanView/GeoFenceMapVisuals.qml
src/QmlControls/IndicatorButton.qml
src/QmlControls/JoystickThumbPad.qml
- src/ui/toolbar/MainToolBar.qml
- src/ui/toolbar/MainToolBarIndicators.qml
src/QmlControls/MissionCommandDialog.qml
- src/PlanView/MissionItemEditor.qml
src/QmlControls/MissionItemIndexLabel.qml
- src/PlanView/MissionItemMapVisual.qml
- src/PlanView/MissionItemStatus.qml
src/QmlControls/ModeSwitchDisplay.qml
src/QmlControls/MultiRotorMotorDisplay.qml
src/QmlControls/OfflineMapButton.qml
+ src/QmlControls/PIDTuning.qml
src/QmlControls/PageView.qml
src/QmlControls/ParameterEditor.qml
src/QmlControls/ParameterEditorDialog.qml
- src/QmlControls/PIDTuning.qml
- src/PlanView/PlanToolBar.qml
src/QmlControls/PreFlightCheckButton.qml
src/QmlControls/PreFlightCheckGroup.qml
src/QmlControls/PreFlightCheckList.qml
src/QmlControls/PreFlightCheckModel.qml
src/QmlControls/QGCButton.qml
+ src/QmlControls/QGCButtonColumn.qml
src/QmlControls/QGCCheckBox.qml
src/QmlControls/QGCColoredImage.qml
src/QmlControls/QGCComboBox.qml
@@ -105,7 +158,6 @@
src/QmlControls/QGCLabel.qml
src/QmlControls/QGCListView.qml
src/QmlControls/QGCMapLabel.qml
- src/MissionManager/QGCMapPolygonVisuals.qml
src/QmlControls/QGCMouseArea.qml
src/QmlControls/QGCMovableItem.qml
src/QmlControls/QGCPipable.qml
@@ -120,142 +172,83 @@
src/QmlControls/QGCViewMessage.qml
src/QmlControls/QGCViewPanel.qml
src/QmlControls/QGroundControl.Controls.qmldir
- src/PlanView/RallyPointEditorHeader.qml
- src/PlanView/RallyPointItemEditor.qml
- src/PlanView/RallyPointMapVisuals.qml
+ src/QmlControls/QGroundControl.ScreenTools.qmldir
+ src/QmlControls/QmlTest.qml
src/QmlControls/RCChannelMonitor.qml
src/QmlControls/RoundButton.qml
+ src/QmlControls/ScreenTools.qml
src/QmlControls/SectionHeader.qml
- src/AutoPilotPlugins/Common/SetupPage.qml
- src/ui/toolbar/SignalStrength.qml
- src/PlanView/SimpleItemMapVisual.qml
src/QmlControls/SliderSwitch.qml
src/QmlControls/SubMenuButton.qml
- src/PlanView/SurveyMapVisual.qml
- src/PlanView/TransectStyleComplexItemStats.qml
src/QmlControls/ToolStrip.qml
src/QmlControls/VehicleRotationCal.qml
src/QmlControls/VehicleSummaryRow.qml
- src/ViewWidgets/ViewWidget.qml
- src/FactSystem/FactControls/AltitudeFactTextField.qml
- src/FactSystem/FactControls/FactBitmask.qml
- src/FactSystem/FactControls/FactCheckBox.qml
- src/FactSystem/FactControls/FactComboBox.qml
- src/FactSystem/FactControls/FactLabel.qml
- src/FactSystem/FactControls/FactPanel.qml
- src/FactSystem/FactControls/FactTextField.qml
- src/FactSystem/FactControls/FactTextFieldGrid.qml
- src/FactSystem/FactControls/FactTextFieldRow.qml
- src/FactSystem/FactControls/FactValueSlider.qml
- src/FactSystem/FactControls/FactTextFieldSlider.qml
- src/FactSystem/FactControls/qmldir
- src/FlightDisplay/FlightDisplayView.qml
- src/FlightDisplay/FlightDisplayViewMap.qml
- src/FlightDisplay/FlightDisplayViewVideo.qml
- src/FlightDisplay/FlightDisplayViewWidgets.qml
- src/FlightDisplay/GuidedActionConfirm.qml
- src/FlightDisplay/GuidedActionList.qml
- src/FlightDisplay/GuidedActionsController.qml
- src/FlightDisplay/GuidedAltitudeSlider.qml
- src/FlightDisplay/MultiVehicleList.qml
- src/FlightDisplay/PreFlightBatteryCheck.qml
- src/FlightDisplay/BuiltInPreFlightCheckModel.qml
- src/FlightDisplay/PreFlightGPSCheck.qml
- src/FlightDisplay/PreFlightRCCheck.qml
- src/FlightDisplay/PreFlightSensorsHealthCheck.qml
- src/FlightDisplay/PreFlightSoundCheck.qml
- src/FlightDisplay/qmldir
- src/FlightMap/MapItems/CameraTriggerIndicator.qml
- src/FlightMap/Widgets/CenterMapDropButton.qml
- src/FlightMap/Widgets/CenterMapDropPanel.qml
- src/FlightMap/Widgets/CompassRing.qml
- src/FlightMap/MapItems/CustomMapItems.qml
- src/FlightMap/FlightMap.qml
- src/FlightMap/Widgets/InstrumentSwipeView.qml
- src/FlightMap/Widgets/MapFitFunctions.qml
- src/FlightMap/MapScale.qml
- src/FlightMap/MapItems/MissionItemIndicator.qml
- src/FlightMap/MapItems/MissionItemIndicatorDrag.qml
- src/FlightMap/MapItems/MissionItemView.qml
- src/FlightMap/MapItems/MissionLineView.qml
- src/FlightMap/MapItems/PlanMapItems.qml
- src/FlightMap/MapItems/PolygonEditor.qml
- src/FlightMap/Widgets/QGCArtificialHorizon.qml
- src/FlightMap/Widgets/QGCAttitudeHUD.qml
- src/FlightMap/Widgets/QGCAttitudeWidget.qml
- src/FlightMap/Widgets/QGCCompassWidget.qml
- src/FlightMap/Widgets/QGCPitchIndicator.qml
- src/FlightMap/QGCVideoBackground.qml
- src/FlightMap/qmldir
- src/FlightMap/MapItems/VehicleMapItem.qml
- src/QmlControls/QGroundControl.ScreenTools.qmldir
- src/QmlControls/ScreenTools.qml
- src/QmlControls/QmlTest.qml
- src/AutoPilotPlugins/Common/RadioComponent.qml
- src/ui/preferences/SerialSettings.qml
+ src/QtLocationPlugin/QMLControl/OfflineMap.qml
+ src/Taisync/TaisyncSettings.qml
+ src/VehicleSetup/FirmwareUpgrade.qml
+ src/VehicleSetup/JoystickConfig.qml
+ src/VehicleSetup/PX4FlowSensor.qml
src/VehicleSetup/SetupParameterEditor.qml
src/VehicleSetup/SetupView.qml
- src/PlanView/SimpleItemEditor.qml
- src/PlanView/StructureScanEditor.qml
- src/PlanView/SurveyItemEditor.qml
- src/AutoPilotPlugins/Common/SyslinkComponent.qml
- src/ui/preferences/TcpSettings.qml
- src/Taisync/TaisyncSettings.qml
- src/test.qml
- src/ui/preferences/UdpSettings.qml
- src/FlightMap/Widgets/ValuePageWidget.qml
src/VehicleSetup/VehicleSummary.qml
- src/FlightMap/Widgets/VibrationPageWidget.qml
- src/FlightMap/Widgets/VideoPageWidget.qml
- src/FlightDisplay/VirtualJoystick.qml
- src/WimaView/WimaToolBar.qml
+ src/ViewWidgets/CustomCommandWidget.qml
+ src/ViewWidgets/ViewWidget.qml
+ src/Wima/Snake/WimaAreaNoVisual.qml
+ src/WimaView/CircularGeneratorEditor.qml
+ src/WimaView/CircularGeneratorMapVisual.qml
+ src/WimaView/CircularSurveyItemEditor.qml
+ src/WimaView/CircularSurveyMapVisual.qml
+ src/WimaView/CoordinateIndicator.qml
+ src/WimaView/CoordinateIndicatorDrag.qml
+ src/WimaView/DragCoordinate.qml
+ src/WimaView/LinearGeneratorEditor.qml
+ src/WimaView/ProgressIndicator.qml
+ src/WimaView/Wima.qmldir
+ src/WimaView/WimaAreaMapVisual.qml
+ src/WimaView/WimaCorridorDataVisual.qml
+ src/WimaView/WimaCorridorEditor.qml
+ src/WimaView/WimaCorridorMapVisual.qml
+ src/WimaView/WimaItemEditor.qml
+ src/WimaView/WimaJoinedAreaDataVisual.qml
+ src/WimaView/WimaJoinedAreaMapVisual.qml
+ src/WimaView/WimaMapPolygonVisuals.qml
+ src/WimaView/WimaMapPolylineVisuals.qml
+ src/WimaView/WimaMapVisual.qml
+ src/WimaView/WimaMeasurementAreaDataVisual.qml
+ src/WimaView/WimaMeasurementAreaEditor.qml
+ src/WimaView/WimaMeasurementAreaMapVisual.qml
+ src/WimaView/WimaServiceAreaDataVisual.qml
+ src/WimaView/WimaServiceAreaEditor.qml
+ src/WimaView/WimaServiceAreaMapVisual.qml
+ src/WimaView/WimaToolBar.qml
src/WimaView/WimaView.qml
- src/WimaView/WimaMapVisual.qml
- src/WimaView/WimaItemEditor.qml
- src/WimaView/WimaMapPolylineVisuals.qml
- src/WimaView/WimaMapPolygonVisuals.qml
- src/WimaView/WimaServiceAreaMapVisual.qml
- src/WimaView/WimaServiceAreaEditor.qml
- src/WimaView/WimaAreaMapVisual.qml
- src/WimaView/WimaMeasurementAreaMapVisual.qml
- src/WimaView/WimaCorridorMapVisual.qml
- src/WimaView/WimaMeasurementAreaEditor.qml
- src/PlanView/CircularSurveyItemEditor.qml
- src/WimaView/DragCoordinate.qml
- src/WimaView/CoordinateIndicatorDrag.qml
- src/WimaView/CoordinateIndicator.qml
- src/WimaView/WimaJoinedAreaMapVisual.qml
- src/WimaView/WimaCorridorEditor.qml
- src/FlightMap/MapItems/WimaPlanMapItems.qml
- src/PlanView/WimaMissionItemMapVisual.qml
- src/FlightDisplay/FlightDisplayWimaMenu.qml
- src/WimaView/CircularSurveyMapVisual.qml
- src/FlightDisplay/SmallValue.qml
- src/WimaView/ProgressIndicator.qml
- src/WimaView/WimaServiceAreaDataVisual.qml
- src/WimaView/WimaCorridorDataVisual.qml
- src/WimaView/WimaJoinedAreaDataVisual.qml
- src/Wima/Snake/WimaAreaNoVisual.qml
- src/WimaView/WimaMeasurementAreaDataVisual.qml
- src/QmlControls/QGCButtonColumn.qml
+ src/test.qml
+ src/ui/AppSettings.qml
+ src/ui/MainWindowHybrid.qml
+ src/ui/MainWindowInner.qml
+ src/ui/MainWindowNative.qml
+ src/ui/preferences/BluetoothSettings.qml
+ src/ui/preferences/DebugWindow.qml
+ src/ui/preferences/GeneralSettings.qml
+ src/ui/preferences/HelpSettings.qml
+ src/ui/preferences/LinkSettings.qml
+ src/ui/preferences/LogReplaySettings.qml
+ src/ui/preferences/MavlinkSettings.qml
+ src/ui/preferences/MockLink.qml
+ src/ui/preferences/MockLinkSettings.qml
+ src/ui/preferences/SerialSettings.qml
+ src/ui/preferences/TcpSettings.qml
+ src/ui/preferences/UdpSettings.qml
+ src/ui/toolbar/MainToolBar.qml
+ src/ui/toolbar/MainToolBarIndicators.qml
+ src/ui/toolbar/SignalStrength.qml
- src/Settings/APMMavlinkStreamRate.SettingsGroup.json
src/MissionManager/CameraCalc.FactMetaData.json
+ src/MissionManager/CameraSection.FactMetaData.json
src/MissionManager/CameraSpec.FactMetaData.json
src/MissionManager/CorridorScan.SettingsGroup.json
- src/QmlControls/EditPositionDialog.FactMetaData.json
- src/MissionManager/QGCMapCircle.Facts.json
- src/MissionManager/StructureScan.SettingsGroup.json
- src/MissionManager/TransectStyle.SettingsGroup.json
- src/Settings/App.SettingsGroup.json
- src/Settings/AutoConnect.SettingsGroup.json
- src/Settings/BrandImage.SettingsGroup.json
- src/MissionManager/CameraSection.FactMetaData.json
- src/Settings/FlightMap.SettingsGroup.json
src/MissionManager/FWLandingPattern.FactMetaData.json
- src/Settings/FlyView.SettingsGroup.json
- src/Settings/PlanView.SettingsGroup.json
src/MissionManager/MavCmdInfoCommon.json
src/MissionManager/MavCmdInfoFixedWing.json
src/MissionManager/MavCmdInfoMultiRotor.json
@@ -263,12 +256,24 @@
src/MissionManager/MavCmdInfoSub.json
src/MissionManager/MavCmdInfoVTOL.json
src/MissionManager/MissionSettings.FactMetaData.json
+ src/MissionManager/QGCMapCircle.Facts.json
src/MissionManager/RallyPoint.FactMetaData.json
- src/Settings/RTK.SettingsGroup.json
src/MissionManager/SpeedSection.FactMetaData.json
+ src/MissionManager/StructureScan.SettingsGroup.json
src/MissionManager/Survey.SettingsGroup.json
+ src/MissionManager/TransectStyle.SettingsGroup.json
+ src/QmlControls/EditPositionDialog.FactMetaData.json
+ src/Settings/APMMavlinkStreamRate.SettingsGroup.json
+ src/Settings/App.SettingsGroup.json
+ src/Settings/AutoConnect.SettingsGroup.json
+ src/Settings/BrandImage.SettingsGroup.json
+ src/Settings/FlightMap.SettingsGroup.json
+ src/Settings/FlyView.SettingsGroup.json
+ src/Settings/PlanView.SettingsGroup.json
+ src/Settings/RTK.SettingsGroup.json
src/Settings/Units.SettingsGroup.json
- src/comm/USBBoardInfo.json
+ src/Settings/Video.SettingsGroup.json
+ src/Settings/Wima.SettingsGroup.json
src/Vehicle/BatteryFact.json
src/Vehicle/ClockFact.json
src/Vehicle/DistanceSensorFact.json
@@ -281,14 +286,13 @@
src/Vehicle/VehicleFact.json
src/Vehicle/VibrationFact.json
src/Vehicle/WindFact.json
- src/Settings/Video.SettingsGroup.json
- src/Wima/Geometry/json/WimaMeasurementArea.SettingsGroup.json
- src/Wima/json/CircularSurvey.SettingsGroup.json
src/Wima/Geometry/json/WimaArea.SettingsGroup.json
- src/Wima/json/WimaController.SettingsGroup.json
- src/Settings/Wima.SettingsGroup.json
+ src/Wima/Geometry/json/WimaMeasurementArea.SettingsGroup.json
src/Wima/Snake/json/CircularGenerator.SettingsGroup.json
src/Wima/Snake/json/LinearGenerator.SettingsGroup.json
+ src/Wima/json/CircularSurvey.SettingsGroup.json
+ src/Wima/json/WimaController.SettingsGroup.json
+ src/comm/USBBoardInfo.json
src/comm/APMArduCopterMockLink.params
diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml
index b3faab35d9543d45d74fa92b3f4e4738a1f5c73b..12ce0a1e7709ab015dc7f03af4bba9d1517482b3 100644
--- a/src/FlightDisplay/FlightDisplayViewMap.qml
+++ b/src/FlightDisplay/FlightDisplayViewMap.qml
@@ -24,6 +24,8 @@ import QGroundControl.Palette 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Vehicle 1.0
+import Wima 1.0
+
FlightMap {
id: flightMap
anchors.fill: parent
diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc
index b6adf4980c33914108681a933f59a1a8adcdbf55..9241b9b6212a5becb7597d48fb1d0682f1b491ce 100644
--- a/src/QGCApplication.cc
+++ b/src/QGCApplication.cc
@@ -89,6 +89,8 @@
#include "VideoSurface.h"
#include "ViewWidgetController.h"
#include "VisualMissionItem.h"
+#include "Wima/Snake/CircularGenerator.h"
+#include "Wima/Snake/LinearGenerator.h"
#include "Wima/Snake/NemoInterface.h"
#include "Wima/WimaController.h"
#include "Wima/WimaPlaner.h"
@@ -520,6 +522,10 @@ void QGCApplication::_initCommon(void) {
qmlRegisterType("Wima", 1, 0, "WimaController");
qmlRegisterType("Wima", 1, 0, "WimaPlaner");
qmlRegisterType("Wima", 1, 0, "NemoInterface");
+ qmlRegisterInterface("GeneratorBase");
+ qmlRegisterType("Wima", 1, 0,
+ "CircularGenerator");
+ qmlRegisterType("Wima", 1, 0, "LinearGenerator");
// Register Qml Singletons
qmlRegisterSingletonType(
diff --git a/src/QmlControls/QGroundControl.Controls.qmldir b/src/QmlControls/QGroundControl.Controls.qmldir
index 83953b980534590a92c5a85957d9716638473ac3..14d85db16be3fc6a4268129ef7dc05e3ca954f5a 100644
--- a/src/QmlControls/QGroundControl.Controls.qmldir
+++ b/src/QmlControls/QGroundControl.Controls.qmldir
@@ -65,7 +65,6 @@ QGCViewDialog 1.0 QGCViewDialog.qml
QGCViewDialogContainer 1.0 QGCViewDialogContainer.qml
QGCViewMessage 1.0 QGCViewMessage.qml
QGCViewPanel 1.0 QGCViewPanel.qml
-WimaToolBar 1.0 WimaToolBar.qml
RallyPointEditorHeader 1.0 RallyPointEditorHeader.qml
RallyPointItemEditor 1.0 RallyPointItemEditor.qml
RallyPointMapVisuals 1.0 RallyPointMapVisuals.qml
@@ -85,22 +84,6 @@ VehicleSummaryRow 1.0 VehicleSummaryRow.qml
ViewWidget 1.0 ViewWidget.qml
FlyAreaItemEditor 1.0 FlyAreaItemEditor.qml
-WimaMapVisual 1.0 WimaMapVisual.qml
-WimaMeasurementAreaMapVisual 1.0 WimaMeasurementAreaMapVisual.qml
-WimaJoinedAreaMapVisual 1.0 WimaJoinedAreaMapVisual.qml
-WimaMeasurementAreaEditor 1.0 WimaMeasurementAreaEditor.qml
-WimaServiceAreaMapVisual 1.0 WimaServiceAreaMapVisual.qml
-WimaAreaMapVisual 1.0 WimaAreaMapVisual.qml
-WimaServiceAreaEditor 1.0 WimaServiceAreaEditor.qml
-WimaCorridorMapVisual 1.0 WimaCorridorMapVisual.qml
-WimaItemEditor 1.0 WimaItemEditor.qml
-WimaMapPolygonVisuals 1.0 WimaMapPolygonVisuals.qml
-WimaMapPolylineVisuals 1.0 WimaMapPolylineVisuals.qml
-CircularSurveyMapVisual 1.0 CircularSurveyMapVisual.qml
-DragCoordinate 1.0 DragCoordinate.qml
-CoordinateIndicator 1.0 CoordinateIndicator.qml
-CoordinateIndicatorDrag 1.0 CoordinateIndicatorDrag.qml
-ProgressIndicator 1.0 ProgressIndicator.qml
QGCButtonColumn 1.0 QGCButtonColumn.qml
diff --git a/src/Wima/CircularSurvey.cc b/src/Wima/CircularSurvey.cc
index 391029f28e5deed45d9e502a36731e6510388e12..625abee8f52124eff91e0b9e15078e6d820a567b 100644
--- a/src/Wima/CircularSurvey.cc
+++ b/src/Wima/CircularSurvey.cc
@@ -27,7 +27,6 @@ constexpr typename std::underlying_type::type integral(T value) {
}
const char *CircularSurvey::settingsGroup = "CircularSurvey";
-const char *CircularSurvey::typeName = "Type";
const char *CircularSurvey::CircularSurveyName = "CircularSurvey";
const char *CircularSurvey::variantName = "Variant";
@@ -37,17 +36,14 @@ CircularSurvey::CircularSurvey(Vehicle *vehicle, bool flyView,
_state(STATE::IDLE),
_metaDataMap(FactMetaData::createMapFromJsonFile(
QStringLiteral(":/json/CircularSurvey.SettingsGroup.json"), this)),
- _type(settingsGroup, _metaDataMap[typeName]),
_variant(settingsGroup, _metaDataMap[variantName]),
- _areaData(std::make_shared()),
+ _pAreaData(std::make_shared()),
_pWorker(std::make_unique()) {
Q_UNUSED(kmlOrShpFile)
_editorQml = "qrc:/qml/CircularSurveyItemEditor.qml";
// Connect facts.
- connect(&this->_type, &Fact::rawValueChanged, this,
- &CircularSurvey::_rebuildTransects);
connect(&this->_variant, &Fact::rawValueChanged, this,
&CircularSurvey::_changeVariant);
@@ -65,10 +61,10 @@ CircularSurvey::CircularSurvey(Vehicle *vehicle, bool flyView,
&CircularSurvey::exitCoordinateHasRelativeAltitudeChanged);
// Register Generators.
- auto cg = std::make_shared(this->_areaData);
- registerGenerator(cg->name(), cg);
- auto lg = std::make_shared(this->_areaData);
+ auto lg = std::make_shared(this->_pAreaData);
registerGenerator(lg->name(), lg);
+ auto cg = std::make_shared(this->_pAreaData);
+ registerGenerator(cg->name(), cg);
}
CircularSurvey::~CircularSurvey() {}
@@ -79,10 +75,10 @@ void CircularSurvey::reverse() {
}
void CircularSurvey::setPlanData(const WimaPlanData &d) {
- *this->_areaData = d;
+ *this->_pAreaData = d;
}
-QList CircularSurvey::variantNames() const { return _variantNames; }
+QStringList CircularSurvey::variantNames() const { return _variantNames; }
bool CircularSurvey::load(const QJsonObject &complexObject, int sequenceNumber,
QString &errorString) {
@@ -105,16 +101,7 @@ bool CircularSurvey::load(const QJsonObject &complexObject, int sequenceNumber,
QList keyInfoList = {
{VisualMissionItem::jsonTypeKey, QJsonValue::String, true},
{ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true},
- {transectDistanceName, QJsonValue::Double, true},
- {alphaName, QJsonValue::Double, true},
- {minLengthName, QJsonValue::Double, true},
- {typeName, QJsonValue::Double, true},
{variantName, QJsonValue::Double, false},
- {numRunsName, QJsonValue::Double, false},
- {runName, QJsonValue::Double, false},
- {refPointLatitudeName, QJsonValue::Double, true},
- {refPointLongitudeName, QJsonValue::Double, true},
- {refPointAltitudeName, QJsonValue::Double, true},
};
if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
@@ -149,13 +136,7 @@ bool CircularSurvey::load(const QJsonObject &complexObject, int sequenceNumber,
return false;
}
- _type.setRawValue(complexObject[typeName].toInt());
_variant.setRawValue(complexObject[variantName].toInt());
- _numRuns.setRawValue(complexObject[numRunsName].toInt());
- _run.setRawValue(complexObject[runName].toInt());
- _referencePoint.setLongitude(complexObject[refPointLongitudeName].toDouble());
- _referencePoint.setLatitude(complexObject[refPointLatitudeName].toDouble());
- _referencePoint.setAltitude(complexObject[refPointAltitudeName].toDouble());
_ignoreRecalc = false;
@@ -182,13 +163,7 @@ void CircularSurvey::save(QJsonArray &planItems) {
VisualMissionItem::jsonTypeComplexItemValue;
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = CircularSurveyName;
- saveObject[typeName] = double(_type.rawValue().toUInt());
saveObject[variantName] = double(_variant.rawValue().toUInt());
- saveObject[numRunsName] = double(_numRuns.rawValue().toUInt());
- saveObject[runName] = double(_numRuns.rawValue().toUInt());
- saveObject[refPointLongitudeName] = _referencePoint.longitude();
- saveObject[refPointLatitudeName] = _referencePoint.latitude();
- saveObject[refPointAltitudeName] = _referencePoint.altitude();
// Polygon shape
_surveyAreaPolygon.saveToJson(saveObject);
@@ -264,13 +239,15 @@ bool CircularSurvey::_switchToGenerator(
const CircularSurvey::PtrGenerator &newG) {
if (this->_pGenerator != newG) {
if (this->_pGenerator != nullptr) {
- disconnect(this->_pGenerator.get(), &GeneratorBase::generatorChanged,
- this, &CircularSurvey::_rebuildTransects);
+ disconnect(this->_pGenerator.get(),
+ &routing::GeneratorBase::generatorChanged, this,
+ &CircularSurvey::_rebuildTransects);
}
this->_pGenerator = newG;
- connect(this->_pGenerator.get(), &GeneratorBase::generatorChanged, this,
- &CircularSurvey::_rebuildTransects);
+ connect(this->_pGenerator.get(), &routing::GeneratorBase::generatorChanged,
+ this, &CircularSurvey::_rebuildTransects);
+ emit generatorChanged();
this->_state = STATE::IDLE;
_rebuildTransects();
@@ -286,11 +263,6 @@ void CircularSurvey::_changeVariant() {
this->_rebuildTransects();
}
-void CircularSurvey::_changeRun() {
- this->_state = STATE::RUN_CHANGE;
- this->_rebuildTransects();
-}
-
void CircularSurvey::_updateWorker() {
// Mark transects as dirty.
this->_transectsDirty = true;
@@ -300,12 +272,19 @@ void CircularSurvey::_updateWorker() {
this->_variantNames.clear();
emit variantNamesChanged();
- if (this->_areaData->isValid()) {
+ if (this->_pAreaData->isValid()) {
// Prepare data.
- auto origin = this->_areaData->origin();
+ auto origin = this->_pAreaData->origin();
+ origin.setAltitude(0);
+ if (!origin.isValid()) {
+ qCWarning(CircularSurveyLog)
+ << "_updateWorker(): origin invalid." << origin;
+ return;
+ }
+
// Convert safe area.
- auto geoSafeArea = this->_jArea.coordinateList();
+ auto geoSafeArea = this->_pAreaData->joinedArea().coordinateList();
if (!(geoSafeArea.size() >= 3)) {
qCWarning(CircularSurveyLog)
<< "_updateWorker(): safe area invalid." << geoSafeArea;
@@ -329,13 +308,20 @@ void CircularSurvey::_updateWorker() {
snake::areaToEnu(origin, geoSafeArea, safeAreaENU);
// Create generator.
- GeneratorBase::Generator g; // Transect generator.
- if (_pGenerator->get(g)) {
- // Start/Restart routing worker.
- this->_pWorker->route(par, g);
+ if (this->_pGenerator) {
+ routing::GeneratorBase::Generator g; // Transect generator.
+ if (this->_pGenerator->get(g)) {
+ // Start/Restart routing worker.
+ this->_pWorker->route(par, g);
+ } else {
+ qCWarning(CircularSurveyLog)
+ << "_updateWorker(): generator creation failed.";
+ }
} else {
qCWarning(CircularSurveyLog)
- << "_updateWorker(): generator creation failed.";
+ << "_updateWorker(): pGenerator == nullptr, number of registered "
+ "generators: "
+ << this->_generatorList.size();
}
} else {
qCWarning(CircularSurveyLog) << "_updateWorker(): plan data invalid.";
@@ -344,78 +330,42 @@ void CircularSurvey::_updateWorker() {
void CircularSurvey::_changeVariantWorker() {
auto variant = this->_variant.rawValue().toUInt();
- auto run = this->_run.rawValue().toUInt();
// Find old variant and run. Old run corresponts with empty list.
std::size_t old_variant = std::numeric_limits::max();
- std::size_t old_run = std::numeric_limits::max();
for (std::size_t i = 0; i < std::size_t(this->_variantVector.size()); ++i) {
- const auto &solution = this->_variantVector.at(i);
- for (std::size_t j = 0; j < std::size_t(solution.size()); ++j) {
- const auto &r = solution[j];
- if (r.isEmpty()) {
- old_variant = i;
- old_run = j;
- // break
- i = std::numeric_limits::max() - 1;
- j = std::numeric_limits::max() - 1;
- }
+ const auto &variantCoordinates = this->_variantVector.at(i);
+ if (variantCoordinates.isEmpty()) {
+ old_variant = i;
+ break;
}
}
// Swap route.
- if (variant != old_variant || run != old_run) {
+ if (variant != old_variant) {
// Swap in new variant, if condition.
- if (variant < std::size_t(this->_variantVector.size()) &&
- run < std::size_t(this->_variantVector.at(variant).size())) {
+ if (variant < std::size_t(this->_variantVector.size())) {
if (old_variant != std::numeric_limits::max()) {
// this->_transects containes a route, swap it back to
// this->_solutionVector
- auto &old_solution = this->_variantVector[old_variant];
- auto &old_route = old_solution[old_run];
- old_route.swap(this->_transects);
- }
- auto &solution = this->_variantVector[variant];
- auto &route = solution[run];
- this->_transects.swap(route);
-
- if (variant != old_variant) {
- // Add run names.
- this->_runNames.clear();
- for (std::size_t i = 1; i <= std::size_t(solution.size()); ++i) {
- this->_runNames.append(QString::number(i));
- }
- emit runNamesChanged();
+ auto &oldVariantCoordinates = this->_variantVector[old_variant];
+ oldVariantCoordinates.swap(this->_transects);
}
+ auto &newVariantCoordinates = this->_variantVector[variant];
+ this->_transects.swap(newVariantCoordinates);
} else { // error
qCWarning(CircularSurveyLog)
- << "Variant or run out of bounds (variant = " << variant
- << ", run = " << run << ").";
- qCWarning(CircularSurveyLog) << "Resetting variant and run.";
+ << "Variant out of bounds (variant =" << variant << ").";
+ qCWarning(CircularSurveyLog) << "Resetting variant to zero.";
disconnect(&this->_variant, &Fact::rawValueChanged, this,
&CircularSurvey::_changeVariant);
- disconnect(&this->_run, &Fact::rawValueChanged, this,
- &CircularSurvey::_changeRun);
- if (old_variant < std::size_t(this->_variantVector.size())) {
- this->_variant.setCookedValue(QVariant::fromValue(old_variant));
- auto &solution = this->_variantVector[old_variant];
- if (old_run < std::size_t(solution.size())) {
- this->_run.setCookedValue(QVariant::fromValue(old_run));
- } else {
- this->_run.setCookedValue(QVariant(0));
- }
- } else {
- this->_variant.setCookedValue(QVariant(0));
- this->_run.setCookedValue(QVariant(0));
- }
+ this->_variant.setCookedValue(QVariant(0));
connect(&this->_variant, &Fact::rawValueChanged, this,
&CircularSurvey::_changeVariant);
- connect(&this->_run, &Fact::rawValueChanged, this,
- &CircularSurvey::_changeRun);
- if (this->_variantVector.size() > 0 &&
- this->_variantVector.front().size() > 0) {
+
+ if (this->_variantVector.size() > 0) {
this->_changeVariantWorker();
}
}
@@ -438,143 +388,22 @@ void CircularSurvey::_storeWorker() {
_loadedMissionItemsParent = nullptr;
}
- // Store raw transects.
- const auto &pRoutingData = this->_pRoutingData;
- const auto &ori = this->_referencePoint;
- const auto &transectsENU = pRoutingData->transects;
- QList> rawTransects;
- for (std::size_t i = 1; i < transectsENU.size(); ++i) {
- const auto &t = transectsENU[i];
- rawTransects.append(QList());
- auto trGeo = rawTransects.back();
- for (auto &v : t) {
- QGeoCoordinate c;
- snake::fromENU(ori, v, c);
- trGeo.append(c);
- }
- }
-
- // Store solutions.
- QVector solutionVector;
- const auto nSolutions = pRoutingData->solutionVector.size();
- for (std::size_t j = 0; j < nSolutions; ++j) {
- const auto &solution = pRoutingData->solutionVector.at(j);
- const auto nRuns = solution.size();
- // Store runs.
- Variant runs(nRuns, Transects{QList()});
- for (std::size_t k = 0; k < nRuns; ++k) {
- const auto &route = solution.at(k);
- const auto &path = route.path;
- const auto &info = route.info;
- if (info.size() > 1) {
- // Find index of first waypoint.
- std::size_t idxFirst = 0;
- const auto &infoFirst = info.at(1);
- const auto &firstTransect = transectsENU[infoFirst.index];
- if (firstTransect.size() > 0) {
- const auto &firstWaypoint =
- infoFirst.reversed ? firstTransect.back() : firstTransect.front();
- double th = 0.01;
- for (std::size_t i = 0; i < path.size(); ++i) {
- auto dist = bg::distance(path[i], firstWaypoint);
- if (dist < th) {
- idxFirst = i;
- break;
- }
- }
-
- // Find index of last waypoint.
- std::size_t idxLast = path.size() - 1;
- const auto &infoLast = info.at(info.size() - 2);
- const auto &lastTransect = transectsENU[infoLast.index];
- if (lastTransect.size() > 0) {
- const auto &lastWaypoint =
- infoLast.reversed ? lastTransect.front() : lastTransect.back();
- for (long i = path.size() - 1; i >= 0; --i) {
- auto dist = bg::distance(path[i], lastWaypoint);
- if (dist < th) {
- idxLast = i;
- break;
- }
- }
-
- // Convert to geo coordinates.
- auto &list = runs[k].front();
- for (std::size_t i = idxFirst; i <= idxLast; ++i) {
- auto &vertex = path[i];
- QGeoCoordinate c;
- snake::fromENU(ori, vertex, c);
- list.append(CoordInfo_t{c, CoordTypeInterior});
- }
- } else {
- qCWarning(CircularSurveyLog)
- << "_storeWorker(): lastTransect.size() == 0";
- }
- } else {
- qCWarning(CircularSurveyLog)
- << "_storeWorker(): firstTransect.size() == 0";
- }
- } else {
- qCWarning(CircularSurveyLog)
- << "_storeWorker(): transectsInfo.size() <= 1";
- }
- }
- // Remove empty runs.
- bool error = true;
- for (auto it = runs.begin(); it < runs.end();) {
- if (it->size() > 0 && it->front().size() > 0) {
- error = false;
- ++it;
- } else {
- it = runs.erase(it);
- }
- }
- if (!error) {
- solutionVector.push_back(std::move(runs));
- }
- }
-
- // Remove empty solutions.
- std::size_t nSol = 0;
- for (auto it = solutionVector.begin(); it < solutionVector.end();) {
- if (it->size() > 0 && it->front().size() > 0) {
- ++it;
- ++nSol;
- } else {
- it = solutionVector.erase(it);
- }
+ // Add route variant names.
+ this->_variantNames.clear();
+ for (std::size_t i = 1; i <= std::size_t(this->_variantVector.size()); ++i) {
+ this->_variantNames.append(QString::number(i));
}
+ emit variantNamesChanged();
- // Assign routes if no error occured.
- if (nSol > 0) {
- // Swap first route to _transects.
- this->_variantVector.swap(solutionVector);
+ disconnect(&this->_variant, &Fact::rawValueChanged, this,
+ &CircularSurvey::_changeVariant);
+ this->_variant.setCookedValue(QVariant(0));
+ connect(&this->_variant, &Fact::rawValueChanged, this,
+ &CircularSurvey::_changeVariant);
+ this->_changeVariantWorker();
- // Add route variant names.
- this->_variantNames.clear();
- for (std::size_t i = 1; i <= std::size_t(this->_variantVector.size());
- ++i) {
- this->_variantNames.append(QString::number(i));
- }
- emit variantNamesChanged();
-
- // Swap in rawTransects.
- this->_rawTransects.swap(rawTransects);
-
- disconnect(&this->_variant, &Fact::rawValueChanged, this,
- &CircularSurvey::_changeVariant);
- disconnect(&this->_run, &Fact::rawValueChanged, this,
- &CircularSurvey::_changeRun);
- this->_variant.setCookedValue(QVariant(0));
- this->_run.setCookedValue(QVariant(0));
- connect(&this->_variant, &Fact::rawValueChanged, this,
- &CircularSurvey::_changeVariant);
- connect(&this->_run, &Fact::rawValueChanged, this,
- &CircularSurvey::_changeRun);
- this->_changeVariantWorker();
- // Mark transect as stored and ready.
- this->_transectsDirty = false;
- }
+ // Mark transect as stored and ready.
+ this->_transectsDirty = false;
}
void CircularSurvey::applyNewAltitude(double newAltitude) {
@@ -600,14 +429,14 @@ bool CircularSurvey::readyForSave() const {
double CircularSurvey::additionalTimeDelay() const { return 0; }
-bool CircularSurvey::registerGenerator(const QString &name,
- std::shared_ptr g) {
+bool CircularSurvey::registerGenerator(
+ const QString &name, std::shared_ptr g) {
if (name.isEmpty()) {
qCWarning(CircularSurveyLog) << "registerGenerator(): empty name string.";
return false;
}
- if (g) {
+ if (!g) {
qCWarning(CircularSurveyLog) << "registerGenerator(): empty generator.";
return false;
}
@@ -620,7 +449,7 @@ bool CircularSurvey::registerGenerator(const QString &name,
this->_generatorNameList.push_back(name);
this->_generatorList.push_back(g);
if (this->_generatorList.size() == 1) {
- this->_pGenerator = g;
+ _switchToGenerator(g);
}
emit generatorNameListChanged();
@@ -633,7 +462,7 @@ bool CircularSurvey::unregisterGenerator(const QString &name) {
if (index >= 0) {
// Is this the current generator?
const auto &g = this->_generatorList.at(index);
- if (g.get() == this->_pGenerator.get()) {
+ if (g == this->_pGenerator) {
if (index > 0) {
_switchToGenerator(this->_generatorList.at(index - 1));
} else {
@@ -692,10 +521,18 @@ bool CircularSurvey::switchToGenerator(int index) {
}
}
-QList CircularSurvey::generatorNameList() {
+QStringList CircularSurvey::generatorNameList() {
return this->_generatorNameList;
}
+routing::GeneratorBase *CircularSurvey::generator() {
+ return _pGenerator.get();
+}
+
+int CircularSurvey::generatorIndex() {
+ return this->_generatorList.indexOf(this->_pGenerator);
+}
+
void CircularSurvey::_rebuildTransectsPhase1(void) {
auto start = std::chrono::high_resolution_clock::now();
@@ -747,388 +584,98 @@ void CircularSurvey::_recalcComplexDistance() {
void CircularSurvey::_recalcCameraShots() { _cameraShots = 0; }
void CircularSurvey::_setTransects(CircularSurvey::PtrRoutingData pRoute) {
- this->_pRoutingData = pRoute;
- this->_state = STATE::STORE;
- this->_rebuildTransects();
-}
-
-Fact *CircularSurvey::type() { return &_type; }
-
-Fact *CircularSurvey::variant() { return &_variant; }
-
-Fact *CircularSurvey::numRuns() { return &_numRuns; }
-
-Fact *CircularSurvey::run() { return &_run; }
-
-int CircularSurvey::typeCount() const { return int(integral(Type::Count)); }
-
-bool CircularSurvey::calculating() const {
- return this->_pWorker->calculating();
-}
-
-bool circularTransects(const snake::FPolygon &polygon,
- const std::vector &tiles,
- snake::Length deltaR, snake::Angle deltaAlpha,
- snake::Length minLength, snake::Transects &transects) {
- auto s1 = std::chrono::high_resolution_clock::now();
-
- // Check preconitions
- if (polygon.outer().size() >= 3) {
- using namespace boost::units;
- // Convert geo polygon to ENU polygon.
- snake::FPoint origin{0, 0};
- std::string error;
- // Check validity.
- if (!bg::is_valid(polygon, error)) {
- qCWarning(CircularSurveyLog) << "circularTransects(): "
- "invalid polygon.";
- qCWarning(CircularSurveyLog) << error.c_str();
- std::stringstream ss;
- ss << bg::wkt(polygon);
- qCWarning(CircularSurveyLog) << ss.str().c_str();
- } else {
- // Calculate polygon distances and angles.
- std::vector distances;
- distances.reserve(polygon.outer().size());
- std::vector angles;
- angles.reserve(polygon.outer().size());
- //#ifdef DEBUG_CIRCULAR_SURVEY
- // qCWarning(CircularSurveyLog) << "circularTransects():";
- //#endif
- for (const auto &p : polygon.outer()) {
- snake::Length distance = bg::distance(origin, p) * si::meter;
- distances.push_back(distance);
- snake::Angle alpha = (std::atan2(p.get<1>(), p.get<0>())) * si::radian;
- alpha = alpha < 0 * si::radian ? alpha + 2 * M_PI * si::radian : alpha;
- angles.push_back(alpha);
- //#ifdef DEBUG_CIRCULAR_SURVEY
- // qCWarning(CircularSurveyLog) << "distances, angles,
- // coordinates:"; qCWarning(CircularSurveyLog) <<
- // to_string(distance).c_str(); qCWarning(CircularSurveyLog) <<
- // to_string(snake::Degree(alpha)).c_str();
- // qCWarning(CircularSurveyLog) << "x = " << p.get<0>() << "y = "
- // << p.get<1>();
- //#endif
- }
-
- auto rMin = deltaR; // minimal circle radius
- snake::Angle alpha1(0 * degree::degree);
- snake::Angle alpha2(360 * degree::degree);
- // Determine r_min by successive approximation
- if (!bg::within(origin, polygon.outer())) {
- rMin = bg::distance(origin, polygon) * si::meter;
- }
+ // Store solutions.
+ const auto &ori = this->_pAreaData->origin();
+ const auto &transectsENU = pRoute->transects;
+ QVector variantVector;
+ const auto nSolutions = pRoute->solutionVector.size();
- auto rMax = (*std::max_element(distances.begin(),
- distances.end())); // maximal circle radius
-
- // Scale parameters and coordinates.
- const auto rMinScaled =
- ClipperLib::cInt(std::round(rMin.value() * CLIPPER_SCALE));
- const auto deltaRScaled =
- ClipperLib::cInt(std::round(deltaR.value() * CLIPPER_SCALE));
- auto originScaled =
- ClipperLib::IntPoint{ClipperLib::cInt(std::round(origin.get<0>())),
- ClipperLib::cInt(std::round(origin.get<1>()))};
-
- // Generate circle sectors.
- auto rScaled = rMinScaled;
- const auto nTran = long(std::ceil(((rMax - rMin) / deltaR).value()));
- vector sectors(nTran, ClipperLib::Path());
- const auto nSectors =
- long(std::round(((alpha2 - alpha1) / deltaAlpha).value()));
- //#ifdef DEBUG_CIRCULAR_SURVEY
- // qCWarning(CircularSurveyLog) << "circularTransects(): sector
- // parameres:"; qCWarning(CircularSurveyLog) << "alpha1: " <<
- // to_string(snake::Degree(alpha1)).c_str();
- // qCWarning(CircularSurveyLog) << "alpha2:
- // "
- // << to_string(snake::Degree(alpha2)).c_str();
- // qCWarning(CircularSurveyLog) << "n: "
- // << to_string((alpha2 - alpha1) / deltaAlpha).c_str();
- // qCWarning(CircularSurveyLog)
- // << "nSectors: " << nSectors; qCWarning(CircularSurveyLog) <<
- // "rMin: " << to_string(rMin).c_str(); qCWarning(CircularSurveyLog)
- // << "rMax: " << to_string(rMax).c_str();
- // qCWarning(CircularSurveyLog) << "nTran: " << nTran;
- //#endif
- using ClipperCircle =
- GenericCircle;
- for (auto §or : sectors) {
- ClipperCircle circle(rScaled, originScaled);
- approximate(circle, nSectors, sector);
- rScaled += deltaRScaled;
- }
- // Clip sectors to polygonENU.
- ClipperLib::Path polygonClipper;
- snake::FPolygon shrinked;
- snake::offsetPolygon(polygon, shrinked, -0.3);
- auto &outer = shrinked.outer();
- polygonClipper.reserve(outer.size());
- for (auto it = outer.begin(); it < outer.end() - 1; ++it) {
- auto x = ClipperLib::cInt(std::round(it->get<0>() * CLIPPER_SCALE));
- auto y = ClipperLib::cInt(std::round(it->get<1>() * CLIPPER_SCALE));
- polygonClipper.push_back(ClipperLib::IntPoint{x, y});
- }
- ClipperLib::Clipper clipper;
- clipper.AddPath(polygonClipper, ClipperLib::ptClip, true);
- clipper.AddPaths(sectors, ClipperLib::ptSubject, false);
- ClipperLib::PolyTree transectsClipper;
- clipper.Execute(ClipperLib::ctIntersection, transectsClipper,
- ClipperLib::pftNonZero, ClipperLib::pftNonZero);
-
- // Subtract holes.
- if (tiles.size() > 0) {
- vector processedTiles;
- for (const auto &tile : tiles) {
- ClipperLib::Path path;
- for (const auto &v : tile.outer()) {
- path.push_back(ClipperLib::IntPoint{
- static_cast(v.get<0>() * CLIPPER_SCALE),
- static_cast(v.get<1>() * CLIPPER_SCALE)});
+ for (std::size_t j = 0; j < nSolutions; ++j) {
+ Variant var{QList()};
+ const auto &solution = pRoute->solutionVector.at(j);
+ if (solution.size() > 0) {
+ const auto &route = solution.at(0);
+ const auto &path = route.path;
+ const auto &info = route.info;
+ if (info.size() > 1) {
+ // Find index of first waypoint.
+ std::size_t idxFirst = 0;
+ const auto &infoFirst = info.at(1);
+ const auto &firstTransect = transectsENU[infoFirst.index];
+ if (firstTransect.size() > 0) {
+ const auto &firstWaypoint =
+ infoFirst.reversed ? firstTransect.back() : firstTransect.front();
+ double th = 0.01;
+ for (std::size_t i = 0; i < path.size(); ++i) {
+ auto dist = bg::distance(path[i], firstWaypoint);
+ if (dist < th) {
+ idxFirst = i;
+ break;
+ }
}
- processedTiles.push_back(std::move(path));
- }
- clipper.Clear();
- for (const auto &child : transectsClipper.Childs) {
- clipper.AddPath(child->Contour, ClipperLib::ptSubject, false);
- }
- clipper.AddPaths(processedTiles, ClipperLib::ptClip, true);
- transectsClipper.Clear();
- clipper.Execute(ClipperLib::ctDifference, transectsClipper,
- ClipperLib::pftNonZero, ClipperLib::pftNonZero);
- }
-
- // Extract transects from PolyTree and convert them to
- // BoostLineString
- for (const auto &child : transectsClipper.Childs) {
- snake::FLineString transect;
- transect.reserve(child->Contour.size());
- for (const auto &vertex : child->Contour) {
- auto x = static_cast(vertex.X) / CLIPPER_SCALE;
- auto y = static_cast(vertex.Y) / CLIPPER_SCALE;
- transect.push_back(snake::FPoint(x, y));
- }
- transects.push_back(transect);
- }
-
- // Join sectors which where slit due to clipping.
- const double th = 0.01;
- for (auto ito = transects.begin(); ito < transects.end(); ++ito) {
- for (auto iti = ito + 1; iti < transects.end(); ++iti) {
- auto dist1 = bg::distance(ito->front(), iti->front());
- if (dist1 < th) {
- snake::FLineString temp;
- for (auto it = iti->end() - 1; it >= iti->begin(); --it) {
- temp.push_back(*it);
+ // Find index of last waypoint.
+ std::size_t idxLast = path.size() - 1;
+ const auto &infoLast = info.at(info.size() - 2);
+ const auto &lastTransect = transectsENU[infoLast.index];
+ if (lastTransect.size() > 0) {
+ const auto &lastWaypoint =
+ infoLast.reversed ? lastTransect.front() : lastTransect.back();
+ for (long i = path.size() - 1; i >= 0; --i) {
+ auto dist = bg::distance(path[i], lastWaypoint);
+ if (dist < th) {
+ idxLast = i;
+ break;
+ }
}
- temp.insert(temp.end(), ito->begin(), ito->end());
- *ito = temp;
- transects.erase(iti);
- break;
- }
- auto dist2 = bg::distance(ito->front(), iti->back());
- if (dist2 < th) {
- snake::FLineString temp;
- temp.insert(temp.end(), iti->begin(), iti->end());
- temp.insert(temp.end(), ito->begin(), ito->end());
- *ito = temp;
- transects.erase(iti);
- break;
- }
- auto dist3 = bg::distance(ito->back(), iti->front());
- if (dist3 < th) {
- snake::FLineString temp;
- temp.insert(temp.end(), ito->begin(), ito->end());
- temp.insert(temp.end(), iti->begin(), iti->end());
- *ito = temp;
- transects.erase(iti);
- break;
- }
- auto dist4 = bg::distance(ito->back(), iti->back());
- if (dist4 < th) {
- snake::FLineString temp;
- temp.insert(temp.end(), ito->begin(), ito->end());
- for (auto it = iti->end() - 1; it >= iti->begin(); --it) {
- temp.push_back(*it);
+
+ // Convert to geo coordinates.
+ auto &list = var.front();
+ for (std::size_t i = idxFirst; i <= idxLast; ++i) {
+ auto &vertex = path[i];
+ QGeoCoordinate c;
+ snake::fromENU(ori, vertex, c);
+ list.append(CoordInfo_t{c, CoordTypeInterior});
}
- *ito = temp;
- transects.erase(iti);
- break;
- }
- }
- }
- // Remove short transects
- for (auto it = transects.begin(); it < transects.end();) {
- if (bg::length(*it) < minLength.value()) {
- it = transects.erase(it);
+ } else {
+ qCWarning(CircularSurveyLog)
+ << "_setTransects(): lastTransect.size() == 0";
+ }
} else {
- ++it;
+ qCWarning(CircularSurveyLog)
+ << "_setTransects(): firstTransect.size() == 0";
}
+ } else {
+ qCWarning(CircularSurveyLog)
+ << "_setTransects(): transectsInfo.size() <= 1";
}
+ } else {
+ qCWarning(CircularSurveyLog) << "_setTransects(): solution.size() == 0";
+ }
- qCWarning(CircularSurveyLog)
- << "circularTransects(): transect gen. time: "
- << std::chrono::duration_cast(
- std::chrono::high_resolution_clock::now() - s1)
- .count()
- << " ms";
- return true;
+ if (var.size() > 0 && var.front().size() > 0) {
+ variantVector.push_back(std::move(var));
}
}
- return false;
-}
-
-bool linearTransects(const snake::FPolygon &polygon,
- const std::vector &tiles,
- snake::Length distance, snake::Angle angle,
- snake::Length minLength, snake::Transects &transects) {
- namespace tr = bg::strategy::transform;
- auto s1 = std::chrono::high_resolution_clock::now();
-
- // Check preconitions
- if (polygon.outer().size() >= 3) {
- // Convert to ENU system.
- std::string error;
- // Check validity.
- if (!bg::is_valid(polygon, error)) {
- std::stringstream ss;
- ss << bg::wkt(polygon);
-
- qCWarning(CircularSurveyLog) << "linearTransects(): "
- "invalid polygon. "
- << error.c_str() << ss.str().c_str();
- } else {
- tr::rotate_transformer rotate(angle.value() *
- 180 / M_PI);
- // Rotate polygon by angle and calculate bounding box.
- snake::FPolygon polygonENURotated;
- bg::transform(polygon.outer(), polygonENURotated.outer(), rotate);
- snake::FBox box;
- boost::geometry::envelope(polygonENURotated, box);
- double x0 = box.min_corner().get<0>();
- double y0 = box.min_corner().get<1>();
- double x1 = box.max_corner().get<0>();
- double y1 = box.max_corner().get<1>();
-
- // Generate transects and convert them to clipper path.
- size_t num_t = ceil((y1 - y0) / distance.value()); // number of transects
- vector transectsClipper;
- transectsClipper.reserve(num_t);
- for (size_t i = 0; i < num_t; ++i) {
- // calculate transect
- snake::FPoint v1{x0, y0 + i * distance.value()};
- snake::FPoint v2{x1, y0 + i * distance.value()};
- snake::FLineString transect;
- transect.push_back(v1);
- transect.push_back(v2);
- // transform back
- snake::FLineString temp_transect;
- tr::rotate_transformer rotate_back(
- -angle.value() * 180 / M_PI);
- bg::transform(transect, temp_transect, rotate_back);
- // to clipper
- ClipperLib::IntPoint c1{static_cast(
- temp_transect[0].get<0>() * CLIPPER_SCALE),
- static_cast(
- temp_transect[0].get<1>() * CLIPPER_SCALE)};
- ClipperLib::IntPoint c2{static_cast(
- temp_transect[1].get<0>() * CLIPPER_SCALE),
- static_cast(
- temp_transect[1].get<1>() * CLIPPER_SCALE)};
- ClipperLib::Path path{c1, c2};
- transectsClipper.push_back(path);
- }
-
- if (transectsClipper.size() == 0) {
- std::stringstream ss;
- ss << "Not able to generate transects. Parameter: distance = "
- << distance << std::endl;
- qCWarning(CircularSurveyLog)
- << "linearTransects(): " << ss.str().c_str();
- return false;
- }
-
- // Convert measurement area to clipper path.
- snake::FPolygon shrinked;
- snake::offsetPolygon(polygon, shrinked, -0.2);
- auto &outer = shrinked.outer();
- ClipperLib::Path polygonClipper;
- for (auto vertex : outer) {
- polygonClipper.push_back(ClipperLib::IntPoint{
- static_cast(vertex.get<0>() * CLIPPER_SCALE),
- static_cast(vertex.get<1>() * CLIPPER_SCALE)});
- }
-
- // Perform clipping.
- // Clip transects to measurement area.
- ClipperLib::Clipper clipper;
- clipper.AddPath(polygonClipper, ClipperLib::ptClip, true);
- clipper.AddPaths(transectsClipper, ClipperLib::ptSubject, false);
- ClipperLib::PolyTree clippedTransecs;
- clipper.Execute(ClipperLib::ctIntersection, clippedTransecs,
- ClipperLib::pftNonZero, ClipperLib::pftNonZero);
-
- // Subtract holes.
- if (tiles.size() > 0) {
- vector processedTiles;
- for (const auto &tile : tiles) {
- ClipperLib::Path path;
- for (const auto &v : tile.outer()) {
- path.push_back(ClipperLib::IntPoint{
- static_cast(v.get<0>() * CLIPPER_SCALE),
- static_cast(v.get<1>() * CLIPPER_SCALE)});
- }
- processedTiles.push_back(std::move(path));
- }
- clipper.Clear();
- for (const auto &child : clippedTransecs.Childs) {
- clipper.AddPath(child->Contour, ClipperLib::ptSubject, false);
- }
- clipper.AddPaths(processedTiles, ClipperLib::ptClip, true);
- clippedTransecs.Clear();
- clipper.Execute(ClipperLib::ctDifference, clippedTransecs,
- ClipperLib::pftNonZero, ClipperLib::pftNonZero);
- }
+ // Assign routes if no error occured.
+ if (variantVector.size() > 0) {
+ // Swap first route to _transects.
+ this->_variantVector.swap(variantVector);
+ this->_state = STATE::STORE;
+ this->_rebuildTransects();
+ } else {
+ this->_state = STATE::IDLE;
+ }
+}
- // Extract transects from PolyTree and convert them to BoostLineString
- for (const auto &child : clippedTransecs.Childs) {
- const auto &clipperTransect = child->Contour;
- snake::FPoint v1{
- static_cast(clipperTransect[0].X) / CLIPPER_SCALE,
- static_cast(clipperTransect[0].Y) / CLIPPER_SCALE};
- snake::FPoint v2{
- static_cast(clipperTransect[1].X) / CLIPPER_SCALE,
- static_cast(clipperTransect[1].Y) / CLIPPER_SCALE};
-
- snake::FLineString transect{v1, v2};
- if (bg::length(transect) >= minLength.value()) {
- transects.push_back(transect);
- }
- }
+Fact *CircularSurvey::variant() { return &_variant; }
- if (transects.size() == 0) {
- std::stringstream ss;
- ss << "Not able to generatetransects. Parameter: minLength = "
- << minLength << std::endl;
- qCWarning(CircularSurveyLog)
- << "linearTransects(): " << ss.str().c_str();
- return false;
- }
- qCWarning(CircularSurveyLog)
- << "linearTransects(): transect gen. time: "
- << std::chrono::duration_cast(
- std::chrono::high_resolution_clock::now() - s1)
- .count()
- << " ms";
- return true;
- }
- }
- return false;
+bool CircularSurvey::calculating() const {
+ return this->_pWorker->calculating();
}
+
/*!
\class CircularSurveyComplexItem
\inmodule Wima
diff --git a/src/Wima/CircularSurvey.h b/src/Wima/CircularSurvey.h
index 2b6c9820a73732e136f194ff9e23924c14a27f21..06a1a93d844decd10b3170a6174db8fa9ec39d05 100644
--- a/src/Wima/CircularSurvey.h
+++ b/src/Wima/CircularSurvey.h
@@ -13,13 +13,17 @@
class RoutingThread;
class RoutingData;
+
+namespace routing {
class GeneratorBase;
+}
class CircularSurvey : public TransectStyleComplexItem {
Q_OBJECT
- using PtrGenerator = std::shared_ptr;
+ using PtrGenerator = std::shared_ptr;
using PtrRoutingData = std::shared_ptr;
+ using PtrWorker = std::shared_ptr;
public:
/// @param vehicle Vehicle which this is being contructed for
@@ -31,14 +35,15 @@ public:
QObject *parent);
~CircularSurvey();
- Q_PROPERTY(Fact *type READ type CONSTANT)
- Q_PROPERTY(int typeCount READ typeCount CONSTANT)
Q_PROPERTY(Fact *variant READ variant CONSTANT)
Q_PROPERTY(
- QList variantNames READ variantNames NOTIFY variantNamesChanged)
- Q_PROPERTY(QList generatorNameList READ generatorNameList NOTIFY
+ QStringList variantNames READ variantNames NOTIFY variantNamesChanged)
+ Q_PROPERTY(QStringList generatorNameList READ generatorNameList NOTIFY
generatorNameListChanged)
Q_PROPERTY(bool calculating READ calculating NOTIFY calculatingChanged)
+ Q_PROPERTY(
+ routing::GeneratorBase *generator READ generator NOTIFY generatorChanged)
+ Q_PROPERTY(int generatorIndex READ generatorIndex NOTIFY generatorChanged)
Q_INVOKABLE void reverse(void);
@@ -46,10 +51,9 @@ public:
void setPlanData(const WimaPlanData &d);
// Property getters
- Fact *type();
- int typeCount() const;
Fact *variant();
- QList variantNames() const;
+ QStringList variantNames() const;
+ bool calculating() const;
// Overrides
bool load(const QJsonObject &complexObject, int sequenceNumber,
@@ -68,15 +72,17 @@ public:
double additionalTimeDelay(void) const override final;
// Generator
- bool registerGenerator(const QString &name, std::shared_ptr g);
+ bool registerGenerator(const QString &name,
+ std::shared_ptr g);
bool unregisterGenerator(const QString &name);
bool unregisterGenerator(int index);
Q_INVOKABLE bool switchToGenerator(const QString &name);
Q_INVOKABLE bool switchToGenerator(int index);
- QList generatorNameList();
+ QStringList generatorNameList();
+ routing::GeneratorBase *generator();
+ int generatorIndex();
static const char *settingsGroup;
- static const char *typeName;
static const char *variantName;
static const char *CircularSurveyName;
@@ -120,20 +126,18 @@ private:
// center of the circular lanes, e.g. base station
QMap _metaDataMap;
- SettingsFact _type;
SettingsFact _variant;
- QList _variantNames;
+ QStringList _variantNames;
// Area data
- std::shared_ptr _areaData;
+ std::shared_ptr _pAreaData;
// Generators
QList _generatorList;
- QList _generatorNameList;
+ QStringList _generatorNameList;
PtrGenerator _pGenerator;
// Worker
- using PtrWorker = std::shared_ptr;
PtrWorker _pWorker;
PtrRoutingData _pRoutingData; // remove this, not necessary.
diff --git a/src/Wima/Snake/CircularGenerator.cpp b/src/Wima/Snake/CircularGenerator.cpp
index 3b7167a27eafa4b9dd4aac7f71f0fe47f93284d4..3267d5ab473080c8c829c95c5be2090878e7d215 100644
--- a/src/Wima/Snake/CircularGenerator.cpp
+++ b/src/Wima/Snake/CircularGenerator.cpp
@@ -43,11 +43,11 @@ CircularGenerator::CircularGenerator(GeneratorBase::Data d, QObject *parent)
establishConnections();
}
-QString CircularGenerator::editorQML() {
+QString CircularGenerator::editorQml() {
return QStringLiteral("CircularGeneratorEditor.qml");
}
-QString CircularGenerator::mapVisualQML() {
+QString CircularGenerator::mapVisualQml() {
return QStringLiteral("CircularGeneratorMapVisual.qml");
}
@@ -61,13 +61,15 @@ bool CircularGenerator::get(Generator &generator) {
if (this->_d) {
if (this->_d->isValid()) {
// Prepare data.
- const auto &origin = this->_d->origin();
+ auto origin = this->_d->origin();
+ origin.setAltitude(0);
if (!origin.isValid()) {
qCWarning(CircularGeneratorLog) << "get(): origin invalid." << origin;
return false;
}
- const auto &ref = this->_reference;
+ auto ref = this->_reference;
+ ref.setAltitude(0);
if (!ref.isValid()) {
qCWarning(CircularGeneratorLog) << "get(): reference invalid." << ref;
return false;
diff --git a/src/Wima/Snake/CircularGenerator.h b/src/Wima/Snake/CircularGenerator.h
index 37c4bcaba8e613061e3412e14a16684fb3ac9665..e286fe584fa3a904b2b586356b74c61a1d0508c9 100644
--- a/src/Wima/Snake/CircularGenerator.h
+++ b/src/Wima/Snake/CircularGenerator.h
@@ -16,8 +16,8 @@ public:
Q_PROPERTY(Fact *deltaAlpha READ deltaAlpha CONSTANT)
Q_PROPERTY(Fact *minLength READ minLength CONSTANT)
- virtual QString editorQML() override;
- virtual QString mapVisualQML() override;
+ virtual QString editorQml() override;
+ virtual QString mapVisualQml() override;
virtual QString name() override;
virtual QString abbreviation() override;
@@ -30,7 +30,7 @@ public:
Fact *minLength();
void setReference(const QGeoCoordinate &reference);
- void resetReference();
+ Q_INVOKABLE void resetReference();
static const char *settingsGroup;
static const char *distanceName;
diff --git a/src/Wima/Snake/GeneratorBase.cc b/src/Wima/Snake/GeneratorBase.cc
index 77aa3c7731c4a7a296e6673717d6d088a1d91fda..03d8d581ac4c6b18bf930172724380f7a78dbc43 100644
--- a/src/Wima/Snake/GeneratorBase.cc
+++ b/src/Wima/Snake/GeneratorBase.cc
@@ -12,6 +12,14 @@ GeneratorBase::GeneratorBase(GeneratorBase::Data d, QObject *parent)
GeneratorBase::~GeneratorBase() {}
+QString GeneratorBase::editorQml() {
+ return QStringLiteral("EmptyGeneratorEditor.qml");
+}
+
+QString GeneratorBase::mapVisualQml() {
+ return QStringLiteral("EmptyGeneratorMapVisual.qml");
+}
+
GeneratorBase::Data GeneratorBase::data() const { return _d; }
void GeneratorBase::setData(const Data &d) {
diff --git a/src/Wima/Snake/GeneratorBase.h b/src/Wima/Snake/GeneratorBase.h
index c60249d055f76351df0549e18e8ad807fd60b249..89fd78fef245107e59d1e7db948ed7b1954fa532 100644
--- a/src/Wima/Snake/GeneratorBase.h
+++ b/src/Wima/Snake/GeneratorBase.h
@@ -1,3 +1,5 @@
+#pragma once
+
#include
#include
@@ -19,8 +21,11 @@ public:
explicit GeneratorBase(Data d, QObject *parent = nullptr);
~GeneratorBase();
- virtual QString editorQML() = 0;
- virtual QString mapVisualQML() = 0;
+ Q_PROPERTY(QString editorQml READ editorQml CONSTANT)
+ Q_PROPERTY(QString mapVisualQml READ mapVisualQml CONSTANT)
+
+ virtual QString editorQml();
+ virtual QString mapVisualQml();
virtual QString name() = 0;
virtual QString abbreviation() = 0;
diff --git a/src/Wima/Snake/LinearGenerator.cpp b/src/Wima/Snake/LinearGenerator.cpp
index 0a019de8dde2c9a91906c0d709cc45624e19d59d..6fa668de1fed36ae1b573e683c1d4f948c091a8e 100644
--- a/src/Wima/Snake/LinearGenerator.cpp
+++ b/src/Wima/Snake/LinearGenerator.cpp
@@ -34,25 +34,24 @@ LinearGenerator::LinearGenerator(GeneratorBase::Data d, QObject *parent)
establishConnections();
}
-QString LinearGenerator::editorQML() {
+QString LinearGenerator::editorQml() {
return QStringLiteral("LinearGeneratorEditor.qml");
}
-QString LinearGenerator::mapVisualQML() {
- return QStringLiteral("LinearGeneratorMapVisual.qml");
-}
-
QString LinearGenerator::name() { return QStringLiteral("Linear Generator"); }
QString LinearGenerator::abbreviation() { return QStringLiteral("L. Gen."); }
bool LinearGenerator::get(Generator &generator) {
if (_d) {
-
if (this->_d->isValid()) {
-
// Prepare data.
- const auto &origin = this->_d->origin();
+ auto origin = this->_d->origin();
+ origin.setAltitude(0);
+ if (!origin.isValid()) {
+ qCWarning(LinearGeneratorLog) << "get(): origin invalid.";
+ }
+
auto geoPolygon = this->_d->measurementArea().coordinateList();
for (auto &v : geoPolygon) {
if (v.isValid()) {
diff --git a/src/Wima/Snake/LinearGenerator.h b/src/Wima/Snake/LinearGenerator.h
index eb1c1bdcbb74d3cc803fd173706d93e595699f3d..ba63cf51a322f7c6e3d0b3cdc30ae3a6b5c6183e 100644
--- a/src/Wima/Snake/LinearGenerator.h
+++ b/src/Wima/Snake/LinearGenerator.h
@@ -14,8 +14,7 @@ public:
Q_PROPERTY(Fact *alpha READ alpha CONSTANT)
Q_PROPERTY(Fact *minLength READ minLength CONSTANT)
- virtual QString editorQML() override;
- virtual QString mapVisualQML() override;
+ virtual QString editorQml() override;
virtual QString name() override;
virtual QString abbreviation() override;
diff --git a/src/Wima/Snake/snake.cpp b/src/Wima/Snake/snake.cpp
index c7517cb5c46e0e02c92de2969067b344e3f71f56..8886d35d43adcf3124f29f2d53702f9411a75820 100644
--- a/src/Wima/Snake/snake.cpp
+++ b/src/Wima/Snake/snake.cpp
@@ -760,7 +760,17 @@ bool route(const FPolygon &area, const Transects &transects,
if (std::isinf(dist)) {
std::vector route;
if (!dijkstraAlgorithm(n, i, j, route, dist, distLambda)) {
- par.errorString = "Distance matrix calculation failed.";
+ std::stringstream ss;
+ ss << "Distance matrix calculation failed. connection graph: "
+ << connectionGraph << std::endl;
+ ss << "area: " << bg::wkt(area) << std::endl;
+ ss << "transects:" << std::endl;
+ for (const auto &t : transects) {
+
+ ss << bg::wkt(t) << std::endl;
+ }
+
+ par.errorString = ss.str();
return false;
}
(void)route;
diff --git a/src/Wima/WimaPlaner.cc b/src/Wima/WimaPlaner.cc
index 2be79d99706f04aeca92a9d3900e6892de954985..cceeb54b1a6ec53b2fcce499e1ae2bea7a818cdb 100644
--- a/src/Wima/WimaPlaner.cc
+++ b/src/Wima/WimaPlaner.cc
@@ -356,8 +356,6 @@ void WimaPlaner::_update() {
}
// establish connections
- _survey->setRefPoint(_measurementArea.center());
- _survey->setHidePolygon(true);
connect(_survey, &CircularSurvey::calculatingChanged, this,
&WimaPlaner::CSCalculatingChangedHandler);
connect(_survey, &CircularSurvey::missionItemReady, this,
@@ -369,9 +367,14 @@ void WimaPlaner::_update() {
// update survey area
disconnect(_survey, &CircularSurvey::calculatingChanged, this,
&WimaPlaner::CSCalculatingChangedHandler);
- _survey->setMeasurementArea(this->_measurementArea);
- _survey->setJoinedArea(this->_joinedArea);
- _survey->setDepot(this->_serviceArea.depot());
+
+ WimaPlanData planData;
+ if (!toPlanData(planData)) {
+ qCWarning(WimaPlanerLog) << "not able to create plan data.";
+ return;
+ }
+ _survey->setPlanData(planData);
+
connect(_survey, &CircularSurvey::calculatingChanged, this,
&WimaPlaner::CSCalculatingChangedHandler);
@@ -772,7 +775,6 @@ bool WimaPlaner::loadFromFile(const QString &filename) {
for (int i = 0; i < missionItems->count(); i++) {
_survey = missionItems->value(i);
if (_survey != nullptr) {
- _survey->setHidePolygon(true);
connect(_survey, &CircularSurvey::calculatingChanged, this,
&WimaPlaner::CSCalculatingChangedHandler);
connect(_survey, &CircularSurvey::missionItemReady, this,
diff --git a/src/WimaView/CircularGeneratorEditor.qml b/src/WimaView/CircularGeneratorEditor.qml
new file mode 100644
index 0000000000000000000000000000000000000000..b0c8eb6ecdecd383346b50aeb7fc2f3f55f30e61
--- /dev/null
+++ b/src/WimaView/CircularGeneratorEditor.qml
@@ -0,0 +1,44 @@
+import QtQuick 2.0
+
+import QtQuick.Layouts 1.11
+
+import QGroundControl.Controls 1.0
+import QGroundControl.FactControls 1.0
+import QGroundControl.ScreenTools 1.0
+
+GridLayout {
+
+ // Item must be loaded, expects the following properties:
+// property var generator
+
+ property real _margin: ScreenTools.defaultFontPixelWidth / 2
+
+ columnSpacing: _margin
+ rowSpacing: _margin
+ columns: 2
+
+ QGCLabel { text: qsTr("Distance") }
+ FactTextField {
+ fact: generator.distance
+ Layout.fillWidth: true
+ }
+
+ QGCLabel { text: qsTr("Delta Alpha") }
+ FactTextField {
+ fact: generator.deltaAlpha
+ Layout.fillWidth: true
+ }
+
+ QGCLabel { text: qsTr("Min. Length") }
+ FactTextField {
+ fact: generator.minLength
+ Layout.fillWidth: true
+ }
+
+ QGCButton {
+ text: qsTr("Reset Ref.")
+ onClicked: generator.resetReference();
+ Layout.fillWidth: true
+ Layout.columnSpan: 2
+ }
+}
diff --git a/src/WimaView/CircularGeneratorMapVisual.qml b/src/WimaView/CircularGeneratorMapVisual.qml
new file mode 100644
index 0000000000000000000000000000000000000000..1e9ee419dc8a8fa6146e9b726ad53410558eb75d
--- /dev/null
+++ b/src/WimaView/CircularGeneratorMapVisual.qml
@@ -0,0 +1,69 @@
+import QtQuick 2.0
+
+Item {
+ id: _root
+
+ property var map ///< Map control to place item in
+ property var qgcView ///< QGCView to use for popping dialogs
+ property var generator
+ property bool checked: false
+
+ property var _referenceComponent
+
+ signal clicked()
+
+ function _addRefPoint(){
+ if (!_referenceComponent){
+ _referenceComponent = refPointComponent.createObject(_root)
+ map.addMapItem(_referenceComponent)
+ }
+ }
+
+ function _destroyRefPoint(){
+ if (_referenceComponent){
+ map.removeMapItem(_referenceComponent)
+ _referenceComponent.destroy()
+ _referenceComponent = undefined
+ }
+ }
+
+ onVisibleChanged: {
+ if (visible){
+ _addRefPoint()
+ } else {
+ _destroyRefPoint()
+ }
+ }
+
+ Component.onCompleted: {
+ if (visible){
+ _addRefPoint()
+ }
+ }
+
+ Component.onDestroyed: {
+ _destroyRefPoint()
+ }
+
+ // Ref. point (Base Station)
+ Component {
+ id: refPointComponent
+
+ DragCoordinate {
+ map: _root.map
+ qgcView: _root.qgcView
+ z: QGroundControl.zOrderMapItems
+ checked: _root.checked
+ coordinate: _root.generator.reference
+
+ onClicked: {
+ _root.clicked()
+ }
+
+ onDragReleased: {
+ _root.generator.reference = coordinate
+ coordinate = Qt.binding(function (){return _root.generator.reference})
+ }
+ }
+ }
+}
diff --git a/src/PlanView/CircularSurveyItemEditor.qml b/src/WimaView/CircularSurveyItemEditor.qml
similarity index 67%
rename from src/PlanView/CircularSurveyItemEditor.qml
rename to src/WimaView/CircularSurveyItemEditor.qml
index 2bc9fb7a0a63fc051bca2559126edb12ea520d93..932131f2f1e635539b0f6240786cffe919e92060 100644
--- a/src/PlanView/CircularSurveyItemEditor.qml
+++ b/src/WimaView/CircularSurveyItemEditor.qml
@@ -30,6 +30,8 @@ Rectangle {
property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
property real _cameraMinTriggerInterval: missionItem.cameraCalc.minTriggerInterval.rawValue
+ property var _generator: missionItem.generator
+
function polygonCaptureStarted() {
missionItem.clearPolygon()
}
@@ -95,31 +97,24 @@ Rectangle {
}
QGCLabel {
- text: qsTr("Type")
+ text: qsTr("Generator Type")
Layout.columnSpan: 2
}
- Repeater{
- id: typeRepeater
- property var typeFact: missionItem.type
- property int type: typeFact.value
- property var names: ["Circular", "Linear"]
+ QGCComboBox {
+ property var names: missionItem.generatorNameList
+ property int length: names.length
- model: missionItem.typeCount
- QGCRadioButton {
- checked: index === typeRepeater.type
- text: qsTr(typeRepeater.names[index])
+ anchors.margins: ScreenTools.defaultFontPixelWidth
+ currentIndex: missionItem.generatorIndex
+ Layout.columnSpan: 2
+ model: missionItem.generatorNameList
- onCheckedChanged: {
- if (checked){
- missionItem.type.value = index
- }
- checked = Qt.binding(function(){ return index === typeRepeater.type})
- }
+ onActivated: {
+ missionItem.switchToGenerator(index)
}
}
-
QGCLabel {
text: qsTr("Variant")
Layout.columnSpan: 2
@@ -156,74 +151,18 @@ Rectangle {
}
}
+ // Generator Editor
SectionHeader {
id: transectsHeader
- text: qsTr("Transects")
+ text: qsTr("Generator")
}
-
- GridLayout {
- anchors.left: parent.left
- anchors.right: parent.right
- columnSpacing: _margin
- rowSpacing: _margin
- columns: 2
- visible: transectsHeader.checked
-
- QGCLabel { text: qsTr("Distance") }
- FactTextField {
- fact: missionItem.transectDistance
- Layout.fillWidth: true
- }
-
- /*QGCSlider {
- id: rSlider
- minimumValue: 0.3
- maximumValue: 20
- stepSize: 0.1
- tickmarksEnabled: false
- Layout.fillWidth: true
- Layout.columnSpan: 2
- Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5
- onValueChanged: missionItem.deltaR.value = value
- Component.onCompleted: value = missionItem.deltaR.defaultValue
- updateValueWhileDragging: true
- }*/
-
- QGCLabel { text: qsTr("Alpha") }
- FactTextField {
- fact: missionItem.alpha
- Layout.fillWidth: true
- }
-
- QGCLabel { text: qsTr("Min. Length") }
- FactTextField {
- fact: missionItem.minLength
- Layout.fillWidth: true
- }
+ Loader{
+ source: _generator.editorQml
+ property var generator: _generator
+ property real margin: _margin
+ visible: transectsHeader.checked
}
- GridLayout {
- anchors.left: parent.left
- anchors.right: parent.right
- columnSpacing: _margin
- rowSpacing: _margin
- columns: 2
- visible: transectsHeader.checked
-
- QGCButton {
- text: qsTr("Reverse")
- onClicked: missionItem.reverse();
- Layout.fillWidth: true
- }
-
- QGCButton {
- text: qsTr("Reset Ref.")
- onClicked: missionItem.resetReference();
- Layout.fillWidth: true
- }
-
-
- }
Column{
anchors.left: parent.left
diff --git a/src/WimaView/CircularSurveyMapVisual.qml b/src/WimaView/CircularSurveyMapVisual.qml
index 9aa783792c9e6b376232dac00f9f5951e39f732f..71e229c3fbda2ea41c98935d6f4f5d5a67e31f98 100644
--- a/src/WimaView/CircularSurveyMapVisual.qml
+++ b/src/WimaView/CircularSurveyMapVisual.qml
@@ -26,12 +26,9 @@ Item {
property var qgcView ///< QGCView to use for popping dialogs
property var _missionItem: object
- property var _mapPolygon: object.surveyAreaPolygon
property var _transectsComponent
property var _entryCoordinate
property var _exitCoordinate
- property var _refPoint
- property bool showRefPoint: _missionItem.type.value === 0 // type == Circular
signal clicked(int sequenceNumber)
@@ -56,13 +53,6 @@ Item {
}
}
- function _addRefPoint(){
- if (!_refPoint){
- _refPoint = refPointComponent.createObject(_root)
- map.addMapItem(_refPoint)
- }
- }
-
function _destroyEntryCoordinate(){
if (_entryCoordinate){
map.removeMapItem(_entryCoordinate)
@@ -79,14 +69,6 @@ Item {
}
}
- function _destroyRefPoint(){
- if (_refPoint){
- map.removeMapItem(_refPoint)
- _refPoint.destroy()
- _refPoint = undefined
- }
- }
-
function _destroyTransectsComponent(){
if (_transectsComponent){
map.removeMapItem(_transectsComponent)
@@ -95,79 +77,18 @@ Item {
}
}
- /// Add an initial 4 sided polygon if there is none
- function _addInitialPolygon() {
- if (_mapPolygon.count < 3) {
- // Initial polygon is inset to take 2/3rds space
- var rect = Qt.rect(map.centerViewport.x, map.centerViewport.y, map.centerViewport.width, map.centerViewport.height)
- rect.x += (rect.width * 0.25) / 2
- rect.y += (rect.height * 0.25) / 2
- rect.width *= 0.75
- rect.height *= 0.75
-
- var centerCoord = map.toCoordinate(Qt.point(rect.x + (rect.width / 2), rect.y + (rect.height / 2)), false /* clipToViewPort */)
- var topLeftCoord = map.toCoordinate(Qt.point(rect.x, rect.y), false /* clipToViewPort */)
- var topRightCoord = map.toCoordinate(Qt.point(rect.x + rect.width, rect.y), false /* clipToViewPort */)
- var bottomLeftCoord = map.toCoordinate(Qt.point(rect.x, rect.y + rect.height), false /* clipToViewPort */)
- var bottomRightCoord = map.toCoordinate(Qt.point(rect.x + rect.width, rect.y + rect.height), false /* clipToViewPort */)
-
- // Initial polygon has max width and height of 3000 meters
- var halfWidthMeters = Math.min(topLeftCoord.distanceTo(topRightCoord), 3000) / 2
- var halfHeightMeters = Math.min(topLeftCoord.distanceTo(bottomLeftCoord), 3000) / 2
- topLeftCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 0)
- topRightCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 0)
- bottomLeftCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, -90).atDistanceAndAzimuth(halfHeightMeters, 180)
- bottomRightCoord = centerCoord.atDistanceAndAzimuth(halfWidthMeters, 90).atDistanceAndAzimuth(halfHeightMeters, 180)
-
- _mapPolygon.appendVertex(topLeftCoord)
- _mapPolygon.appendVertex(topRightCoord)
- _mapPolygon.appendVertex(bottomRightCoord)
- _mapPolygon.appendVertex(bottomLeftCoord)
- }
- }
-
-
Component.onCompleted: {
- if ( _mapPolygon.count === 0 ) {
- _addInitialPolygon()
- _missionItem.resetReference();
- }
_addEntryCoordinate()
_addExitCoordinate()
- if (showRefPoint){
- _addRefPoint()
- }
_addTransectsComponent()
}
Component.onDestruction: {
_destroyEntryCoordinate()
_destroyExitCoordinate()
- _destroyRefPoint()
_destroyTransectsComponent()
}
- onShowRefPointChanged: {
- if (showRefPoint){
- _addRefPoint()
- } else {
- _destroyRefPoint()
- }
- }
-
- WimaMapPolygonVisuals {
- id: mapPolygonVisuals
- qgcView: _root.qgcView
- mapControl: map
- mapPolygon: _mapPolygon
- interactive: _missionItem.isCurrentItem
- borderWidth: 1
- borderColor: "black"
- interiorColor: "green"
- interiorOpacity: 0.5
- visible: !_missionItem.hidePolygon
- }
-
// Transect lines
Component {
id: visualTransectsComponent
@@ -219,26 +140,4 @@ Item {
}
}
}
-
- // Ref. point (Base Station)
- Component {
- id: refPointComponent
-
- DragCoordinate {
- map: _root.map
- qgcView: _root.qgcView
- z: QGroundControl.zOrderMapItems
- checked: _missionItem.isCurrentItem
- coordinate: _missionItem.refPoint
-
- onClicked: {
- _root.clicked(_missionItem.sequenceNumber)
- }
-
- onDragReleased: {
- _missionItem.refPoint = coordinate
- coordinate = Qt.binding(function (){return _missionItem.refPoint})
- }
- }
- }
}
diff --git a/src/WimaView/LinearGeneratorEditor.qml b/src/WimaView/LinearGeneratorEditor.qml
new file mode 100644
index 0000000000000000000000000000000000000000..2b47ff76e4c33a53fbb13263249956abc17565a0
--- /dev/null
+++ b/src/WimaView/LinearGeneratorEditor.qml
@@ -0,0 +1,46 @@
+import QtQuick 2.0
+
+import QtQuick.Layouts 1.11
+
+import QGroundControl.Controls 1.0
+import QGroundControl.FactControls 1.0
+import QGroundControl.ScreenTools 1.0
+
+GridLayout {
+
+ // Item must be loaded, expects the following properties:
+// property var generator
+
+ property real _margin: ScreenTools.defaultFontPixelWidth / 2
+
+ columnSpacing: _margin
+ rowSpacing: _margin
+ columns: 2
+
+ QGCLabel { text: qsTr("Distance") }
+ FactTextField {
+ fact: generator.distance
+ Layout.fillWidth: true
+ }
+
+ QGCLabel { text: qsTr("Alpha") }
+ QGCSlider {
+ id: rSlider
+ minimumValue: 0
+ maximumValue: 180
+ stepSize: 0.1
+ tickmarksEnabled: false
+ Layout.fillWidth: true
+ Layout.columnSpan: 2
+ Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5
+ onValueChanged: generator.alpha.value = value
+ Component.onCompleted: value = 0
+ updateValueWhileDragging: true
+ }
+
+ QGCLabel { text: qsTr("Min. Length") }
+ FactTextField {
+ fact: generator.minLength
+ Layout.fillWidth: true
+ }
+}
diff --git a/src/WimaView/Wima.qmldir b/src/WimaView/Wima.qmldir
new file mode 100644
index 0000000000000000000000000000000000000000..b308e2a9f1261750222669d0055f786068139cc4
--- /dev/null
+++ b/src/WimaView/Wima.qmldir
@@ -0,0 +1,18 @@
+WimaMapVisual 1.0 WimaMapVisual.qml
+WimaMeasurementAreaMapVisual 1.0 WimaMeasurementAreaMapVisual.qml
+WimaJoinedAreaMapVisual 1.0 WimaJoinedAreaMapVisual.qml
+WimaMeasurementAreaEditor 1.0 WimaMeasurementAreaEditor.qml
+WimaServiceAreaMapVisual 1.0 WimaServiceAreaMapVisual.qml
+WimaAreaMapVisual 1.0 WimaAreaMapVisual.qml
+WimaServiceAreaEditor 1.0 WimaServiceAreaEditor.qml
+WimaCorridorMapVisual 1.0 WimaCorridorMapVisual.qml
+WimaItemEditor 1.0 WimaItemEditor.qml
+WimaMapPolygonVisuals 1.0 WimaMapPolygonVisuals.qml
+WimaMapPolylineVisuals 1.0 WimaMapPolylineVisuals.qml
+CircularSurveyMapVisual 1.0 CircularSurveyMapVisual.qml
+DragCoordinate 1.0 DragCoordinate.qml
+CoordinateIndicator 1.0 CoordinateIndicator.qml
+CoordinateIndicatorDrag 1.0 CoordinateIndicatorDrag.qml
+ProgressIndicator 1.0 ProgressIndicator.qml
+WimaToolBar 1.0 WimaToolBar.qml
+
diff --git a/src/comm/LinkConfiguration.h b/src/comm/LinkConfiguration.h
index c8805f185fc2e22bdbf0d4fc574f046d495e392b..a32e65f53e2caa0c0189315e43c3faf1a36adb30 100644
--- a/src/comm/LinkConfiguration.h
+++ b/src/comm/LinkConfiguration.h
@@ -213,5 +213,5 @@ private:
bool _highLatency;
};
-typedef shared_ptr SharedLinkConfigurationPointer;
+typedef QSharedPointer SharedLinkConfigurationPointer;
diff --git a/src/comm/LinkInterface.h b/src/comm/LinkInterface.h
index 78b2db66a8eaf8601d8f108f72d9dd4e4ecd8800..36c01fb72f6edefb2c9d6a2074428959bc28cb61 100644
--- a/src/comm/LinkInterface.h
+++ b/src/comm/LinkInterface.h
@@ -305,5 +305,5 @@ private:
QMap _mavlinkMessagesTimers;
};
-typedef shared_ptr SharedLinkInterfacePointer;
+typedef QSharedPointer SharedLinkInterfacePointer;
diff --git a/src/qgcunittest/UnitTest.h b/src/qgcunittest/UnitTest.h
index 74cfb544130af99b9ccdfa4d65105f2a95c2b4c2..f9d555dc0a3bd673a258bf7ee9ad8e92c000bf94 100644
--- a/src/qgcunittest/UnitTest.h
+++ b/src/qgcunittest/UnitTest.h
@@ -215,7 +215,7 @@ public:
}
private:
- shared_ptr _unitTest;
+ QSharedPointer _unitTest;
};
#endif