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
d1eac7fe
Commit
d1eac7fe
authored
Oct 14, 2020
by
Valentin Platzgummer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
wima planer and wima controller edited
parent
a0e0f804
Changes
27
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
27 changed files
with
550 additions
and
581 deletions
+550
-581
qgroundcontrol.pro
qgroundcontrol.pro
+2
-0
qgroundcontrol.qrc
qgroundcontrol.qrc
+5
-0
FlightDisplayViewMap.qml
src/FlightDisplay/FlightDisplayViewMap.qml
+7
-89
FlightDisplayWimaMenu.qml
src/FlightDisplay/FlightDisplayWimaMenu.qml
+39
-3
WimaAreaData.h
src/Wima/Geometry/WimaAreaData.h
+3
-0
WimaCorridorData.cpp
src/Wima/Geometry/WimaCorridorData.cpp
+26
-34
WimaCorridorData.h
src/Wima/Geometry/WimaCorridorData.h
+13
-14
WimaJoinedAreaData.cc
src/Wima/Geometry/WimaJoinedAreaData.cc
+4
-0
WimaJoinedAreaData.h
src/Wima/Geometry/WimaJoinedAreaData.h
+15
-14
WimaMeasurementAreaData.cc
src/Wima/Geometry/WimaMeasurementAreaData.cc
+22
-4
WimaMeasurementAreaData.h
src/Wima/Geometry/WimaMeasurementAreaData.h
+14
-1
WimaServiceAreaData.cc
src/Wima/Geometry/WimaServiceAreaData.cc
+4
-0
WimaServiceAreaData.h
src/Wima/Geometry/WimaServiceAreaData.h
+2
-0
SnakeTile.cpp
src/Wima/Snake/SnakeTile.cpp
+4
-0
SnakeTile.h
src/Wima/Snake/SnakeTile.h
+2
-0
WimaAreaNoVisual.qml
src/Wima/Snake/WimaAreaNoVisual.qml
+12
-0
StateMachine.cpp
src/Wima/StateMachine.cpp
+1
-1
EmptyManager.cpp
src/Wima/WaypointManager/EmptyManager.cpp
+18
-0
EmptyManager.h
src/Wima/WaypointManager/EmptyManager.h
+31
-0
WimaController.cc
src/Wima/WimaController.cc
+18
-312
WimaController.h
src/Wima/WimaController.h
+4
-104
CircularSurveyMapVisual.qml
src/WimaView/CircularSurveyMapVisual.qml
+4
-4
WimaCorridorDataVisual.qml
src/WimaView/WimaCorridorDataVisual.qml
+58
-0
WimaJoinedAreaDataVisual.qml
src/WimaView/WimaJoinedAreaDataVisual.qml
+58
-0
WimaMeasurementAreaDataVisual.qml
src/WimaView/WimaMeasurementAreaDataVisual.qml
+124
-0
WimaServiceAreaDataVisual.qml
src/WimaView/WimaServiceAreaDataVisual.qml
+58
-0
WimaToolBar.qml
src/WimaView/WimaToolBar.qml
+2
-1
No files found.
qgroundcontrol.pro
View file @
d1eac7fe
...
@@ -457,6 +457,7 @@ HEADERS += \
...
@@ -457,6 +457,7 @@ HEADERS += \
src
/
Wima
/
StateMachine
.
h
\
src
/
Wima
/
StateMachine
.
h
\
src
/
Wima
/
WaypointManager
/
AreaInterface
.
h
\
src
/
Wima
/
WaypointManager
/
AreaInterface
.
h
\
src
/
Wima
/
WaypointManager
/
DefaultManager
.
h
\
src
/
Wima
/
WaypointManager
/
DefaultManager
.
h
\
src
/
Wima
/
WaypointManager
/
EmptyManager
.
h
\
src
/
Wima
/
WaypointManager
/
GenericWaypointManager
.
h
\
src
/
Wima
/
WaypointManager
/
GenericWaypointManager
.
h
\
src
/
Wima
/
WaypointManager
/
RTLManager
.
h
\
src
/
Wima
/
WaypointManager
/
RTLManager
.
h
\
src
/
Wima
/
WaypointManager
/
Settings
.
h
\
src
/
Wima
/
WaypointManager
/
Settings
.
h
\
...
@@ -519,6 +520,7 @@ SOURCES += \
...
@@ -519,6 +520,7 @@ SOURCES += \
src
/
Wima
/
StateMachine
.
cpp
\
src
/
Wima
/
StateMachine
.
cpp
\
src
/
Wima
/
WaypointManager
/
AreaInterface
.
cpp
\
src
/
Wima
/
WaypointManager
/
AreaInterface
.
cpp
\
src
/
Wima
/
WaypointManager
/
DefaultManager
.
cpp
\
src
/
Wima
/
WaypointManager
/
DefaultManager
.
cpp
\
src
/
Wima
/
WaypointManager
/
EmptyManager
.
cpp
\
src
/
Wima
/
WaypointManager
/
GenericWaypointManager
.
cpp
\
src
/
Wima
/
WaypointManager
/
GenericWaypointManager
.
cpp
\
src
/
Wima
/
WaypointManager
/
RTLManager
.
cpp
\
src
/
Wima
/
WaypointManager
/
RTLManager
.
cpp
\
src
/
Wima
/
WaypointManager
/
Settings
.
cpp
\
src
/
Wima
/
WaypointManager
/
Settings
.
cpp
\
...
...
qgroundcontrol.qrc
View file @
d1eac7fe
...
@@ -232,6 +232,11 @@
...
@@ -232,6 +232,11 @@
<file alias="QGroundControl/Controls/CircularSurveyMapVisual.qml">src/WimaView/CircularSurveyMapVisual.qml</file>
<file alias="QGroundControl/Controls/CircularSurveyMapVisual.qml">src/WimaView/CircularSurveyMapVisual.qml</file>
<file alias="QGroundControl/FlightDisplay/SmallValue.qml">src/FlightDisplay/SmallValue.qml</file>
<file alias="QGroundControl/FlightDisplay/SmallValue.qml">src/FlightDisplay/SmallValue.qml</file>
<file alias="QGroundControl/Controls/ProgressIndicator.qml">src/WimaView/ProgressIndicator.qml</file>
<file alias="QGroundControl/Controls/ProgressIndicator.qml">src/WimaView/ProgressIndicator.qml</file>
<file alias="QGroundControl/Controls/WimaServiceAreaDataVisual.qml">src/WimaView/WimaServiceAreaDataVisual.qml</file>
<file alias="QGroundControl/Controls/WimaCorridorDataVisual.qml">src/WimaView/WimaCorridorDataVisual.qml</file>
<file alias="QGroundControl/Controls/WimaJoinedAreaDataVisual.qml">src/WimaView/WimaJoinedAreaDataVisual.qml</file>
<file alias="QGroundControl/Controls/WimaAreaNoVisual.qml">src/Wima/Snake/WimaAreaNoVisual.qml</file>
<file alias="QGroundControl/Controls/WimaMeasurementAreaDataVisual.qml">src/WimaView/WimaMeasurementAreaDataVisual.qml</file>
</qresource>
</qresource>
<qresource prefix="/json">
<qresource prefix="/json">
<file alias="APMMavlinkStreamRate.SettingsGroup.json">src/Settings/APMMavlinkStreamRate.SettingsGroup.json</file>
<file alias="APMMavlinkStreamRate.SettingsGroup.json">src/Settings/APMMavlinkStreamRate.SettingsGroup.json</file>
...
...
src/FlightDisplay/FlightDisplayViewMap.qml
View file @
d1eac7fe
...
@@ -59,8 +59,6 @@ FlightMap {
...
@@ -59,8 +59,6 @@ FlightMap {
property
bool
_keepVehicleCentered
:
_mainIsMap
?
false
:
true
property
bool
_keepVehicleCentered
:
_mainIsMap
?
false
:
true
property
bool
_wimaEnabled
:
wimaController
.
enableWimaController
.
value
property
bool
_wimaEnabled
:
wimaController
.
enableWimaController
.
value
property
bool
_showAllWimaItems
:
wimaController
.
showAllMissionItems
.
value
property
bool
_showCurrentWimaItems
:
wimaController
.
showCurrentMissionItems
.
value
function
updateAirspace
(
reset
)
{
function
updateAirspace
(
reset
)
{
if
(
_airspaceEnabled
)
{
if
(
_airspaceEnabled
)
{
...
@@ -200,109 +198,29 @@ FlightMap {
...
@@ -200,109 +198,29 @@ FlightMap {
}
}
// Add wima Areas to the Map
// Add wima Areas to the Map
MapItemView
{
Repeater
{
property
bool
_enableWima
:
wimaController
.
enableWimaController
.
value
property
bool
_enableWima
:
wimaController
.
enableWimaController
.
value
model
:
_enableWima
?
wimaController
.
visualItems
:
0
model
:
_enableWima
?
wimaController
.
visualItems
:
0
delegate
:
WimaMapVisual
{
delegate
:
MapPolygon
{
map
:
flightMap
path
:
object
.
path
;
qgcView
:
flightMap
.
qgcView
border.color
:
"
black
"
visible
:
true
color
:
object
.
type
===
"
WimaJoinedAreaData
"
?
"
gray
"
:
object
.
type
===
"
WimaServiceAreaData
"
?
"
yellow
"
:
object
.
type
===
"
WimaMeasurementAreaData
"
?
"
green
"
:
"
transparent
"
opacity
:
0.25
z
:
0
}
}
}
}
// Add mission
i
tems generated by wima planer to the map
// Add mission
I
tems generated by wima planer to the map
// all Items
// all Items
WimaPlanMapItems
{
WimaPlanMapItems
{
map
:
flightMap
map
:
flightMap
largeMapView
:
_mainIsMap
largeMapView
:
_mainIsMap
missionItems
:
wimaController
.
missionItems
missionItems
:
wimaController
.
missionItems
path
:
wimaController
.
waypointPath
path
:
wimaController
.
waypointPath
showItems
:
_wimaEnabled
&&
_showAllWimaItems
showItems
:
_wimaEnabled
zOrderWP
:
QGroundControl
.
zOrderWimaAllWaypointIndicators
zOrderWP
:
QGroundControl
.
zOrderWimaAllWaypointIndicators
zOrderLines
:
QGroundControl
.
zOrderWimaAllWaypointLines
zOrderLines
:
QGroundControl
.
zOrderWimaAllWaypointLines
color
:
"
gray
"
}
// current Items
WimaPlanMapItems
{
map
:
flightMap
largeMapView
:
_mainIsMap
missionItems
:
wimaController
.
currentMissionItems
path
:
wimaController
.
currentWaypointPath
showItems
:
_wimaEnabled
&&
_showCurrentWimaItems
zOrderWP
:
QGroundControl
.
zOrderWimaCurrentWaypointIndicators
zOrderLines
:
QGroundControl
.
zOrderWimaCurrentWaypointLines
color
:
"
green
"
color
:
"
green
"
}
}
// // Add Snake tile center points to the map
// MapItemView {
// id:progressView
// property bool _enable: wimaController.enableWimaController.value
// && wimaController.enableSnake.value
// property bool valid: wimaController.snakeTileCenterPoints.length
// === wimaController.nemoProgress.length
// model: _enable ? wimaController.snakeTileCenterPoints : 0
// delegate: ProgressIndicator{
// coordinate: modelData
// currentValue: getProgress()
// z: 1
// function getProgress() {
// var progress = 0
// if (progressView.valid){
// progress = wimaController.nemoProgress[index]
// }
// if (progress < 0)
// progress = 0
// if (progress > 100)
// progress = 100
// return progress
// }
// }
// }
// Add Snake tiles to the map
MapItemView
{
id
:
tileView
property
bool
_enable
:
wimaController
.
enableWimaController
.
value
property
bool
valid
:
wimaController
.
snakeTileCenterPoints
.
length
===
wimaController
.
nemoProgress
.
length
model
:
_enable
?
wimaController
.
snakeTiles
:
0
delegate
:
MapPolygon
{
path
:
object
.
path
;
border.color
:
"
black
"
border.width
:
1
color
:
getColor
()
opacity
:
0.6
z
:
2
function
getColor
()
{
var
progress
=
0
if
(
tileView
.
valid
){
progress
=
wimaController
.
nemoProgress
[
index
]
}
if
(
progress
<
25
)
return
"
transparent
"
if
(
progress
<
50
)
return
"
orange
"
if
(
progress
<
75
)
return
"
yellow
"
if
(
progress
<
100
)
return
"
greenyellow
"
return
"
limegreen
"
}
}
}
// Add trajectory points to the map
// Add trajectory points to the map
MapItemView
{
MapItemView
{
model
:
_mainIsMap
?
_activeVehicle
?
_activeVehicle
.
trajectoryPoints
:
0
:
0
model
:
_mainIsMap
?
_activeVehicle
?
_activeVehicle
.
trajectoryPoints
:
0
:
0
...
...
src/FlightDisplay/FlightDisplayWimaMenu.qml
View file @
d1eac7fe
...
@@ -171,11 +171,11 @@ Item {
...
@@ -171,11 +171,11 @@ Item {
id
:
mainColumn
id
:
mainColumn
spacing
:
ScreenTools
.
defaultFontPixelHeight
*
0.3
spacing
:
ScreenTools
.
defaultFontPixelHeight
*
0.3
SectionHeader
{
SectionHeader
{
id
:
vehicleHeader
id
:
vehicleHeader
text
:
qsTr
(
"
Vehicle
"
)
text
:
qsTr
(
"
Vehicle
"
)
}
}
GridLayout
{
GridLayout
{
columns
:
2
columns
:
2
rowSpacing
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
rowSpacing
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
...
@@ -183,6 +183,17 @@ Item {
...
@@ -183,6 +183,17 @@ Item {
visible
:
vehicleHeader
.
checked
visible
:
vehicleHeader
.
checked
width
:
parent
.
width
width
:
parent
.
width
QGCButton
{
id
:
buttonUpload
text
:
qsTr
(
"
Upload
"
)
onClicked
:
{
if
(
!
planMasterController
.
offline
)
{
wimaController
.
upload
()
}
}
Layout
.
fillWidth
:
true
}
QGCButton
{
QGCButton
{
id
:
buttonRemoveFromVehicle
id
:
buttonRemoveFromVehicle
text
:
qsTr
(
"
Remove
"
)
text
:
qsTr
(
"
Remove
"
)
...
@@ -194,6 +205,7 @@ Item {
...
@@ -194,6 +205,7 @@ Item {
id
:
buttonSmartRTL
id
:
buttonSmartRTL
text
:
qsTr
(
"
Smart RTL
"
)
text
:
qsTr
(
"
Smart RTL
"
)
onClicked
:
wimaController
.
requestSmartRTL
();
onClicked
:
wimaController
.
requestSmartRTL
();
Layout.columnSpan
:
2
Layout.fillWidth
:
true
Layout.fillWidth
:
true
}
}
...
@@ -204,7 +216,32 @@ Item {
...
@@ -204,7 +216,32 @@ Item {
Layout.columnSpan
:
2
Layout.columnSpan
:
2
Layout.fillWidth
:
true
Layout.fillWidth
:
true
}
}
}
GridLayout
{
columns
:
2
rowSpacing
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
columnSpacing
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
visible
:
vehicleHeader
.
checked
width
:
parent
.
width
QGCLabel
{
text
:
qsTr
(
"
Speed
"
)
Layout.fillWidth
:
true
}
FactTextField
{
fact
:
wimaController
.
flightSpeed
Layout.fillWidth
:
true
}
QGCLabel
{
text
:
qsTr
(
"
Altitude
"
)
Layout.fillWidth
:
true
}
FactTextField
{
fact
:
wimaController
.
altitude
Layout.fillWidth
:
true
}
// progess bar
// progess bar
Rectangle
{
Rectangle
{
...
@@ -223,7 +260,7 @@ Item {
...
@@ -223,7 +260,7 @@ Item {
Layout.columnSpan
:
2
Layout.columnSpan
:
2
horizontalAlignment
:
Text
.
AlignHCenter
horizontalAlignment
:
Text
.
AlignHCenter
verticalAlignment
:
Text
.
AlignVCenter
verticalAlignment
:
Text
.
AlignVCenter
text
:
"
Upload Complet
e
"
text
:
"
Don
e
"
visible
:
false
visible
:
false
Layout.fillWidth
:
true
Layout.fillWidth
:
true
}
}
...
@@ -233,7 +270,6 @@ Item {
...
@@ -233,7 +270,6 @@ Item {
id
:
statsHeader
id
:
statsHeader
text
:
qsTr
(
"
Statistics
"
)
text
:
qsTr
(
"
Statistics
"
)
}
}
GridLayout
{
GridLayout
{
columns
:
3
columns
:
3
rowSpacing
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
rowSpacing
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
...
...
src/Wima/Geometry/WimaAreaData.h
View file @
d1eac7fe
...
@@ -13,6 +13,7 @@ class WimaAreaData
...
@@ -13,6 +13,7 @@ class WimaAreaData
public:
public:
Q_PROPERTY
(
const
QVariantList
path
READ
path
NOTIFY
pathChanged
)
Q_PROPERTY
(
const
QVariantList
path
READ
path
NOTIFY
pathChanged
)
Q_PROPERTY
(
QString
type
READ
type
CONSTANT
)
Q_PROPERTY
(
QString
type
READ
type
CONSTANT
)
Q_PROPERTY
(
QString
mapVisualQML
READ
mapVisualQML
CONSTANT
)
WimaAreaData
(
QObject
*
parent
=
nullptr
);
WimaAreaData
(
QObject
*
parent
=
nullptr
);
~
WimaAreaData
();
~
WimaAreaData
();
...
@@ -23,6 +24,8 @@ public:
...
@@ -23,6 +24,8 @@ public:
bool
operator
==
(
const
WimaAreaData
&
data
)
const
;
bool
operator
==
(
const
WimaAreaData
&
data
)
const
;
bool
operator
!=
(
const
WimaAreaData
&
data
)
const
;
bool
operator
!=
(
const
WimaAreaData
&
data
)
const
;
virtual
QString
mapVisualQML
(
void
)
const
=
0
;
QVariantList
path
()
const
;
QVariantList
path
()
const
;
QGeoCoordinate
center
()
const
;
QGeoCoordinate
center
()
const
;
const
QList
<
QGeoCoordinate
>
&
coordinateList
()
const
;
const
QList
<
QGeoCoordinate
>
&
coordinateList
()
const
;
...
...
src/Wima/Geometry/WimaCorridorData.cpp
View file @
d1eac7fe
...
@@ -2,22 +2,17 @@
...
@@ -2,22 +2,17 @@
const
char
*
WimaCorridorData
::
typeString
=
"WimaCorridorData"
;
const
char
*
WimaCorridorData
::
typeString
=
"WimaCorridorData"
;
WimaCorridorData
::
WimaCorridorData
(
QObject
*
parent
)
WimaCorridorData
::
WimaCorridorData
(
QObject
*
parent
)
:
WimaAreaData
(
parent
)
{}
:
WimaAreaData
(
parent
)
{
}
WimaCorridorData
::
WimaCorridorData
(
const
WimaCorridorData
&
other
,
QObject
*
parent
)
WimaCorridorData
::
WimaCorridorData
(
const
WimaCorridorData
&
other
,
QObject
*
parent
)
:
WimaAreaData
(
parent
)
{
:
WimaAreaData
(
parent
)
*
this
=
other
;
{
*
this
=
other
;
}
}
WimaCorridorData
::
WimaCorridorData
(
const
WimaCorridor
&
other
,
QObject
*
parent
)
WimaCorridorData
::
WimaCorridorData
(
const
WimaCorridor
&
other
,
QObject
*
parent
)
:
WimaAreaData
(
parent
)
:
WimaAreaData
(
parent
)
{
{
*
this
=
other
;
*
this
=
other
;
}
}
/*!
/*!
...
@@ -25,11 +20,10 @@ WimaCorridorData::WimaCorridorData(const WimaCorridor &other, QObject *parent)
...
@@ -25,11 +20,10 @@ WimaCorridorData::WimaCorridorData(const WimaCorridor &other, QObject *parent)
*
*
* Assigns \a other to the invoking object.
* Assigns \a other to the invoking object.
*/
*/
WimaCorridorData
&
WimaCorridorData
::
operator
=
(
const
WimaCorridorData
&
other
)
WimaCorridorData
&
WimaCorridorData
::
operator
=
(
const
WimaCorridorData
&
other
)
{
{
this
->
assign
(
other
);
this
->
assign
(
other
);
return
*
this
;
return
*
this
;
}
}
/*!
/*!
...
@@ -37,36 +31,34 @@ WimaCorridorData &WimaCorridorData::operator=(const WimaCorridorData &other)
...
@@ -37,36 +31,34 @@ WimaCorridorData &WimaCorridorData::operator=(const WimaCorridorData &other)
*
*
* Assigns \a other to the invoking object.
* Assigns \a other to the invoking object.
*/
*/
WimaCorridorData
&
WimaCorridorData
::
operator
=
(
const
WimaCorridor
&
other
)
WimaCorridorData
&
WimaCorridorData
::
operator
=
(
const
WimaCorridor
&
other
)
{
{
this
->
assign
(
other
);
this
->
assign
(
other
);
return
*
this
;
return
*
this
;
}
}
QString
WimaCorridorData
::
type
()
const
QString
WimaCorridorData
::
mapVisualQML
()
const
{
{
return
QStringLiteral
(
"WimaAreaDataVisual.qml"
);
return
this
->
typeString
;
}
}
void
WimaCorridorData
::
assign
(
const
WimaCorridorData
&
corridorData
)
QString
WimaCorridorData
::
type
()
const
{
return
this
->
typeString
;
}
{
WimaAreaData
::
assign
(
corridorData
);
}
void
WimaCorridorData
::
assign
(
const
WimaCorridor
&
corridor
)
void
WimaCorridorData
::
assign
(
const
WimaCorridorData
&
corridorData
)
{
{
WimaAreaData
::
assign
(
corridorData
);
WimaAreaData
::
assign
(
corridor
);
}
}
void
WimaCorridorData
::
assign
(
const
WimaCorridor
&
corridor
)
{
WimaAreaData
::
assign
(
corridor
);
}
/*!
/*!
* \class WimaAreaData::WimaCorridorData
* \class WimaAreaData::WimaCorridorData
* \brief Class to store and exchange data of a \c WimaCorridorData Object.
* \brief Class to store and exchange data of a \c WimaCorridorData Object.
* Class to store and exchange data of a \c WimaCorridor Object. In contrast to \c WimaCorridor this class
* Class to store and exchange data of a \c WimaCorridor Object. In contrast to
* does not provied any interface to a grafical user interface, neiter it uses the QGC Fact System.
* \c WimaCorridor this class does not provied any interface to a grafical user
* It is designed to exchange data between the \c WimaPlaner and the \c WimaController class. And it
* interface, neiter it uses the QGC Fact System. It is designed to exchange
* is the derived from WimaAreaData.
* data between the \c WimaPlaner and the \c WimaController class. And it is the
* derived from WimaAreaData.
*
*
* \sa WimaCorridor, WimaAreaData
* \sa WimaCorridor, WimaAreaData
*/
*/
src/Wima/Geometry/WimaCorridorData.h
View file @
d1eac7fe
...
@@ -7,31 +7,30 @@
...
@@ -7,31 +7,30 @@
#include "QGeoCoordinate"
#include "QGeoCoordinate"
class
WimaCorridorData
:
public
WimaAreaData
class
WimaCorridorData
:
public
WimaAreaData
{
{
Q_OBJECT
Q_OBJECT
public:
public:
WimaCorridorData
(
QObject
*
parent
=
nullptr
);
WimaCorridorData
(
QObject
*
parent
=
nullptr
);
WimaCorridorData
(
const
WimaCorridorData
&
other
,
QObject
*
parent
=
nullptr
);
WimaCorridorData
(
const
WimaCorridorData
&
other
,
QObject
*
parent
=
nullptr
);
WimaCorridorData
(
const
WimaCorridor
&
other
,
QObject
*
parent
=
nullptr
);
WimaCorridorData
(
const
WimaCorridor
&
other
,
QObject
*
parent
=
nullptr
);
WimaCorridorData
&
operator
=
(
const
WimaCorridorData
&
other
);
WimaCorridorData
&
operator
=
(
const
WimaCorridorData
&
other
);
WimaCorridorData
&
operator
=
(
const
WimaCorridor
&
other
);
WimaCorridorData
&
operator
=
(
const
WimaCorridor
&
other
);
QString
type
()
const
;
virtual
QString
mapVisualQML
()
const
override
;
WimaCorridorData
*
Clone
()
const
{
return
new
WimaCorridorData
(
*
this
);}
static
const
char
*
typeString
;
QString
type
()
const
;
WimaCorridorData
*
Clone
()
const
{
return
new
WimaCorridorData
(
*
this
);
}
static
const
char
*
typeString
;
signals:
signals:
public
slots
:
public
slots
:
protected:
protected:
void
assign
(
const
WimaCorridorData
&
corridorData
);
void
assign
(
const
WimaCorridorData
&
corridorData
);
void
assign
(
const
WimaCorridor
&
corridor
);
void
assign
(
const
WimaCorridor
&
corridor
);
private:
private:
};
};
src/Wima/Geometry/WimaJoinedAreaData.cc
View file @
d1eac7fe
...
@@ -39,6 +39,10 @@ WimaJoinedAreaData &WimaJoinedAreaData::operator=(const WimaJoinedArea &other) {
...
@@ -39,6 +39,10 @@ WimaJoinedAreaData &WimaJoinedAreaData::operator=(const WimaJoinedArea &other) {
return
*
this
;
return
*
this
;
}
}
QString
WimaJoinedAreaData
::
mapVisualQML
()
const
{
return
QStringLiteral
(
"WimaJoinedAreaDataVisual.qml"
);
}
QString
WimaJoinedAreaData
::
type
()
const
{
return
this
->
typeString
;
}
QString
WimaJoinedAreaData
::
type
()
const
{
return
this
->
typeString
;
}
void
WimaJoinedAreaData
::
assign
(
const
WimaJoinedAreaData
&
other
)
{
void
WimaJoinedAreaData
::
assign
(
const
WimaJoinedAreaData
&
other
)
{
...
...
src/Wima/Geometry/WimaJoinedAreaData.h
View file @
d1eac7fe
...
@@ -7,26 +7,27 @@
...
@@ -7,26 +7,27 @@
#include "QGeoCoordinate"
#include "QGeoCoordinate"
class
WimaJoinedAreaData
:
public
WimaAreaData
class
WimaJoinedAreaData
:
public
WimaAreaData
{
{
Q_OBJECT
Q_OBJECT
public:
public:
WimaJoinedAreaData
(
QObject
*
parent
=
nullptr
);
WimaJoinedAreaData
(
QObject
*
parent
=
nullptr
);
WimaJoinedAreaData
(
const
WimaJoinedAreaData
&
other
,
QObject
*
parent
=
nullptr
);
WimaJoinedAreaData
(
const
WimaJoinedAreaData
&
other
,
WimaJoinedAreaData
(
const
WimaJoinedArea
&
other
,
QObject
*
parent
=
nullptr
);
QObject
*
parent
=
nullptr
);
WimaJoinedAreaData
&
operator
=
(
const
WimaJoinedAreaData
&
other
);
WimaJoinedAreaData
(
const
WimaJoinedArea
&
other
,
QObject
*
parent
=
nullptr
);
WimaJoinedAreaData
&
operator
=
(
const
WimaJoinedArea
&
other
);
WimaJoinedAreaData
&
operator
=
(
const
WimaJoinedAreaData
&
other
);
WimaJoinedAreaData
&
operator
=
(
const
WimaJoinedArea
&
other
);
QString
type
()
const
;
virtual
QString
mapVisualQML
()
const
override
;
WimaJoinedAreaData
*
Clone
()
const
{
return
new
WimaJoinedAreaData
(
*
this
);}
static
const
char
*
typeString
;
QString
type
()
const
;
WimaJoinedAreaData
*
Clone
()
const
{
return
new
WimaJoinedAreaData
(
*
this
);
}
static
const
char
*
typeString
;
protected:
protected:
void
assign
(
const
WimaJoinedAreaData
&
other
);
void
assign
(
const
WimaJoinedAreaData
&
other
);
void
assign
(
const
WimaJoinedArea
&
other
);
void
assign
(
const
WimaJoinedArea
&
other
);
private:
private:
};
};
src/Wima/Geometry/WimaMeasurementAreaData.cc
View file @
d1eac7fe
...
@@ -30,6 +30,20 @@ operator!=(const WimaMeasurementAreaData &other) const {
...
@@ -30,6 +30,20 @@ operator!=(const WimaMeasurementAreaData &other) const {
return
!
(
*
this
==
other
);
return
!
(
*
this
==
other
);
}
}
void
WimaMeasurementAreaData
::
setTileData
(
const
TileData
&
d
)
{
if
(
this
->
_tileData
!=
d
)
{
this
->
_tileData
=
d
;
emit
tileDataChanged
();
}
}
void
WimaMeasurementAreaData
::
setProgress
(
const
QVector
<
int
>
&
d
)
{
if
(
this
->
_progress
!=
d
)
{
this
->
_progress
=
d
;
emit
progressChanged
();
}
}
/*!
/*!
* \overload operator=();
* \overload operator=();
*
*
...
@@ -54,6 +68,10 @@ operator=(const WimaMeasurementArea &other) {
...
@@ -54,6 +68,10 @@ operator=(const WimaMeasurementArea &other) {
return
*
this
;
return
*
this
;
}
}
QString
WimaMeasurementAreaData
::
mapVisualQML
()
const
{
return
QStringLiteral
(
"WimaMeasurementAreaDataVisual.qml"
);
}
QString
WimaMeasurementAreaData
::
type
()
const
{
return
this
->
typeString
;
}
QString
WimaMeasurementAreaData
::
type
()
const
{
return
this
->
typeString
;
}
QmlObjectListModel
*
WimaMeasurementAreaData
::
tiles
()
{
QmlObjectListModel
*
WimaMeasurementAreaData
::
tiles
()
{
...
@@ -86,15 +104,15 @@ QVector<int> &WimaMeasurementAreaData::progress() { return this->_progress; }
...
@@ -86,15 +104,15 @@ QVector<int> &WimaMeasurementAreaData::progress() { return this->_progress; }
void
WimaMeasurementAreaData
::
assign
(
const
WimaMeasurementAreaData
&
other
)
{
void
WimaMeasurementAreaData
::
assign
(
const
WimaMeasurementAreaData
&
other
)
{
WimaAreaData
::
assign
(
other
);
WimaAreaData
::
assign
(
other
);
this
->
_tileData
=
other
.
_tileData
;
setTileData
(
other
.
_tileData
)
;
this
->
_progress
=
other
.
_progress
;
setProgress
(
other
.
_progress
)
;
}
}
void
WimaMeasurementAreaData
::
assign
(
const
WimaMeasurementArea
&
other
)
{
void
WimaMeasurementAreaData
::
assign
(
const
WimaMeasurementArea
&
other
)
{
WimaAreaData
::
assign
(
other
);
WimaAreaData
::
assign
(
other
);
if
(
other
.
ready
())
{
if
(
other
.
ready
())
{
this
->
_tileData
=
other
.
tileData
(
);
setTileData
(
other
.
tileData
()
);
this
->
_progress
=
other
.
progress
(
);
setProgress
(
other
.
progress
()
);
}
else
{
}
else
{
qWarning
()
qWarning
()
<<
"WimaMeasurementAreaData::assign(): WimaMeasurementArea not ready."
;
<<
"WimaMeasurementAreaData::assign(): WimaMeasurementArea not ready."
;
...
...
src/Wima/Geometry/WimaMeasurementAreaData.h
View file @
d1eac7fe
...
@@ -18,14 +18,23 @@ public:
...
@@ -18,14 +18,23 @@ public:
WimaMeasurementAreaData
&
operator
=
(
const
WimaMeasurementAreaData
&
other
);
WimaMeasurementAreaData
&
operator
=
(
const
WimaMeasurementAreaData
&
other
);
WimaMeasurementAreaData
&
operator
=
(
const
WimaMeasurementArea
&
other
);
WimaMeasurementAreaData
&
operator
=
(
const
WimaMeasurementArea
&
other
);
Q_PROPERTY
(
QmlObjectListModel
*
tiles
READ
tiles
NOTIFY
tileDataChanged
)
Q_PROPERTY
(
QVector
<
int
>
progress
READ
progress
NOTIFY
progressChanged
)
virtual
QString
mapVisualQML
()
const
override
;
bool
operator
==
(
const
WimaMeasurementAreaData
&
other
)
const
;
bool
operator
==
(
const
WimaMeasurementAreaData
&
other
)
const
;
bool
operator
!=
(
const
WimaMeasurementAreaData
&
other
)
const
;
bool
operator
!=
(
const
WimaMeasurementAreaData
&
other
)
const
;
// Property setters.
void
setTileData
(
const
TileData
&
d
);
void
setProgress
(
const
QVector
<
int
>
&
d
);
// Property getters.
QString
type
()
const
;
QString
type
()
const
;
WimaMeasurementAreaData
*
Clone
()
const
{
WimaMeasurementAreaData
*
Clone
()
const
{
return
new
WimaMeasurementAreaData
(
*
this
);
return
new
WimaMeasurementAreaData
(
*
this
);
}
}
QmlObjectListModel
*
tiles
();
QmlObjectListModel
*
tiles
();
const
QmlObjectListModel
*
tiles
()
const
;
const
QmlObjectListModel
*
tiles
()
const
;
const
QVariantList
&
tileCenterPoints
()
const
;
const
QVariantList
&
tileCenterPoints
()
const
;
...
@@ -37,6 +46,10 @@ public:
...
@@ -37,6 +46,10 @@ public:
static
const
char
*
typeString
;
static
const
char
*
typeString
;
signals:
void
tileDataChanged
();
void
progressChanged
();
protected:
protected:
void
assign
(
const
WimaMeasurementAreaData
&
other
);
void
assign
(
const
WimaMeasurementAreaData
&
other
);
void
assign
(
const
WimaMeasurementArea
&
other
);
void
assign
(
const
WimaMeasurementArea
&
other
);
...
...
src/Wima/Geometry/WimaServiceAreaData.cc
View file @
d1eac7fe
...
@@ -31,6 +31,10 @@ operator=(const WimaServiceArea &otherArea) {
...
@@ -31,6 +31,10 @@ operator=(const WimaServiceArea &otherArea) {
return
*
this
;
return
*
this
;
}
}
QString
WimaServiceAreaData
::
mapVisualQML
()
const
{
return
QStringLiteral
(
"WimaServiceAreaDataVisual.qml"
);
}
/*!
/*!
* \fn const QGeoCoordinate &WimaServiceAreaData::takeOffPosition() const
* \fn const QGeoCoordinate &WimaServiceAreaData::takeOffPosition() const
* Returns a constant reference to the takeOffPosition.
* Returns a constant reference to the takeOffPosition.
...
...
src/Wima/Geometry/WimaServiceAreaData.h
View file @
d1eac7fe
...
@@ -17,6 +17,8 @@ public:
...
@@ -17,6 +17,8 @@ public:
WimaServiceAreaData
&
operator
=
(
const
WimaServiceAreaData
&
otherData
);
WimaServiceAreaData
&
operator
=
(
const
WimaServiceAreaData
&
otherData
);
WimaServiceAreaData
&
operator
=
(
const
WimaServiceArea
&
otherArea
);
WimaServiceAreaData
&
operator
=
(
const
WimaServiceArea
&
otherArea
);
virtual
QString
mapVisualQML
()
const
override
;
const
QGeoCoordinate
&
depot
()
const
;
const
QGeoCoordinate
&
depot
()
const
;
QString
type
()
const
;
QString
type
()
const
;
...
...
src/Wima/Snake/SnakeTile.cpp
View file @
d1eac7fe
...
@@ -9,6 +9,10 @@ SnakeTile::SnakeTile(const SnakeTile &other, QObject *parent)
...
@@ -9,6 +9,10 @@ SnakeTile::SnakeTile(const SnakeTile &other, QObject *parent)
SnakeTile
::~
SnakeTile
()
{}
SnakeTile
::~
SnakeTile
()
{}
QString
SnakeTile
::
mapVisualQML
()
const
{
return
QStringLiteral
(
"WimaAreaNoVisual.qml"
);
}
QString
SnakeTile
::
type
()
const
{
return
"Tile"
;
}
QString
SnakeTile
::
type
()
const
{
return
"Tile"
;
}
SnakeTile
*
SnakeTile
::
Clone
()
const
{
return
new
SnakeTile
(
*
this
);
}
SnakeTile
*
SnakeTile
::
Clone
()
const
{
return
new
SnakeTile
(
*
this
);
}
...
...
src/Wima/Snake/SnakeTile.h
View file @
d1eac7fe
...
@@ -9,6 +9,8 @@ public:
...
@@ -9,6 +9,8 @@ public:
SnakeTile
(
const
SnakeTile
&
other
,
QObject
*
parent
=
nullptr
);
SnakeTile
(
const
SnakeTile
&
other
,
QObject
*
parent
=
nullptr
);
~
SnakeTile
();
~
SnakeTile
();
virtual
QString
mapVisualQML
()
const
override
;
QString
type
()
const
override
;
QString
type
()
const
override
;
SnakeTile
*
Clone
()
const
;
SnakeTile
*
Clone
()
const
;
...
...
src/Wima/Snake/WimaAreaNoVisual.qml
0 → 100644
View file @
d1eac7fe
import
QtQuick
2.3
Item
{
id
:
_root
property
var
map
///< Map control to place item in
property
var
qgcView
///< QGCView to use for popping dialogs
Component.onCompleted
:
{
console
.
log
(
"
WimaAreaNoVisual.qml is a place holder and not meant to be instanciated.
"
)
}
}
src/Wima/StateMachine.cpp
View file @
d1eac7fe
...
@@ -253,7 +253,7 @@ void StateMachine::setState(STATE s) {
...
@@ -253,7 +253,7 @@ void StateMachine::setState(STATE s) {
emit
upToDateChanged
();
emit
upToDateChanged
();
}
}
if
(
surveyReady
(
oldState
)
!=
surveyReady
(
s
))
{
if
(
surveyReady
(
oldState
)
!=
surveyReady
(
s
))
{
emit
surveyReady
();
emit
surveyReady
Changed
();
}
}
qCDebug
(
WimaPlanerLog
)
<<
"StateMachine::setState():"
<<
oldState
<<
"->"
qCDebug
(
WimaPlanerLog
)
<<
"StateMachine::setState():"
<<
oldState
<<
"->"
<<
s
;
<<
s
;
...
...
src/Wima/WaypointManager/EmptyManager.cpp
0 → 100644
View file @
d1eac7fe
#include "EmptyManager.h"
namespace
WaypointManager
{
WaypointManager
::
EmptyManager
::
EmptyManager
(
Settings
&
settings
,
AreaInterface
&
)
:
ManagerBase
(
settings
)
{}
void
WaypointManager
::
EmptyManager
::
clear
()
{}
bool
WaypointManager
::
EmptyManager
::
update
()
{}
bool
WaypointManager
::
EmptyManager
::
next
()
{}
bool
WaypointManager
::
EmptyManager
::
previous
()
{}
bool
WaypointManager
::
EmptyManager
::
reset
()
{}
}
// namespace WaypointManager
src/Wima/WaypointManager/EmptyManager.h
0 → 100644
View file @
d1eac7fe
#pragma once
#include <QGeoCoordinate>
#include <QVector>
#include "AreaInterface.h"
#include "GenericWaypointManager.h"
#include "QmlObjectListModel.h"
#include "Settings.h"
namespace
WaypointManager
{
typedef
GenericWaypointManager
<
QGeoCoordinate
,
QVector
,
QmlObjectListModel
,
Settings
>
ManagerBase
;
//!
//! \brief The EmptyManager is a place holder and does noting.
class
EmptyManager
:
public
ManagerBase
{
public:
EmptyManager
()
=
delete
;
EmptyManager
(
Settings
&
settings
,
AreaInterface
&
);
void
clear
()
override
;
virtual
bool
update
()
override
;
virtual
bool
next
()
override
;
virtual
bool
previous
()
override
;
virtual
bool
reset
()
override
;
};
}
// namespace WaypointManager
src/Wima/WimaController.cc
View file @
d1eac7fe
This diff is collapsed.
Click to expand it.
src/Wima/WimaController.h
View file @
d1eac7fe
...
@@ -18,7 +18,7 @@
...
@@ -18,7 +18,7 @@
#include "RoutingThread.h"
#include "RoutingThread.h"
#include "Snake/NemoInterface.h"
#include "Snake/NemoInterface.h"
#include "WaypointManager/
Default
Manager.h"
#include "WaypointManager/
Empty
Manager.h"
#include "WaypointManager/RTLManager.h"
#include "WaypointManager/RTLManager.h"
#include "utilities.h"
#include "utilities.h"
...
@@ -42,42 +42,13 @@ public:
...
@@ -42,42 +42,13 @@ public:
visualItemsChanged
)
visualItemsChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
missionItems
READ
missionItems
NOTIFY
Q_PROPERTY
(
QmlObjectListModel
*
missionItems
READ
missionItems
NOTIFY
missionItemsChanged
)
missionItemsChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
currentMissionItems
READ
currentMissionItems
NOTIFY
currentMissionItemsChanged
)
Q_PROPERTY
(
Q_PROPERTY
(
QVariantList
waypointPath
READ
waypointPath
NOTIFY
waypointPathChanged
)
QVariantList
waypointPath
READ
waypointPath
NOTIFY
waypointPathChanged
)
Q_PROPERTY
(
QVariantList
currentWaypointPath
READ
currentWaypointPath
NOTIFY
currentWaypointPathChanged
)
Q_PROPERTY
(
Fact
*
enableWimaController
READ
enableWimaController
CONSTANT
)
Q_PROPERTY
(
Fact
*
enableWimaController
READ
enableWimaController
CONSTANT
)
// Waypoint navigaton.
// Waypoint navigaton.
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
)
// Waypoint settings.
Q_PROPERTY
(
Fact
*
flightSpeed
READ
flightSpeed
CONSTANT
)
Q_PROPERTY
(
Fact
*
flightSpeed
READ
flightSpeed
CONSTANT
)
Q_PROPERTY
(
Fact
*
altitude
READ
altitude
CONSTANT
)
Q_PROPERTY
(
Fact
*
altitude
READ
altitude
CONSTANT
)
Q_PROPERTY
(
Fact
*
arrivalReturnSpeed
READ
arrivalReturnSpeed
CONSTANT
)
// Waypoint statistics.
Q_PROPERTY
(
double
phaseDistance
READ
phaseDistance
NOTIFY
phaseDistanceChanged
)
Q_PROPERTY
(
double
phaseDuration
READ
phaseDuration
NOTIFY
phaseDurationChanged
)
// Snake
Q_PROPERTY
(
int
nemoStatus
READ
nemoStatus
NOTIFY
nemoStatusChanged
)
Q_PROPERTY
(
QString
nemoStatusString
READ
nemoStatusString
NOTIFY
nemoStatusStringChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
snakeTiles
READ
snakeTiles
NOTIFY
snakeTilesChanged
)
Q_PROPERTY
(
QVariantList
snakeTileCenterPoints
READ
snakeTileCenterPoints
NOTIFY
snakeTilesChanged
)
Q_PROPERTY
(
QVector
<
int
>
nemoProgress
READ
nemoProgress
NOTIFY
nemoProgressChanged
)
// Property accessors
// Controllers.
// Controllers.
PlanMasterController
*
masterController
(
void
);
PlanMasterController
*
masterController
(
void
);
MissionController
*
missionController
(
void
);
MissionController
*
missionController
(
void
);
...
@@ -86,31 +57,14 @@ public:
...
@@ -86,31 +57,14 @@ public:
QGCMapPolygon
joinedArea
(
void
)
const
;
QGCMapPolygon
joinedArea
(
void
)
const
;
// Waypoints.
// Waypoints.
QmlObjectListModel
*
missionItems
(
void
);
QmlObjectListModel
*
missionItems
(
void
);
QmlObjectListModel
*
currentMissionItems
(
void
);
QVariantList
waypointPath
(
void
);
QVariantList
waypointPath
(
void
);
QVariantList
currentWaypointPath
(
void
);
// Settings facts.
// Settings facts.
Fact
*
enableWimaController
(
void
);
Fact
*
enableWimaController
(
void
);
Fact
*
overlapWaypoints
(
void
);
Fact
*
maxWaypointsPerPhase
(
void
);
Fact
*
startWaypointIndex
(
void
);
Fact
*
showAllMissionItems
(
void
);
Fact
*
showCurrentMissionItems
(
void
);
Fact
*
flightSpeed
(
void
);
Fact
*
flightSpeed
(
void
);
Fact
*
arrivalReturnSpeed
(
void
);
Fact
*
altitude
(
void
);
Fact
*
altitude
(
void
);
// Snake data.
QmlObjectListModel
*
snakeTiles
(
void
);
QVariantList
snakeTileCenterPoints
(
void
);
QVector
<
int
>
nemoProgress
(
void
);
int
nemoStatus
(
void
)
const
;
QString
nemoStatusString
(
void
)
const
;
bool
uploadOverrideRequired
(
void
)
const
;
bool
uploadOverrideRequired
(
void
)
const
;
bool
vehicleHasLowBattery
(
void
)
const
;
bool
vehicleHasLowBattery
(
void
)
const
;
// Waypoint statistics.
double
phaseDistance
(
void
)
const
;
double
phaseDuration
(
void
)
const
;
// Property setters
// Property setters
void
setMasterController
(
PlanMasterController
*
masterController
);
void
setMasterController
(
PlanMasterController
*
masterController
);
...
@@ -119,10 +73,6 @@ public:
...
@@ -119,10 +73,6 @@ public:
// Member Methodes
// Member Methodes
Q_INVOKABLE
WimaController
*
thisPointer
();
Q_INVOKABLE
WimaController
*
thisPointer
();
// Waypoint navigation.
Q_INVOKABLE
void
nextPhase
();
Q_INVOKABLE
void
previousPhase
();
Q_INVOKABLE
void
resetPhase
();
// Smart RTL.
// Smart RTL.
Q_INVOKABLE
void
requestSmartRTL
();
Q_INVOKABLE
void
requestSmartRTL
();
Q_INVOKABLE
void
initSmartRTL
();
Q_INVOKABLE
void
initSmartRTL
();
...
@@ -137,15 +87,8 @@ public:
...
@@ -137,15 +87,8 @@ public:
static
const
char
*
areaItemsName
;
static
const
char
*
areaItemsName
;
static
const
char
*
missionItemsName
;
static
const
char
*
missionItemsName
;
static
const
char
*
settingsGroup
;
static
const
char
*
settingsGroup
;
static
const
char
*
endWaypointIndexName
;
static
const
char
*
enableWimaControllerName
;
static
const
char
*
enableWimaControllerName
;
static
const
char
*
overlapWaypointsName
;
static
const
char
*
maxWaypointsPerPhaseName
;
static
const
char
*
startWaypointIndexName
;
static
const
char
*
showAllMissionItemsName
;
static
const
char
*
showCurrentMissionItemsName
;
static
const
char
*
flightSpeedName
;
static
const
char
*
flightSpeedName
;
static
const
char
*
arrivalReturnSpeedName
;
static
const
char
*
altitudeName
;
static
const
char
*
altitudeName
;
signals:
signals:
...
@@ -156,42 +99,20 @@ signals:
...
@@ -156,42 +99,20 @@ signals:
void
visualItemsChanged
(
void
);
void
visualItemsChanged
(
void
);
// Waypoints.
// Waypoints.
void
missionItemsChanged
(
void
);
void
missionItemsChanged
(
void
);
void
currentMissionItemsChanged
(
void
);
void
waypointPathChanged
(
void
);
void
waypointPathChanged
(
void
);
void
currentWaypointPathChanged
(
void
);
// Smart RTL.
// Smart RTL.
void
smartRTLRequestConfirm
(
void
);
void
smartRTLRequestConfirm
(
void
);
void
smartRTLPathConfirm
(
void
);
void
smartRTLPathConfirm
(
void
);
// Upload.
// Upload.
void
forceUploadConfirm
(
void
);
void
forceUploadConfirm
(
void
);
// Waypoint statistics.
void
phaseDistanceChanged
(
void
);
void
phaseDurationChanged
(
void
);
// Snake.
void
snakeTilesChanged
(
void
);
void
nemoProgressChanged
(
void
);
void
nemoStatusChanged
(
void
);
void
nemoStatusStringChanged
(
void
);
private
slots
:
private
slots
:
// Waypoint navigation / helper.
bool
_calcNextPhase
(
void
);
void
_recalcCurrentPhase
(
void
);
bool
_calcShortestPath
(
const
QGeoCoordinate
&
start
,
bool
_calcShortestPath
(
const
QGeoCoordinate
&
start
,
const
QGeoCoordinate
&
destination
,
const
QGeoCoordinate
&
destination
,
QVector
<
QGeoCoordinate
>
&
path
);
QVector
<
QGeoCoordinate
>
&
path
);
// Slicing parameters
bool
_setStartIndex
(
void
);
void
_updateOverlap
(
void
);
void
_updateMaxWaypoints
(
void
);
// Waypoint settings.
void
_updateflightSpeed
(
void
);
void
_updateflightSpeed
(
void
);
void
_updateArrivalReturnSpeed
(
void
);
void
_updateAltitude
(
void
);
void
_updateAltitude
(
void
);
// Waypoint Statistics.
void
_setPhaseDistance
(
double
distance
);
void
_setPhaseDuration
(
double
duration
);
// SMART RTL
// SMART RTL
void
_checkBatteryLevel
(
void
);
void
_checkBatteryLevel
(
void
);
bool
_SRTLPrecondition
(
QString
&
errorString
);
bool
_SRTLPrecondition
(
QString
&
errorString
);
...
@@ -219,7 +140,7 @@ private:
...
@@ -219,7 +140,7 @@ private:
// Waypoint Managers.
// Waypoint Managers.
WaypointManager
::
AreaInterface
_areaInterface
;
WaypointManager
::
AreaInterface
_areaInterface
;
WaypointManager
::
Settings
_WMSettings
;
// Waypoint Manager Settings
WaypointManager
::
Settings
_WMSettings
;
// Waypoint Manager Settings
WaypointManager
::
DefaultManager
_default
WM
;
WaypointManager
::
EmptyManager
_empty
WM
;
WaypointManager
::
RTLManager
_rtlWM
;
WaypointManager
::
RTLManager
_rtlWM
;
WaypointManager
::
ManagerBase
*
_currentWM
;
WaypointManager
::
ManagerBase
*
_currentWM
;
using
ManagerList
=
QList
<
WaypointManager
::
ManagerBase
*>
;
using
ManagerList
=
QList
<
WaypointManager
::
ManagerBase
*>
;
...
@@ -230,34 +151,13 @@ private:
...
@@ -230,34 +151,13 @@ private:
SettingsFact
_enableWimaController
;
// enables or disables the wimaControler
SettingsFact
_enableWimaController
;
// enables or disables the wimaControler
// determines the number of overlapping waypoints between two consecutive
// determines the number of overlapping waypoints between two consecutive
// mission phases
// mission phases
SettingsFact
_overlapWaypoints
;
SettingsFact
_flightSpeed
;
// mission flight speed
// determines the maximum number waypoints per phase
SettingsFact
_altitude
;
// mission altitude
SettingsFact
_maxWaypointsPerPhase
;
SettingsFact
_nextPhaseStartWaypointIndex
;
// 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.
SettingsFact
_flightSpeed
;
// mission flight speed
SettingsFact
_arrivalReturnSpeed
;
// arrival and return path speed
SettingsFact
_altitude
;
// mission altitude
// Smart RTL.
// Smart RTL.
QTimer
_smartRTLTimer
;
QTimer
_smartRTLTimer
;
bool
_lowBatteryHandlingTriggered
;
bool
_lowBatteryHandlingTriggered
;
// Waypoint statistics.
double
_measurementPathLength
;
// the lenght of the phase in meters
using
StatusMap
=
std
::
map
<
int
,
QString
>
;
static
StatusMap
_nemoStatusMap
;
// Periodic tasks.
// Periodic tasks.
QTimer
_eventTimer
;
QTimer
_eventTimer
;
EventTicker
_batteryLevelTicker
;
EventTicker
_batteryLevelTicker
;
...
...
src/WimaView/CircularSurveyMapVisual.qml
View file @
d1eac7fe
...
@@ -37,28 +37,28 @@ Item {
...
@@ -37,28 +37,28 @@ Item {
function
_addTransectsComponent
(){
function
_addTransectsComponent
(){
if
(
!
_transectsComponent
){
if
(
!
_transectsComponent
){
_transectsComponent
=
visualTransectsComponent
.
createObject
(
map
)
_transectsComponent
=
visualTransectsComponent
.
createObject
(
_root
)
map
.
addMapItem
(
_transectsComponent
)
map
.
addMapItem
(
_transectsComponent
)
}
}
}
}
function
_addExitCoordinate
(){
function
_addExitCoordinate
(){
if
(
!
_exitCoordinate
){
if
(
!
_exitCoordinate
){
_exitCoordinate
=
exitPointComponent
.
createObject
(
map
)
_exitCoordinate
=
exitPointComponent
.
createObject
(
_root
)
map
.
addMapItem
(
_exitCoordinate
)
map
.
addMapItem
(
_exitCoordinate
)
}
}
}
}
function
_addEntryCoordinate
(){
function
_addEntryCoordinate
(){
if
(
!
_entryCoordinate
){
if
(
!
_entryCoordinate
){
_entryCoordinate
=
entryPointComponent
.
createObject
(
map
)
_entryCoordinate
=
entryPointComponent
.
createObject
(
_root
)
map
.
addMapItem
(
_entryCoordinate
)
map
.
addMapItem
(
_entryCoordinate
)
}
}
}
}
function
_addRefPoint
(){
function
_addRefPoint
(){
if
(
!
_refPoint
){
if
(
!
_refPoint
){
_refPoint
=
refPointComponent
.
createObject
(
map
)
_refPoint
=
refPointComponent
.
createObject
(
_root
)
map
.
addMapItem
(
_refPoint
)
map
.
addMapItem
(
_refPoint
)
}
}
}
}
...
...
src/WimaView/WimaCorridorDataVisual.qml
0 → 100644
View file @
d1eac7fe
import
QtQuick
2.3
import
QtQuick
.
Controls
1.2
import
QtLocation
5.3
import
QtPositioning
5.3
import
QGroundControl
1.0
import
QGroundControl
.
ScreenTools
1.0
import
QGroundControl
.
Palette
1.0
import
QGroundControl
.
Controls
1.0
import
QGroundControl
.
FlightMap
1.0
/// Wima Measurement Area Data visuals
Item
{
id
:
_root
property
var
map
///< Map control to place item in
property
var
qgcView
///< QGCView to use for popping dialogs
property
var
areaItem
:
object
signal
clicked
(
int
sequenceNumber
)
property
var
_polygonComponent
function
_addPolygon
(){
if
(
!
_polygonComponent
){
_polygonComponent
=
polygon
.
createObject
(
_root
)
map
.
addMapItem
(
_polygonComponent
)
}
}
function
_destroyPolygon
(){
if
(
_polygonComponent
){
map
.
removeMapItem
(
_polygonComponent
)
_polygonComponent
.
destroy
()
}
}
Component.onCompleted
:
{
_addPolygon
()
}
Component.onDestruction
:
{
_destroyPolygon
()
}
// Polygon component.
Component
{
id
:
polygon
MapPolygon
{
path
:
object
.
path
;
border.color
:
"
black
"
color
:
"
blue
"
opacity
:
0.25
}
}
}
src/WimaView/WimaJoinedAreaDataVisual.qml
0 → 100644
View file @
d1eac7fe
import
QtQuick
2.3
import
QtQuick
.
Controls
1.2
import
QtLocation
5.3
import
QtPositioning
5.3
import
QGroundControl
1.0
import
QGroundControl
.
ScreenTools
1.0
import
QGroundControl
.
Palette
1.0
import
QGroundControl
.
Controls
1.0
import
QGroundControl
.
FlightMap
1.0
/// Wima Measurement Area Data visuals
Item
{
id
:
_root
property
var
map
///< Map control to place item in
property
var
qgcView
///< QGCView to use for popping dialogs
property
var
areaItem
:
object
signal
clicked
(
int
sequenceNumber
)
property
var
_polygonComponent
function
_addPolygon
(){
if
(
!
_polygonComponent
){
_polygonComponent
=
polygon
.
createObject
(
_root
)
map
.
addMapItem
(
_polygonComponent
)
}
}
function
_destroyPolygon
(){
if
(
_polygonComponent
){
map
.
removeMapItem
(
_polygonComponent
)
_polygonComponent
.
destroy
()
}
}
Component.onCompleted
:
{
_addPolygon
()
}
Component.onDestruction
:
{
_destroyPolygon
()
}
// Polygon component.
Component
{
id
:
polygon
MapPolygon
{
path
:
object
.
path
;
border.color
:
"
black
"
color
:
"
gray
"
opacity
:
0.25
}
}
}
src/WimaView/WimaMeasurementAreaDataVisual.qml
0 → 100644
View file @
d1eac7fe
import
QtQuick
2.3
import
QtQuick
.
Controls
1.2
import
QtLocation
5.3
import
QtPositioning
5.3
import
QGroundControl
1.0
import
QGroundControl
.
ScreenTools
1.0
import
QGroundControl
.
Palette
1.0
import
QGroundControl
.
Controls
1.0
import
QGroundControl
.
FlightMap
1.0
/// Wima Measurement Area Data visuals
Item
{
id
:
_root
property
var
map
///< Map control to place item in
property
var
qgcView
///< QGCView to use for popping dialogs
property
var
areaItem
:
object
signal
clicked
(
int
sequenceNumber
)
property
var
_polygonComponent
function
_addPolygon
(){
if
(
!
_polygonComponent
){
_polygonComponent
=
polygon
.
createObject
(
_root
)
map
.
addMapItem
(
_polygonComponent
)
}
}
function
_destroyPolygon
(){
if
(
_polygonComponent
){
map
.
removeMapItem
(
_polygonComponent
)
_polygonComponent
.
destroy
()
}
}
Component.onCompleted
:
{
_addPolygon
()
}
Component.onDestruction
:
{
_destroyPolygon
()
}
// Add tiles.
Repeater
{
id
:
progressRepeater
model
:
areaItem
.
tiles
Item
{
property
var
_tileComponent
property
int
_progress
:
_root
.
areaItem
.
progress
[
index
]
?
_root
.
areaItem
.
progress
[
index
]
:
0
Component.onCompleted
:
{
_tileComponent
=
tileComponent
.
createObject
(
map
)
_tileComponent
.
polygon
.
path
=
Qt
.
binding
(
function
(){
return
object
.
path
})
_tileComponent
.
polygon
.
opacity
=
0.6
_tileComponent
.
polygon
.
border
.
color
=
"
black
"
_tileComponent
.
polygon
.
border
.
width
=
1
_tileComponent
.
polygon
.
color
=
Qt
.
binding
(
function
(){
return
getColor
(
_progress
)})
}
Component.onDestruction
:
{
_tileComponent
.
destroy
()
}
}
}
// Polygon component.
Component
{
id
:
polygon
MapPolygon
{
path
:
object
.
path
;
border.color
:
"
black
"
color
:
"
green
"
opacity
:
0.25
}
}
// Tile component.
Component
{
id
:
tileComponent
Item
{
id
:
root
property
MapPolygon
polygon
MapPolygon
{
id
:
mapPolygon
path
:
[]
}
Component.onCompleted
:
{
polygon
=
mapPolygon
map
.
addMapItem
(
mapPolygon
)
}
Component.onDestruction
:
{
map
.
removeMapItem
(
mapPolygon
)
}
}
}
function
getColor
(
progress
)
{
if
(
progress
===
0
)
return
"
transparent
"
if
(
progress
<
33
)
return
"
orange
"
if
(
progress
<
66
)
return
"
yellow
"
if
(
progress
<
100
)
return
"
greenyellow
"
return
"
limegreen
"
}
}
src/WimaView/WimaServiceAreaDataVisual.qml
0 → 100644
View file @
d1eac7fe
import
QtQuick
2.3
import
QtQuick
.
Controls
1.2
import
QtLocation
5.3
import
QtPositioning
5.3
import
QGroundControl
1.0
import
QGroundControl
.
ScreenTools
1.0
import
QGroundControl
.
Palette
1.0
import
QGroundControl
.
Controls
1.0
import
QGroundControl
.
FlightMap
1.0
/// Wima Measurement Area Data visuals
Item
{
id
:
_root
property
var
map
///< Map control to place item in
property
var
qgcView
///< QGCView to use for popping dialogs
property
var
areaItem
:
object
signal
clicked
(
int
sequenceNumber
)
property
var
_polygonComponent
function
_addPolygon
(){
if
(
!
_polygonComponent
){
_polygonComponent
=
polygon
.
createObject
(
_root
)
map
.
addMapItem
(
_polygonComponent
)
}
}
function
_destroyPolygon
(){
if
(
_polygonComponent
){
map
.
removeMapItem
(
_polygonComponent
)
_polygonComponent
.
destroy
()
}
}
Component.onCompleted
:
{
_addPolygon
()
}
Component.onDestruction
:
{
_destroyPolygon
()
}
// Polygon component.
Component
{
id
:
polygon
MapPolygon
{
path
:
object
.
path
;
border.color
:
"
black
"
color
:
"
yellow
"
opacity
:
0.25
}
}
}
src/WimaView/WimaToolBar.qml
View file @
d1eac7fe
...
@@ -356,7 +356,8 @@ Rectangle {
...
@@ -356,7 +356,8 @@ Rectangle {
QGCButton
{
QGCButton
{
id
:
uploadButton
id
:
uploadButton
text
:
qsTr
(
"
Upload
"
)
text
:
qsTr
(
"
Upload
"
)
enabled
:
true
enabled
:
wimaPlaner
?
wimaPlaner
.
readyForSynchronization
:
false
onClicked
:
{
onClicked
:
{
if
(
wimaPlaner
){
if
(
wimaPlaner
){
if
(
wimaPlaner
.
readyForSynchronization
)
{
if
(
wimaPlaner
.
readyForSynchronization
)
{
...
...
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