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
a6776c0a
Commit
a6776c0a
authored
Oct 19, 2019
by
Valentin Platzgummer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
flight view edited
parent
175e7c28
Changes
14
Hide whitespace changes
Inline
Side-by-side
Showing
14 changed files
with
3648 additions
and
333 deletions
+3648
-333
airstrip.wima
Paths/airstrip.wima
+3392
-0
FlightDisplayView.qml
src/FlightDisplay/FlightDisplayView.qml
+0
-21
FlightDisplayWimaMenu.qml
src/FlightDisplay/FlightDisplayWimaMenu.qml
+3
-12
MissionController.cc
src/MissionManager/MissionController.cc
+25
-0
MissionController.h
src/MissionManager/MissionController.h
+6
-0
WimaAreaData.cc
src/Wima/WimaAreaData.cc
+17
-1
WimaAreaData.h
src/Wima/WimaAreaData.h
+8
-4
WimaController.SettingsGroup.json
src/Wima/WimaController.SettingsGroup.json
+4
-2
WimaController.cc
src/Wima/WimaController.cc
+171
-183
WimaController.h
src/Wima/WimaController.h
+6
-10
WimaDataContainer.cc
src/Wima/WimaDataContainer.cc
+2
-38
WimaDataContainer.h
src/Wima/WimaDataContainer.h
+1
-3
WimaPlaner.cc
src/Wima/WimaPlaner.cc
+11
-54
WimaPlaner.h
src/Wima/WimaPlaner.h
+2
-5
No files found.
Paths/airstrip.wima
0 → 100644
View file @
a6776c0a
This source diff could not be displayed because it is too large. You can
view the blob
instead.
src/FlightDisplay/FlightDisplayView.qml
View file @
a6776c0a
...
...
@@ -528,26 +528,6 @@ 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
anchors.top
:
singleMultiSelector
.
bottom
qgcView
:
root
useLightColors
:
isBackgroundDark
missionController
:
_missionController
visible
:
singleVehicleView
.
checked
&&
!
QGroundControl
.
videoManager
.
fullScreen
}
FlightDisplayWimaMenu
{
id
:
wimaMenu
z
:
1000
//_panel.z + 4
anchors.right
:
altitudeSlider
.
visible
?
altitudeSlider
.
left
:
parent
.
right
anchors.top
:
flightDisplayViewWidgets
.
bottom
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
...
...
@@ -568,7 +548,6 @@ QGCView {
wimaController
:
wimaController
>>>>>>>
bf3b5ebeb517fcf1caf74f7b1df73c550c4741b8
}
//-------------------------------------------------------------------------
...
...
src/FlightDisplay/FlightDisplayWimaMenu.qml
View file @
a6776c0a
...
...
@@ -19,15 +19,9 @@ import QGroundControl.FactControls 1.0
Item
{
id
:
_root
height
:
400
width
:
250
<<<<<<<
HEAD
Text
{
id
:
enableWima
text
:
qsTr
(
"
WiMA
"
)
font.pointSize
:
40
=======
height
:
500
width
:
300
property
var
wimaController
// must be provided by the user
// box containing all items
...
...
@@ -161,8 +155,5 @@ Item {
}
}
}
>>>>>>>
bf3b5ebeb517fcf1caf74f7b1df73c550c4741b8
}
}
src/MissionManager/MissionController.cc
View file @
a6776c0a
...
...
@@ -1053,6 +1053,31 @@ bool MissionController::readyForSaveSend(void) const
return
true
;
}
bool
MissionController
::
setTakeoffCommand
(
SimpleMissionItem
&
missionItem
,
Vehicle
&
vehicle
)
{
if
(
vehicle
.
fixedWing
()
||
vehicle
.
vtol
()
||
vehicle
.
multiRotor
())
{
MAV_CMD
takeoffCmd
=
_controllerVehicle
->
vtol
()
?
MAV_CMD_NAV_VTOL_TAKEOFF
:
MAV_CMD_NAV_TAKEOFF
;
if
(
_controllerVehicle
->
firmwarePlugin
()
->
supportedMissionCommands
().
contains
(
takeoffCmd
))
{
missionItem
.
setCommand
(
takeoffCmd
);
}
}
else
return
false
;
return
true
;
}
bool
MissionController
::
setLandCommand
(
SimpleMissionItem
&
missionItem
,
Vehicle
&
vehicle
)
{
MAV_CMD
landCmd
=
vehicle
.
vtol
()
?
MAV_CMD_NAV_VTOL_LAND
:
MAV_CMD_NAV_LAND
;
if
(
vehicle
.
firmwarePlugin
()
->
supportedMissionCommands
().
contains
(
landCmd
))
{
missionItem
.
setCommand
(
landCmd
);
}
else
return
false
;
return
true
;
}
void
MissionController
::
save
(
QJsonObject
&
json
)
{
json
[
JsonHelper
::
jsonVersionKey
]
=
_missionFileVersion
;
...
...
src/MissionManager/MissionController.h
View file @
a6776c0a
...
...
@@ -150,12 +150,18 @@ public:
/// would return false is when it is still waiting on terrain data to determine correct altitudes.
bool
readyForSaveSend
(
void
)
const
;
/// sets the command in missionItem to a land command
bool
setLandCommand
(
SimpleMissionItem
&
missionItem
,
Vehicle
&
vehicle
);
/// sets the command in missionItem to a takeoff command
bool
setTakeoffCommand
(
SimpleMissionItem
&
missionItem
,
Vehicle
&
vehicle
);
/// Sends the mission items to the specified vehicle
static
void
sendItemsToVehicle
(
Vehicle
*
vehicle
,
QmlObjectListModel
*
visualMissionItems
);
static
bool
convertToMissionItems
(
QmlObjectListModel
*
visualMissionItems
,
QList
<
MissionItem
*>&
rgMissionItems
,
QObject
*
missionItemParent
);
bool
loadJsonFile
(
QFile
&
file
,
QString
&
errorString
);
bool
loadTextFile
(
QFile
&
file
,
QString
&
errorString
);
...
...
src/Wima/WimaAreaData.cc
View file @
a6776c0a
...
...
@@ -26,6 +26,11 @@ QVariantList WimaAreaData::path() const
return
_path
;
}
QGeoCoordinate
WimaAreaData
::
center
()
const
{
return
_center
;
}
QList
<
QGeoCoordinate
>
WimaAreaData
::
coordinateList
()
const
{
QList
<
QGeoCoordinate
>
coordinateList
;
...
...
@@ -57,6 +62,15 @@ void WimaAreaData::setPath(const QVariantList &coordinateList)
_path
.
append
(
coordinateList
);
}
void
WimaAreaData
::
setCenter
(
const
QGeoCoordinate
&
center
)
{
if
(
_center
!=
center
)
{
_center
=
center
;
emit
centerChanged
();
}
}
/*!
* \fn void WimaAreaData::assign(const WimaAreaData &other)
*
...
...
@@ -66,12 +80,14 @@ void WimaAreaData::assign(const WimaAreaData &other)
{
setMaxAltitude
(
other
.
maxAltitude
());
setPath
(
other
.
path
());
setCenter
(
other
.
center
());
}
void
WimaAreaData
::
assign
(
const
WimaArea
&
other
)
{
setMaxAltitude
(
other
.
maxAltitude
());
setPath
(
other
.
path
());
setPath
(
other
.
path
());
setCenter
(
other
.
center
());
}
...
...
src/Wima/WimaAreaData.h
View file @
a6776c0a
...
...
@@ -19,9 +19,10 @@ public:
//WimaAreaData(const WimaArea &other, QObject *parent = nullptr);
WimaAreaData
&
operator
=
(
const
WimaAreaData
&
otherData
)
=
delete
;
// avoid slicing
double
maxAltitude
()
const
;
QVariantList
path
()
const
;
QList
<
QGeoCoordinate
>
coordinateList
()
const
;
double
maxAltitude
()
const
;
QVariantList
path
()
const
;
QGeoCoordinate
center
()
const
;
QList
<
QGeoCoordinate
>
coordinateList
()
const
;
virtual
QString
type
()
const
=
0
;
...
...
@@ -29,11 +30,13 @@ public:
signals:
void
maxAltitudeChanged
(
double
maxAltitude
);
void
pathChanged
(
const
QVariantList
&
coordinateList
);
void
centerChanged
(
void
);
public
slots
:
void
setMaxAltitude
(
double
maxAltitude
);
void
setPath
(
const
QList
<
QGeoCoordinate
>
&
coordinateList
);
void
setPath
(
const
QVariantList
&
coordinateList
);
void
setPath
(
const
QVariantList
&
coordinateList
);
void
setCenter
(
const
QGeoCoordinate
&
center
);
protected:
void
assign
(
const
WimaAreaData
&
other
);
...
...
@@ -46,5 +49,6 @@ private:
// see WimaArea.h for explanation
double
_maxAltitude
;
QVariantList
_path
;
QGeoCoordinate
_center
;
};
src/Wima/WimaController.SettingsGroup.json
View file @
a6776c0a
...
...
@@ -13,14 +13,16 @@
},
{
"name"
:
"MaxWaypointsPerPhase"
,
"shortDescription"
:
"Determines the maximum number of waypoints per phase."
,
"shortDescription"
:
"Determines the maximum number of waypoints per phase.
This number does not include the arrival and return path.
"
,
"type"
:
"uint32"
,
"min"
:
1
,
"defaultValue"
:
30
},
{
"name"
:
"StartWaypointIndex"
,
"shortDescription"
:
"The index of the start waypoint for the next mission phase."
,
"type"
:
"uint32"
,
"type"
:
"uint32"
,
"min"
:
1
,
"defaultValue"
:
1
},
{
...
...
src/Wima/WimaController.cc
View file @
a6776c0a
...
...
@@ -23,16 +23,17 @@ WimaController::WimaController(QObject *parent)
,
_enableWimaController
(
settingsGroup
,
_metaDataMap
[
enableWimaControllerName
])
,
_overlapWaypoints
(
settingsGroup
,
_metaDataMap
[
overlapWaypointsName
])
,
_maxWaypointsPerPhase
(
settingsGroup
,
_metaDataMap
[
maxWaypointsPerPhaseName
])
,
_ne
s
tPhaseStartWaypointIndex
(
settingsGroup
,
_metaDataMap
[
startWaypointIndexName
])
,
_ne
x
tPhaseStartWaypointIndex
(
settingsGroup
,
_metaDataMap
[
startWaypointIndexName
])
,
_showAllMissionItems
(
settingsGroup
,
_metaDataMap
[
showAllMissionItemsName
])
,
_showCurrentMissionItems
(
settingsGroup
,
_metaDataMap
[
showCurrentMissionItemsName
])
,
_lastMissionPhaseReached
(
false
)
{
_ne
s
tPhaseStartWaypointIndex
.
setRawValue
(
int
(
1
));
_ne
x
tPhaseStartWaypointIndex
.
setRawValue
(
int
(
1
));
_showAllMissionItems
.
setRawValue
(
true
);
_showCurrentMissionItems
.
setRawValue
(
true
);
connect
(
&
_overlapWaypoints
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
updateNextWaypoint
);
connect
(
&
_maxWaypointsPerPhase
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
recalcCurrentPhase
);
connect
(
&
_ne
s
tPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
connect
(
&
_ne
x
tPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
}
QmlObjectListModel
*
WimaController
::
visualItems
()
...
...
@@ -109,7 +110,7 @@ Fact *WimaController::showCurrentMissionItems()
Fact
*
WimaController
::
startWaypointIndex
()
{
return
&
_ne
s
tPhaseStartWaypointIndex
;
return
&
_ne
x
tPhaseStartWaypointIndex
;
}
void
WimaController
::
setMasterController
(
PlanMasterController
*
masterC
)
...
...
@@ -134,11 +135,11 @@ void WimaController::setDataContainer(WimaDataContainer *container)
{
if
(
container
!=
nullptr
)
{
if
(
_container
!=
nullptr
)
{
disconnect
(
_container
,
&
WimaDataContainer
::
dataValidChanged
,
this
,
&
WimaController
::
fetchContainerData
);
disconnect
(
_container
,
&
WimaDataContainer
::
newDataAvailable
,
this
,
&
WimaController
::
fetchContainerData
);
}
_container
=
container
;
connect
(
_container
,
&
WimaDataContainer
::
dataValidChanged
,
this
,
&
WimaController
::
fetchContainerData
);
connect
(
_container
,
&
WimaDataContainer
::
newDataAvailable
,
this
,
&
WimaController
::
fetchContainerData
);
emit
dataContainerChanged
();
}
...
...
@@ -151,8 +152,9 @@ void WimaController::nextPhase()
void
WimaController
::
previousPhase
()
{
if
(
_nestPhaseStartWaypointIndex
.
rawValue
().
toInt
()
>
0
)
{
_nestPhaseStartWaypointIndex
.
setRawValue
(
1
+
std
::
max
(
_startWaypointIndex
if
(
_nextPhaseStartWaypointIndex
.
rawValue
().
toInt
()
>
0
)
{
_lastMissionPhaseReached
=
false
;
_nextPhaseStartWaypointIndex
.
setRawValue
(
1
+
std
::
max
(
_startWaypointIndex
-
_maxWaypointsPerPhase
.
rawValue
().
toInt
()
+
_overlapWaypoints
.
rawValue
().
toInt
(),
0
));
}
...
...
@@ -160,13 +162,14 @@ void WimaController::previousPhase()
void
WimaController
::
resetPhase
()
{
_nestPhaseStartWaypointIndex
.
setRawValue
(
int
(
1
));
_lastMissionPhaseReached
=
false
;
_nextPhaseStartWaypointIndex
.
setRawValue
(
int
(
1
));
}
void
WimaController
::
uploadToVehicle
()
bool
WimaController
::
uploadToVehicle
()
{
if
(
_currentMissionItems
.
count
()
<
1
)
return
;
return
false
;
_missionController
->
removeAll
();
// set homeposition of settingsItem
...
...
@@ -174,7 +177,7 @@ void WimaController::uploadToVehicle()
MissionSettingsItem
*
settingsItem
=
visuals
->
value
<
MissionSettingsItem
*>
(
0
);
if
(
settingsItem
==
nullptr
)
{
qWarning
(
"WimaController::updateCurrentMissionItems(): nullptr"
);
return
;
return
false
;
}
settingsItem
->
setCoordinate
(
_takeoffLandPostion
);
...
...
@@ -216,6 +219,8 @@ void WimaController::uploadToVehicle()
qWarning
(
" "
);
}
_masterController
->
sendToVehicle
();
return
true
;
}
void
WimaController
::
removeFromVehicle
()
...
...
@@ -223,28 +228,9 @@ void WimaController::removeFromVehicle()
_masterController
->
removeAllFromVehicle
();
}
void
WimaController
::
startMission
()
{
}
void
WimaController
::
abortMission
()
{
}
void
WimaController
::
pauseMission
()
{
}
void
WimaController
::
resumeMission
()
{
}
void
WimaController
::
saveToCurrent
()
{
}
void
WimaController
::
saveToFile
(
const
QString
&
filename
)
...
...
@@ -349,175 +335,173 @@ bool WimaController::extractCoordinateList(QmlObjectListModel &missionItems, QVa
*
* \sa WimaDataContainer, WimaPlaner, WimaPlanData
*/
void
WimaController
::
fetchContainerData
(
bool
valid
)
bool
WimaController
::
fetchContainerData
(
)
{
if
(
valid
)
{
if
(
_container
==
nullptr
)
{
qWarning
(
"WimaController::containerDataValidChanged(): No container assigned!"
);
}
_localPlanDataValid
=
false
;
_visualItems
.
clear
();
_missionItems
.
clear
();
WimaPlanData
planData
=
_container
->
pull
();
// fetch only if valid, return true on sucess
// extract list with WimaAreas
QList
<
const
WimaAreaData
*>
areaList
=
planData
.
areaList
();
// reset visual items
_visualItems
.
clear
();
_missionItems
.
clear
();
_currentMissionItems
.
clear
();
_waypointPath
.
clear
();
_currentWaypointPath
.
clear
();
int
areaCounter
=
0
;
int
numAreas
=
4
;
// extract only numAreas Areas, if there are more they are invalid and ignored
for
(
int
i
=
0
;
i
<
areaList
.
size
();
i
++
)
{
const
WimaAreaData
*
areaData
=
areaList
[
i
]
;
emit
visualItemsChanged
()
;
emit
missionItemsChanged
();
emit
currentMissionItemsChanged
();
emit
currentWaypointPathChanged
()
;
if
(
areaData
->
type
()
==
WimaServiceAreaData
::
typeString
)
{
// is it a service area?
_serviceArea
=
*
qobject_cast
<
const
WimaServiceAreaData
*>
(
areaData
);
areaCounter
++
;
_visualItems
.
append
(
&
_serviceArea
);
_localPlanDataValid
=
false
;
_lastMissionPhaseReached
=
false
;
continue
;
}
if
(
_container
==
nullptr
)
{
qWarning
(
"WimaController::fetchContainerData(): No container assigned!"
);
return
false
;
}
if
(
areaData
->
type
()
==
WimaMeasurementAreaData
::
typeString
)
{
// is it a measurement area?
_measurementArea
=
*
qobject_cast
<
const
WimaMeasurementAreaData
*>
(
areaData
);
areaCounter
++
;
_visualItems
.
append
(
&
_measurementArea
);
WimaPlanData
planData
=
_container
->
pull
();
continue
;
}
// extract list with WimaAreas
QList
<
const
WimaAreaData
*>
areaList
=
planData
.
areaList
();
if
(
areaData
->
type
()
==
WimaCorridorData
::
typeString
)
{
// is it a corridor?
_corridor
=
*
qobject_cast
<
const
WimaCorridorData
*>
(
areaData
);
areaCounter
++
;
//_visualItems.append(&_corridor); // not needed
int
areaCounter
=
0
;
int
numAreas
=
4
;
// extract only numAreas Areas, if there are more they are invalid and ignored
for
(
int
i
=
0
;
i
<
areaList
.
size
();
i
++
)
{
const
WimaAreaData
*
areaData
=
areaList
[
i
];
continue
;
}
if
(
areaData
->
type
()
==
WimaServiceAreaData
::
typeString
)
{
// is it a service area?
_serviceArea
=
*
qobject_cast
<
const
WimaServiceAreaData
*>
(
areaData
);
areaCounter
++
;
_visualItems
.
append
(
&
_serviceArea
);
if
(
areaData
->
type
()
==
WimaJoinedAreaData
::
typeString
)
{
// is it a corridor?
_joinedArea
=
*
qobject_cast
<
const
WimaJoinedAreaData
*>
(
areaData
);
areaCounter
++
;
_visualItems
.
append
(
&
_joinedArea
);
continue
;
}
continue
;
}
if
(
areaData
->
type
()
==
WimaMeasurementAreaData
::
typeString
)
{
// is it a measurement area?
_measurementArea
=
*
qobject_cast
<
const
WimaMeasurementAreaData
*>
(
areaData
);
areaCounter
++
;
_visualItems
.
append
(
&
_measurementArea
);
if
(
areaCounter
>=
numAreas
)
break
;
continue
;
}
QList
<
const
MissionItem
*>
tempMissionItems
=
planData
.
missionItems
();
// create mission items
_missionController
->
removeAll
();
QmlObjectListModel
*
missionControllerVisualItems
=
_missionController
->
visualItems
();
if
(
areaData
->
type
()
==
WimaCorridorData
::
typeString
)
{
// is it a corridor?
_corridor
=
*
qobject_cast
<
const
WimaCorridorData
*>
(
areaData
);
areaCounter
++
;
//_visualItems.append(&_corridor); // not needed
continue
;
}
// find takeoff command
int
begin
=
-
1
;
for
(
int
i
=
0
;
i
<
tempMissionItems
.
size
();
i
++
)
{
const
MissionItem
*
missionItem
=
tempMissionItems
[
i
];
if
(
missionItem
->
command
()
==
MAV_CMD_NAV_VTOL_TAKEOFF
||
missionItem
->
command
()
==
MAV_CMD_NAV_TAKEOFF
)
{
if
(
areaData
->
type
()
==
WimaJoinedAreaData
::
typeString
)
{
// is it a corridor?
_joinedArea
=
*
qobject_cast
<
const
WimaJoinedAreaData
*>
(
areaData
);
areaCounter
++
;
_visualItems
.
append
(
&
_joinedArea
);
_missionController
->
insertSimpleMissionItem
(
*
missionItem
,
missionControllerVisualItems
->
count
());
continue
;
}
QGeoCoordinate
coordinate
=
missionItem
->
coordinate
();
_takeoffLandPostion
.
setAltitude
(
coordinate
.
altitude
());
_takeoffLandPostion
.
setLatitude
(
coordinate
.
latitude
());
_takeoffLandPostion
.
setLongitude
(
coordinate
.
longitude
());
if
(
areaCounter
>=
numAreas
)
break
;
}
begin
=
i
+
1
;
break
;
}
}
// extract mission items
QList
<
const
MissionItem
*>
tempMissionItems
=
planData
.
missionItems
()
;
if
(
tempMissionItems
.
size
()
<
1
)
return
false
;
// check if takeoff command found
if
(
begin
<
0
)
{
qWarning
(
"WimaController::containerDataValidChanged(): No takeoff found."
);
return
;
// create mission items
_missionController
->
removeAll
();
QmlObjectListModel
*
missionControllerVisualItems
=
_missionController
->
visualItems
();
// create SimpleMissionItem by using _missionController
for
(
int
i
=
0
;
i
<
tempMissionItems
.
size
();
i
++
)
{
const
MissionItem
*
missionItem
=
tempMissionItems
[
i
];
_missionController
->
insertSimpleMissionItem
(
*
missionItem
,
missionControllerVisualItems
->
count
());
}
// copy mission items from _missionController to _missionItems
for
(
int
i
=
1
;
i
<
missionControllerVisualItems
->
count
();
i
++
)
{
SimpleMissionItem
*
visualItem
=
qobject_cast
<
SimpleMissionItem
*>
((
*
missionControllerVisualItems
)[
i
]);
if
(
visualItem
==
nullptr
)
{
qWarning
(
"WimaController::fetchContainerData(): Nullptr at SimpleMissionItem!"
);
return
false
;
}
SimpleMissionItem
*
visualItemCopy
=
new
SimpleMissionItem
(
*
visualItem
,
true
,
this
);
_missionItems
.
append
(
visualItemCopy
);
}
if
(
areaCounter
!=
numAreas
)
return
false
;
// copy mission items and create SimpleMissionItem by using _missionController
for
(
int
i
=
begin
;
i
<
tempMissionItems
.
size
();
i
++
)
{
const
MissionItem
*
missionItem
=
tempMissionItems
[
i
];
_missionController
->
insertSimpleMissionItem
(
*
missionItem
,
missionControllerVisualItems
->
count
());
if
(
!
setTakeoffLandPosition
())
return
false
;
if
(
missionItem
->
command
()
==
MAV_CMD_NAV_VTOL_LAND
||
missionItem
->
command
()
==
MAV_CMD_NAV_LAND
)
break
;
}
updateWaypointPath
();
for
(
int
i
=
1
;
i
<
missionControllerVisualItems
->
count
();
i
++
)
{
SimpleMissionItem
*
visualItem
=
qobject_cast
<
SimpleMissionItem
*>
((
*
missionControllerVisualItems
)[
i
]);
if
(
visualItem
==
nullptr
)
{
qWarning
(
"WimaController::containerDataValidChanged(): Nullptr at SimpleMissionItem!"
);
return
;
}
SimpleMissionItem
*
visualItemCopy
=
new
SimpleMissionItem
(
*
visualItem
,
true
,
this
);
_missionItems
.
append
(
visualItemCopy
);
}
// set _nextPhaseStartWaypointIndex to 1
disconnect
(
&
_nextPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
_nextPhaseStartWaypointIndex
.
setRawValue
(
int
(
1
));
connect
(
&
_nextPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
if
(
areaCounter
==
numAreas
)
_localPlanDataValid
=
tru
e
;
if
(
!
calcNextPhase
()
)
return
fals
e
;
updateWaypointPath
();
_nestPhaseStartWaypointIndex
.
setRawValue
(
int
(
1
));
calcNextPhase
();
}
else
{
_localPlanDataValid
=
false
;
_visualItems
.
clear
();
_missionItems
.
clear
();
}
emit
visualItemsChanged
();
emit
missionItemsChanged
();
#ifdef QT_DEBUG
//qWarning("Mission Items count: ");
//qWarning() << _missionItems.count();
#endif
_localPlanDataValid
=
true
;
return
true
;
}
void
WimaController
::
calcNextPhase
()
bool
WimaController
::
calcNextPhase
()
{
_startWaypointIndex
=
_nestPhaseStartWaypointIndex
.
rawValue
().
toInt
()
-
1
;
// check if data was fetched and mission end is not reached yet
if
(
_missionItems
.
count
()
<
1
||
!
_localPlanDataValid
||
_startWaypointIndex
>=
_missionItems
.
count
()
-
2
)
return
;
if
(
_missionItems
.
count
()
<
1
||
_lastMissionPhaseReached
)
return
false
;
_currentMissionItems
.
clear
();
_currentWaypointPath
.
clear
();
emit
currentMissionItemsChanged
();
emit
currentWaypointPathChanged
();
_startWaypointIndex
=
_nextPhaseStartWaypointIndex
.
rawValue
().
toInt
()
-
1
;
if
(
_startWaypointIndex
>
_missionItems
.
count
()
-
1
)
return
false
;
int
maxWaypointsPerPhaseInt
=
_maxWaypointsPerPhase
.
rawValue
().
toInt
();
// determine end waypoint index
_endWaypointIndex
=
std
::
min
(
_startWaypointIndex
+
maxWaypointsPerPhaseInt
-
1
,
_missionItems
.
count
()
-
2
);
// -2 -> last item is land item
_endWaypointIndex
=
std
::
min
(
_startWaypointIndex
+
maxWaypointsPerPhaseInt
-
1
,
_missionItems
.
count
()
-
1
);
if
(
_endWaypointIndex
==
_missionItems
.
count
()
-
1
)
_lastMissionPhaseReached
=
true
;
// extract waypoints
QList
<
QGeoCoordinate
>
geoCoordinateList
;
// list with potential waypoints (from _missionItems), for _currentMissionItems
if
(
!
extractCoordinateList
(
_missionItems
,
geoCoordinateList
,
_startWaypointIndex
,
_endWaypointIndex
))
{
qWarning
(
"WimaController::updateCurrentMissionItems(): error on waypoint extraction."
);
_currentMissionItems
.
clear
();
return
;
qWarning
(
"WimaController::calcNextPhase(): error on waypoint extraction."
);
return
false
;
}
// set start waypoint index for next phase
if
(
_endWaypointIndex
<
_missionItems
.
count
()
-
2
)
{
_startWaypointIndexList
.
append
(
_nestPhaseStartWaypointIndex
.
rawValue
().
toInt
());
disconnect
(
&
_nestPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
int
temp
=
1
+
std
::
max
(
_endWaypointIndex
+
1
-
_overlapWaypoints
.
rawValue
().
toInt
(),
0
);
_nestPhaseStartWaypointIndex
.
setRawValue
(
std
::
min
(
temp
,
_missionItems
.
count
()
-
1
));
connect
(
&
_nestPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
}
else
{
disconnect
(
&
_nestPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
_nestPhaseStartWaypointIndex
.
setRawValue
(
_missionItems
.
count
()
-
1
);
// marks that end of mission is reached
connect
(
&
_nestPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
if
(
!
_lastMissionPhaseReached
)
{
disconnect
(
&
_nextPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
int
untruncated
=
std
::
max
(
_endWaypointIndex
+
1
-
_overlapWaypoints
.
rawValue
().
toInt
(),
0
);
int
truncated
=
std
::
min
(
untruncated
,
_missionItems
.
count
()
-
1
);
_nextPhaseStartWaypointIndex
.
setRawValue
(
truncated
+
1
);
connect
(
&
_nextPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
}
// calculate path from home to first waypoint
QList
<
QGeoCoordinate
>
path
;
if
(
!
_takeoffLandPostion
.
isValid
()){
qWarning
(
"WimaController::calcNextPhase(): _takeoffLandPostion not valid."
);
return
false
;
}
if
(
!
calcShortestPath
(
_takeoffLandPostion
,
geoCoordinateList
[
0
],
path
)
)
{
qWarning
(
"WimaController::updateCurrentMissionItems(): Not able to calc path from home to first waypoint."
);
_currentMissionItems
.
clear
();
return
;
qWarning
(
"WimaController::calcNextPhase(): Not able to calc path from home to first waypoint."
);
return
false
;
}
// prepend to geoCoordinateList
for
(
int
i
=
path
.
size
()
-
2
;
i
>=
0
;
i
--
)
// i = path.size()-2 : last coordinate already in geoCoordinateList
...
...
@@ -526,9 +510,8 @@ void WimaController::calcNextPhase()
// calculate path from last waypoint to home
path
.
clear
();
if
(
!
calcShortestPath
(
geoCoordinateList
.
last
(),
_takeoffLandPostion
,
path
)
)
{
qWarning
(
"WimaController::updateCurrentMissionItems(): Not able to calc path from home to first waypoint."
);
_currentMissionItems
.
clear
();
return
;
qWarning
(
"WimaController::calcNextPhase(): Not able to calc path from home to first waypoint."
);
return
false
;
}
path
.
removeFirst
();
// first coordinate already in geoCoordinateList
geoCoordinateList
.
append
(
path
);
...
...
@@ -541,9 +524,8 @@ void WimaController::calcNextPhase()
// set homeposition of settingsItem
MissionSettingsItem
*
settingsItem
=
missionControllerVisuals
->
value
<
MissionSettingsItem
*>
(
0
);
if
(
settingsItem
==
nullptr
)
{
qWarning
(
"WimaController::updateCurrentMissionItems(): nullptr"
);
_currentMissionItems
.
clear
();
return
;
qWarning
(
"WimaController::calcNextPhase(): nullptr"
);
return
false
;
}
settingsItem
->
setCoordinate
(
_takeoffLandPostion
);
...
...
@@ -551,44 +533,38 @@ void WimaController::calcNextPhase()
_missionController
->
insertSimpleMissionItem
(
coordinate
,
missionControllerVisuals
->
count
());
}
// set homeposition for take off item (somehow not working with insertSimpleMissionItem)
SimpleMissionItem
*
takeoff
=
missionControllerVisuals
->
value
<
SimpleMissionItem
*>
(
1
);
if
(
takeoff
==
nullptr
)
{
qWarning
(
"WimaController::updateCurrentMissionItems(): nullptr"
);
_currentMissionItems
.
clear
();
return
;
// set takeoff position for first mission item (bug)
SimpleMissionItem
*
takeoffItem
=
missionControllerVisuals
->
value
<
SimpleMissionItem
*>
(
1
);
if
(
takeoffItem
==
nullptr
)
{
qWarning
(
"WimaController::calcNextPhase(): nullptr"
);
return
false
;
}
takeoff
->
setCoordinate
(
_takeoffLandPostion
);
takeoff
Item
->
setCoordinate
(
_takeoffLandPostion
);
// set land command for last mission item
SimpleMissionItem
*
landItem
=
missionControllerVisuals
->
value
<
SimpleMissionItem
*>
(
missionControllerVisuals
->
count
()
-
1
);
if
(
landItem
==
nullptr
)
{
qWarning
(
"WimaController::updateCurrentMissionItems(): nullptr"
);
_currentMissionItems
.
clear
();
return
;
}
// check vehicle type, before setting land command
Vehicle
*
controllerVehicle
=
_masterController
->
controllerVehicle
();
MAV_CMD
landCmd
=
controllerVehicle
->
vtol
()
?
MAV_CMD_NAV_VTOL_LAND
:
MAV_CMD_NAV_LAND
;
if
(
controllerVehicle
->
firmwarePlugin
()
->
supportedMissionCommands
().
contains
(
landCmd
))
{
landItem
->
setCommand
(
landCmd
);
}
else
{
_currentMissionItems
.
clear
();
return
;
qWarning
(
"WimaController::calcNextPhase(): nullptr"
);
return
false
;
}
_missionController
->
setLandCommand
(
*
landItem
,
*
_masterController
->
controllerVehicle
());
// copy to _currentMissionItems
_currentMissionItems
.
clear
();
for
(
int
i
=
1
;
i
<
missionControllerVisuals
->
count
();
i
++
)
{
SimpleMissionItem
*
visualItem
=
missionControllerVisuals
->
value
<
SimpleMissionItem
*>
(
i
);
if
(
visualItem
==
nullptr
)
{
qWarning
(
"WimaController::
updateCurrentMissionItems(): Nullptr at SimpleMissionItem!"
);
qWarning
(
"WimaController::
calcNextPhase(): Nullptr at SimpleMissionItem!"
);
_currentMissionItems
.
clear
();
return
;
return
false
;
}
SimpleMissionItem
*
visualItemCopy
=
new
SimpleMissionItem
(
*
visualItem
,
true
,
this
);
qWarning
()
<<
visualItem
->
command
();
qWarning
()
<<
visualItem
->
coordinate
();
qWarning
()
<<
visualItemCopy
->
command
();
qWarning
()
<<
visualItemCopy
->
command
();
qWarning
(
" "
);
_currentMissionItems
.
append
(
visualItemCopy
);
}
...
...
@@ -596,6 +572,8 @@ void WimaController::calcNextPhase()
updateCurrentPath
();
emit
currentMissionItemsChanged
();
return
true
;
}
void
WimaController
::
updateWaypointPath
()
...
...
@@ -616,15 +594,25 @@ void WimaController::updateCurrentPath()
void
WimaController
::
updateNextWaypoint
()
{
if
(
_endWaypointIndex
<
_missionItems
.
count
()
-
2
)
{
disconnect
(
&
_ne
s
tPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
_ne
s
tPhaseStartWaypointIndex
.
setRawValue
(
1
+
std
::
max
(
_endWaypointIndex
+
1
-
_overlapWaypoints
.
rawValue
().
toInt
(),
0
));
connect
(
&
_ne
s
tPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
disconnect
(
&
_ne
x
tPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
_ne
x
tPhaseStartWaypointIndex
.
setRawValue
(
1
+
std
::
max
(
_endWaypointIndex
+
1
-
_overlapWaypoints
.
rawValue
().
toInt
(),
0
));
connect
(
&
_ne
x
tPhaseStartWaypointIndex
,
&
Fact
::
rawValueChanged
,
this
,
&
WimaController
::
calcNextPhase
);
}
}
void
WimaController
::
recalcCurrentPhase
()
{
_nestPhaseStartWaypointIndex
.
setRawValue
(
_startWaypointIndex
+
1
);
_lastMissionPhaseReached
=
false
;
_nextPhaseStartWaypointIndex
.
setRawValue
(
_startWaypointIndex
+
1
);
}
bool
WimaController
::
setTakeoffLandPosition
()
{
_takeoffLandPostion
.
setAltitude
(
0
);
_takeoffLandPostion
.
setLongitude
(
_serviceArea
.
center
().
longitude
());
_takeoffLandPostion
.
setLatitude
(
_serviceArea
.
center
().
latitude
());
return
true
;
}
...
...
src/Wima/WimaController.h
View file @
a6776c0a
...
...
@@ -85,12 +85,8 @@ public:
Q_INVOKABLE
void
nextPhase
();
Q_INVOKABLE
void
previousPhase
();
Q_INVOKABLE
void
resetPhase
();
Q_INVOKABLE
void
uploadToVehicle
();
Q_INVOKABLE
bool
uploadToVehicle
();
Q_INVOKABLE
void
removeFromVehicle
();
Q_INVOKABLE
void
startMission
();
Q_INVOKABLE
void
abortMission
();
Q_INVOKABLE
void
pauseMission
();
Q_INVOKABLE
void
resumeMission
();
Q_INVOKABLE
void
saveToCurrent
();
Q_INVOKABLE
void
saveToFile
(
const
QString
&
filename
);
...
...
@@ -137,12 +133,13 @@ signals:
void
currentWaypointPathChanged
(
void
);
private
slots
:
void
fetchContainerData
(
bool
valid
);
void
calcNextPhase
(
void
);
bool
fetchContainerData
(
);
bool
calcNextPhase
(
void
);
void
updateWaypointPath
(
void
);
void
updateCurrentPath
(
void
);
void
updateNextWaypoint
(
void
);
void
recalcCurrentPhase
(
void
);
bool
setTakeoffLandPosition
(
void
);
private:
...
...
@@ -161,8 +158,6 @@ 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
QList
<
int
>
_startWaypointIndexList
;
// list containing the last start waypoint indices, used by previosPhase
QGeoCoordinate
_takeoffLandPostion
;
...
...
@@ -170,7 +165,7 @@ private:
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
_ne
s
tPhaseStartWaypointIndex
;
// index (displayed on the map, -1 to get index of item in _missionItems) of the mission item
SettingsFact
_ne
x
tPhaseStartWaypointIndex
;
// 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.
...
...
@@ -179,4 +174,5 @@ private:
// (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
bool
_lastMissionPhaseReached
;
};
src/Wima/WimaDataContainer.cc
View file @
a6776c0a
...
...
@@ -3,29 +3,10 @@
WimaDataContainer
::
WimaDataContainer
(
QObject
*
parent
)
:
QObject
(
parent
)
,
_planData
(
this
/* parent */
)
,
_dataValid
(
false
)
{
}
/*!
* \fn bool WimaDataContainer::dataValid() const
* Returns \c true if the data is valid, \c false else.
*/
bool
WimaDataContainer
::
dataValid
()
const
/*!
* \fn bool dijkstraAlgorithm(int startIndex, int endIndex, const QList<T> elements, QList<T> &elementPath, double(*distance)(const T &t1, const T &t2))
* Calculates the shortest path between the elements stored in \a elements.
* The \l {Dijkstra Algorithm} is used to find the shorest path.
* Stores the result inside \a elementPath when sucessfull.
* The function handle \a distance is used to calculate the distance between two elements. The distance must be positive.
* Returns \c true if successful, \c false else.
*
* \sa QList
*/
{
return
_dataValid
;
}
/*!
* \fn void WimaDataContainer::push(const WimaPlanData &planData)
*
...
...
@@ -36,9 +17,9 @@ bool WimaDataContainer::dataValid() const/*!
*/
void
WimaDataContainer
::
push
(
const
WimaPlanData
&
planData
)
{
setDataValid
(
false
);
_planData
=
planData
;
setDataValid
(
true
);
emit
newDataAvailable
();
}
/*!
...
...
@@ -53,23 +34,6 @@ const WimaPlanData &WimaDataContainer::pull() const
return
_planData
;
}
/*!
* \fn void WimaDataContainer::setDataValid(bool valid)
*
* Sets the validity of the data to \a valid.
* Mainly for internal usage. Should be invoked from \c WimaPlaner only.
*
* \sa WimaPlanData
*/
void
WimaDataContainer
::
setDataValid
(
bool
valid
)
{
if
(
_dataValid
!=
valid
)
{
_dataValid
=
valid
;
emit
dataValidChanged
(
_dataValid
);
}
}
/*!
* \class WimaDataContainer
* \brief Data container designed for data exchange between \c WimaPlaner and \c WimaController.
...
...
src/Wima/WimaDataContainer.h
View file @
a6776c0a
...
...
@@ -17,16 +17,14 @@ public:
bool
dataValid
()
const
;
signals:
void
dataValidChanged
(
bool
val
id
);
void
newDataAvailable
(
vo
id
);
public
slots
:
void
push
(
const
WimaPlanData
&
planData
);
const
WimaPlanData
&
pull
()
const
;
void
setDataValid
(
bool
valid
);
private:
WimaPlanData
_planData
;
bool
_dataValid
;
};
src/Wima/WimaPlaner.cc
View file @
a6776c0a
...
...
@@ -73,11 +73,11 @@ void WimaPlaner::setDataContainer(WimaDataContainer *container)
{
if
(
container
!=
nullptr
)
{
if
(
_container
!=
nullptr
)
{
disconnect
(
this
,
&
WimaPlaner
::
missionReadyChanged
,
_container
,
&
WimaDataContainer
::
setDataValid
);
disconnect
(
this
,
&
WimaPlaner
::
missionReadyChanged
,
_container
,
&
WimaDataContainer
::
newDataAvailable
);
}
_container
=
container
;
connect
(
this
,
&
WimaPlaner
::
missionReadyChanged
,
_container
,
&
WimaDataContainer
::
setDataValid
);
connect
(
this
,
&
WimaPlaner
::
missionReadyChanged
,
_container
,
&
WimaDataContainer
::
newDataAvailable
);
emit
dataContainerChanged
();
}
...
...
@@ -178,32 +178,9 @@ void WimaPlaner::removeAll()
emit
visualItemsChanged
();
}
void
WimaPlaner
::
startMission
()
{
}
void
WimaPlaner
::
abortMission
()
{
}
void
WimaPlaner
::
pauseMission
()
{
}
void
WimaPlaner
::
resumeMission
()
{
}
bool
WimaPlaner
::
updateMission
()
{
#if TEST_FUN
TestPlanimetryCalculus
::
test
();
TestPolygonCalculus
::
test
();
#endif
QString
errorString
;
setMissionReady
(
false
);
#define debug 0
...
...
@@ -306,11 +283,7 @@ bool WimaPlaner::updateMission()
qgcApp
()
->
showMessage
(
QString
(
tr
(
"Not able to calculate the path from takeoff position to measurement area."
)).
toLocal8Bit
().
data
());
return
false
;
}
// path.clear();
// path.append(end);
// path.append(start);
// path.append(end);
// path.append(end);
_arrivalPathLength
=
path
.
size
()
-
1
;
// -1: last item is first measurement point
for
(
int
i
=
1
;
i
<
path
.
count
()
-
1
;
i
++
)
{
sequenceNumber
=
_missionController
->
insertSimpleMissionItem
(
path
.
value
(
i
),
missionItems
->
count
()
-
1
);
_missionController
->
setCurrentPlanViewIndex
(
sequenceNumber
,
true
);
...
...
@@ -324,7 +297,7 @@ bool WimaPlaner::updateMission()
qgcApp
()
->
showMessage
(
QString
(
tr
(
"Not able to calculate the path from measurement area to landing position."
)).
toLocal8Bit
().
data
());
return
false
;
}
_returnPathLength
=
path
.
size
()
-
1
;
// -1: fist item is last measurement point
for
(
int
i
=
1
;
i
<
path
.
count
()
-
1
;
i
++
)
{
sequenceNumber
=
_missionController
->
insertSimpleMissionItem
(
path
.
value
(
i
),
missionItems
->
count
());
_missionController
->
setCurrentPlanViewIndex
(
sequenceNumber
,
true
);
...
...
@@ -338,13 +311,8 @@ bool WimaPlaner::updateMission()
qWarning
(
"WimaPlaner::updateMission(): landItem == nullptr"
);
return
false
;
}
else
{
Vehicle
*
controllerVehicle
=
_masterController
->
controllerVehicle
();
MAV_CMD
landCmd
=
controllerVehicle
->
vtol
()
?
MAV_CMD_NAV_VTOL_LAND
:
MAV_CMD_NAV_LAND
;
if
(
controllerVehicle
->
firmwarePlugin
()
->
supportedMissionCommands
().
contains
(
landCmd
))
{
landItem
->
setCommand
(
landCmd
);
}
else
{
if
(
!
_missionController
->
setLandCommand
(
*
landItem
,
*
_masterController
->
controllerVehicle
()))
return
false
;
}
}
pushToContainer
();
// exchange plan data with the WimaController via the _container
...
...
@@ -662,23 +630,12 @@ WimaPlanData WimaPlaner::toPlanData()
QList
<
MissionItem
*>
rgMissionItems
;
MissionController
::
convertToMissionItems
(
_missionController
->
visualItems
(),
rgMissionItems
,
this
);
// remove warnings if you read this
// qWarning("WimaPlaner::toPlanData(): rgMissionItems");
// for (auto item : rgMissionItems) {
// qWarning() << item->command();
// qWarning() << item->param1();
// qWarning() << item->param2();
// qWarning() << item->param3();
// qWarning() << item->param4();
// qWarning() << item->param5();
// qWarning() << item->param6();
// qWarning() << item->param7();
// qWarning(" ");
// }
// add const qualifier...
QList
<
const
MissionItem
*>
rgMissionItemsConst
;
for
(
auto
missionItem
:
rgMissionItems
)
rgMissionItemsConst
.
append
(
missionItem
);
for
(
int
i
=
_arrivalPathLength
+
1
;
i
<
rgMissionItems
.
size
()
-
_returnPathLength
;
i
++
)
{
// i = _arrivalPathLength + 1: + 1 = MissionSettingsItem ...
rgMissionItemsConst
.
append
(
rgMissionItems
.
value
(
i
));
}
// store mavlink commands
planData
.
append
(
rgMissionItemsConst
);
...
...
src/Wima/WimaPlaner.h
View file @
a6776c0a
...
...
@@ -91,11 +91,6 @@ public:
Q_INVOKABLE
bool
addCorridor
();
/// Remove all areas from WimaPlaner and all mission items from MissionController
Q_INVOKABLE
void
removeAll
();
Q_INVOKABLE
void
startMission
();
Q_INVOKABLE
void
abortMission
();
Q_INVOKABLE
void
pauseMission
();
Q_INVOKABLE
void
resumeMission
();
/// Recalculates vehicle corridor, flight path, etc.
Q_INVOKABLE
bool
updateMission
();
...
...
@@ -147,4 +142,6 @@ private:
WimaMeasurementArea
_measurementArea
;
// measurement area
WimaServiceArea
_serviceArea
;
// area for supplying
WimaCorridor
_corridor
;
// corridor connecting _measurementArea and _serviceArea
int
_arrivalPathLength
;
// the number waypoints the arrival path consists of (path from takeoff to first measurement point)
int
_returnPathLength
;
// the number waypoints the return path consists of (path from last measurement point to land)
};
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