Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
3f64f28b
Commit
3f64f28b
authored
Aug 22, 2017
by
Beat Küng
Browse files
AirMap traffic: remove inactive vehicles after a timeout of 5 seconds
parent
b0fcbe05
Changes
4
Hide whitespace changes
Inline
Side-by-side
src/Vehicle/ADSBVehicle.cc
View file @
3f64f28b
...
...
@@ -41,6 +41,7 @@ void ADSBVehicle::update(const QGeoCoordinate& location, float heading)
emit
coordinateChanged
(
_coordinate
);
emit
altitudeChanged
(
_altitude
);
emit
headingChanged
(
_heading
);
_lastUpdateTimer
.
restart
();
}
void
ADSBVehicle
::
update
(
mavlink_adsb_vehicle_t
&
adsbVehicle
)
...
...
@@ -84,4 +85,10 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle)
_heading
=
newHeading
;
emit
headingChanged
(
_heading
);
}
_lastUpdateTimer
.
restart
();
}
bool
ADSBVehicle
::
expired
()
{
return
_lastUpdateTimer
.
hasExpired
(
expirationTimeoutMs
);
}
src/Vehicle/ADSBVehicle.h
View file @
3f64f28b
...
...
@@ -11,6 +11,7 @@
#include
<QObject>
#include
<QGeoCoordinate>
#include
<QElapsedTimer>
#include
"QGCMAVLink.h"
...
...
@@ -39,6 +40,10 @@ public:
void
update
(
mavlink_adsb_vehicle_t
&
adsbVehicle
);
void
update
(
const
QGeoCoordinate
&
location
,
float
heading
);
/// check if the vehicle is expired and should be removed
bool
expired
();
signals:
void
coordinateChanged
(
QGeoCoordinate
coordinate
);
void
callsignChanged
(
QString
callsign
);
...
...
@@ -46,9 +51,14 @@ signals:
void
headingChanged
(
double
heading
);
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
;
QString
_callsign
;
QGeoCoordinate
_coordinate
;
double
_altitude
;
double
_heading
;
QElapsedTimer
_lastUpdateTimer
;
};
src/Vehicle/Vehicle.cc
View file @
3f64f28b
...
...
@@ -251,6 +251,10 @@ Vehicle::Vehicle(LinkInterface* link,
_cameras
=
_firmwarePlugin
->
createCameraManager
(
this
);
emit
dynamicCamerasChanged
();
connect
(
&
_adsbTimer
,
&
QTimer
::
timeout
,
this
,
&
Vehicle
::
_adsbTimerTimeout
);
_adsbTimer
.
setSingleShot
(
false
);
_adsbTimer
.
start
(
1000
);
_airMapController
=
new
AirMapController
(
this
);
connect
(
qgcApp
()
->
toolbox
()
->
airMapManager
(),
&
AirMapManager
::
trafficUpdate
,
this
,
&
Vehicle
::
_trafficUpdate
);
}
...
...
@@ -2928,7 +2932,6 @@ void Vehicle::_trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordin
Q_UNUSED
(
vehicle_id
);
// 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
{
...
...
@@ -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:
void
_vehicleParamLoaded
(
bool
ready
);
void
_trafficUpdate
(
QString
traffic_id
,
QString
vehicle_id
,
QGeoCoordinate
location
,
float
heading
);
void
_adsbTimerTimeout
();
private:
bool
_containsLink
(
LinkInterface
*
link
);
...
...
@@ -1028,6 +1029,7 @@ private:
QmlObjectListModel
_adsbVehicles
;
QMap
<
uint32_t
,
ADSBVehicle
*>
_adsbICAOMap
;
QMap
<
QString
,
ADSBVehicle
*>
_trafficVehicleMap
;
QTimer
_adsbTimer
;
// Toolbox references
FirmwarePluginManager
*
_firmwarePluginManager
;
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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