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
1f3100cf
Commit
1f3100cf
authored
Oct 14, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #1984 from DonLakeFlyer/LiveHome
Support live home position in Mission Editor
parents
a1765794
b43ccf87
Changes
6
Show whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
213 additions
and
45 deletions
+213
-45
MissionEditor.cc
src/MissionEditor/MissionEditor.cc
+39
-1
MissionEditor.h
src/MissionEditor/MissionEditor.h
+18
-5
MissionEditor.qml
src/MissionEditor/MissionEditor.qml
+131
-34
Vehicle.cc
src/Vehicle/Vehicle.cc
+1
-5
MockLink.cc
src/comm/MockLink.cc
+23
-0
MockLink.h
src/comm/MockLink.h
+1
-0
No files found.
src/MissionEditor/MissionEditor.cc
View file @
1f3100cf
...
...
@@ -38,6 +38,8 @@ MissionEditor::MissionEditor(QWidget *parent)
:
QGCQmlWidgetHolder
(
QString
(),
NULL
,
parent
)
,
_missionItems
(
NULL
)
,
_canEdit
(
true
)
,
_activeVehicle
(
NULL
)
,
_liveHomePositionAvailable
(
false
)
{
// Get rid of layout default margins
QLayout
*
pl
=
layout
();
...
...
@@ -45,11 +47,16 @@ MissionEditor::MissionEditor(QWidget *parent)
pl
->
setContentsMargins
(
0
,
0
,
0
,
0
);
}
Vehicle
*
activeVehicle
=
MultiVehicleManager
::
instance
()
->
activeVehicle
();
MultiVehicleManager
*
multiVehicleMgr
=
MultiVehicleManager
::
instance
();
connect
(
multiVehicleMgr
,
&
MultiVehicleManager
::
activeVehicleChanged
,
this
,
&
MissionEditor
::
_activeVehicleChanged
);
Vehicle
*
activeVehicle
=
multiVehicleMgr
->
activeVehicle
();
if
(
activeVehicle
)
{
MissionManager
*
missionManager
=
activeVehicle
->
missionManager
();
connect
(
missionManager
,
&
MissionManager
::
newMissionItemsAvailable
,
this
,
&
MissionEditor
::
_newMissionItemsAvailable
);
_newMissionItemsAvailable
();
_activeVehicleChanged
(
activeVehicle
);
}
else
{
_missionItems
=
new
QmlObjectListModel
(
this
);
_initAllMissionItems
();
...
...
@@ -389,3 +396,34 @@ void MissionEditor::_itemCommandChanged(MavlinkQmlSingleton::Qml_MAV_CMD command
_recalcChildItems
();
_recalcWaypointLines
();
}
void
MissionEditor
::
_activeVehicleChanged
(
Vehicle
*
activeVehicle
)
{
if
(
_activeVehicle
)
{
disconnect
(
_activeVehicle
,
&
Vehicle
::
homePositionAvailableChanged
,
this
,
&
MissionEditor
::
_activeVehicleHomePositionAvailableChanged
);
disconnect
(
_activeVehicle
,
&
Vehicle
::
homePositionChanged
,
this
,
&
MissionEditor
::
_activeVehicleHomePositionChanged
);
_activeVehicle
=
NULL
;
_activeVehicleHomePositionAvailableChanged
(
false
);
}
_activeVehicle
=
activeVehicle
;
if
(
_activeVehicle
)
{
connect
(
_activeVehicle
,
&
Vehicle
::
homePositionAvailableChanged
,
this
,
&
MissionEditor
::
_activeVehicleHomePositionAvailableChanged
);
connect
(
_activeVehicle
,
&
Vehicle
::
homePositionChanged
,
this
,
&
MissionEditor
::
_activeVehicleHomePositionChanged
);
_activeVehicleHomePositionChanged
(
_activeVehicle
->
homePosition
());
_activeVehicleHomePositionAvailableChanged
(
_activeVehicle
->
homePositionAvailable
());
}
}
void
MissionEditor
::
_activeVehicleHomePositionAvailableChanged
(
bool
homePositionAvailable
)
{
_liveHomePositionAvailable
=
homePositionAvailable
;
emit
liveHomePositionAvailableChanged
(
_liveHomePositionAvailable
);
}
void
MissionEditor
::
_activeVehicleHomePositionChanged
(
const
QGeoCoordinate
&
homePosition
)
{
_liveHomePosition
=
homePosition
;
emit
liveHomePositionChanged
(
_liveHomePosition
);
}
src/MissionEditor/MissionEditor.h
View file @
1f3100cf
...
...
@@ -26,6 +26,7 @@ This file is part of the QGROUNDCONTROL project
#include "QGCQmlWidgetHolder.h"
#include "QmlObjectListModel.h"
#include "Vehicle.h"
class
MissionEditor
:
public
QGCQmlWidgetHolder
{
...
...
@@ -38,6 +39,8 @@ public:
Q_PROPERTY
(
QmlObjectListModel
*
missionItems
READ
missionItems
NOTIFY
missionItemsChanged
)
Q_PROPERTY
(
QmlObjectListModel
*
waypointLines
READ
waypointLines
NOTIFY
waypointLinesChanged
)
Q_PROPERTY
(
bool
canEdit
READ
canEdit
NOTIFY
canEditChanged
)
Q_PROPERTY
(
bool
liveHomePositionAvailable
READ
liveHomePositionAvailable
NOTIFY
liveHomePositionAvailableChanged
)
Q_PROPERTY
(
QGeoCoordinate
liveHomePosition
READ
liveHomePosition
NOTIFY
liveHomePositionChanged
)
Q_INVOKABLE
int
addMissionItem
(
QGeoCoordinate
coordinate
);
Q_INVOKABLE
void
getMissionItems
(
void
);
...
...
@@ -53,16 +56,23 @@ public:
QmlObjectListModel
*
missionItems
(
void
)
{
return
_missionItems
;
}
QmlObjectListModel
*
waypointLines
(
void
)
{
return
&
_waypointLines
;
}
bool
canEdit
(
void
)
{
return
_canEdit
;
}
bool
liveHomePositionAvailable
(
void
)
{
return
_liveHomePositionAvailable
;
}
QGeoCoordinate
liveHomePosition
(
void
)
{
return
_liveHomePosition
;
}
signals:
void
missionItemsChanged
(
void
);
void
canEditChanged
(
bool
canEdit
);
void
waypointLinesChanged
(
void
);
void
liveHomePositionAvailableChanged
(
bool
homePositionAvailable
);
void
liveHomePositionChanged
(
const
QGeoCoordinate
&
homePosition
);
private
slots
:
void
_newMissionItemsAvailable
();
void
_itemCoordinateChanged
(
const
QGeoCoordinate
&
coordinate
);
void
_itemCommandChanged
(
MavlinkQmlSingleton
::
Qml_MAV_CMD
command
);
void
_activeVehicleChanged
(
Vehicle
*
activeVehicle
);
void
_activeVehicleHomePositionAvailableChanged
(
bool
homePositionAvailable
);
void
_activeVehicleHomePositionChanged
(
const
QGeoCoordinate
&
homePosition
);
private:
void
_recalcSequence
(
void
);
...
...
@@ -78,6 +88,9 @@ private:
QmlObjectListModel
*
_missionItems
;
QmlObjectListModel
_waypointLines
;
bool
_canEdit
;
///< true: UI can edit these items, false: can't edit, can only send to vehicle or save
Vehicle
*
_activeVehicle
;
bool
_liveHomePositionAvailable
;
QGeoCoordinate
_liveHomePosition
;
static
const
char
*
_settingsGroup
;
};
...
...
src/MissionEditor/MissionEditor.qml
View file @
1f3100cf
...
...
@@ -52,7 +52,11 @@ QGCView {
property
var
_homePositionManager
:
QGroundControl
.
homePositionManager
property
string
_homePositionName
:
_homePositionManager
.
homePositions
.
get
(
0
).
name
property
var
homePositionCoordinate
:
_homePositionManager
.
homePositions
.
get
(
0
).
coordinate
property
var
offlineHomePosition
:
_homePositionManager
.
homePositions
.
get
(
0
).
coordinate
property
var
liveHomePosition
:
controller
.
liveHomePosition
property
var
liveHomePositionAvailable
:
controller
.
liveHomePositionAvailable
property
var
homePosition
:
offlineHomePosition
// live or offline depending on state
QGCPalette
{
id
:
_qgcPal
;
colorGroupEnabled
:
enabled
}
...
...
@@ -76,20 +80,24 @@ QGCView {
}
}
// Home position is mission item 0, so keep them in sync
onHomePositionCoordinateChanged
:
{
function
updateHomePosition
()
{
homePosition
=
liveHomePositionAvailable
?
liveHomePosition
:
offlineHomePosition
// Changing the coordinate will set the dirty bit, so we save and reset it
var
dirtyBit
=
_missionItems
.
dirty
_missionItems
.
get
(
0
).
coordinate
=
homePosition
Coordinate
_missionItems
.
get
(
0
).
coordinate
=
homePosition
_missionItems
.
dirty
=
dirtyBit
}
Component.onCompleted
:
onHomePositionCoordinateChanged
Component.onCompleted
:
updateHomePosition
()
onOfflineHomePositionChanged
:
updateHomePosition
()
onLiveHomePositionAvailableChanged
:
updateHomePosition
()
onLiveHomePositionChanged
:
updateHomePosition
()
Connections
{
target
:
controller
onMissionItemsChanged
:
_missionItems
.
get
(
0
).
coordinate
=
homePositionCoordinate
// When the mission items change _missionsItems[0] changes as well so we need to reset it to home
onMissionItemsChanged
:
updateHomePosition
}
QGCViewPanel
{
...
...
@@ -108,8 +116,8 @@ QGCView {
mapName
:
"
MissionEditor
"
Component.onCompleted
:
{
latitude
=
homePosition
Coordinate
.
latitude
longitude
=
homePosition
Coordinate
.
longitude
latitude
=
homePosition
.
latitude
longitude
=
homePosition
.
longitude
}
MouseArea
{
...
...
@@ -121,7 +129,7 @@ QGCView {
coordinate
.
longitude
=
coordinate
.
longitude
.
toFixed
(
_decimalPlaces
)
coordinate
.
altitude
=
coordinate
.
altitude
.
toFixed
(
_decimalPlaces
)
if
(
_showHomePositionManager
)
{
homePositionCoordinate
=
coordinate
offlineHomePosition
=
coordinate
}
else
if
(
_addMissionItems
)
{
var
index
=
controller
.
addMissionItem
(
coordinate
)
setCurrentItem
(
index
)
...
...
@@ -200,7 +208,7 @@ QGCView {
onClicked
:
{
centerMapButton
.
hideDropDown
()
editorMap
.
center
=
QtPositioning
.
coordinate
(
homePosition
Coordinate
.
latitude
,
homePositionCoordinate
.
longitude
)
editorMap
.
center
=
QtPositioning
.
coordinate
(
homePosition
.
latitude
,
homePosition
.
longitude
)
_showHomePositionManager
=
true
}
}
...
...
@@ -229,8 +237,8 @@ QGCView {
centerMapButton.hideDropDown()
// Begin with only the home position in the region
var region = QtPositioning.rectangle(QtPositioning.coordinate(homePosition
Coordinate.latitude, _homePositionCoordinate
.longitude),
QtPositioning.coordinate(homePosition
Coordinate.latitude, _homePositionCoordinate
.longitude))
var region = QtPositioning.rectangle(QtPositioning.coordinate(homePosition
.latitude, homePosition
.longitude),
QtPositioning.coordinate(homePosition
.latitude, homePosition
.longitude))
// Now expand the region to include all mission items
for (var i=0; i<_missionItems.count; i++) {
...
...
@@ -510,10 +518,22 @@ QGCView {
Column
{
anchors.fill
:
parent
visible
:
!
liveHomePositionAvailable
QGCLabel
{
font.pixelSize
:
ScreenTools
.
mediumFontPixelSize
text
:
"
Home Position Manager
"
text
:
"
Offline Home Position Manager
"
}
Item
{
width
:
10
height
:
ScreenTools
.
defaultFontPixelHeight
}
QGCLabel
{
width
:
parent
.
width
wrapMode
:
Text
.
WordWrap
text
:
"
This is used to specify a simulated home position while you are not connected to a Vehicle.
"
}
Item
{
...
...
@@ -535,9 +555,9 @@ QGCView {
if
(
currentIndex
!=
-
1
)
{
var
homePos
=
_homePositionManager
.
homePositions
.
get
(
currentIndex
)
_homePositionName
=
homePos
.
name
homePositionCoordinate
=
homePos
.
coordinate
editorMap
.
latitude
=
homePositionCoordinate
.
latitude
editorMap
.
longitude
=
homePositionCoordinate
.
longitude
offlineHomePosition
=
homePos
.
coordinate
editorMap
.
latitude
=
offlineHomePosition
.
latitude
editorMap
.
longitude
=
offlineHomePosition
.
longitude
}
}
}
...
...
@@ -585,18 +605,18 @@ QGCView {
Item
{
width
:
parent
.
width
height
:
l
atitudeField
.
height
height
:
offlineL
atitudeField
.
height
QGCLabel
{
anchors.baseline
:
l
atitudeField
.
baseline
anchors.baseline
:
offlineL
atitudeField
.
baseline
text
:
"
Lat:
"
}
QGCTextField
{
id
:
l
atitudeField
id
:
offlineL
atitudeField
anchors.right
:
parent
.
right
width
:
_editFieldWidth
text
:
homePositionCoordinate
.
latitude
text
:
offlineHomePosition
.
latitude
}
}
...
...
@@ -607,18 +627,18 @@ QGCView {
Item
{
width
:
parent
.
width
height
:
l
ongitudeField
.
height
height
:
offlineL
ongitudeField
.
height
QGCLabel
{
anchors.baseline
:
l
ongitudeField
.
baseline
anchors.baseline
:
offlineL
ongitudeField
.
baseline
text
:
"
Lon:
"
}
QGCTextField
{
id
:
l
ongitudeField
id
:
offlineL
ongitudeField
anchors.right
:
parent
.
right
width
:
_editFieldWidth
text
:
homePositionCoordinate
.
longitude
text
:
offlineHomePosition
.
longitude
}
}
...
...
@@ -629,18 +649,18 @@ QGCView {
Item
{
width
:
parent
.
width
height
:
a
ltitudeField
.
height
height
:
offlineA
ltitudeField
.
height
QGCLabel
{
anchors.baseline
:
a
ltitudeField
.
baseline
anchors.baseline
:
offlineA
ltitudeField
.
baseline
text
:
"
Alt:
"
}
QGCTextField
{
id
:
a
ltitudeField
id
:
offlineA
ltitudeField
anchors.right
:
parent
.
right
width
:
_editFieldWidth
text
:
homePositionCoordinate
.
altitude
text
:
offlineHomePosition
.
altitude
}
}
...
...
@@ -656,8 +676,8 @@ QGCView {
text
:
"
Add/Update
"
onClicked
:
{
homePositionCoordinate
=
QtPositioning
.
coordinate
(
latitudeField
.
text
,
longitudeField
.
text
,
altitudeField
.
text
)
_homePositionManager
.
updateHomePosition
(
nameField
.
text
,
homePositionCoordinate
)
offlineHomePosition
=
QtPositioning
.
coordinate
(
latitudeField
.
text
,
longitudeField
.
text
,
altitudeField
.
text
)
_homePositionManager
.
updateHomePosition
(
nameField
.
text
,
offlineHomePosition
)
homePosCombo
.
currentIndex
=
homePosCombo
.
find
(
nameField
.
text
)
}
}
...
...
@@ -671,11 +691,88 @@ QGCView {
homePosCombo
.
currentIndex
=
0
var
homePos
=
_homePositionManager
.
homePositions
.
get
(
0
)
_homePositionName
=
homePos
.
name
homePositionCoordinate
=
homePos
.
coordinate
offlineHomePosition
=
homePos
.
coordinate
}
}
}
}
// Column
}
// Column - Offline view
Column
{
anchors.fill
:
parent
visible
:
liveHomePositionAvailable
QGCLabel
{
font.pixelSize
:
ScreenTools
.
mediumFontPixelSize
text
:
"
Vehicle Home Position
"
}
Item
{
width
:
10
height
:
ScreenTools
.
defaultFontPixelHeight
}
Item
{
width
:
parent
.
width
height
:
liveLatitudeField
.
height
QGCLabel
{
anchors.baseline
:
liveLatitudeField
.
baseline
text
:
"
Lat:
"
}
QGCLabel
{
id
:
liveLatitudeField
anchors.right
:
parent
.
right
width
:
_editFieldWidth
text
:
liveHomePosition
.
latitude
}
}
Item
{
width
:
10
height
:
ScreenTools
.
defaultFontPixelHeight
/
3
}
Item
{
width
:
parent
.
width
height
:
liveLongitudeField
.
height
QGCLabel
{
anchors.baseline
:
liveLongitudeField
.
baseline
text
:
"
Lon:
"
}
QGCLabel
{
id
:
liveLongitudeField
anchors.right
:
parent
.
right
width
:
_editFieldWidth
text
:
liveHomePosition
.
longitude
}
}
Item
{
width
:
10
height
:
ScreenTools
.
defaultFontPixelHeight
/
3
}
Item
{
width
:
parent
.
width
height
:
liveAltitudeField
.
height
QGCLabel
{
anchors.baseline
:
liveAltitudeField
.
baseline
text
:
"
Alt:
"
}
QGCLabel
{
id
:
liveAltitudeField
anchors.right
:
parent
.
right
width
:
_editFieldWidth
text
:
liveHomePosition
.
altitude
}
}
}
// Column - Online view
}
// Item - Home Position Manager
// Help Panel
...
...
src/Vehicle/Vehicle.cc
View file @
1f3100cf
...
...
@@ -227,8 +227,8 @@ void Vehicle::_handleHomePosition(mavlink_message_t& message)
_homePosition
.
setAltitude
(
homePos
.
altitude
/
1000.0
);
_homePositionAvailable
=
true
;
emit
homePositionAvailableChanged
(
true
);
emit
homePositionChanged
(
_homePosition
);
emit
homePositionAvailableChanged
(
true
);
}
void
Vehicle
::
_handleHeartbeat
(
mavlink_message_t
&
message
)
...
...
@@ -963,10 +963,6 @@ bool Vehicle::homePositionAvailable(void)
QGeoCoordinate
Vehicle
::
homePosition
(
void
)
{
if
(
!
_homePositionAvailable
)
{
qWarning
()
<<
"Call to homePosition while _homePositionAvailable == false"
;
}
return
_homePosition
;
}
...
...
src/comm/MockLink.cc
View file @
1f3100cf
...
...
@@ -157,6 +157,7 @@ void MockLink::_run1HzTasks(void)
{
if
(
_mavlinkStarted
&&
_connected
)
{
_sendHeartBeat
();
_sendHomePosition
();
}
}
...
...
@@ -692,3 +693,25 @@ void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode
{
_missionItemHandler
.
setMissionItemFailureMode
(
failureMode
,
firstTimeOnly
);
}
void
MockLink
::
_sendHomePosition
(
void
)
{
mavlink_message_t
msg
;
float
bogus
[
4
];
bogus
[
0
]
=
0.0
f
;
bogus
[
1
]
=
0.0
f
;
bogus
[
2
]
=
0.0
f
;
bogus
[
3
]
=
0.0
f
;
mavlink_msg_home_position_pack
(
_vehicleSystemId
,
_vehicleComponentId
,
&
msg
,
(
int32_t
)(
47.633033
f
*
1E7
),
(
int32_t
)(
-
122.08794
f
*
1E7
),
(
int32_t
)(
2.0
f
*
1000
),
0.0
f
,
0.0
f
,
0.0
f
,
&
bogus
[
0
],
0.0
f
,
0.0
f
,
0.0
f
);
respondWithMavlinkMessage
(
msg
);
}
src/comm/MockLink.h
View file @
1f3100cf
...
...
@@ -143,6 +143,7 @@ private:
void
_handleCommandLong
(
const
mavlink_message_t
&
msg
);
float
_floatUnionForParam
(
int
componentId
,
const
QString
&
paramName
);
void
_setParamFloatUnionIntoMap
(
int
componentId
,
const
QString
&
paramName
,
float
paramFloat
);
void
_sendHomePosition
(
void
);
MockLinkMissionItemHandler
_missionItemHandler
;
...
...
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