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
Expand all
Hide 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
{
...
...
@@ -35,9 +36,11 @@ public:
MissionEditor
(
QWidget
*
parent
=
NULL
);
~
MissionEditor
();
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
(
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,7 +88,10 @@ 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
This diff is collapsed.
Click to expand it.
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