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
3f64f28b
Commit
3f64f28b
authored
Aug 22, 2017
by
Beat Küng
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
AirMap traffic: remove inactive vehicles after a timeout of 5 seconds
parent
b0fcbe05
Changes
4
Hide whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
37 additions
and
1 deletion
+37
-1
ADSBVehicle.cc
src/Vehicle/ADSBVehicle.cc
+7
-0
ADSBVehicle.h
src/Vehicle/ADSBVehicle.h
+10
-0
Vehicle.cc
src/Vehicle/Vehicle.cc
+18
-1
Vehicle.h
src/Vehicle/Vehicle.h
+2
-0
No files found.
src/Vehicle/ADSBVehicle.cc
View file @
3f64f28b
...
@@ -41,6 +41,7 @@ void ADSBVehicle::update(const QGeoCoordinate& location, float heading)
...
@@ -41,6 +41,7 @@ void ADSBVehicle::update(const QGeoCoordinate& location, float heading)
emit
coordinateChanged
(
_coordinate
);
emit
coordinateChanged
(
_coordinate
);
emit
altitudeChanged
(
_altitude
);
emit
altitudeChanged
(
_altitude
);
emit
headingChanged
(
_heading
);
emit
headingChanged
(
_heading
);
_lastUpdateTimer
.
restart
();
}
}
void
ADSBVehicle
::
update
(
mavlink_adsb_vehicle_t
&
adsbVehicle
)
void
ADSBVehicle
::
update
(
mavlink_adsb_vehicle_t
&
adsbVehicle
)
...
@@ -84,4 +85,10 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle)
...
@@ -84,4 +85,10 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle)
_heading
=
newHeading
;
_heading
=
newHeading
;
emit
headingChanged
(
_heading
);
emit
headingChanged
(
_heading
);
}
}
_lastUpdateTimer
.
restart
();
}
bool
ADSBVehicle
::
expired
()
{
return
_lastUpdateTimer
.
hasExpired
(
expirationTimeoutMs
);
}
}
src/Vehicle/ADSBVehicle.h
View file @
3f64f28b
...
@@ -11,6 +11,7 @@
...
@@ -11,6 +11,7 @@
#include <QObject>
#include <QObject>
#include <QGeoCoordinate>
#include <QGeoCoordinate>
#include <QElapsedTimer>
#include "QGCMAVLink.h"
#include "QGCMAVLink.h"
...
@@ -39,6 +40,10 @@ public:
...
@@ -39,6 +40,10 @@ public:
void
update
(
mavlink_adsb_vehicle_t
&
adsbVehicle
);
void
update
(
mavlink_adsb_vehicle_t
&
adsbVehicle
);
void
update
(
const
QGeoCoordinate
&
location
,
float
heading
);
void
update
(
const
QGeoCoordinate
&
location
,
float
heading
);
/// check if the vehicle is expired and should be removed
bool
expired
();
signals:
signals:
void
coordinateChanged
(
QGeoCoordinate
coordinate
);
void
coordinateChanged
(
QGeoCoordinate
coordinate
);
void
callsignChanged
(
QString
callsign
);
void
callsignChanged
(
QString
callsign
);
...
@@ -46,9 +51,14 @@ signals:
...
@@ -46,9 +51,14 @@ signals:
void
headingChanged
(
double
heading
);
void
headingChanged
(
double
heading
);
private:
private:
static
constexpr
qint64
expirationTimeoutMs
=
5000
;
///< timeout with no update in ms after which the vehicle is removed.
///< AirMap sends updates for each vehicle every second.
uint32_t
_icaoAddress
;
uint32_t
_icaoAddress
;
QString
_callsign
;
QString
_callsign
;
QGeoCoordinate
_coordinate
;
QGeoCoordinate
_coordinate
;
double
_altitude
;
double
_altitude
;
double
_heading
;
double
_heading
;
QElapsedTimer
_lastUpdateTimer
;
};
};
src/Vehicle/Vehicle.cc
View file @
3f64f28b
...
@@ -251,6 +251,10 @@ Vehicle::Vehicle(LinkInterface* link,
...
@@ -251,6 +251,10 @@ Vehicle::Vehicle(LinkInterface* link,
_cameras
=
_firmwarePlugin
->
createCameraManager
(
this
);
_cameras
=
_firmwarePlugin
->
createCameraManager
(
this
);
emit
dynamicCamerasChanged
();
emit
dynamicCamerasChanged
();
connect
(
&
_adsbTimer
,
&
QTimer
::
timeout
,
this
,
&
Vehicle
::
_adsbTimerTimeout
);
_adsbTimer
.
setSingleShot
(
false
);
_adsbTimer
.
start
(
1000
);
_airMapController
=
new
AirMapController
(
this
);
_airMapController
=
new
AirMapController
(
this
);
connect
(
qgcApp
()
->
toolbox
()
->
airMapManager
(),
&
AirMapManager
::
trafficUpdate
,
this
,
&
Vehicle
::
_trafficUpdate
);
connect
(
qgcApp
()
->
toolbox
()
->
airMapManager
(),
&
AirMapManager
::
trafficUpdate
,
this
,
&
Vehicle
::
_trafficUpdate
);
}
}
...
@@ -2928,7 +2932,6 @@ void Vehicle::_trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordin
...
@@ -2928,7 +2932,6 @@ void Vehicle::_trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordin
Q_UNUSED
(
vehicle_id
);
Q_UNUSED
(
vehicle_id
);
// qDebug() << "traffic update:" << traffic_id << vehicle_id << heading << location;
// qDebug() << "traffic update:" << traffic_id << vehicle_id << heading << location;
// TODO: filter based on minimum altitude?
// TODO: filter based on minimum altitude?
// TODO: remove a vehicle after a timeout?
if
(
_trafficVehicleMap
.
contains
(
traffic_id
))
{
if
(
_trafficVehicleMap
.
contains
(
traffic_id
))
{
_trafficVehicleMap
[
traffic_id
]
->
update
(
location
,
heading
);
_trafficVehicleMap
[
traffic_id
]
->
update
(
location
,
heading
);
}
else
{
}
else
{
...
@@ -2938,6 +2941,20 @@ void Vehicle::_trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordin
...
@@ -2938,6 +2941,20 @@ void Vehicle::_trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordin
}
}
}
}
void
Vehicle
::
_adsbTimerTimeout
()
{
// TODO: take into account _adsbICAOMap as well? Needs to be tested, especially the timeout
for
(
auto
it
=
_trafficVehicleMap
.
begin
();
it
!=
_trafficVehicleMap
.
end
();)
{
if
(
it
.
value
()
->
expired
())
{
_adsbVehicles
.
removeOne
(
it
.
value
());
delete
it
.
value
();
it
=
_trafficVehicleMap
.
erase
(
it
);
}
else
{
++
it
;
}
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
...
src/Vehicle/Vehicle.h
View file @
3f64f28b
...
@@ -848,6 +848,7 @@ private slots:
...
@@ -848,6 +848,7 @@ private slots:
void
_vehicleParamLoaded
(
bool
ready
);
void
_vehicleParamLoaded
(
bool
ready
);
void
_trafficUpdate
(
QString
traffic_id
,
QString
vehicle_id
,
QGeoCoordinate
location
,
float
heading
);
void
_trafficUpdate
(
QString
traffic_id
,
QString
vehicle_id
,
QGeoCoordinate
location
,
float
heading
);
void
_adsbTimerTimeout
();
private:
private:
bool
_containsLink
(
LinkInterface
*
link
);
bool
_containsLink
(
LinkInterface
*
link
);
...
@@ -1028,6 +1029,7 @@ private:
...
@@ -1028,6 +1029,7 @@ private:
QmlObjectListModel
_adsbVehicles
;
QmlObjectListModel
_adsbVehicles
;
QMap
<
uint32_t
,
ADSBVehicle
*>
_adsbICAOMap
;
QMap
<
uint32_t
,
ADSBVehicle
*>
_adsbICAOMap
;
QMap
<
QString
,
ADSBVehicle
*>
_trafficVehicleMap
;
QMap
<
QString
,
ADSBVehicle
*>
_trafficVehicleMap
;
QTimer
_adsbTimer
;
// Toolbox references
// Toolbox references
FirmwarePluginManager
*
_firmwarePluginManager
;
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