Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
175e7c28
Commit
175e7c28
authored
Oct 19, 2019
by
Valentin Platzgummer
Browse files
Options
Browse Files
Download
Plain Diff
merge with remote/master
parents
dc158d8f
bf3b5ebe
Changes
28
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
28 changed files
with
662 additions
and
189 deletions
+662
-189
KlinbenbachCircle.png
WimaDok/pics/KlinbenbachCircle.png
+0
-0
QGroundControl.AppImage
deploy/QGroundControl.AppImage
+0
-0
qgroundcontrol.pro
qgroundcontrol.pro
+1
-1
qgroundcontrol.qrc
qgroundcontrol.qrc
+1
-0
FlightDisplayView.qml
src/FlightDisplay/FlightDisplayView.qml
+25
-1
FlightDisplayViewMap.qml
src/FlightDisplay/FlightDisplayViewMap.qml
+11
-10
FlightDisplayWimaMenu.qml
src/FlightDisplay/FlightDisplayWimaMenu.qml
+143
-1
WimaPlanMapItems.qml
src/FlightMap/MapItems/WimaPlanMapItems.qml
+13
-15
MissionController.cc
src/MissionManager/MissionController.cc
+22
-8
MissionController.h
src/MissionManager/MissionController.h
+5
-0
SimpleMissionItem.cc
src/MissionManager/SimpleMissionItem.cc
+2
-2
SimpleMissionItem.h
src/MissionManager/SimpleMissionItem.h
+1
-1
StructureScanComplexItem.cc
src/MissionManager/StructureScanComplexItem.cc
+1
-1
StructureScanComplexItem.h
src/MissionManager/StructureScanComplexItem.h
+1
-1
TransectStyleComplexItem.cc
src/MissionManager/TransectStyleComplexItem.cc
+1
-1
TransectStyleComplexItem.h
src/MissionManager/TransectStyleComplexItem.h
+1
-1
VisualMissionItem.cc
src/MissionManager/VisualMissionItem.cc
+7
-1
VisualMissionItem.h
src/MissionManager/VisualMissionItem.h
+1
-1
CircularSurveyItemEditor.qml
src/PlanView/CircularSurveyItemEditor.qml
+24
-27
QGroundControlQmlGlobal.h
src/QmlControls/QGroundControlQmlGlobal.h
+4
-4
CircularSurvey.SettingsGroup.json
src/Wima/CircularSurvey.SettingsGroup.json
+6
-0
CircularSurveyComplexItem.cc
src/Wima/CircularSurveyComplexItem.cc
+21
-5
CircularSurveyComplexItem.h
src/Wima/CircularSurveyComplexItem.h
+17
-10
WimaController.SettingsGroup.json
src/Wima/WimaController.SettingsGroup.json
+38
-0
WimaController.cc
src/Wima/WimaController.cc
+242
-72
WimaController.h
src/Wima/WimaController.h
+61
-18
WimaPlaner.cc
src/Wima/WimaPlaner.cc
+2
-5
SphericalSurveyMapVisual.qml
src/WimaView/SphericalSurveyMapVisual.qml
+11
-3
No files found.
WimaDok/pics/KlinbenbachCircle.png
0 → 100644
View file @
175e7c28
310 KB
deploy/QGroundControl.AppImage
View file @
175e7c28
No preview for this file type
qgroundcontrol.pro
View file @
175e7c28
...
...
@@ -1345,4 +1345,4 @@ contains (CONFIG, QGC_DISABLE_INSTALLER_SETUP) {
}
DISTFILES
+=
\
src
/
WimaView
/
WimaMeasurementAreaEditor
.
qml
src
/
WimaView
/
WimaMeasurementAreaEditor
.
qml
\
qgroundcontrol.qrc
View file @
175e7c28
...
...
@@ -277,6 +277,7 @@
<file alias="WimaMeasurementArea.SettingsGroup.json">src/Wima/WimaMeasurementArea.SettingsGroup.json</file>
<file alias="CircularSurvey.SettingsGroup.json">src/Wima/CircularSurvey.SettingsGroup.json</file>
<file alias="WimaArea.SettingsGroup.json">src/Wima/WimaArea.SettingsGroup.json</file>
<file alias="WimaController.SettingsGroup.json">src/Wima/WimaController.SettingsGroup.json</file>
</qresource>
<qresource prefix="/MockLink">
<file alias="APMArduCopterMockLink.params">src/comm/APMArduCopterMockLink.params</file>
...
...
src/FlightDisplay/FlightDisplayView.qml
View file @
175e7c28
...
...
@@ -402,7 +402,8 @@ QGCView {
script
:
{
// Stop video, restart it again with Timer
// Avoiding crashs if ParentChange is not yet done
QGroundControl
.
videoManager
.
stopVideo
()
QGroundControl
.
video
visible
:
_splitConcave
.
visibleManager
.
stopVideo
()
videoPopUpTimer
.
running
=
true
}
}
...
...
@@ -527,6 +528,7 @@ QGCView {
FlightDisplayViewWidgets
{
id
:
flightDisplayViewWidgets
z
:
_panel
.
z
+
4
<<<<<<<
HEAD
height
:
ScreenTools
.
availableHeight
-
(
singleMultiSelector
.
visible
?
singleMultiSelector
.
height
+
_margins
:
0
)
-
wimaMenu
.
height
anchors.left
:
parent
.
left
anchors.right
:
altitudeSlider
.
visible
?
altitudeSlider
.
left
:
parent
.
right
...
...
@@ -545,6 +547,28 @@ QGCView {
visible
:
true
height
:
300
width
:
200
=======
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
anchors.left
:
parent
.
left
anchors.bottom
:
parent
.
bottom
anchors.leftMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.25
anchors.bottomMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.25
wimaController
:
wimaController
>>>>>>>
bf3b5ebeb517fcf1caf74f7b1df73c550c4741b8
}
//-------------------------------------------------------------------------
...
...
src/FlightDisplay/FlightDisplayViewMap.qml
View file @
175e7c28
...
...
@@ -193,9 +193,18 @@ FlightMap {
property
real
leftToolWidth
:
toolStrip
.
x
+
toolStrip
.
width
}
// Add mission items generated by wima planer to the map
WimaPlanMapItems
{
map
:
flightMap
largeMapView
:
_mainIsMap
wimaController
:
flightMap
.
wimaController
}
// Add wima Areas to the Map
MapItemView
{
model
:
wimaController
.
visualItems
property
bool
_enableWima
:
wimaController
.
enableWimaController
.
value
model
:
_enableWima
?
wimaController
.
visualItems
:
0
delegate
:
MapPolygon
{
path
:
object
.
path
;
...
...
@@ -205,18 +214,10 @@ FlightMap {
:
object
.
type
===
"
WimaMeasurementAreaData
"
?
"
green
"
:
"
transparent
"
opacity
:
0.25
z
:
QGroundControl
.
zOrder
Trajectory
Lines
-
2
z
:
QGroundControl
.
zOrder
Waypoint
Lines
-
2
}
}
// Add mission items generated by wima planer to the map
WimaPlanMapItems
{
map
:
flightMap
largeMapView
:
_mainIsMap
wimaController
:
flightMap
.
wimaController
z
:
QGroundControl
.
zOrderTrajectoryLines
-
1
}
// Add trajectory points to the map
MapItemView
{
model
:
_mainIsMap
?
_activeVehicle
?
_activeVehicle
.
trajectoryPoints
:
0
:
0
...
...
src/FlightDisplay/FlightDisplayWimaMenu.qml
View file @
175e7c28
...
...
@@ -14,13 +14,155 @@ import QGroundControl.Vehicle 1.0
import
QGroundControl
.
FlightMap
1.0
import
QGroundControl
.
Airspace
1.0
import
QGroundControl
.
Airmap
1.0
import
QGroundControl
.
FactSystem
1.0
import
QGroundControl
.
FactControls
1.0
Item
{
id
:
_root
id
:
_root
height
:
400
width
:
250
<<<<<<<
HEAD
Text
{
id
:
enableWima
text
:
qsTr
(
"
WiMA
"
)
font.pointSize
:
40
=======
property
var
wimaController
// must be provided by the user
// box containing all items
Rectangle
{
anchors.left
:
parent
.
left
anchors.bottom
:
parent
.
bottom
height
:
enableWima
.
enableWimaBoolean
?
parent
.
height
:
enableWima
.
height
width
:
enableWima
.
enableWimaBoolean
?
parent
.
width
:
enableWima
.
width
color
:
enableWima
.
enableWimaBoolean
?
qgcPal
.
window
:
"
transparent
"
radius
:
ScreenTools
.
defaultFontPixelHeight
/
4
anchors.topMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
anchors.bottomMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
anchors.rightMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
anchors.leftMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
// checkbox to enable/ disable wima
SliderSwitch
{
id
:
enableWima
anchors.horizontalCenter
:
parent
.
horizontalCenter
anchors.topMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.25
anchors.top
:
parent
.
top
confirmText
:
enableWimaBoolean
?
qsTr
(
"
disable WiMA
"
)
:
qsTr
(
"
enable WiMA
"
)
property
var
enableWimaFact
:
wimaController
.
enableWimaController
property
bool
enableWimaBoolean
:
enableWimaFact
.
value
onAccept
:
{
if
(
enableWimaBoolean
)
{
enableWimaFact
.
value
=
false
}
else
{
enableWimaFact
.
value
=
true
}
}
}
Column
{
id
:
mainColumn
anchors.top
:
enableWima
.
bottom
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.bottom
:
parent
.
bottom
anchors.margins
:
ScreenTools
.
defaultFontPixelHeight
*
0.4
spacing
:
ScreenTools
.
defaultFontPixelHeight
*
0.25
SectionHeader
{
id
:
settingsHeader
text
:
qsTr
(
"
Settings
"
)
}
GridLayout
{
columns
:
2
rowSpacing
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
anchors.topMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.25
visible
:
settingsHeader
.
checked
// Settings
QGCLabel
{
text
:
qsTr
(
"
Next Waypoint
"
)
}
FactTextField
{
fact
:
wimaController
.
startWaypointIndex
Layout.fillWidth
:
true
}
QGCLabel
{
text
:
qsTr
(
"
Max Waypoints
"
)
}
FactTextField
{
fact
:
wimaController
.
maxWaypointsPerPhase
Layout.fillWidth
:
true
}
QGCLabel
{
text
:
qsTr
(
"
Overlap
"
)
}
FactTextField
{
fact
:
wimaController
.
overlapWaypoints
Layout.fillWidth
:
true
}
FactCheckBox
{
text
:
qsTr
(
"
Show All
"
)
fact
:
wimaController
.
showAllMissionItems
}
FactCheckBox
{
text
:
qsTr
(
"
Show Current
"
)
fact
:
wimaController
.
showCurrentMissionItems
}
}
SectionHeader
{
id
:
commandHeader
text
:
qsTr
(
"
Commands
"
)
}
GridLayout
{
columns
:
2
rowSpacing
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
anchors.topMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.25
visible
:
commandHeader
.
checked
// Buttons
QGCButton
{
id
:
buttonPreviousMissionPhase
text
:
qsTr
(
"
Reverse
"
)
onClicked
:
wimaController
.
previousPhase
();
Layout.fillWidth
:
true
}
QGCButton
{
id
:
buttonNextMissionPhase
text
:
qsTr
(
"
Forward
"
)
onClicked
:
wimaController
.
nextPhase
();
Layout.fillWidth
:
true
}
QGCButton
{
id
:
buttonResetPhase
text
:
qsTr
(
"
Reset Phase
"
)
onClicked
:
wimaController
.
resetPhase
();
Layout.fillWidth
:
true
}
QGCButton
{
id
:
buttonUpload
text
:
qsTr
(
"
Upload
"
)
onClicked
:
wimaController
.
uploadToVehicle
();
Layout.fillWidth
:
true
}
QGCButton
{
id
:
buttonRemoveFromVehicle
text
:
qsTr
(
"
Remove
"
)
onClicked
:
wimaController
.
removeFromVehicle
();
Layout.fillWidth
:
true
}
}
}
>>>>>>>
bf3b5ebeb517fcf1caf74f7b1df73c550c4741b8
}
}
src/FlightMap/MapItems/WimaPlanMapItems.qml
View file @
175e7c28
...
...
@@ -31,9 +31,14 @@ Item {
property
var
_missionLineViewComponent
property
var
_currentMissionLineViewComponent
property
bool
_showAllItems
:
wimaController
.
showAllMissionItems
.
value
property
bool
_showCurrentItems
:
wimaController
.
showCurrentMissionItems
.
value
property
bool
_wimaEnabled
:
wimaController
.
enableWimaController
.
value
// Add the mission item visuals to the map
Repeater
{
model
:
largeMapView
?
wimaController
.
missionItems
:
0
Repeater
{
model
:
largeMapView
?
(
_showAllItems
?
(
_wimaEnabled
?
wimaController
.
missionItems
:
0
)
:
0
)
:
0
z
:
QGroundControl
.
zOrderWaypointIndicators
-
2
delegate
:
WimaMissionItemMapVisual
{
map
:
_map
...
...
@@ -45,19 +50,12 @@ Item {
// }
// }
}
/*onItemAdded: {
console.log(wimaController.missionItems.count)
}
onItemRemoved: {
console.log(wimaController.missionItems.count)
}*/
}
// Add the current mission item visuals to the map
Repeater
{
model
:
largeMapView
?
wimaController
.
currentMissionItems
:
0
model
:
largeMapView
?
(
_showCurrentItems
?
(
_wimaEnabled
?
wimaController
.
currentMissionItems
:
0
)
:
0
)
:
0
z
:
QGroundControl
.
zOrderWaypointIndicators
-
1
delegate
:
WimaMissionItemMapVisual
{
map
:
_map
...
...
@@ -88,8 +86,8 @@ Item {
MapPolyline
{
line.width
:
3
line.color
:
mIlineColor
z
:
QGroundControl
.
zOrderWaypointLines
line.color
:
_showAllItems
?
(
_wimaEnabled
?
mIlineColor
:
"
transparent
"
):
"
transparent
"
z
:
QGroundControl
.
zOrderWaypointLines
-
2
path
:
wimaController
.
waypointPath
}
}
...
...
@@ -99,8 +97,8 @@ Item {
MapPolyline
{
line.width
:
3
line.color
:
cMIlineColor
z
:
QGroundControl
.
zOrderWaypointLines
line.color
:
_showCurrentItems
?
(
_wimaEnabled
?
cMIlineColor
:
"
transparent
"
)
:
"
transparent
"
z
:
QGroundControl
.
zOrderWaypointLines
-
1
path
:
wimaController
.
currentWaypointPath
}
}
...
...
src/MissionManager/MissionController.cc
View file @
175e7c28
...
...
@@ -391,24 +391,38 @@ int MissionController::insertSimpleMissionItem(const MissionItem &missionItem, 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
))
{
newItem
->
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
return
-
1
;
// can not add this takeoff command for this vehicle
}
}
if
(
newItem
->
specifiesAltitude
())
{
double
prevAltitude
;
int
prevAltitudeMode
;
if
(
newItem
->
specifiesAltitude
())
{
newItem
->
altitude
()
->
setRawValue
(
missionItem
.
relativeAltitude
());
newItem
->
setAltitudeMode
(
QGroundControlQmlGlobal
::
AltitudeMode
::
AltitudeModeRelative
);
}
newItem
->
setMissionFlightStatus
(
_missionFlightStatus
);
_visualItems
->
insert
(
i
,
newItem
);
if
(
_findPreviousAltitude
(
i
,
&
prevAltitude
,
&
prevAltitudeMode
))
{
newItem
->
altitude
()
->
setRawValue
(
prevAltitude
);
newItem
->
setAltitudeMode
(
static_cast
<
QGroundControlQmlGlobal
::
AltitudeMode
>
(
prevAltitudeMode
));
return
newItem
->
sequenceNumber
();
}
int
MissionController
::
insertSimpleMissionItem
(
SimpleMissionItem
&
missionItem
,
int
i
)
{
int
sequenceNumber
=
_nextSequenceNumber
();
SimpleMissionItem
*
newItem
=
new
SimpleMissionItem
(
missionItem
,
_flyView
,
this
);
newItem
->
setSequenceNumber
(
sequenceNumber
);
_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
))
{
newItem
->
setCommand
(
MAV_CMD_NAV_WAYPOINT
);
return
-
1
;
// can not add this takeoff command for this vehicle
}
}
newItem
->
setMissionFlightStatus
(
_missionFlightStatus
);
//
newItem->setMissionFlightStatus(_missionFlightStatus);
_visualItems
->
insert
(
i
,
newItem
);
return
newItem
->
sequenceNumber
();
...
...
src/MissionManager/MissionController.h
View file @
175e7c28
...
...
@@ -113,6 +113,11 @@ public:
/// @return Sequence number for new item
int
insertSimpleMissionItem
(
const
MissionItem
&
missionItem
,
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
(
SimpleMissionItem
&
missionItem
,
int
i
);
/// Add a new ROI mission item to the list
/// @param i: index to insert at
/// @return Sequence number for new item
...
...
src/MissionManager/SimpleMissionItem.cc
View file @
175e7c28
...
...
@@ -168,7 +168,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, bool flyVie
_editorQml
=
QStringLiteral
(
"qrc:/qml/SimpleItemEditor.qml"
);
_altitudeFact
.
setRawValue
(
other
.
_altitudeFact
.
rawValue
());
_amslAltAboveTerrainFact
.
setRawValue
(
other
.
_amslAltAboveTerrainFact
.
rawValue
());
_amslAltAboveTerrainFact
.
setRawValue
(
other
.
_amslAltAboveTerrainFact
.
rawValue
());
_setupMetaData
();
_connectSignals
();
...
...
@@ -954,7 +954,7 @@ void SimpleMissionItem::applyNewAltitude(double newAltitude)
}
}
void
SimpleMissionItem
::
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
void
SimpleMissionItem
::
setMissionFlightStatus
(
const
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
{
// If user has not already set speed/gimbal, set defaults from previous items.
VisualMissionItem
::
setMissionFlightStatus
(
missionFlightStatus
);
...
...
src/MissionManager/SimpleMissionItem.h
View file @
175e7c28
...
...
@@ -112,7 +112,7 @@ public:
QString
mapVisualQML
(
void
)
const
final
{
return
QStringLiteral
(
"SimpleItemMapVisual.qml"
);
}
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
;
void
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
final
;
void
setMissionFlightStatus
(
const
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
final
;
bool
readyForSave
(
void
)
const
final
;
double
additionalTimeDelay
(
void
)
const
final
;
...
...
src/MissionManager/StructureScanComplexItem.cc
View file @
175e7c28
...
...
@@ -441,7 +441,7 @@ int StructureScanComplexItem::cameraShots(void) const
return
_cameraShots
;
}
void
StructureScanComplexItem
::
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
void
StructureScanComplexItem
::
setMissionFlightStatus
(
const
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
{
ComplexMissionItem
::
setMissionFlightStatus
(
missionFlightStatus
);
if
(
!
qFuzzyCompare
(
_cruiseSpeed
,
missionFlightStatus
.
vehicleSpeed
))
{
...
...
src/MissionManager/StructureScanComplexItem.h
View file @
175e7c28
...
...
@@ -86,7 +86,7 @@ public:
double
specifiedGimbalYaw
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalPitch
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
appendMissionItems
(
QList
<
MissionItem
*>&
items
,
QObject
*
missionItemParent
)
final
;
void
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
final
;
void
setMissionFlightStatus
(
const
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
final
;
void
applyNewAltitude
(
double
newAltitude
)
final
;
double
additionalTimeDelay
(
void
)
const
final
{
return
0
;
}
...
...
src/MissionManager/TransectStyleComplexItem.cc
View file @
175e7c28
...
...
@@ -291,7 +291,7 @@ double TransectStyleComplexItem::greatestDistanceTo(const QGeoCoordinate &other)
return
greatestDistance
;
}
void
TransectStyleComplexItem
::
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
void
TransectStyleComplexItem
::
setMissionFlightStatus
(
const
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
{
ComplexMissionItem
::
setMissionFlightStatus
(
missionFlightStatus
);
if
(
!
qFuzzyCompare
(
_cruiseSpeed
,
missionFlightStatus
.
vehicleSpeed
))
{
...
...
src/MissionManager/TransectStyleComplexItem.h
View file @
175e7c28
...
...
@@ -98,7 +98,7 @@ public:
double
specifiedFlightSpeed
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalYaw
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
double
specifiedGimbalPitch
(
void
)
final
{
return
std
::
numeric_limits
<
double
>::
quiet_NaN
();
}
void
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
final
;
void
setMissionFlightStatus
(
const
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
final
;
bool
readyForSave
(
void
)
const
override
;
QString
commandDescription
(
void
)
const
override
{
return
tr
(
"Transect"
);
}
QString
commandName
(
void
)
const
override
{
return
tr
(
"Transect"
);
}
...
...
src/MissionManager/VisualMissionItem.cc
View file @
175e7c28
...
...
@@ -85,8 +85,14 @@ const VisualMissionItem& VisualMissionItem::operator=(const VisualMissionItem& o
setAltDifference
(
other
.
_altDifference
);
setAltPercent
(
other
.
_altPercent
);
setTerrainPercent
(
other
.
_terrainPercent
);
setTerrainCollision
(
other
.
_terrainCollision
);
setAzimuth
(
other
.
_azimuth
);
setDistance
(
other
.
_distance
);
_missionGimbalYaw
=
other
.
_missionGimbalYaw
;
_missionVehicleYaw
=
other
.
_missionVehicleYaw
;
_setBoundingCube
(
other
.
_boundingCube
);
setMissionFlightStatus
(
other
.
_missionFlightStatus
);
// _childItems // necessary here?
return
*
this
;
}
...
...
@@ -151,7 +157,7 @@ void VisualMissionItem::setAzimuth(double azimuth)
}
}
void
VisualMissionItem
::
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
void
VisualMissionItem
::
setMissionFlightStatus
(
const
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
)
{
_missionFlightStatus
=
missionFlightStatus
;
if
(
qIsNaN
(
_missionFlightStatus
.
gimbalYaw
)
&&
qIsNaN
(
_missionGimbalYaw
))
{
...
...
src/MissionManager/VisualMissionItem.h
View file @
175e7c28
...
...
@@ -128,7 +128,7 @@ public:
/// Update item to mission flight status at point where this item appears in mission.
/// IMPORTANT: Overrides must call base class implementation
virtual
void
setMissionFlightStatus
(
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
);
virtual
void
setMissionFlightStatus
(
const
MissionController
::
MissionFlightStatus_t
&
missionFlightStatus
);
virtual
bool
coordinateHasRelativeAltitude
(
void
)
const
=
0
;
virtual
bool
exitCoordinateHasRelativeAltitude
(
void
)
const
=
0
;
...
...
src/PlanView/CircularSurveyItemEditor.qml
View file @
175e7c28
...
...
@@ -129,20 +129,6 @@ Rectangle {
Layout.fillWidth
:
true
//onUpdated: angleSlider.value = missionItem.deltaAlpha.value
}
/*QGCSlider {
id: angleSlider
minimumValue: 0.3
maximumValue: 10
stepSize: 0.1
tickmarksEnabled: false
Layout.fillWidth: true
Layout.columnSpan: 2
Layout.preferredHeight: ScreenTools.defaultFontPixelHeight * 1.5
Component.onCompleted: value = missionItem.deltaAlpha.value
onValueChanged: missionItem.deltaAlpha.value = value
updateValueWhileDragging: false
}*/
}
ColumnLayout
{
...
...
@@ -151,21 +137,10 @@ Rectangle {
spacing
:
_margin
visible
:
transectsHeader
.
checked
QGCButton
{
text
:
qsTr
(
"
Rotate Entry Point
"
)
onClicked
:
missionItem
.
rotateEntryPoint
();
}
/*
Temporarily removed due to bug https://github.com/mavlink/qgroundcontrol/issues/7005
FactCheckBox
{
text: qsTr("Split concave polygons")
fact: _splitConcave
visible: _splitConcave.visible
property Fact _splitConcave: missionItem.splitConcavePolygons
text
:
qsTr
(
"
Snake Path
"
)
fact
:
missionItem
.
isSnakePath
}
*/
QGCCheckBox
{
id
:
relAlt
...
...
@@ -181,6 +156,28 @@ Rectangle {
onDistanceToSurfaceRelativeChanged
:
relAlt
.
checked
=
missionItem
.
cameraCalc
.
distanceToSurfaceRelative
}
}
QGCButton
{
text
:
qsTr
(
"
Reset Reference
"
)
onClicked
:
missionItem
.
resetReference
();
Layout.fillWidth
:
true
}
QGCButton
{
text
:
qsTr
(
"
Rotate Entry Point
"
)
onClicked
:
missionItem
.
rotateEntryPoint
();
Layout.fillWidth
:
true
}
/*
Temporarily removed due to bug https://github.com/mavlink/qgroundcontrol/issues/7005
FactCheckBox {
text: qsTr("Split concave polygons")
fact: _splitConcave
visible: _splitConcave.visible
property Fact _splitConcave: missionItem.splitConcavePolygons
}
*/
}
SectionHeader
{
...
...
src/QmlControls/QGroundControlQmlGlobal.h
View file @
175e7c28
...
...
@@ -173,10 +173,10 @@ public:
qreal
zOrderTopMost
()
{
return
1000
;
}
qreal
zOrderWidgets
()
{
return
100
;
}
qreal
zOrderMapItems
()
{
return
50
;
}
qreal
zOrderWaypointIndicators
()
{
return
5
0
;
}
qreal
zOrderVehicles
()
{
return
49
;
}
qreal
zOrderTrajectoryLines
()
{
return
48
;
}
qreal
zOrderWaypointLines
()
{
return
47
;
}
qreal
zOrderWaypointIndicators
()
{
return
4
0
;
}
qreal
zOrderVehicles
()
{
return
30
;
}
qreal
zOrderTrajectoryLines
()
{
return
20
;
}
qreal
zOrderWaypointLines
()
{
return
10
;
}
bool
isVersionCheckEnabled
()
{
return
_toolbox
->
mavlinkProtocol
()
->
versionCheckEnabled
();
}
int
mavlinkSystemID
()
{
return
_toolbox
->
mavlinkProtocol
()
->
getSystemId
();
}
...
...
src/Wima/CircularSurvey.SettingsGroup.json
View file @
175e7c28
...
...
@@ -26,5 +26,11 @@
"min"
:
0.3
,
"decimalPlaces"
:
1
,
"defaultValue"
:
5.0
},
{
"name"
:
"IsSnakePath"
,
"shortDescription"
:
"Determines whether the transects are arranged in a snake or a zig-zag manner."
,
"type"
:
"bool"
,
"defaultValue"
:
1
}
]
src/Wima/CircularSurveyComplexItem.cc
View file @
175e7c28
...
...
@@ -7,12 +7,14 @@ const char* CircularSurveyComplexItem::settingsGroup = "CircularSur
const
char
*
CircularSurveyComplexItem
::
deltaRName
=
"DeltaR"
;
const
char
*
CircularSurveyComplexItem
::
deltaAlphaName
=
"DeltaAlpha"
;
const
char
*
CircularSurveyComplexItem
::
transectMinLengthName
=
"TransectMinLength"
;
const
char
*
CircularSurveyComplexItem
::
isSnakePathName
=
"IsSnakePath"
;
const
char
*
CircularSurveyComplexItem
::
jsonComplexItemTypeValue
=
"circularSurvey"
;
const
char
*
CircularSurveyComplexItem
::
jsonDeltaRKey
=
"deltaR"
;
const
char
*
CircularSurveyComplexItem
::
jsonDeltaAlphaKey
=
"deltaAlpha"
;
const
char
*
CircularSurveyComplexItem
::
jsonTransectMinLengthKey
=
"transectMinLength"
;
const
char
*
CircularSurveyComplexItem
::
jsonIsSnakePathKey
=
"isSnakePath"
;
const
char
*
CircularSurveyComplexItem
::
jsonReferencePointLatKey
=
"referencePointLat"
;
const
char
*
CircularSurveyComplexItem
::
jsonReferencePointLongKey
=
"referencePointLong"
;
const
char
*
CircularSurveyComplexItem
::
jsonReferencePointAltKey
=
"referencePointAlt"
;
...
...
@@ -24,23 +26,29 @@ CircularSurveyComplexItem::CircularSurveyComplexItem(Vehicle *vehicle, bool flyV
,
_deltaR
(
settingsGroup
,
_metaDataMap
[
deltaRName
])
,
_deltaAlpha
(
settingsGroup
,
_metaDataMap
[
deltaAlphaName
])
,
_transectMinLength
(
settingsGroup
,
_metaDataMap
[
transectMinLengthName
])
,
_isSnakePath
(
settingsGroup
,
_metaDataMap
[
isSnakePathName
])
,
_autoGenerated
(
false
)
{
_editorQml
=
"qrc:/qml/CircularSurveyItemEditor.qml"
;
connect
(
&
_deltaR
,
&
Fact
::
valueChanged
,
this
,
&
CircularSurveyComplexItem
::
_rebuildTransects
);
connect
(
&
_deltaAlpha
,
&
Fact
::
valueChanged
,
this
,
&
CircularSurveyComplexItem
::
_rebuildTransects
);
connect
(
&
_transectMinLength
,
&
Fact
::
valueChanged
,
this
,
&
CircularSurveyComplexItem
::
_rebuildTransects
);
connect
(
&
_isSnakePath
,
&
Fact
::
valueChanged
,
this
,
&
CircularSurveyComplexItem
::
_rebuildTransects
);
connect
(
this
,
&
CircularSurveyComplexItem
::
refPointChanged
,
this
,
&
CircularSurveyComplexItem
::
_rebuildTransects
);
}
void
CircularSurveyComplexItem
::
resetReference
()
{
setRefPoint
(
_surveyAreaPolygon
.
center
());
}
void
CircularSurveyComplexItem
::
setRefPoint
(
const
QGeoCoordinate
&
refPt
)
{
if
(
refPt
!=
_referencePoint
){
_referencePoint
=
refPt
;
emit
refPointChanged
();
//qDebug() << _referencePoint.toString();
}
}
...
...
@@ -95,12 +103,12 @@ bool CircularSurveyComplexItem::load(const QJsonObject &complexObject, int seque
{
jsonDeltaRKey
,
QJsonValue
::
Double
,
true
},
{
jsonDeltaAlphaKey
,
QJsonValue
::
Double
,
true
},
{
jsonTransectMinLengthKey
,
QJsonValue
::
Double
,
true
},
{
jsonIsSnakePathKey
,
QJsonValue
::
Bool
,
true
},
{
jsonReferencePointLatKey
,
QJsonValue
::
Double
,
true
},
{
jsonReferencePointLongKey
,
QJsonValue
::
Double
,
true
},
{
jsonReferencePointAltKey
,
QJsonValue
::
Double
,
true
},
};
if
(
!
JsonHelper
::
validateKeys
(
complexObject
,
keyInfoList
,
errorString
))
{
return
false
;
}
...
...
@@ -132,6 +140,7 @@ bool CircularSurveyComplexItem::load(const QJsonObject &complexObject, int seque
_referencePoint
.
setLongitude
(
complexObject
[
jsonReferencePointLongKey
].
toDouble
());
_referencePoint
.
setLatitude
(
complexObject
[
jsonReferencePointLatKey
].
toDouble
());
_referencePoint
.
setAltitude
(
complexObject
[
jsonReferencePointAltKey
].
toDouble
());
_isSnakePath
.
setRawValue
(
complexObject
[
jsonIsSnakePathKey
].
toBool
());
_autoGenerated
=
true
;
_ignoreRecalc
=
false
;
...
...
@@ -156,8 +165,9 @@ void CircularSurveyComplexItem::save(QJsonArray &planItems)
saveObject
[
ComplexMissionItem
::
jsonComplexItemTypeKey
]
=
jsonComplexItemTypeValue
;
saveObject
[
jsonDeltaRKey
]
=
_deltaR
.
rawValue
().
toDouble
();
saveObject
[
jsonDeltaAlphaKey
]
=
_deltaAlpha
.
rawValue
().
toDouble
();
saveObject
[
jsonDeltaAlphaKey
]
=
_deltaAlpha
.
rawValue
().
toDouble
();
saveObject
[
jsonTransectMinLengthKey
]
=
_transectMinLength
.
rawValue
().
toDouble
();
saveObject
[
jsonIsSnakePathKey
]
=
_isSnakePath
.
rawValue
().
toBool
();
saveObject
[
jsonReferencePointLongKey
]
=
_referencePoint
.
longitude
();
saveObject
[
jsonReferencePointLatKey
]
=
_referencePoint
.
latitude
();
saveObject
[
jsonReferencePointAltKey
]
=
_referencePoint
.
altitude
();
...
...
@@ -506,7 +516,8 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
return
;
// optimize path to lawn pattern
// optimize path to snake or zig-zag pattern
bool
isSnakePattern
=
_isSnakePath
.
rawValue
().
toBool
();
QList
<
QPointF
>
currentSection
=
fullPath
.
takeFirst
();
if
(
currentSection
.
isEmpty
()
)
return
;
...
...
@@ -535,7 +546,7 @@ void CircularSurveyComplexItem::_rebuildTransectsPhase1()
}
}
currentSection
=
fullPath
.
takeAt
(
index
);
if
(
reversePath
)
{
if
(
reversePath
&&
isSnakePattern
)
{
PolygonCalculus
::
reversePath
(
currentSection
);
}
}
...
...
@@ -578,6 +589,11 @@ Fact *CircularSurveyComplexItem::transectMinLength()
return
&
_transectMinLength
;
}
Fact
*
CircularSurveyComplexItem
::
isSnakePath
()
{
return
&
_isSnakePath
;
}
...
...
src/Wima/CircularSurveyComplexItem.h
View file @
175e7c28
...
...
@@ -18,11 +18,14 @@ public:
/// @param kmlOrShpFile Polygon comes from this file, empty for default polygon
CircularSurveyComplexItem
(
Vehicle
*
vehicle
,
bool
flyView
,
const
QString
&
kmlOrShpFile
,
QObject
*
parent
);
Q_PROPERTY
(
QGeoCoordinate
refPoint
READ
refPoint
WRITE
setRefPoint
NOTIFY
refPointChanged
)
Q_PROPERTY
(
Fact
*
deltaR
READ
deltaR
CONSTANT
)
Q_PROPERTY
(
Fact
*
deltaAlpha
READ
deltaAlpha
CONSTANT
)
Q_PROPERTY
(
Fact
*
transectMinLength
READ
transectMinLength
CONSTANT
)
Q_PROPERTY
(
bool
autoGenerated
READ
autoGenerated
NOTIFY
autoGeneratedChanged
)
Q_PROPERTY
(
QGeoCoordinate
refPoint
READ
refPoint
WRITE
setRefPoint
NOTIFY
refPointChanged
)
Q_PROPERTY
(
Fact
*
deltaR
READ
deltaR
CONSTANT
)
Q_PROPERTY
(
Fact
*
deltaAlpha
READ
deltaAlpha
CONSTANT
)
Q_PROPERTY
(
Fact
*
transectMinLength
READ
transectMinLength
CONSTANT
)
Q_PROPERTY
(
Fact
*
isSnakePath
READ
isSnakePath
CONSTANT
)
Q_PROPERTY
(
bool
autoGenerated
READ
autoGenerated
NOTIFY
autoGeneratedChanged
)
Q_INVOKABLE
void
resetReference
(
void
);
// Property setters
void
setRefPoint
(
const
QGeoCoordinate
&
refPt
);
...
...
@@ -32,8 +35,9 @@ public:
// Property getters
QGeoCoordinate
refPoint
()
const
;
Fact
*
deltaR
();
Fact
*
deltaAlpha
();
Fact
*
deltaAlpha
();
Fact
*
transectMinLength
();
Fact
*
isSnakePath
();
// Is true if survey was automatically generated, prevents initialisation from gui.
bool
autoGenerated
();
...
...
@@ -59,11 +63,13 @@ public:
static
const
char
*
deltaRName
;
static
const
char
*
deltaAlphaName
;
static
const
char
*
transectMinLengthName
;
static
const
char
*
isSnakePathName
;
static
const
char
*
jsonComplexItemTypeValue
;
static
const
char
*
jsonDeltaRKey
;
static
const
char
*
jsonDeltaAlphaKey
;
static
const
char
*
jsonTransectMinLengthKey
;
static
const
char
*
jsonTransectMinLengthKey
;
static
const
char
*
jsonIsSnakePathKey
;
static
const
char
*
jsonReferencePointLongKey
;
static
const
char
*
jsonReferencePointLatKey
;
static
const
char
*
jsonReferencePointAltKey
;
...
...
@@ -90,9 +96,10 @@ private:
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
SettingsFact
_deltaR
;
SettingsFact
_deltaAlpha
;
SettingsFact
_transectMinLength
;
SettingsFact
_deltaR
;
// distance between two neighbour circles
SettingsFact
_deltaAlpha
;
// angle discretisation of the circles
SettingsFact
_transectMinLength
;
// minimal transect lenght, transects are rejected if they are shorter than this value
SettingsFact
_isSnakePath
;
// bool value, determining if transects are connected in a snake like or zig zag like manner
QTimer
_updateTimer
;
...
...
src/Wima/WimaController.SettingsGroup.json
0 → 100644
View file @
175e7c28
[
{
"name"
:
"EnableWimaController"
,
"shortDescription"
:
"Enables or disables the WimaController, which performes different tasks inside the flight view window."
,
"type"
:
"bool"
,
"defaultValue"
:
1
},
{
"name"
:
"OverlapWaypoints"
,
"shortDescription"
:
"Determines the number of overlapping waypoints between two consecutive mission phases."
,
"type"
:
"uint32"
,
"defaultValue"
:
2
},
{
"name"
:
"MaxWaypointsPerPhase"
,
"shortDescription"
:
"Determines the maximum number of waypoints per phase."
,
"type"
:
"uint32"
,
"defaultValue"
:
30
},
{
"name"
:
"StartWaypointIndex"
,
"shortDescription"
:
"The index of the start waypoint for the next mission phase."
,
"type"
:
"uint32"
,
"defaultValue"
:
1
},
{
"name"
:
"ShowAllMissionItems"
,
"shortDescription"
:
"Determines whether the mission items of the overall mission are displayed or not."
,
"type"
:
"bool"
,
"defaultValue"
:
1
},
{
"name"
:
"ShowCurrentMissionItems"
,
"shortDescription"
:
"Determines whether the mission items of the current mission phase are displayed or not."
,
"type"
:
"bool"
,
"defaultValue"
:
1
}
]
src/Wima/WimaController.cc
View file @
175e7c28
This diff is collapsed.
Click to expand it.
src/Wima/WimaController.h
View file @
175e7c28
...
...
@@ -20,6 +20,7 @@
#include "MissionSettingsItem.h"
#include "JsonHelper.h"
#include "QGCApplication.h"
#include "SettingsFact.h"
class
WimaController
:
public
QObject
...
...
@@ -32,18 +33,25 @@ public:
WimaController
(
QObject
*
parent
=
nullptr
);
Q_PROPERTY
(
PlanMasterController
*
masterController
READ
masterController
WRITE
setMasterController
NOTIFY
masterControllerChanged
)
Q_PROPERTY
(
MissionController
*
missionController
READ
missionController
WRITE
setMissionController
NOTIFY
missionControllerChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
visualItems
READ
visualItems
NOTIFY
visualItemsChanged
)
Q_PROPERTY
(
QString
currentFile
READ
currentFile
NOTIFY
currentFileChanged
)
Q_PROPERTY
(
QStringList
loadNameFilters
READ
loadNameFilters
CONSTANT
)
Q_PROPERTY
(
QStringList
saveNameFilters
READ
saveNameFilters
CONSTANT
)
Q_PROPERTY
(
QString
fileExtension
READ
fileExtension
CONSTANT
)
Q_PROPERTY
(
WimaDataContainer
*
dataContainer
READ
dataContainer
WRITE
setDataContainer
NOTIFY
dataContainerChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
missionItems
READ
missionItems
NOTIFY
missionItemsChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
currentMissionItems
READ
currentMissionItems
NOTIFY
currentMissionItemsChanged
)
Q_PROPERTY
(
QVariantList
waypointPath
READ
waypointPath
NOTIFY
waypointPathChanged
)
Q_PROPERTY
(
QVariantList
currentWaypointPath
READ
currentWaypointPath
NOTIFY
currentWaypointPathChanged
)
Q_PROPERTY
(
PlanMasterController
*
masterController
READ
masterController
WRITE
setMasterController
NOTIFY
masterControllerChanged
)
Q_PROPERTY
(
MissionController
*
missionController
READ
missionController
WRITE
setMissionController
NOTIFY
missionControllerChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
visualItems
READ
visualItems
NOTIFY
visualItemsChanged
)
Q_PROPERTY
(
QString
currentFile
READ
currentFile
NOTIFY
currentFileChanged
)
Q_PROPERTY
(
QStringList
loadNameFilters
READ
loadNameFilters
CONSTANT
)
Q_PROPERTY
(
QStringList
saveNameFilters
READ
saveNameFilters
CONSTANT
)
Q_PROPERTY
(
QString
fileExtension
READ
fileExtension
CONSTANT
)
Q_PROPERTY
(
WimaDataContainer
*
dataContainer
READ
dataContainer
WRITE
setDataContainer
NOTIFY
dataContainerChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
missionItems
READ
missionItems
NOTIFY
missionItemsChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
currentMissionItems
READ
currentMissionItems
NOTIFY
currentMissionItemsChanged
)
Q_PROPERTY
(
QVariantList
waypointPath
READ
waypointPath
NOTIFY
waypointPathChanged
)
Q_PROPERTY
(
QVariantList
currentWaypointPath
READ
currentWaypointPath
NOTIFY
currentWaypointPathChanged
)
Q_PROPERTY
(
Fact
*
enableWimaController
READ
enableWimaController
CONSTANT
)
Q_PROPERTY
(
Fact
*
overlapWaypoints
READ
overlapWaypoints
CONSTANT
)
Q_PROPERTY
(
Fact
*
maxWaypointsPerPhase
READ
maxWaypointsPerPhase
CONSTANT
)
Q_PROPERTY
(
Fact
*
startWaypointIndex
READ
startWaypointIndex
CONSTANT
)
Q_PROPERTY
(
Fact
*
showAllMissionItems
READ
showAllMissionItems
CONSTANT
)
Q_PROPERTY
(
Fact
*
showCurrentMissionItems
READ
showCurrentMissionItems
CONSTANT
)
// Property accessors
...
...
@@ -60,6 +68,12 @@ public:
QmlObjectListModel
*
currentMissionItems
(
void
);
QVariantList
waypointPath
(
void
);
QVariantList
currentWaypointPath
(
void
);
Fact
*
enableWimaController
(
void
);
Fact
*
overlapWaypoints
(
void
);
Fact
*
maxWaypointsPerPhase
(
void
);
Fact
*
startWaypointIndex
(
void
);
Fact
*
showAllMissionItems
(
void
);
Fact
*
showCurrentMissionItems
(
void
);
// Property setters
...
...
@@ -69,6 +83,10 @@ public:
// Member Methodes
Q_INVOKABLE
void
nextPhase
();
Q_INVOKABLE
void
previousPhase
();
Q_INVOKABLE
void
resetPhase
();
Q_INVOKABLE
void
uploadToVehicle
();
Q_INVOKABLE
void
removeFromVehicle
();
Q_INVOKABLE
void
startMission
();
Q_INVOKABLE
void
abortMission
();
Q_INVOKABLE
void
pauseMission
();
...
...
@@ -83,7 +101,15 @@ public:
// static Members
static
const
char
*
wimaFileExtension
;
static
const
char
*
areaItemsName
;
static
const
char
*
missionItemsName
;
static
const
char
*
missionItemsName
;
static
const
char
*
settingsGroup
;
static
const
char
*
endWaypointIndexName
;
static
const
char
*
enableWimaControllerName
;
static
const
char
*
overlapWaypointsName
;
static
const
char
*
maxWaypointsPerPhaseName
;
static
const
char
*
startWaypointIndexName
;
static
const
char
*
showAllMissionItemsName
;
static
const
char
*
showCurrentMissionItemsName
;
// Member Methodes
QJsonDocument
saveToJson
(
FileType
fileType
);
...
...
@@ -111,10 +137,12 @@ signals:
void
currentWaypointPathChanged
(
void
);
private
slots
:
void
containerDataValidChanged
(
bool
valid
);
void
updateCurrentMissionItems
(
void
);
void
fetchContainerData
(
bool
valid
);
void
calcNextPhase
(
void
);
void
updateWaypointPath
(
void
);
void
updateCurrentPath
(
void
);
void
updateNextWaypoint
(
void
);
void
recalcCurrentPhase
(
void
);
private:
...
...
@@ -133,7 +161,22 @@ private:
// _currentMissionItems contains a number of mission items which can be worked off with a single battery chrage
QVariantList
_waypointPath
;
// path connecting the items in _missionItems
QVariantList
_currentWaypointPath
;
// path connecting the items in _currentMissionItems
int
_startWaypointIndex
;
// index to the mission item stored in _missionItems defining the first element of _currentMissionItems
int
_endWaypointIndex
;
// index to the mission item stored in _missionItems defining the last element of _currentMissionItems
}
;
QList
<
int
>
_startWaypointIndexList
;
// list containing the last start waypoint indices, used by previosPhase
QGeoCoordinate
_takeoffLandPostion
;
QMap
<
QString
,
FactMetaData
*>
_metaDataMap
;
SettingsFact
_enableWimaController
;
// enables or disables the wimaControler
SettingsFact
_overlapWaypoints
;
// determines the number of overlapping waypoints between two consecutive mission phases
SettingsFact
_maxWaypointsPerPhase
;
// determines the maximum number waypoints per phase
SettingsFact
_nestPhaseStartWaypointIndex
;
// index (displayed on the map, -1 to get index of item in _missionItems) of the mission item
// defining the first element of the next phase
SettingsFact
_showAllMissionItems
;
// bool value, Determines whether the mission items of the overall mission are displayed or not.
SettingsFact
_showCurrentMissionItems
;
// bool value, Determines whether the mission items of the current mission phase are displayed or not.
int
_endWaypointIndex
;
// indes of the mission item stored in _missionItems defining the last element
// (which is not part of the return path) of _currentMissionItem
int
_startWaypointIndex
;
// indes of the mission item stored in _missionItems defining the first element
// (which is not part of the arrival path) of _currentMissionItem
};
src/Wima/WimaPlaner.cc
View file @
175e7c28
...
...
@@ -100,6 +100,7 @@ void WimaPlaner::removeArea(int index)
if
(
_visualItems
.
count
()
==
0
)
{
// this branch is reached if all items are removed
// to guarentee proper behavior, _currentAreaIndex must be set to a invalid value, as on constructor init.
resetAllInteractive
();
_currentAreaIndex
=
-
1
;
return
;
}
...
...
@@ -323,11 +324,7 @@ bool WimaPlaner::updateMission()
qgcApp
()
->
showMessage
(
QString
(
tr
(
"Not able to calculate the path from measurement area to landing position."
)).
toLocal8Bit
().
data
());
return
false
;
}
// path.clear();
// path.append(end);
// path.append(start);
// path.append(end);
// path.append(end);
for
(
int
i
=
1
;
i
<
path
.
count
()
-
1
;
i
++
)
{
sequenceNumber
=
_missionController
->
insertSimpleMissionItem
(
path
.
value
(
i
),
missionItems
->
count
());
_missionController
->
setCurrentPlanViewIndex
(
sequenceNumber
,
true
);
...
...
src/WimaView/SphericalSurveyMapVisual.qml
View file @
175e7c28
...
...
@@ -86,7 +86,7 @@ Item {
}
function
_setRefPoint
()
{
_missionItem
.
re
fPoint
=
map
.
toCoordinate
(
map
.
centerViewport
.
x
,
map
.
centerViewport
.
y
,
false
/* clipToViewPort */
)
_missionItem
.
re
setReference
();
}
Component.onCompleted
:
{
...
...
@@ -172,11 +172,19 @@ Item {
DragCoordinate
{
map
:
_root
.
map
qgcView
:
_root
.
qgcView
z
:
QGroundControl
.
zOrderMapItems
z
:
QGroundControl
.
zOrderMapItems
checked
:
_missionItem
.
isCurrentItem
coordinate
:
_missionItem
.
refPoint
onCoordinateChanged
:
_missionItem
.
refPoint
=
coordinate
property
var
refPoint
:
_missionItem
.
refPoint
onCoordinateChanged
:
_missionItem
.
refPoint
=
coordinate
onRefPointChanged
:
{
if
(
refPoint
!==
coordinate
)
{
coordinate
=
refPoint
}
}
onClicked
:
_root
.
clicked
(
_missionItem
.
sequenceNumber
)
}
}
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment