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
fd653f79
Commit
fd653f79
authored
Oct 11, 2019
by
Valentin Platzgummer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
adding currentMissionItems
parent
de01b189
Changes
5
Show whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
97 additions
and
16 deletions
+97
-16
qgroundcontrol.qrc
qgroundcontrol.qrc
+1
-1
FlightDisplayViewMap.qml
src/FlightDisplay/FlightDisplayViewMap.qml
+2
-2
MissionItemIndicator.qml
src/FlightMap/MapItems/MissionItemIndicator.qml
+2
-1
WimaPlanMapItems.qml
src/FlightMap/MapItems/WimaPlanMapItems.qml
+2
-1
WimaController.cc
src/Wima/WimaController.cc
+90
-11
No files found.
qgroundcontrol.qrc
View file @
fd653f79
...
@@ -228,7 +228,7 @@
...
@@ -228,7 +228,7 @@
<file alias="QGroundControl/Controls/WimaJoinedAreaMapVisual.qml">src/WimaView/WimaJoinedAreaMapVisual.qml</file>
<file alias="QGroundControl/Controls/WimaJoinedAreaMapVisual.qml">src/WimaView/WimaJoinedAreaMapVisual.qml</file>
<file alias="QGroundControl/Controls/WimaCorridorEditor.qml">src/WimaView/WimaCorridorEditor.qml</file>
<file alias="QGroundControl/Controls/WimaCorridorEditor.qml">src/WimaView/WimaCorridorEditor.qml</file>
<file alias="QGroundControl/FlightMap/WimaPlanMapItems.qml">src/FlightMap/MapItems/WimaPlanMapItems.qml</file>
<file alias="QGroundControl/FlightMap/WimaPlanMapItems.qml">src/FlightMap/MapItems/WimaPlanMapItems.qml</file>
<file alias="QGroundControl/
Controls
/WimaMissionItemMapVisual.qml">src/PlanView/WimaMissionItemMapVisual.qml</file>
<file alias="QGroundControl/
FlightMap
/WimaMissionItemMapVisual.qml">src/PlanView/WimaMissionItemMapVisual.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 @
fd653f79
...
@@ -215,7 +215,7 @@ FlightMap {
...
@@ -215,7 +215,7 @@ FlightMap {
largeMapView
:
_mainIsMap
largeMapView
:
_mainIsMap
wimaController
:
flightMap
.
wimaController
wimaController
:
flightMap
.
wimaController
z
:
QGroundControl
.
zOrderTrajectoryLines
-
1
z
:
QGroundControl
.
zOrderTrajectoryLines
-
1
color
:
"
gray
"
color
:
"
#B4808080
"
// gray with alpha #AARRGGBB
}
}
// Add trajectory points to the map
// Add trajectory points to the map
...
...
src/FlightMap/MapItems/MissionItemIndicator.qml
View file @
fd653f79
...
@@ -38,7 +38,8 @@ MapQuickItem {
...
@@ -38,7 +38,8 @@ MapQuickItem {
vehicleYaw
:
missionItem
.
missionVehicleYaw
vehicleYaw
:
missionItem
.
missionVehicleYaw
showGimbalYaw
:
!
isNaN
(
missionItem
.
missionGimbalYaw
)
showGimbalYaw
:
!
isNaN
(
missionItem
.
missionGimbalYaw
)
onClicked
:
_item
.
clicked
()
onClicked
:
_item
.
clicked
()
color
:
_item
.
color
color
:
_item
.
color
?
_item
.
color
:
checked
?
"
green
"
:
(
child
?
qgcPal
.
mapIndicatorChild
:
qgcPal
.
mapIndicator
)
property
bool
_isCurrentItem
:
missionItem
?
missionItem
.
isCurrentItem
:
false
property
bool
_isCurrentItem
:
missionItem
?
missionItem
.
isCurrentItem
:
false
}
}
...
...
src/FlightMap/MapItems/WimaPlanMapItems.qml
View file @
fd653f79
...
@@ -23,6 +23,7 @@ Item {
...
@@ -23,6 +23,7 @@ Item {
property
bool
largeMapView
///< true: map takes up entire view, false: map is in small window
property
bool
largeMapView
///< true: map takes up entire view, false: map is in small window
property
var
wimaController
property
var
wimaController
property
var
color
property
var
color
property
var
lineColor
:
color
property
var
_map
:
map
property
var
_map
:
map
property
var
_missionLineViewComponent
property
var
_missionLineViewComponent
...
@@ -68,7 +69,7 @@ Item {
...
@@ -68,7 +69,7 @@ Item {
MapPolyline
{
MapPolyline
{
line.width
:
3
line.width
:
3
line.color
:
"
gray
"
// Hack, can't get palette to work in here
line.color
:
lineColor
// Hack, can't get palette to work in here
z
:
QGroundControl
.
zOrderWaypointLines
z
:
QGroundControl
.
zOrderWaypointLines
path
:
wimaController
.
waypointPath
path
:
wimaController
.
waypointPath
}
}
...
...
src/Wima/WimaController.cc
View file @
fd653f79
...
@@ -12,6 +12,7 @@ WimaController::WimaController(QObject *parent)
...
@@ -12,6 +12,7 @@ WimaController::WimaController(QObject *parent)
,
_serviceArea
(
this
)
,
_serviceArea
(
this
)
,
_corridor
(
this
)
,
_corridor
(
this
)
,
_localPlanDataValid
(
false
)
,
_localPlanDataValid
(
false
)
,
_firstWaypointIndex
(
2
)
// starts with 2, 0 is home position, 1 is takeoff
{
{
}
}
...
@@ -141,6 +142,74 @@ QJsonDocument WimaController::saveToJson(FileType fileType)
...
@@ -141,6 +142,74 @@ QJsonDocument WimaController::saveToJson(FileType fileType)
return
QJsonDocument
();
return
QJsonDocument
();
}
}
bool
WimaController
::
calcShortestPath
(
const
QGeoCoordinate
&
start
,
const
QGeoCoordinate
&
destination
,
QList
<
QGeoCoordinate
>
&
path
)
{
using
namespace
GeoUtilities
;
using
namespace
PolygonCalculus
;
QList
<
QPointF
>
path2D
;
bool
retVal
=
PolygonCalculus
::
shortestPath
(
toQPolygonF
(
toCartesian2D
(
_joinedArea
.
coordinateList
(),
/*origin*/
start
)),
/*start point*/
QPointF
(
0
,
0
),
/*destination*/
toCartesian2D
(
destination
,
start
),
/*shortest path*/
path2D
);
path
.
append
(
toGeo
(
path2D
,
/*origin*/
start
));
return
retVal
;
}
bool
WimaController
::
extractCoordinateList
(
const
QmlObjectListModel
&
missionItems
,
QList
<
QGeoCoordinate
>
&
coordinateList
)
{
return
extractCoordinateList
(
missionItems
,
coordinateList
,
0
,
missionItems
.
count
()
-
1
);
}
bool
WimaController
::
extractCoordinateList
(
const
QmlObjectListModel
&
missionItems
,
QList
<
QGeoCoordinate
>
&
coordinateList
,
int
startIndex
,
int
endIndex
)
{
if
(
startIndex
>=
0
&&
startIndex
<
missionItems
.
count
()
&&
endIndex
>=
0
&&
endIndex
<
missionItems
.
count
())
{
if
(
startIndex
>
endIndex
)
{
if
(
!
extractCoordinateList
(
missionItems
,
coordinateList
,
startIndex
,
missionItems
.
count
()
-
1
))
return
false
;
if
(
!
extractCoordinateList
(
missionItems
,
coordinateList
,
0
,
endIndex
))
return
false
;
}
else
{
for
(
int
i
=
startIndex
;
i
<=
endIndex
;
i
++
)
{
const
MissionItem
*
mItem
=
qobject_cast
<
MissionItem
*>
(
missionItems
[
i
]);
if
(
mItem
==
nullptr
)
{
coordinateList
.
clear
();
return
false
;
}
coordinateList
.
append
(
mItem
->
coordinate
());
}
}
}
else
return
false
;
return
true
;
}
bool
WimaController
::
extractCoordinateList
(
const
QmlObjectListModel
&
missionItems
,
QVariantList
&
coordinateList
)
{
return
extractCoordinateList
(
missionItems
,
coordinateList
,
0
,
missionItems
.
count
()
-
1
);
}
bool
WimaController
::
extractCoordinateList
(
const
QmlObjectListModel
&
missionItems
,
QVariantList
&
coordinateList
,
int
startIndex
,
int
endIndex
)
{
QList
<
QGeoCoordinate
>
geoCoordintateList
;
bool
retValue
=
extractCoordinateList
(
missionItems
,
geoCoordintateList
,
startIndex
,
endIndex
);
if
(
!
retValue
)
return
false
;
for
(
auto
coordinate
:
geoCoordintateList
)
coordinateList
.
append
(
QVariant
::
fromValue
(
coordinate
));
return
true
;
}
/*!
/*!
* \fn void WimaController::containerDataValidChanged(bool valid)
* \fn void WimaController::containerDataValidChanged(bool valid)
* Pulls plan data generated by \c WimaPlaner from the \c _container if the data is valid (\a valid equals true).
* Pulls plan data generated by \c WimaPlaner from the \c _container if the data is valid (\a valid equals true).
...
@@ -254,25 +323,35 @@ void WimaController::containerDataValidChanged(bool valid)
...
@@ -254,25 +323,35 @@ void WimaController::containerDataValidChanged(bool valid)
#endif
#endif
}
}
void
WimaController
::
update
WaypointPath
()
void
WimaController
::
update
CurrentMissionItems
()
{
{
_waypointPath
.
clear
();
int
numberWaypoints
=
30
;
// the number of waypoints currentMissionItems must not exceed
for
(
int
i
=
1
;
i
<
_missionItems
.
count
();
i
++
)
{
QList
<
QGeoCoordinate
>
geoCoordinateList
;
// list with potential waypoints (from _missionItems), for _currentMissionItems
SimpleMissionItem
*
item
=
qobject_cast
<
SimpleMissionItem
*>
(
_missionItems
[
i
]);
if
(
!
extractCoordinateList
(
_missionItems
,
geoCoordinateList
,
_firstWaypointIndex
,
if
(
item
==
nullptr
)
{
std
::
min
(
_firstWaypointIndex
+
numberWaypoints
,
_missionItems
.
count
()
-
2
)))
// -2 -> last item is land item
qWarning
(
"WimaController::updateWaypointPath(): nullptr"
);
{
qWarning
(
"WimaController::updateCurrentMissionItems(): error on waypoint extraction."
);
return
;
return
;
}
}
_waypointPath
.
append
(
QVariant
::
fromValue
(
item
->
coordinate
()));
}
emit
waypointPathChanged
();
}
}
void
WimaController
::
updateWaypointPath
()
{
_waypointPath
.
clear
();
extractCoordinateList
(
_missionItems
,
_waypointPath
,
1
,
_missionItems
.
count
()
-
1
);
emit
waypointPathChanged
();
}
void
WimaController
::
updateCurrentPath
()
{
_currentWaypointPath
.
clear
();
extractCoordinateList
(
_currentMissionItems
,
_currentWaypointPath
,
1
,
_currentMissionItems
.
count
()
-
1
);
emit
currentWaypointPathChanged
();
}
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