From caca0d0b5c68088e6efa0349791c4b9272785d81 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Beat=20K=C3=BCng?= Date: Tue, 8 Aug 2017 16:24:15 +0200 Subject: [PATCH] Vehicle: display AirMap traffic alerts using ADSBVehicle --- src/Vehicle/ADSBVehicle.cc | 16 ++++++++++++++++ src/Vehicle/ADSBVehicle.h | 3 +++ src/Vehicle/Vehicle.cc | 17 +++++++++++++++++ src/Vehicle/Vehicle.h | 3 +++ 4 files changed, 39 insertions(+) diff --git a/src/Vehicle/ADSBVehicle.cc b/src/Vehicle/ADSBVehicle.cc index bd796cf0b..2aca47e5a 100644 --- a/src/Vehicle/ADSBVehicle.cc +++ b/src/Vehicle/ADSBVehicle.cc @@ -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) { diff --git a/src/Vehicle/ADSBVehicle.h b/src/Vehicle/ADSBVehicle.h index fe6046fc1..5590c9c68 100644 --- a/src/Vehicle/ADSBVehicle.h +++ b/src/Vehicle/ADSBVehicle.h @@ -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); diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 422637e5a..3ebc22c63 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -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); + } + +} + //----------------------------------------------------------------------------- //----------------------------------------------------------------------------- diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index e1ff02c72..f7362fcda 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -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 _adsbICAOMap; + QMap _trafficVehicleMap; // Toolbox references FirmwarePluginManager* _firmwarePluginManager; -- 2.22.0