diff --git a/qgcresources.qrc b/qgcresources.qrc index 73fc128a1a79fecac7996091f074ae560b2a3e34..22e8205e473d013ad80fc4b90b8d40b205aa9106 100644 --- a/qgcresources.qrc +++ b/qgcresources.qrc @@ -172,6 +172,7 @@ src/FirmwarePlugin/APM/APMBrandImageSub.png src/FirmwarePlugin/PX4/PX4BrandImage.png src/FlightMap/Images/sub.png + src/FlightMap/Images/AlertAircraft.svg src/FlightMap/Images/AwarenessAircraft.svg diff --git a/src/Airmap/AirMapAdvisoryManager.cc b/src/Airmap/AirMapAdvisoryManager.cc index c9b585cb3b92acad768cbadfb3cad7599353d7c9..76e8860150636110beaedcbc39e75d64e6ad1044 100644 --- a/src/Airmap/AirMapAdvisoryManager.cc +++ b/src/Airmap/AirMapAdvisoryManager.cc @@ -47,7 +47,7 @@ adv_sort(QObject* a, QObject* b) AirMapAdvisory* aa = qobject_cast(a); AirMapAdvisory* bb = qobject_cast(b); if(!aa || !bb) return false; - return aa->color() > bb->color(); + return (int)aa->color() > (int)bb->color(); } //----------------------------------------------------------------------------- diff --git a/src/Airmap/AirMapRestrictionManager.cc b/src/Airmap/AirMapRestrictionManager.cc index e39bb66fddf9e78b6f48b4c5915142a880fb48ad..db6432b49fbdbd768e05a71e93977b028e158e20 100644 --- a/src/Airmap/AirMapRestrictionManager.cc +++ b/src/Airmap/AirMapRestrictionManager.cc @@ -72,9 +72,7 @@ AirMapRestrictionManager::setROI(const QGeoCoordinate& center, double radiusMete qWarning() << "unsupported geometry type: "<<(int)geometry.type(); break; } - } - } else { QString description = QString::fromStdString(result.error().description() ? result.error().description().get() : ""); emit error("Failed to retrieve Geofences", diff --git a/src/Airmap/AirMapTrafficMonitor.cc b/src/Airmap/AirMapTrafficMonitor.cc index f2ec0faabbd7b4bc06fdd4e25fb4bc5544c61eca..9fec2972bb7f4a2060fe2d963f77a2ce3c2af97d 100644 --- a/src/Airmap/AirMapTrafficMonitor.cc +++ b/src/Airmap/AirMapTrafficMonitor.cc @@ -48,8 +48,8 @@ AirMapTrafficMonitor::_update(Traffic::Update::Type type, const std::vector& update); diff --git a/src/Airmap/AirspaceControl.qml b/src/Airmap/AirspaceControl.qml index 2bd6f5e0e59f0ffea13e03952add1af6601c1e47..0ebda974cb220836a16312202f18a96dc555054a 100644 --- a/src/Airmap/AirspaceControl.qml +++ b/src/Airmap/AirspaceControl.qml @@ -17,9 +17,8 @@ import QGroundControl.Airmap 1.0 Item { id: _root width: parent.width - height: colapsed ? colapsedRect.height : expandedRect.height + height: _colapsed ? colapsedRect.height : expandedRect.height - property bool colapsed: true property bool showColapse: true property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle @@ -27,6 +26,7 @@ Item { property bool _validRules: _activeVehicle ? _activeVehicle.airspaceController.rulesets.valid : false property bool _validAdvisories: _activeVehicle ? _activeVehicle.airspaceController.advisories.valid : false property color _textColor: qgcPal.text + property bool _colapsed: _activeVehicle ? !_activeVehicle.airspaceController.airspaceVisible : true readonly property real _radius: ScreenTools.defaultFontPixelWidth * 0.5 readonly property color _colorOrange: "#d75e0d" @@ -67,10 +67,10 @@ Item { Rectangle { id: colapsedRect width: parent.width - height: colapsed ? colapsedRow.height + ScreenTools.defaultFontPixelHeight : 0 + height: _colapsed ? colapsedRow.height + ScreenTools.defaultFontPixelHeight : 0 color: _validAdvisories ? getAispaceColor(_activeVehicle.airspaceController.advisories.airspaceColor) : _colorGray radius: _radius - visible: colapsed + visible: _colapsed Row { id: colapsedRow spacing: ScreenTools.defaultFontPixelWidth @@ -113,7 +113,10 @@ Item { } MouseArea { anchors.fill: parent - onClicked: colapsed = false + enabled: _activeVehicle + onClicked: { + _activeVehicle.airspaceController.airspaceVisible = true + } } } //--------------------------------------------------------------- @@ -121,10 +124,10 @@ Item { Rectangle { id: expandedRect width: parent.width - height: !colapsed ? expandedCol.height + ScreenTools.defaultFontPixelHeight : 0 + height: !_colapsed ? expandedCol.height + ScreenTools.defaultFontPixelHeight : 0 color: _validAdvisories ? getAispaceColor(_activeVehicle.airspaceController.advisories.airspaceColor) : _colorGray radius: _radius - visible: !colapsed + visible: !_colapsed MouseArea { anchors.fill: parent onWheel: { wheel.accepted = true; } @@ -191,8 +194,8 @@ Item { anchors.verticalCenter: parent.verticalCenter MouseArea { anchors.fill: parent - enabled: showColapse - onClicked: colapsed = true + enabled: showColapse && _activeVehicle + onClicked: _activeVehicle.airspaceController.airspaceVisible = false } } AirspaceWeather { diff --git a/src/Airmap/README.md b/src/Airmap/README.md new file mode 100644 index 0000000000000000000000000000000000000000..b05b646cbd9af6039a0021609c8755051ffe4a85 --- /dev/null +++ b/src/Airmap/README.md @@ -0,0 +1,8 @@ +## To be deleted when development is complete + +* AirMapRestrictionManager seems to be incomplete (if not redundant). Shouldn't we use the array of AirSpace items returned by AirMapAdvisoryManager instead? In addition to the AirSpace object, it gives you a color to use in order of importance. + +* Traffic monitor timeout is now set to 2 minutes following instructions from Thomas Voß. + +* Add a "Wrong Way" icon to the airspace widget when not connected + diff --git a/src/AirspaceManagement/AirspaceController.cc b/src/AirspaceManagement/AirspaceController.cc index 02648932db3e30c15789ed5c4958e74e1e9bd980..91397ddc1ffaf7c8acf8b69bbdfb2197573ebb71 100644 --- a/src/AirspaceManagement/AirspaceController.cc +++ b/src/AirspaceManagement/AirspaceController.cc @@ -19,6 +19,7 @@ AirspaceController::AirspaceController(QObject* parent) : QObject(parent) , _manager(qgcApp()->toolbox()->airspaceManager()) + , _airspaceVisible(false) { } diff --git a/src/AirspaceManagement/AirspaceController.h b/src/AirspaceManagement/AirspaceController.h index 8e6d6a43999601e88c9eb8e30c4acd1454ebc20a..ef1b0f905ab3365833081b7e0ab3d9e6d2dbb7de 100644 --- a/src/AirspaceManagement/AirspaceController.h +++ b/src/AirspaceManagement/AirspaceController.h @@ -25,22 +25,30 @@ public: AirspaceController(QObject* parent = NULL); ~AirspaceController() = default; - Q_PROPERTY(QmlObjectListModel* polygons READ polygons CONSTANT) ///< List of AirspacePolygonRestriction objects - Q_PROPERTY(QmlObjectListModel* circles READ circles CONSTANT) ///< List of AirspaceCircularRestriction objects - Q_PROPERTY(QString providerName READ providerName CONSTANT) - Q_PROPERTY(AirspaceWeatherInfoProvider* weatherInfo READ weatherInfo CONSTANT) - Q_PROPERTY(AirspaceAdvisoryProvider* advisories READ advisories CONSTANT) - Q_PROPERTY(AirspaceRulesetsProvider* rulesets READ rulesets CONSTANT) - - Q_INVOKABLE void setROI (QGeoCoordinate center, double radius); - - QmlObjectListModel* polygons (); - QmlObjectListModel* circles (); - QString providerName(); - AirspaceWeatherInfoProvider* weatherInfo (); - AirspaceAdvisoryProvider* advisories (); - AirspaceRulesetsProvider* rulesets (); + Q_PROPERTY(QmlObjectListModel* polygons READ polygons CONSTANT) ///< List of AirspacePolygonRestriction objects + Q_PROPERTY(QmlObjectListModel* circles READ circles CONSTANT) ///< List of AirspaceCircularRestriction objects + Q_PROPERTY(QString providerName READ providerName CONSTANT) + Q_PROPERTY(AirspaceWeatherInfoProvider* weatherInfo READ weatherInfo CONSTANT) + Q_PROPERTY(AirspaceAdvisoryProvider* advisories READ advisories CONSTANT) + Q_PROPERTY(AirspaceRulesetsProvider* rulesets READ rulesets CONSTANT) + Q_PROPERTY(bool airspaceVisible READ airspaceVisible WRITE setairspaceVisible NOTIFY airspaceVisibleChanged) + + Q_INVOKABLE void setROI (QGeoCoordinate center, double radius); + + QmlObjectListModel* polygons (); + QmlObjectListModel* circles (); + QString providerName (); + AirspaceWeatherInfoProvider* weatherInfo (); + AirspaceAdvisoryProvider* advisories (); + AirspaceRulesetsProvider* rulesets (); + bool airspaceVisible () { return _airspaceVisible; } + + void setairspaceVisible (bool set) { _airspaceVisible = set; emit airspaceVisibleChanged(); } + +signals: + void airspaceVisibleChanged (); private: AirspaceManager* _manager; + bool _airspaceVisible; }; diff --git a/src/AirspaceManagement/AirspaceVehicleManager.h b/src/AirspaceManagement/AirspaceVehicleManager.h index 12805f01c54dbcfdac826479820c3db590719919..448c097c86292cdbb15e3174bceafd287e6edc0f 100644 --- a/src/AirspaceManagement/AirspaceVehicleManager.h +++ b/src/AirspaceManagement/AirspaceVehicleManager.h @@ -53,7 +53,7 @@ public slots: virtual void endFlight () = 0; signals: - void trafficUpdate (QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading); + void trafficUpdate (bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading); void flightPermitStatusChanged (); protected slots: diff --git a/src/FlightDisplay/FlightDisplayViewMap.qml b/src/FlightDisplay/FlightDisplayViewMap.qml index 87ecb3daa81194b3f8e996dc5c604d59c0eb6f6b..ca85172637f3199c3cbaedbf6e6e5e540a6fbee9 100644 --- a/src/FlightDisplay/FlightDisplayViewMap.qml +++ b/src/FlightDisplay/FlightDisplayViewMap.qml @@ -51,6 +51,7 @@ FlightMap { property var _activeVehicleCoordinate: _activeVehicle ? _activeVehicle.coordinate : QtPositioning.coordinate() property var _gotoHereCoordinate: QtPositioning.coordinate() property real _toolButtonTopMargin: parent.height - ScreenTools.availableHeight + (ScreenTools.defaultFontPixelHeight / 2) + property bool _airspaceManagement: QGroundControl.airmapSupported && _activeVehicle property bool _disableVehicleTracking: false property bool _keepVehicleCentered: _mainIsMap ? false : true @@ -198,15 +199,14 @@ FlightMap { // Add ADSB vehicles to the map MapItemView { - model: _activeVehicle ? _activeVehicle.adsbVehicles : 0 - + model: _activeVehicle ? _activeVehicle.adsbVehicles : [] property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle - delegate: VehicleMapItem { coordinate: object.coordinate altitude: object.altitude callsign: object.callsign heading: object.heading + alert: object.alert map: flightMap z: QGroundControl.zOrderVehicles } @@ -331,22 +331,20 @@ FlightMap { // Airspace overlap support MapItemView { - model: QGroundControl.airmapSupported && _activeVehicle ? _activeVehicle.airspaceController.circles : [] + model: _airspaceManagement && _activeVehicle.airspaceController.airspaceVisible ? _activeVehicle.airspaceController.circles : [] delegate: MapCircle { center: object.center radius: object.radius - border.color: "white" - color: "yellow" - opacity: 0.25 + border.color: Qt.rgba(1,1,1,0.85) + color: Qt.rgba(0.94,0.87,0,0.25) } } MapItemView { - model: QGroundControl.airmapSupported && _activeVehicle ? _activeVehicle.airspaceController.polygons : [] + model: _airspaceManagement && _activeVehicle.airspaceController.airspaceVisible ? _activeVehicle.airspaceController.polygons : [] delegate: MapPolygon { - border.color: "white" - color: "yellow" - opacity: 0.25 + border.color: Qt.rgba(1,1,1,0.85) + color: Qt.rgba(0.94,0.87,0,0.25) path: object.polygon } } diff --git a/src/FlightDisplay/FlightDisplayViewWidgets.qml b/src/FlightDisplay/FlightDisplayViewWidgets.qml index 09cba31c57ee791e52023a41ce9008d7a574d22b..f28d0fcb6c29386deb1d69132c47c45b5cd43753 100644 --- a/src/FlightDisplay/FlightDisplayViewWidgets.qml +++ b/src/FlightDisplay/FlightDisplayViewWidgets.qml @@ -79,6 +79,15 @@ Item { onValueChanged: _setInstrumentWidget() } + Connections { + target: _activeVehicle ? _activeVehicle.airspaceController : null + onAirspaceVisibleChanged: { + if(_activeVehicle) { + widgetRoot.showValues = !_activeVehicle.airspaceController.airspaceVisible + } + } + } + Component.onCompleted: { _setInstrumentWidget() } @@ -133,9 +142,6 @@ Item { width: getPreferredInstrumentWidth() visible: _enableAirMap anchors.margins: ScreenTools.defaultFontPixelHeight * 0.5 - onColapsedChanged: { - widgetRoot.showValues = colapsed - } } //------------------------------------------------------- //-- Instrument Panel diff --git a/src/FlightMap/Images/AlertAircraft.svg b/src/FlightMap/Images/AlertAircraft.svg new file mode 100644 index 0000000000000000000000000000000000000000..781b06733ba52bcef97290f251e7e4b0674cd39b --- /dev/null +++ b/src/FlightMap/Images/AlertAircraft.svg @@ -0,0 +1,20 @@ + + + + + + + + + + + + diff --git a/src/FlightMap/MapItems/VehicleMapItem.qml b/src/FlightMap/MapItems/VehicleMapItem.qml index 28f7c11f249443defdf66ab348e1edd965efdd8a..5c8855ec66c32dbbd8628030d2f3e2e3ca71f55f 100644 --- a/src/FlightMap/MapItems/VehicleMapItem.qml +++ b/src/FlightMap/MapItems/VehicleMapItem.qml @@ -25,6 +25,7 @@ MapQuickItem { property string callsign: "" ///< Vehicle callsign property double heading: vehicle ? vehicle.heading.value : Number.NaN ///< Vehicle heading, NAN for none property real size: _adsbVehicle ? _adsbSize : _uavSize /// Size for icon + property bool alert: false /// Collision alert anchorPoint.x: vehicleItem.width / 2 anchorPoint.y: vehicleItem.height / 2 @@ -32,7 +33,7 @@ MapQuickItem { property bool _adsbVehicle: vehicle ? false : true property real _uavSize: ScreenTools.defaultFontPixelHeight * 5 - property real _adsbSize: ScreenTools.defaultFontPixelHeight * 1.5 + property real _adsbSize: ScreenTools.defaultFontPixelHeight * 2.5 property var _map: map property bool _multiVehicle: QGroundControl.multiVehicleManager.vehicles.count > 1 @@ -50,8 +51,8 @@ MapQuickItem { visible: false } DropShadow { - anchors.fill: arrowIconShadow - visible: vehicleIcon.visible + anchors.fill: vehicleShadow + visible: vehicleIcon.visible && _adsbVehicle horizontalOffset: 4 verticalOffset: 4 radius: 32.0 @@ -61,7 +62,7 @@ MapQuickItem { } Image { id: vehicleIcon - source: _adsbVehicle ? "/qmlimages/AwarenessAircraft.svg" : vehicle.vehicleImageOpaque + source: _adsbVehicle ? (alert ? "/qmlimages/AlertAircraft.svg" : "/qmlimages/AwarenessAircraft.svg") : vehicle.vehicleImageOpaque mipmap: true width: size sourceSize.width: size @@ -81,7 +82,6 @@ MapQuickItem { text: vehicleLabelText font.pointSize: ScreenTools.smallFontPointSize visible: _adsbVehicle ? !isNaN(altitude) : _multiVehicle - property string vehicleLabelText: visible ? (_adsbVehicle ? QGroundControl.metersToAppSettingsDistanceUnits(altitude).toFixed(0) + " " + QGroundControl.appSettingsDistanceUnitsString : @@ -97,7 +97,6 @@ MapQuickItem { text: vehicleLabelText font.pointSize: ScreenTools.smallFontPointSize visible: _adsbVehicle ? !isNaN(altitude) : _multiVehicle - property string vehicleLabelText: visible && _adsbVehicle ? callsign : "" } } diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml index 816db62de8726fd2d22022344945394ab8bb6221..3e509aa7e7e8840160d1a08b55b878f7ee2298a0 100644 --- a/src/PlanView/PlanView.qml +++ b/src/PlanView/PlanView.qml @@ -99,7 +99,7 @@ QGCView { if(QGroundControl.airmapSupported) { if(_enableAirMap) { planControlColapsed = true - airspaceControl.colapsed = false + _activeVehicle.airspaceController.airspaceVisible = true } else { planControlColapsed = false } @@ -164,9 +164,15 @@ QGCView { } } + Connections { + target: _activeVehicle ? _activeVehicle.airspaceController : undefined + onColapsedChanged: { + planControlColapsed = _activeVehicle.airspaceController.airspaceVisible + } + } + Component { id: noItemForKML - QGCViewMessage { message: qsTr("You need at least one item to create a KML.") } @@ -530,11 +536,6 @@ QGCView { width: parent.width visible: _enableAirMap showColapse: false - onColapsedChanged: { - if(!airspaceControl.colasped) { - planControlColapsed = true - } - } } //------------------------------------------------------- // Mission Controls (Colapsed) diff --git a/src/QGCMapPalette.cc b/src/QGCMapPalette.cc index 0bdd60f77d678b797e6821cb28cf6aa59ffbd4d1..47af675f1ad355c3939cf33af327e2c80df076c3 100644 --- a/src/QGCMapPalette.cc +++ b/src/QGCMapPalette.cc @@ -15,7 +15,7 @@ QColor QGCMapPalette::_thumbJoystick[QGCMapPalette::_cColorGroups] = { QColor(255,255,255,127), QColor(0,0,0,127) }; QColor QGCMapPalette::_text [QGCMapPalette::_cColorGroups] = { QColor(255,255,255), QColor(0,0,0) }; -QColor QGCMapPalette::_textOutline [QGCMapPalette::_cColorGroups] = { QColor(0,0,0), QColor(255,255,255) }; +QColor QGCMapPalette::_textOutline [QGCMapPalette::_cColorGroups] = { QColor(0,0,0,192), QColor(255,255,255,192) }; QGCMapPalette::QGCMapPalette(QObject* parent) : QObject(parent) diff --git a/src/Vehicle/ADSBVehicle.cc b/src/Vehicle/ADSBVehicle.cc index 6fcda9ef0eedb04f0223b2553232959710279ed9..25e5c04f655f3a8345c9b4c7eafb0cfa741f2d70 100644 --- a/src/Vehicle/ADSBVehicle.cc +++ b/src/Vehicle/ADSBVehicle.cc @@ -18,29 +18,33 @@ ADSBVehicle::ADSBVehicle(mavlink_adsb_vehicle_t& adsbVehicle, QObject* parent) , _callsign (adsbVehicle.callsign) , _altitude (NAN) , _heading (NAN) + , _alert (false) { if (!(adsbVehicle.flags | ADSB_FLAGS_VALID_COORDS)) { qWarning() << "At least coords must be valid"; return; } - update(adsbVehicle); } -ADSBVehicle::ADSBVehicle(const QGeoCoordinate& location, float heading, QObject* parent) - : QObject(parent), _icaoAddress(0) +ADSBVehicle::ADSBVehicle(const QGeoCoordinate& location, float heading, bool alert, QObject* parent) + : QObject(parent) + , _icaoAddress(0) + , _alert(alert) { - update(location, heading); + update(alert, location, heading); } -void ADSBVehicle::update(const QGeoCoordinate& location, float heading) +void ADSBVehicle::update(bool alert, const QGeoCoordinate& location, float heading) { _coordinate = location; - _altitude = location.altitude(); - _heading = heading; - emit coordinateChanged(_coordinate); - emit altitudeChanged(_altitude); - emit headingChanged(_heading); + _altitude = location.altitude(); + _heading = heading; + _alert = alert; + emit coordinateChanged(); + emit altitudeChanged(); + emit headingChanged(); + emit alertChanged(); _lastUpdateTimer.restart(); } @@ -59,13 +63,13 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle) if (currCallsign != _callsign) { _callsign = currCallsign; - emit callsignChanged(_callsign); + emit callsignChanged(); } QGeoCoordinate newCoordinate(adsbVehicle.lat / 1e7, adsbVehicle.lon / 1e7); if (newCoordinate != _coordinate) { _coordinate = newCoordinate; - emit coordinateChanged(_coordinate); + emit coordinateChanged(); } double newAltitude = NAN; @@ -74,7 +78,7 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle) } if (!(qIsNaN(newAltitude) && qIsNaN(_altitude)) && !qFuzzyCompare(newAltitude, _altitude)) { _altitude = newAltitude; - emit altitudeChanged(_altitude); + emit altitudeChanged(); } double newHeading = NAN; @@ -83,7 +87,7 @@ void ADSBVehicle::update(mavlink_adsb_vehicle_t& adsbVehicle) } if (!(qIsNaN(newHeading) && qIsNaN(_heading)) && !qFuzzyCompare(newHeading, _heading)) { _heading = newHeading; - emit headingChanged(_heading); + emit headingChanged(); } _lastUpdateTimer.restart(); } diff --git a/src/Vehicle/ADSBVehicle.h b/src/Vehicle/ADSBVehicle.h index f0124f089bd69cefe68cbfd662fe894099a3e9eb..3ae09da44893a6549985e7cfda3639aa0eb3118a 100644 --- a/src/Vehicle/ADSBVehicle.h +++ b/src/Vehicle/ADSBVehicle.h @@ -22,43 +22,50 @@ class ADSBVehicle : public QObject public: ADSBVehicle(mavlink_adsb_vehicle_t& adsbVehicle, QObject* parent = NULL); - ADSBVehicle(const QGeoCoordinate& location, float heading, QObject* parent = NULL); + ADSBVehicle(const QGeoCoordinate& location, float heading, bool alert = false, 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) Q_PROPERTY(double altitude READ altitude NOTIFY altitudeChanged) // NaN for not available Q_PROPERTY(double heading READ heading NOTIFY headingChanged) // NaN for not available + Q_PROPERTY(bool alert READ alert NOTIFY alertChanged) // Collision path int icaoAddress (void) const { return _icaoAddress; } QString callsign (void) const { return _callsign; } QGeoCoordinate coordinate (void) const { return _coordinate; } double altitude (void) const { return _altitude; } double heading (void) const { return _heading; } + bool alert (void) const { return _alert; } /// Update the vehicle with new information void update(mavlink_adsb_vehicle_t& adsbVehicle); - void update(const QGeoCoordinate& location, float heading); + void update(bool alert, 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); - void altitudeChanged(double altitude); - void headingChanged(double heading); + void coordinateChanged (); + void callsignChanged (); + void altitudeChanged (); + void headingChanged (); + void alertChanged (); private: + /* According with Thomas Voß, we should be using 2 minutes for the time being 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. + */ + static constexpr qint64 expirationTimeoutMs = 120000; uint32_t _icaoAddress; QString _callsign; QGeoCoordinate _coordinate; double _altitude; double _heading; + bool _alert; QElapsedTimer _lastUpdateTimer; }; diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index d4ab591a9ac5e381ec5e6932e6d25b97068e3c5b..1397bccedadadfef6cbe3a3dbf7cc84eaf95134d 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -3009,15 +3009,15 @@ void Vehicle::_updateHighLatencyLink(void) } } -void Vehicle::_trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading) +void Vehicle::_trafficUpdate(bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading) { Q_UNUSED(vehicle_id); // qDebug() << "traffic update:" << traffic_id << vehicle_id << heading << location; // TODO: filter based on minimum altitude? if (_trafficVehicleMap.contains(traffic_id)) { - _trafficVehicleMap[traffic_id]->update(location, heading); + _trafficVehicleMap[traffic_id]->update(alert, location, heading); } else { - ADSBVehicle* vehicle = new ADSBVehicle(location, heading, this); + ADSBVehicle* vehicle = new ADSBVehicle(location, heading, alert, this); _trafficVehicleMap[traffic_id] = vehicle; _adsbVehicles.append(vehicle); } diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index a296d1ec341a47360a2d87ea4749c90f8a4e46ab..1cca1919aa7423d86d41f32d756f0eb0966ba166 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -910,8 +910,8 @@ private slots: void _updateHobbsMeter(void); void _vehicleParamLoaded(bool ready); - void _trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading); - void _adsbTimerTimeout(); + void _trafficUpdate (bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading); + void _adsbTimerTimeout (); private: bool _containsLink(LinkInterface* link);