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
caca0d0b
Commit
caca0d0b
authored
Aug 08, 2017
by
Beat Küng
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Vehicle: display AirMap traffic alerts using ADSBVehicle
parent
ddfbd0ec
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
39 additions
and
0 deletions
+39
-0
ADSBVehicle.cc
src/Vehicle/ADSBVehicle.cc
+16
-0
ADSBVehicle.h
src/Vehicle/ADSBVehicle.h
+3
-0
Vehicle.cc
src/Vehicle/Vehicle.cc
+17
-0
Vehicle.h
src/Vehicle/Vehicle.h
+3
-0
No files found.
src/Vehicle/ADSBVehicle.cc
View file @
caca0d0b
...
...
@@ -27,6 +27,22 @@ ADSBVehicle::ADSBVehicle(mavlink_adsb_vehicle_t& adsbVehicle, QObject* parent)
update
(
adsbVehicle
);
}
ADSBVehicle
::
ADSBVehicle
(
const
QGeoCoordinate
&
location
,
float
heading
,
QObject
*
parent
)
:
QObject
(
parent
),
_icaoAddress
(
0
)
{
update
(
location
,
heading
);
}
void
ADSBVehicle
::
update
(
const
QGeoCoordinate
&
location
,
float
heading
)
{
_coordinate
=
location
;
_altitude
=
location
.
altitude
();
_heading
=
heading
;
emit
coordinateChanged
(
_coordinate
);
emit
altitudeChanged
(
_altitude
);
emit
headingChanged
(
_heading
);
}
void
ADSBVehicle
::
update
(
mavlink_adsb_vehicle_t
&
adsbVehicle
)
{
if
(
_icaoAddress
!=
adsbVehicle
.
ICAO_address
)
{
...
...
src/Vehicle/ADSBVehicle.h
View file @
caca0d0b
...
...
@@ -21,6 +21,8 @@ class ADSBVehicle : public QObject
public:
ADSBVehicle
(
mavlink_adsb_vehicle_t
&
adsbVehicle
,
QObject
*
parent
=
NULL
);
ADSBVehicle
(
const
QGeoCoordinate
&
location
,
float
heading
,
QObject
*
parent
=
NULL
);
Q_PROPERTY
(
int
icaoAddress
READ
icaoAddress
CONSTANT
)
Q_PROPERTY
(
QString
callsign
READ
callsign
NOTIFY
callsignChanged
)
Q_PROPERTY
(
QGeoCoordinate
coordinate
READ
coordinate
NOTIFY
coordinateChanged
)
...
...
@@ -36,6 +38,7 @@ public:
/// Update the vehicle with new information
void
update
(
mavlink_adsb_vehicle_t
&
adsbVehicle
);
void
update
(
const
QGeoCoordinate
&
location
,
float
heading
);
signals:
void
coordinateChanged
(
QGeoCoordinate
coordinate
);
void
callsignChanged
(
QString
callsign
);
...
...
src/Vehicle/Vehicle.cc
View file @
caca0d0b
...
...
@@ -248,6 +248,8 @@ Vehicle::Vehicle(LinkInterface* link,
// Create camera manager instance
_cameras
=
_firmwarePlugin
->
createCameraManager
(
this
);
emit
dynamicCamerasChanged
();
connect
(
qgcApp
()
->
toolbox
()
->
airMapManager
(),
&
AirMapManager
::
trafficUpdate
,
this
,
&
Vehicle
::
_trafficUpdate
);
}
// Disconnected Vehicle for offline editing
...
...
@@ -2917,6 +2919,21 @@ void Vehicle::_vehicleParamLoaded(bool ready)
}
}
void
Vehicle
::
_trafficUpdate
(
QString
traffic_id
,
QString
vehicle_id
,
QGeoCoordinate
location
,
float
heading
)
{
// qDebug() << "traffic update:" << traffic_id << vehicle_id << heading << location;
// TODO: filter based on minimum altitude?
// TODO: remove a vehicle after a timeout?
if
(
_trafficVehicleMap
.
contains
(
traffic_id
))
{
_trafficVehicleMap
[
traffic_id
]
->
update
(
location
,
heading
);
}
else
{
ADSBVehicle
*
vehicle
=
new
ADSBVehicle
(
location
,
heading
,
this
);
_trafficVehicleMap
[
traffic_id
]
=
vehicle
;
_adsbVehicles
.
append
(
vehicle
);
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
...
src/Vehicle/Vehicle.h
View file @
caca0d0b
...
...
@@ -843,6 +843,8 @@ private slots:
void
_updateHobbsMeter
(
void
);
void
_vehicleParamLoaded
(
bool
ready
);
void
_trafficUpdate
(
QString
traffic_id
,
QString
vehicle_id
,
QGeoCoordinate
location
,
float
heading
);
private:
bool
_containsLink
(
LinkInterface
*
link
);
void
_addLink
(
LinkInterface
*
link
);
...
...
@@ -1019,6 +1021,7 @@ private:
QmlObjectListModel
_adsbVehicles
;
QMap
<
uint32_t
,
ADSBVehicle
*>
_adsbICAOMap
;
QMap
<
QString
,
ADSBVehicle
*>
_trafficVehicleMap
;
// Toolbox references
FirmwarePluginManager
*
_firmwarePluginManager
;
...
...
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