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
750901fb
Commit
750901fb
authored
Jan 18, 2020
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Keep track of current vehicle's last known location.
parent
72b172b4
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
35 additions
and
14 deletions
+35
-14
MultiVehicleManager.cc
src/Vehicle/MultiVehicleManager.cc
+14
-0
MultiVehicleManager.h
src/Vehicle/MultiVehicleManager.h
+21
-14
No files found.
src/Vehicle/MultiVehicleManager.cc
View file @
750901fb
...
...
@@ -285,6 +285,14 @@ void MultiVehicleManager::_setActiveVehiclePhase2(void)
{
qCDebug
(
MultiVehicleManagerLog
)
<<
"_setActiveVehiclePhase2 _vehicleBeingSetActive"
<<
_vehicleBeingSetActive
;
//-- Keep track of current vehicle's coordinates
if
(
_activeVehicle
)
{
disconnect
(
_activeVehicle
,
&
Vehicle
::
coordinateChanged
,
this
,
&
MultiVehicleManager
::
_coordinateChanged
);
}
if
(
_vehicleBeingSetActive
)
{
connect
(
_vehicleBeingSetActive
,
&
Vehicle
::
coordinateChanged
,
this
,
&
MultiVehicleManager
::
_coordinateChanged
);
}
// Now we signal the new active vehicle
_activeVehicle
=
_vehicleBeingSetActive
;
emit
activeVehicleChanged
(
_activeVehicle
);
...
...
@@ -302,6 +310,12 @@ void MultiVehicleManager::_setActiveVehiclePhase2(void)
}
}
void
MultiVehicleManager
::
_coordinateChanged
(
QGeoCoordinate
coordinate
)
{
_lastKnownLocation
=
coordinate
;
emit
lastKnownLocationChanged
();
}
void
MultiVehicleManager
::
_vehicleParametersReadyChanged
(
bool
parametersReady
)
{
auto
*
paramMgr
=
qobject_cast
<
ParameterManager
*>
(
sender
());
...
...
src/Vehicle/MultiVehicleManager.h
View file @
750901fb
...
...
@@ -47,6 +47,9 @@ public:
/// A disconnected vehicle used for offline editing. It will match the vehicle type specified in Settings.
Q_PROPERTY
(
Vehicle
*
offlineEditingVehicle
READ
offlineEditingVehicle
CONSTANT
)
//-- The current vehicle's last known location
Q_PROPERTY
(
QGeoCoordinate
lastKnownLocation
READ
lastKnownLocation
NOTIFY
lastKnownLocationChanged
)
// Methods
Q_INVOKABLE
Vehicle
*
getVehicleById
(
int
vehicleId
);
...
...
@@ -78,24 +81,27 @@ public:
// Override from QGCTool
virtual
void
setToolbox
(
QGCToolbox
*
toolbox
);
QGeoCoordinate
lastKnownLocation
()
{
return
_lastKnownLocation
;
}
signals:
void
vehicleAdded
(
Vehicle
*
vehicle
);
void
vehicleRemoved
(
Vehicle
*
vehicle
);
void
activeVehicleAvailableChanged
(
bool
activeVehicleAvailable
);
void
vehicleAdded
(
Vehicle
*
vehicle
);
void
vehicleRemoved
(
Vehicle
*
vehicle
);
void
activeVehicleAvailableChanged
(
bool
activeVehicleAvailable
);
void
parameterReadyVehicleAvailableChanged
(
bool
parameterReadyVehicleAvailable
);
void
activeVehicleChanged
(
Vehicle
*
activeVehicle
);
void
gcsHeartBeatEnabledChanged
(
bool
gcsHeartBeatEnabled
);
void
_deleteVehiclePhase2Signal
(
void
);
void
activeVehicleChanged
(
Vehicle
*
activeVehicle
);
void
gcsHeartBeatEnabledChanged
(
bool
gcsHeartBeatEnabled
);
void
lastKnownLocationChanged
();
void
_deleteVehiclePhase2Signal
(
void
);
private
slots
:
void
_deleteVehiclePhase1
(
Vehicle
*
vehicle
);
void
_deleteVehiclePhase2
(
void
);
void
_setActiveVehiclePhase2
(
void
);
void
_vehicleParametersReadyChanged
(
bool
parametersReady
);
void
_sendGCSHeartbeat
(
void
);
void
_vehicleHeartbeatInfo
(
LinkInterface
*
link
,
int
vehicleId
,
int
componentId
,
int
vehicleFirmwareType
,
int
vehicleType
);
void
_requestProtocolVersion
(
unsigned
version
);
void
_deleteVehiclePhase1
(
Vehicle
*
vehicle
);
void
_deleteVehiclePhase2
(
void
);
void
_setActiveVehiclePhase2
(
void
);
void
_vehicleParametersReadyChanged
(
bool
parametersReady
);
void
_sendGCSHeartbeat
(
void
);
void
_vehicleHeartbeatInfo
(
LinkInterface
*
link
,
int
vehicleId
,
int
componentId
,
int
vehicleFirmwareType
,
int
vehicleType
);
void
_requestProtocolVersion
(
unsigned
version
);
void
_coordinateChanged
(
QGeoCoordinate
coordinate
);
private:
bool
_vehicleExists
(
int
vehicleId
);
...
...
@@ -115,6 +121,7 @@ private:
FirmwarePluginManager
*
_firmwarePluginManager
;
JoystickManager
*
_joystickManager
;
MAVLinkProtocol
*
_mavlinkProtocol
;
QGeoCoordinate
_lastKnownLocation
;
QTimer
_gcsHeartbeatTimer
;
///< Timer to emit heartbeats
bool
_gcsHeartbeatEnabled
;
///< Enabled/disable heartbeat emission
...
...
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