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
e46e65e1
Commit
e46e65e1
authored
Oct 17, 2019
by
Valentin Platzgummer
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
flight view gui modified, added additional features to wimaController
parent
eb694b02
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
169 additions
and
58 deletions
+169
-58
FlightDisplayView.qml
src/FlightDisplay/FlightDisplayView.qml
+21
-15
FlightDisplayWimaMenu.qml
src/FlightDisplay/FlightDisplayWimaMenu.qml
+59
-4
WimaController.cc
src/Wima/WimaController.cc
+82
-34
WimaController.h
src/Wima/WimaController.h
+6
-0
WimaPlaner.cc
src/Wima/WimaPlaner.cc
+1
-5
No files found.
src/FlightDisplay/FlightDisplayView.qml
View file @
e46e65e1
...
...
@@ -510,25 +510,31 @@ QGCView {
}
}
// FlightDisplayViewWidgets {
// id: flightDisplayViewWidgets
// z: _panel.z + 4
// height: ScreenTools.availableHeight - (singleMultiSelector.visible ? singleMultiSelector.height + _margins : 0)
// anchors.left: parent.left
// anchors.right: altitudeSlider.visible ? altitudeSlider.left : parent.right
// anchors.bottom: parent.bottom
// qgcView: root
// useLightColors: isBackgroundDark
// missionController: _missionController
// visible: singleVehicleView.checked && !QGroundControl.videoManager.fullScreen
// }
FlightDisplayWimaMenu
{
id
:
wimaMenu
FlightDisplayViewWidgets
{
id
:
flightDisplayViewWidgets
z
:
_panel
.
z
+
4
height
:
ScreenTools
.
availableHeight
-
(
singleMultiSelector
.
visible
?
singleMultiSelector
.
height
+
_margins
:
0
)
anchors.left
:
parent
.
left
anchors.right
:
altitudeSlider
.
visible
?
altitudeSlider
.
left
:
parent
.
right
anchors.bottom
:
parent
.
bottom
qgcView
:
root
useLightColors
:
isBackgroundDark
missionController
:
_missionController
visible
:
singleVehicleView
.
checked
&&
!
QGroundControl
.
videoManager
.
fullScreen
}
FlightDisplayWimaMenu
{
id
:
wimaMenu
z
:
_panel
.
z
+
4
anchors.left
:
parent
.
left
anchors.bottom
:
parent
.
bottom
anchors.leftMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.25
anchors.bottomMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.25
height
:
300
width
:
300
wimaController
:
wimaController
}
//-------------------------------------------------------------------------
...
...
src/FlightDisplay/FlightDisplayWimaMenu.qml
View file @
e46e65e1
...
...
@@ -18,15 +18,70 @@ import QGroundControl.Airmap 1.0
Item
{
id
:
_root
property
var
wimaController
// must be provided by the user
// box containing all items
Rectangle
{
anchors.top
:
parent
.
top
color
:
"
white
"
height
:
100
width
:
200
anchors.left
:
parent
.
left
anchors.bottom
:
parent
.
bottom
height
:
enableWima
.
checked
?
parent
.
height
:
enableWima
.
height
width
:
enableWima
.
checked
?
parent
.
width
:
enableWima
.
width
color
:
"
black
"
// checkbox to enable/ disable wima
QGCCheckBox
{
id
:
enableWima
checked
:
true
anchors.horizontalCenter
:
parent
.
horizontalCenter
anchors.top
:
parent
.
top
text
:
qsTr
(
"
WiMA
"
)
}
// horizonal line
Rectangle
{
id
:
horizontalLine
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.top
:
enableWima
.
bottom
anchors.leftMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
anchors.rightMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
anchors.topMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.25
height
:
1
color
:
"
white
"
}
ColumnLayout
{
id
:
mainColumn
anchors.left
:
parent
.
left
anchors.right
:
parent
.
right
anchors.top
:
horizontalLine
.
bottom
anchors.bottom
:
parent
.
bottom
anchors.topMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
anchors.bottomMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
anchors.rightMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
anchors.leftMargin
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
spacing
:
ScreenTools
.
defaultFontPixelHeight
*
0.5
QGCButton
{
id
:
buttonNextMissionPhase
text
:
"
Next Phase
"
onClicked
:
wimaController
.
nextPhase
();
}
QGCButton
{
id
:
buttonResetPhase
text
:
"
Reset Phase
"
onClicked
:
wimaController
.
resetPhase
();
}
QGCButton
{
id
:
buttonUpload
text
:
"
Upload
"
onClicked
:
wimaController
.
uploadToVehicle
();
}
}
}
}
src/Wima/WimaController.cc
View file @
e46e65e1
...
...
@@ -103,6 +103,22 @@ void WimaController::nextPhase()
updateCurrentPath
();
}
void
WimaController
::
previousPhase
()
{
}
void
WimaController
::
resetPhase
()
{
_startWaypointIndex
=
1
;
nextPhase
();
}
void
WimaController
::
uploadToVehicle
()
{
}
void
WimaController
::
startMission
()
{
...
...
@@ -294,18 +310,42 @@ void WimaController::containerDataValidChanged(bool valid)
// create mission items
_missionController
->
removeAll
();
QmlObjectListModel
*
missionControllerVisualItems
=
_missionController
->
visualItems
();
bool
copyON
=
false
;
for
(
int
i
=
0
;
i
<
tempMissionItems
.
size
();
i
++
)
{
// find takeoff command
int
begin
=
-
1
;
for
(
int
i
=
0
;
i
<
tempMissionItems
.
size
();
i
++
)
{
const
MissionItem
*
missionItem
=
tempMissionItems
[
i
];
if
(
copyON
||
missionItem
->
command
()
==
MAV_CMD_NAV_VTOL_TAKEOFF
||
missionItem
->
command
()
==
MAV_CMD_NAV_TAKEOFF
)
{
if
(
missionItem
->
command
()
==
MAV_CMD_NAV_VTOL_TAKEOFF
||
missionItem
->
command
()
==
MAV_CMD_NAV_TAKEOFF
)
{
_missionController
->
insertSimpleMissionItem
(
*
missionItem
,
missionControllerVisualItems
->
count
());
copyON
=
true
;
QGeoCoordinate
coordinate
=
missionItem
->
coordinate
();
_takeoffLandPostion
.
setAltitude
(
coordinate
.
altitude
());
_takeoffLandPostion
.
setLatitude
(
coordinate
.
latitude
());
_takeoffLandPostion
.
setLongitude
(
coordinate
.
longitude
());
begin
=
i
+
1
;
break
;
}
}
// check if takeoff command found
if
(
begin
<
0
)
{
qWarning
(
"WimaController::containerDataValidChanged(): No takeoff found."
);
return
;
}
// 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
(
missionItem
->
command
()
==
MAV_CMD_NAV_VTOL_LAND
||
missionItem
->
command
()
==
MAV_CMD_NAV_LAND
)
break
;
||
missionItem
->
command
()
==
MAV_CMD_NAV_LAND
)
break
;
}
...
...
@@ -327,15 +367,14 @@ void WimaController::containerDataValidChanged(bool valid)
_missionItems
.
append
(
visualItemCopy
);
}
updateWaypointPath
();
if
(
areaCounter
==
numAreas
)
_localPlanDataValid
=
true
;
updateWaypointPath
();
_startWaypointIndex
=
1
;
updateCurrentMissionItems
();
updateCurrentPath
();
if
(
areaCounter
==
numAreas
)
_localPlanDataValid
=
true
;
}
else
{
_localPlanDataValid
=
false
;
_visualItems
.
clear
();
...
...
@@ -353,17 +392,12 @@ void WimaController::containerDataValidChanged(bool valid)
void
WimaController
::
updateCurrentMissionItems
()
{
if
(
_missionItems
.
count
()
<
1
||
!
_localPlanDataValid
)
return
;
int
numberWaypoints
=
30
;
// the number of waypoints currentMissionItems must not exceed
int
overlapping
=
2
;
// number of overlapping waypoints of consecutive mission phases
SimpleMissionItem
*
homeItem
=
_missionItems
.
value
<
SimpleMissionItem
*>
(
0
);
if
(
homeItem
==
nullptr
)
{
qWarning
(
"WimaController::updateCurrentMissionItems(): nullptr"
);
_currentMissionItems
.
clear
();
return
;
}
QGeoCoordinate
homeCoordinate
(
homeItem
->
coordinate
());
QList
<
QGeoCoordinate
>
geoCoordinateList
;
// list with potential waypoints (from _missionItems), for _currentMissionItems
_endWaypointIndex
=
std
::
min
(
_startWaypointIndex
+
numberWaypoints
-
1
,
_missionItems
.
count
()
-
2
);
// -2 -> last item is land item
if
(
!
extractCoordinateList
(
_missionItems
,
geoCoordinateList
,
_startWaypointIndex
,
_endWaypointIndex
))
{
...
...
@@ -375,7 +409,7 @@ void WimaController::updateCurrentMissionItems()
// calculate path from home to first waypoint
QList
<
QGeoCoordinate
>
path
;
if
(
!
calcShortestPath
(
homeCoordinate
,
geoCoordinateList
[
0
],
path
)
)
{
if
(
!
calcShortestPath
(
_takeoffLandPostion
,
geoCoordinateList
[
0
],
path
)
)
{
qWarning
(
"WimaController::updateCurrentMissionItems(): Not able to calc path from home to first waypoint."
);
_currentMissionItems
.
clear
();
return
;
...
...
@@ -386,7 +420,7 @@ void WimaController::updateCurrentMissionItems()
// calculate path from last waypoint to home
path
.
clear
();
if
(
!
calcShortestPath
(
geoCoordinateList
.
last
(),
homeCoordinate
,
path
)
)
{
if
(
!
calcShortestPath
(
geoCoordinateList
.
last
(),
_takeoffLandPostion
,
path
)
)
{
qWarning
(
"WimaController::updateCurrentMissionItems(): Not able to calc path from home to first waypoint."
);
_currentMissionItems
.
clear
();
return
;
...
...
@@ -394,11 +428,33 @@ void WimaController::updateCurrentMissionItems()
path
.
removeFirst
();
// first coordinate already in geoCoordinateList
geoCoordinateList
.
append
(
path
);
// create Mission Items
_missionController
->
removeAll
();
QmlObjectListModel
*
missionControllerVisuals
=
_missionController
->
visualItems
();
for
(
auto
coordinate
:
geoCoordinateList
)
// set homeposition of settingsItem
MissionSettingsItem
*
settingsItem
=
missionControllerVisuals
->
value
<
MissionSettingsItem
*>
(
0
);
if
(
settingsItem
==
nullptr
)
{
qWarning
(
"WimaController::updateCurrentMissionItems(): nullptr"
);
_currentMissionItems
.
clear
();
return
;
}
settingsItem
->
setCoordinate
(
_takeoffLandPostion
);
for
(
auto
coordinate
:
geoCoordinateList
)
{
_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
;
}
takeoff
->
setCoordinate
(
_takeoffLandPostion
);
// set land command for last mission item
SimpleMissionItem
*
landItem
=
missionControllerVisuals
->
value
<
SimpleMissionItem
*>
(
missionControllerVisuals
->
count
()
-
1
);
...
...
@@ -417,14 +473,7 @@ void WimaController::updateCurrentMissionItems()
return
;
}
// copy mission items to _currentMissionItems
// MissionSettingsItem *settingsItem = qobject_cast<MissionSettingsItem *>((*missionControllerVisuals)[0]);
// if (settingsItem == nullptr) {
// qWarning("WimaController::containerDataValidChanged(): Nullptr at MissionSettingsItem!");
// return;
// }
// _missionItems.append(settingsItem);
// copy to _currentMissionItems
_currentMissionItems
.
clear
();
for
(
int
i
=
1
;
i
<
missionControllerVisuals
->
count
();
i
++
)
{
SimpleMissionItem
*
visualItem
=
missionControllerVisuals
->
value
<
SimpleMissionItem
*>
(
i
);
...
...
@@ -433,6 +482,7 @@ void WimaController::updateCurrentMissionItems()
_currentMissionItems
.
clear
();
return
;
}
SimpleMissionItem
*
visualItemCopy
=
new
SimpleMissionItem
(
*
visualItem
,
true
,
this
);
_currentMissionItems
.
append
(
visualItemCopy
);
}
...
...
@@ -443,16 +493,14 @@ void WimaController::updateCurrentMissionItems()
void
WimaController
::
updateWaypointPath
()
{
_waypointPath
.
clear
();
if
(
!
extractCoordinateList
(
_missionItems
,
_waypointPath
,
0
,
_missionItems
.
count
()
-
1
))
return
;
extractCoordinateList
(
_missionItems
,
_waypointPath
,
0
,
_missionItems
.
count
()
-
1
);
emit
waypointPathChanged
();
}
void
WimaController
::
updateCurrentPath
()
{
_currentWaypointPath
.
clear
();
if
(
!
extractCoordinateList
(
_currentMissionItems
,
_currentWaypointPath
,
0
,
_currentMissionItems
.
count
()
-
1
))
return
;
extractCoordinateList
(
_currentMissionItems
,
_currentWaypointPath
,
0
,
_currentMissionItems
.
count
()
-
1
);
emit
currentWaypointPathChanged
();
}
...
...
src/Wima/WimaController.h
View file @
e46e65e1
...
...
@@ -69,6 +69,9 @@ public:
// Member Methodes
Q_INVOKABLE
void
nextPhase
();
Q_INVOKABLE
void
previousPhase
();
Q_INVOKABLE
void
resetPhase
();
Q_INVOKABLE
void
uploadToVehicle
();
Q_INVOKABLE
void
startMission
();
Q_INVOKABLE
void
abortMission
();
Q_INVOKABLE
void
pauseMission
();
...
...
@@ -134,6 +137,9 @@ private:
QVariantList
_waypointPath
;
// path connecting the items in _missionItems
QVariantList
_currentWaypointPath
;
// path connecting the items in _currentMissionItems
int
_startWaypointIndex
;
// index to the mission item stored in _missionItems defining the first element of _currentMissionItems
QList
<
int
>
_startWaypointIndexList
;
int
_endWaypointIndex
;
// index to the mission item stored in _missionItems defining the last element of _currentMissionItems
QGeoCoordinate
_takeoffLandPostion
;
};
src/Wima/WimaPlaner.cc
View file @
e46e65e1
...
...
@@ -323,11 +323,7 @@ bool WimaPlaner::updateMission()
qgcApp
()
->
showMessage
(
QString
(
tr
(
"Not able to calculate the path from measurement area to landing position."
)).
toLocal8Bit
().
data
());
return
false
;
}
// path.clear();
// path.append(end);
// path.append(start);
// path.append(end);
// path.append(end);
for
(
int
i
=
1
;
i
<
path
.
count
()
-
1
;
i
++
)
{
sequenceNumber
=
_missionController
->
insertSimpleMissionItem
(
path
.
value
(
i
),
missionItems
->
count
());
_missionController
->
setCurrentPlanViewIndex
(
sequenceNumber
,
true
);
...
...
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