From 5beae411be0d902aab34af83878fa6a42eaa1e7b Mon Sep 17 00:00:00 2001 From: Tory9 Date: Thu, 25 Dec 2025 14:22:16 +0100 Subject: [PATCH 01/17] Add GPS resilience icons --- qgcimages.qrc | 2 ++ src/UI/toolbar/Images/GpsAuthentication.svg | 7 +++++++ src/UI/toolbar/Images/GpsInterference.svg | 18 ++++++++++++++++++ 3 files changed, 27 insertions(+) create mode 100644 src/UI/toolbar/Images/GpsAuthentication.svg create mode 100644 src/UI/toolbar/Images/GpsInterference.svg diff --git a/qgcimages.qrc b/qgcimages.qrc index 5c995eac1753..8a683dea8191 100644 --- a/qgcimages.qrc +++ b/qgcimages.qrc @@ -103,6 +103,8 @@ src/AutoPilotPlugins/PX4/Images/GeoFenceLight.svg src/AnalyzeView/GeoTagIcon.svg src/UI/toolbar/Images/Gps.svg + src/UI/toolbar/Images/GpsAuthentication.svg + src/UI/toolbar/Images/GpsInterference.svg src/UI/toolbar/Images/Hamburger.svg src/UI/toolbar/Images/HamburgerThin.svg src/FlightMap/Images/Help.svg diff --git a/src/UI/toolbar/Images/GpsAuthentication.svg b/src/UI/toolbar/Images/GpsAuthentication.svg new file mode 100644 index 000000000000..8e7094e1bcb4 --- /dev/null +++ b/src/UI/toolbar/Images/GpsAuthentication.svg @@ -0,0 +1,7 @@ + + + + shield-line + + + \ No newline at end of file diff --git a/src/UI/toolbar/Images/GpsInterference.svg b/src/UI/toolbar/Images/GpsInterference.svg new file mode 100644 index 000000000000..f474e26bbdf9 --- /dev/null +++ b/src/UI/toolbar/Images/GpsInterference.svg @@ -0,0 +1,18 @@ +image/svg+xml + + + + + + + + + + + + \ No newline at end of file From c7010427f668df3e9261b9ec4e7b3e058826f70e Mon Sep 17 00:00:00 2001 From: Tory9 Date: Thu, 25 Dec 2025 14:23:21 +0100 Subject: [PATCH 02/17] Extend GPS fact groups with integrity fields --- src/Vehicle/FactGroups/GPSFact.json | 49 +++++++++++++++++++ src/Vehicle/FactGroups/VehicleGPSFactGroup.cc | 47 ++++++++++++++++++ src/Vehicle/FactGroups/VehicleGPSFactGroup.h | 48 ++++++++++++++---- 3 files changed, 135 insertions(+), 9 deletions(-) diff --git a/src/Vehicle/FactGroups/GPSFact.json b/src/Vehicle/FactGroups/GPSFact.json index 989eb1b53688..746c3fa4e985 100644 --- a/src/Vehicle/FactGroups/GPSFact.json +++ b/src/Vehicle/FactGroups/GPSFact.json @@ -58,6 +58,55 @@ "name": "count", "shortDesc": "Sat Count", "type": "uint32" +}, +{ + "name": "systemErrors", + "shortDesc": "General System Errors", + "type": "uint32" +}, +{ + "name": "spoofingState", + "shortDesc": "Signal Spoofing State", + "type": "uint8", + "enumStrings": "Unknown,Not spoofed,Mitigated,Ongoing", + "enumValues": "0,1,2,3", + "decimalPlaces": 0 +}, +{ + "name": "jammingState", + "shortDesc": "Signal Jamming State", + "type": "uint8", + "enumStrings": "Unknown,Not jammed,Mitigated,Ongoing", + "enumValues": "0,1,2,3", + "decimalPlaces": 0 +}, +{ + "name": "authenticationState", + "shortDesc": "Signal Authentication State", + "type": "uint8", + "enumStrings": "Unknown,Initializing,Error,Ok,Disabled", + "enumValues": "0,1,2,3,4", + "decimalPlaces": 0 +}, +{ + "name": "correctionsQuality", + "shortDesc": "Corrections Quality", + "type": "uint8" +}, +{ + "name": "systemQuality", + "shortDesc": "System Status Quality", + "type": "uint8" +}, +{ + "name": "gnssSignalQuality", + "shortDesc": "Gnss Signal Quality", + "type": "uint8" +}, +{ + "name": "postProcessingQuality", + "shortDesc": "Post Processing Quality", + "type": "uint8" } ] } diff --git a/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc b/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc index cebadd664218..ad2e5c8985eb 100644 --- a/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc +++ b/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc @@ -10,6 +10,8 @@ #include "VehicleGPSFactGroup.h" #include "Vehicle.h" #include "QGCGeo.h" +#include "QGCLoggingCategory.h" +#include "development/mavlink_msg_gnss_integrity.h" #include @@ -25,6 +27,14 @@ VehicleGPSFactGroup::VehicleGPSFactGroup(QObject *parent) _addFact(&_yawFact); _addFact(&_lockFact); _addFact(&_countFact); + _addFact(&_systemErrorsFact); + _addFact(&_spoofingStateFact); + _addFact(&_jammingStateFact); + _addFact(&_authenticationStateFact); + _addFact(&_correctionsQualityFact); + _addFact(&_systemQualityFact); + _addFact(&_gnssSignalQualityFact); + _addFact(&_postProcessingQualityFact); _latFact.setRawValue(std::numeric_limits::quiet_NaN()); _lonFact.setRawValue(std::numeric_limits::quiet_NaN()); @@ -33,6 +43,21 @@ VehicleGPSFactGroup::VehicleGPSFactGroup(QObject *parent) _vdopFact.setRawValue(std::numeric_limits::quiet_NaN()); _courseOverGroundFact.setRawValue(std::numeric_limits::quiet_NaN()); _yawFact.setRawValue(std::numeric_limits::quiet_NaN()); + _spoofingStateFact.setRawValue(255); + _jammingStateFact.setRawValue(255); + _authenticationStateFact.setRawValue(255); + _correctionsQualityFact.setRawValue(255); + _systemQualityFact.setRawValue(255); + _gnssSignalQualityFact.setRawValue(255); + _postProcessingQualityFact.setRawValue(255); + + _setGnssIntegrityContext(0, QStringLiteral("GPS1")); +} + +void VehicleGPSFactGroup::_setGnssIntegrityContext(uint8_t id, const QString& logPrefix) +{ + _gnssIntegrityId = id; + _gnssLogPrefix = logPrefix; } void VehicleGPSFactGroup::handleMessage(Vehicle *vehicle, const mavlink_message_t &message) @@ -49,6 +74,9 @@ void VehicleGPSFactGroup::handleMessage(Vehicle *vehicle, const mavlink_message_ case MAVLINK_MSG_ID_HIGH_LATENCY2: _handleHighLatency2(message); break; + case MAVLINK_MSG_ID_GNSS_INTEGRITY: + _handleGnssIntegrity(message); + break; default: break; } @@ -99,3 +127,22 @@ void VehicleGPSFactGroup::_handleHighLatency2(const mavlink_message_t &message) _setTelemetryAvailable(true); } + +void VehicleGPSFactGroup::_handleGnssIntegrity(const mavlink_message_t& message) +{ + mavlink_gnss_integrity_t gnssIntegrity; + mavlink_msg_gnss_integrity_decode(&message, &gnssIntegrity); + + if (gnssIntegrity.id != _gnssIntegrityId) { + return; + } + + systemErrors()->setRawValue (gnssIntegrity.system_errors); + spoofingState()->setRawValue (gnssIntegrity.spoofing_state); + jammingState()->setRawValue (gnssIntegrity.jamming_state); + authenticationState()->setRawValue (gnssIntegrity.authentication_state); + correctionsQuality()->setRawValue (gnssIntegrity.corrections_quality); + systemQuality()->setRawValue (gnssIntegrity.system_status_summary); + gnssSignalQuality()->setRawValue (gnssIntegrity.gnss_signal_quality); + postProcessingQuality()->setRawValue(gnssIntegrity.post_processing_quality); +} diff --git a/src/Vehicle/FactGroups/VehicleGPSFactGroup.h b/src/Vehicle/FactGroups/VehicleGPSFactGroup.h index 75a6aac85b69..b3a3ac2daf42 100644 --- a/src/Vehicle/FactGroups/VehicleGPSFactGroup.h +++ b/src/Vehicle/FactGroups/VehicleGPSFactGroup.h @@ -14,15 +14,23 @@ class VehicleGPSFactGroup : public FactGroup { Q_OBJECT - Q_PROPERTY(Fact *lat READ lat CONSTANT) - Q_PROPERTY(Fact *lon READ lon CONSTANT) - Q_PROPERTY(Fact *mgrs READ mgrs CONSTANT) - Q_PROPERTY(Fact *hdop READ hdop CONSTANT) - Q_PROPERTY(Fact *vdop READ vdop CONSTANT) - Q_PROPERTY(Fact *courseOverGround READ courseOverGround CONSTANT) - Q_PROPERTY(Fact *yaw READ yaw CONSTANT) - Q_PROPERTY(Fact *count READ count CONSTANT) - Q_PROPERTY(Fact *lock READ lock CONSTANT) + Q_PROPERTY(Fact *lat READ lat CONSTANT) + Q_PROPERTY(Fact *lon READ lon CONSTANT) + Q_PROPERTY(Fact *mgrs READ mgrs CONSTANT) + Q_PROPERTY(Fact *hdop READ hdop CONSTANT) + Q_PROPERTY(Fact *vdop READ vdop CONSTANT) + Q_PROPERTY(Fact *courseOverGround READ courseOverGround CONSTANT) + Q_PROPERTY(Fact *yaw READ yaw CONSTANT) + Q_PROPERTY(Fact *count READ count CONSTANT) + Q_PROPERTY(Fact *lock READ lock CONSTANT) + Q_PROPERTY(Fact* systemErrors READ systemErrors CONSTANT) + Q_PROPERTY(Fact* spoofingState READ spoofingState CONSTANT) + Q_PROPERTY(Fact* jammingState READ jammingState CONSTANT) + Q_PROPERTY(Fact* authenticationState READ authenticationState CONSTANT) + Q_PROPERTY(Fact* correctionsQuality READ correctionsQuality CONSTANT) + Q_PROPERTY(Fact* systemQuality READ systemQuality CONSTANT) + Q_PROPERTY(Fact* gnssSignalQuality READ gnssSignalQuality CONSTANT) + Q_PROPERTY(Fact* postProcessingQuality READ postProcessingQuality CONSTANT) public: explicit VehicleGPSFactGroup(QObject *parent = nullptr); @@ -36,14 +44,25 @@ class VehicleGPSFactGroup : public FactGroup Fact *yaw() { return &_yawFact; } Fact *count() { return &_countFact; } Fact *lock() { return &_lockFact; } + Fact *systemErrors() { return &_systemErrorsFact; } + Fact *spoofingState() { return &_spoofingStateFact; } + Fact *jammingState() { return &_jammingStateFact; } + Fact *authenticationState() { return &_authenticationStateFact; } + Fact *correctionsQuality() { return &_correctionsQualityFact; } + Fact *systemQuality() { return &_systemQualityFact; } + Fact *gnssSignalQuality() { return &_gnssSignalQualityFact; } + Fact *postProcessingQuality() { return &_postProcessingQualityFact; } // Overrides from FactGroup void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) override; + + void _setGnssIntegrityContext(uint8_t id, const QString& logPrefix); protected: void _handleGpsRawInt(const mavlink_message_t &message); void _handleHighLatency(const mavlink_message_t &message); void _handleHighLatency2(const mavlink_message_t &message); + void _handleGnssIntegrity(const mavlink_message_t& message); Fact _latFact = Fact(0, QStringLiteral("lat"), FactMetaData::valueTypeDouble); Fact _lonFact = Fact(0, QStringLiteral("lon"), FactMetaData::valueTypeDouble); @@ -54,4 +73,15 @@ class VehicleGPSFactGroup : public FactGroup Fact _yawFact = Fact(0, QStringLiteral("yaw"), FactMetaData::valueTypeDouble); Fact _countFact = Fact(0, QStringLiteral("count"), FactMetaData::valueTypeInt32); Fact _lockFact = Fact(0, QStringLiteral("lock"), FactMetaData::valueTypeInt32); + Fact _systemErrorsFact = Fact(0, QStringLiteral("systemErrors"), FactMetaData::valueTypeUint32); + Fact _spoofingStateFact = Fact(0, QStringLiteral("spoofingState"), FactMetaData::valueTypeUint8); + Fact _jammingStateFact = Fact(0, QStringLiteral("jammingState"), FactMetaData::valueTypeUint8); + Fact _authenticationStateFact = Fact(0, QStringLiteral("authenticationState"), FactMetaData::valueTypeUint8); + Fact _correctionsQualityFact = Fact(0, QStringLiteral("correctionsQuality"), FactMetaData::valueTypeUint8); + Fact _systemQualityFact = Fact(0, QStringLiteral("systemQuality"), FactMetaData::valueTypeUint8); + Fact _gnssSignalQualityFact = Fact(0, QStringLiteral("gnssSignalQuality"), FactMetaData::valueTypeUint8); + Fact _postProcessingQualityFact = Fact(0, QStringLiteral("postProcessingQuality"), FactMetaData::valueTypeUint8); + + uint8_t _gnssIntegrityId; + QString _gnssLogPrefix; }; From 07ac51a6835c4a4d44d04eefe6a2f509561e302a Mon Sep 17 00:00:00 2001 From: Tory9 Date: Thu, 25 Dec 2025 14:23:51 +0100 Subject: [PATCH 03/17] Add GPS2 integrity message handling --- src/Vehicle/FactGroups/VehicleGPS2FactGroup.cc | 6 +++++- src/Vehicle/FactGroups/VehicleGPS2FactGroup.h | 5 ++++- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/src/Vehicle/FactGroups/VehicleGPS2FactGroup.cc b/src/Vehicle/FactGroups/VehicleGPS2FactGroup.cc index 75c58cdbf7a1..8f5017b5a372 100644 --- a/src/Vehicle/FactGroups/VehicleGPS2FactGroup.cc +++ b/src/Vehicle/FactGroups/VehicleGPS2FactGroup.cc @@ -10,6 +10,7 @@ #include "VehicleGPS2FactGroup.h" #include "Vehicle.h" #include "QGCGeo.h" +#include "development/mavlink_msg_gnss_integrity.h" #include @@ -21,11 +22,14 @@ void VehicleGPS2FactGroup::handleMessage(Vehicle *vehicle, const mavlink_message case MAVLINK_MSG_ID_GPS2_RAW: _handleGps2Raw(message); break; + case MAVLINK_MSG_ID_GNSS_INTEGRITY: + _handleGnssIntegrity(message); + break; default: break; } } - + void VehicleGPS2FactGroup::_handleGps2Raw(const mavlink_message_t &message) { mavlink_gps2_raw_t gps2Raw{}; diff --git a/src/Vehicle/FactGroups/VehicleGPS2FactGroup.h b/src/Vehicle/FactGroups/VehicleGPS2FactGroup.h index 05c1c7e4bf3f..1a1142cbc854 100644 --- a/src/Vehicle/FactGroups/VehicleGPS2FactGroup.h +++ b/src/Vehicle/FactGroups/VehicleGPS2FactGroup.h @@ -17,7 +17,10 @@ class VehicleGPS2FactGroup : public VehicleGPSFactGroup public: explicit VehicleGPS2FactGroup(QObject *parent = nullptr) - : VehicleGPSFactGroup(parent) {} + : VehicleGPSFactGroup(parent) + { + _setGnssIntegrityContext(1, QStringLiteral("GPS2")); + } // Overrides from VehicleGPSFactGroup void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) final; From eee7f616740973e20a5c83277b22b2822a65b824 Mon Sep 17 00:00:00 2001 From: Tory9 Date: Thu, 25 Dec 2025 14:24:36 +0100 Subject: [PATCH 04/17] Create GPS aggregate fact group --- src/Vehicle/FactGroups/CMakeLists.txt | 2 + .../VehicleGPSAggregateFactGroup.cc | 164 ++++++++++++++++++ .../FactGroups/VehicleGPSAggregateFactGroup.h | 57 ++++++ 3 files changed, 223 insertions(+) create mode 100644 src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc create mode 100644 src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.h diff --git a/src/Vehicle/FactGroups/CMakeLists.txt b/src/Vehicle/FactGroups/CMakeLists.txt index d69785d883a6..9952307fc8d5 100644 --- a/src/Vehicle/FactGroups/CMakeLists.txt +++ b/src/Vehicle/FactGroups/CMakeLists.txt @@ -27,6 +27,8 @@ target_sources(${CMAKE_PROJECT_NAME} VehicleGPS2FactGroup.h VehicleGPSFactGroup.cc VehicleGPSFactGroup.h + VehicleGPSAggregateFactGroup.cc + VehicleGPSAggregateFactGroup.h VehicleLocalPositionFactGroup.cc VehicleLocalPositionFactGroup.h VehicleLocalPositionSetpointFactGroup.cc diff --git a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc new file mode 100644 index 000000000000..5f0807d7fe58 --- /dev/null +++ b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc @@ -0,0 +1,164 @@ +/**************************************************************************** + * + * (c) 2009-2024 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "VehicleGPSAggregateFactGroup.h" +#include "VehicleGPSFactGroup.h" +#include "VehicleGPS2FactGroup.h" +#include "QGCLoggingCategory.h" +#include + +VehicleGPSAggregateFactGroup::VehicleGPSAggregateFactGroup(QObject *parent) + : FactGroup(0, parent) + , _spoofingStateFact (0, "spoofingState", FactMetaData::valueTypeUint8, this) + , _jammingStateFact (0, "jammingState", FactMetaData::valueTypeUint8, this) + , _authenticationStateFact(0, "authenticationState", FactMetaData::valueTypeUint8, this) + , _isStaleFact (0, "isStale", FactMetaData::valueTypeBool, this) +{ + _spoofingStateFact.setEnumInfo( + QStringList({ "Unknown", "Not spoofed", "Mitigated", "Ongoing" }), + QVariantList({ 0, 1, 2, 3 }) + ); + + _jammingStateFact.setEnumInfo( + QStringList({ "Unknown", "Not jammed", "Mitigated", "Ongoing" }), + QVariantList({ 0, 1, 2, 3 }) + ); + + _authenticationStateFact.setEnumInfo( + QStringList({ "Unknown", "Initializing", "Error", "Ok", "Disabled" }), + QVariantList({ 0, 1, 2, 3, 4 }) + ); + + _addFact(&_spoofingStateFact); + _addFact(&_jammingStateFact); + _addFact(&_authenticationStateFact); + _addFact(&_isStaleFact); + + _spoofingStateFact.setRawValue(255); + _jammingStateFact.setRawValue(255); + _authenticationStateFact.setRawValue(255); + _isStaleFact.setRawValue(true); + + _staleTimer.setSingleShot(true); + _staleTimer.setInterval(5000); + connect(&_staleTimer, &QTimer::timeout, this, &VehicleGPSAggregateFactGroup::_onStaleTimeout); +} + +void VehicleGPSAggregateFactGroup::bindToGps(VehicleGPSFactGroup* gps1, VehicleGPSFactGroup* gps2) +{ + _clearConnections(); + _gps1 = gps1; + _gps2 = gps2; + + auto connectFact = [this](Fact* fact, const QString& name) { + if (fact) { + Q_UNUSED(name); + _connections << connect(fact, &Fact::valueChanged, this, &VehicleGPSAggregateFactGroup::_onIntegrityUpdated); + } + }; + + if (_gps1) { + connectFact(_gps1->spoofingState(), "GPS1 spoofingState"); + connectFact(_gps1->jammingState(), "GPS1 jammingState"); + connectFact(_gps1->authenticationState(), "GPS1 authenticationState"); + } + if (_gps2) { + connectFact(_gps2->spoofingState(), "GPS2 spoofingState"); + connectFact(_gps2->jammingState(), "GPS2 jammingState"); + connectFact(_gps2->authenticationState(), "GPS2 authenticationState"); + } + _updateAggregates(); +} + +void VehicleGPSAggregateFactGroup::_updateAggregates() +{ + updateFromGps(_gps1, _gps2); +} + +void VehicleGPSAggregateFactGroup::_onIntegrityUpdated() +{ + _isStaleFact.setRawValue(false); + _staleTimer.start(); + _updateAggregates(); +} + +void VehicleGPSAggregateFactGroup::_onStaleTimeout() +{ + _spoofingStateFact.setRawValue(255); + _jammingStateFact.setRawValue(255); + _authenticationStateFact.setRawValue(255); + _isStaleFact.setRawValue(true); + _updateAggregates(); +} + +void VehicleGPSAggregateFactGroup::_clearConnections() +{ + for (const auto& c : _connections) { + QObject::disconnect(c); + } + _connections.clear(); +} + +int VehicleGPSAggregateFactGroup::_valueOrInvalid(Fact* fact) +{ + if (!fact) { + return -1; + } + const QVariant v = fact->rawValue(); + if (!v.isValid()) { + return -1; + } + bool ok = false; + const int val = v.toInt(&ok); + if (!ok) { + return -1; + } + return (val == 255) ? -1 : val; +} + +int VehicleGPSAggregateFactGroup::_mergeWorst(int a, int b) +{ + return qMax(a, b); +} + +int VehicleGPSAggregateFactGroup::_mergeAuthentication(int a, int b) +{ + //Priority: 0 (Unknown) < 4 (Disabled) < 1 (Initializing) < 3 (OK) < 2 (Error) + auto getWeight = [](int val) { + switch (val) { + case -1: return -1; + case 0: return 0; + case 4: return 1; + case 1: return 2; + case 3: return 3; + case 2: return 4; + default: return -1; + } + }; + + return (getWeight(a) >= getWeight(b)) ? a : b; +} + +void VehicleGPSAggregateFactGroup::updateFromGps(VehicleGPSFactGroup* gps1, VehicleGPSFactGroup* gps2) +{ + const int spoof1 = _valueOrInvalid(gps1 ? gps1->spoofingState() : nullptr); + const int spoof2 = _valueOrInvalid(gps2 ? gps2->spoofingState() : nullptr); + const int jam1 = _valueOrInvalid(gps1 ? gps1->jammingState() : nullptr); + const int jam2 = _valueOrInvalid(gps2 ? gps2->jammingState() : nullptr); + const int auth1 = _valueOrInvalid(gps1 ? gps1->authenticationState() : nullptr); + const int auth2 = _valueOrInvalid(gps2 ? gps2->authenticationState() : nullptr); + + const int spoofMerged = _mergeWorst(spoof1, spoof2); + const int jamMerged = _mergeWorst(jam1, jam2); + const int authMerged = _mergeAuthentication(auth1, auth2); + + _spoofingStateFact.setRawValue(spoofMerged == -1 ? 255 : spoofMerged); + _jammingStateFact.setRawValue(jamMerged == -1 ? 255 : jamMerged); + _authenticationStateFact.setRawValue(authMerged == -1 ? 255 : authMerged); +} diff --git a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.h b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.h new file mode 100644 index 000000000000..f868603f2d0f --- /dev/null +++ b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.h @@ -0,0 +1,57 @@ +/**************************************************************************** + * + * (c) 2009-2024 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#pragma once + +#include "FactGroup.h" +#include +#include +#include + +class VehicleGPSFactGroup; + +class VehicleGPSAggregateFactGroup : public FactGroup +{ + Q_OBJECT + Q_PROPERTY(Fact* spoofingState READ spoofingState CONSTANT) + Q_PROPERTY(Fact* jammingState READ jammingState CONSTANT) + Q_PROPERTY(Fact* authenticationState READ authenticationState CONSTANT) + Q_PROPERTY(Fact* isStale READ isStale CONSTANT) +public: + explicit VehicleGPSAggregateFactGroup(QObject *parent = nullptr); + + Fact* spoofingState() { return &_spoofingStateFact; } + Fact* jammingState() { return &_jammingStateFact; } + Fact* authenticationState() { return &_authenticationStateFact; } + Fact* isStale() { return &_isStaleFact; } + + void updateFromGps(VehicleGPSFactGroup* gps1, VehicleGPSFactGroup* gps2); + void bindToGps(VehicleGPSFactGroup* gps1, VehicleGPSFactGroup* gps2); + +private slots: + void _updateAggregates(); + void _onIntegrityUpdated(); + void _onStaleTimeout(); + +private: + static int _mergeWorst(int a, int b); + static int _mergeAuthentication(int a, int b); + static int _valueOrInvalid(Fact* fact); + void _clearConnections(); + + VehicleGPSFactGroup* _gps1 = nullptr; + VehicleGPSFactGroup* _gps2 = nullptr; + QTimer _staleTimer; + QVector _connections; + + Fact _spoofingStateFact = Fact(0, QStringLiteral("spoofingState"), FactMetaData::valueTypeUint8); + Fact _jammingStateFact = Fact(0, QStringLiteral("jammingState"), FactMetaData::valueTypeUint8); + Fact _authenticationStateFact = Fact(0, QStringLiteral("authenticationState"), FactMetaData::valueTypeUint8); + Fact _isStaleFact = Fact(0, QStringLiteral("isStale"), FactMetaData::valueTypeBool); +}; \ No newline at end of file From b2a3bb61ca91e3d94e2ffcd38f8d1b67bb3745b3 Mon Sep 17 00:00:00 2001 From: Tory9 Date: Thu, 25 Dec 2025 14:24:57 +0100 Subject: [PATCH 05/17] Wire GPS aggregate into Vehicle class --- src/Vehicle/Vehicle.cc | 5 +++++ src/Vehicle/Vehicle.h | 5 +++++ 2 files changed, 10 insertions(+) diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 56d2ee3fc90c..8690655da7cd 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -101,6 +101,7 @@ Vehicle::Vehicle(LinkInterface* link, , _vehicleFactGroup (this) , _gpsFactGroup (this) , _gps2FactGroup (this) + , _gpsAggregateFactGroup (this) , _windFactGroup (this) , _vibrationFactGroup (this) , _temperatureFactGroup (this) @@ -205,6 +206,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, , _vehicleFactGroup (this) , _gpsFactGroup (this) , _gps2FactGroup (this) + , _gpsAggregateFactGroup (this) , _windFactGroup (this) , _vibrationFactGroup (this) , _clockFactGroup (this) @@ -314,6 +316,8 @@ void Vehicle::_commonInit(LinkInterface* link) // Flight modes can differ based on advanced mode connect(QGCCorePlugin::instance(), &QGCCorePlugin::showAdvancedUIChanged, this, &Vehicle::flightModesChanged); + _gpsAggregateFactGroup.bindToGps(&_gpsFactGroup, &_gps2FactGroup); + _createImageProtocolManager(); _createStatusTextHandler(); _createMAVLinkLogManager(); @@ -321,6 +325,7 @@ void Vehicle::_commonInit(LinkInterface* link) // _addFactGroup(_vehicleFactGroup, _vehicleFactGroupName); _addFactGroup(&_gpsFactGroup, _gpsFactGroupName); _addFactGroup(&_gps2FactGroup, _gps2FactGroupName); + _addFactGroup(&_gpsAggregateFactGroup, _gpsAggregateFactGroupName); _addFactGroup(&_windFactGroup, _windFactGroupName); _addFactGroup(&_vibrationFactGroup, _vibrationFactGroupName); _addFactGroup(&_temperatureFactGroup, _temperatureFactGroupName); diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index d1c56ea091bb..86361854f1b5 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -36,6 +36,7 @@ #include "VehicleGeneratorFactGroup.h" #include "VehicleGPS2FactGroup.h" #include "VehicleGPSFactGroup.h" +#include "VehicleGPSAggregateFactGroup.h" #include "VehicleHygrometerFactGroup.h" #include "VehicleLocalPositionFactGroup.h" #include "VehicleLocalPositionSetpointFactGroup.h" @@ -254,6 +255,7 @@ class Vehicle : public VehicleFactGroup Q_PROPERTY(FactGroup* vehicle READ vehicleFactGroup CONSTANT) Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT) Q_PROPERTY(FactGroup* gps2 READ gps2FactGroup CONSTANT) + Q_PROPERTY(FactGroup* gpsAggregate READ gpsAggregateFactGroup CONSTANT) Q_PROPERTY(FactGroup* wind READ windFactGroup CONSTANT) Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT) Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT) @@ -585,6 +587,7 @@ class Vehicle : public VehicleFactGroup FactGroup* vehicleFactGroup () { return _vehicleFactGroup; } FactGroup* gpsFactGroup () { return &_gpsFactGroup; } FactGroup* gps2FactGroup () { return &_gps2FactGroup; } + FactGroup* gpsAggregateFactGroup () { return &_gpsAggregateFactGroup; } FactGroup* windFactGroup () { return &_windFactGroup; } FactGroup* vibrationFactGroup () { return &_vibrationFactGroup; } FactGroup* temperatureFactGroup () { return &_temperatureFactGroup; } @@ -1220,6 +1223,7 @@ private slots: const QString _vehicleFactGroupName = QStringLiteral("vehicle"); const QString _gpsFactGroupName = QStringLiteral("gps"); const QString _gps2FactGroupName = QStringLiteral("gps2"); + const QString _gpsAggregateFactGroupName = QStringLiteral("gpsAggregate"); const QString _windFactGroupName = QStringLiteral("wind"); const QString _vibrationFactGroupName = QStringLiteral("vibration"); const QString _temperatureFactGroupName = QStringLiteral("temperature"); @@ -1238,6 +1242,7 @@ private slots: VehicleFactGroup* _vehicleFactGroup; VehicleGPSFactGroup _gpsFactGroup; VehicleGPS2FactGroup _gps2FactGroup; + VehicleGPSAggregateFactGroup _gpsAggregateFactGroup; VehicleWindFactGroup _windFactGroup; VehicleVibrationFactGroup _vibrationFactGroup; VehicleTemperatureFactGroup _temperatureFactGroup; From 79c089da8d2fa4b2441c9f0b88e5235a40ba73df Mon Sep 17 00:00:00 2001 From: Tory9 Date: Thu, 25 Dec 2025 14:25:35 +0100 Subject: [PATCH 06/17] Add GPS resilience toolbar indicator --- src/FirmwarePlugin/FirmwarePlugin.cc | 1 + src/UI/toolbar/CMakeLists.txt | 1 + src/UI/toolbar/GPSResilienceIndicator.qml | 166 ++++++++++++++++++++++ 3 files changed, 168 insertions(+) create mode 100644 src/UI/toolbar/GPSResilienceIndicator.qml diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 73aef0074126..004851bb1832 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -204,6 +204,7 @@ const QVariantList &FirmwarePlugin::toolIndicators(const Vehicle*) if (_toolIndicatorList.isEmpty()) { _toolIndicatorList = QVariantList({ QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/VehicleGPSIndicator.qml")), + QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/GPSResilienceIndicator.qml")), QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/TelemetryRSSIIndicator.qml")), QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Toolbar/RCRSSIIndicator.qml")), QVariant::fromValue(QUrl::fromUserInput("qrc:/qml/QGroundControl/Controls/BatteryIndicator.qml")), diff --git a/src/UI/toolbar/CMakeLists.txt b/src/UI/toolbar/CMakeLists.txt index 634b8fbd722f..fc891995d2b1 100644 --- a/src/UI/toolbar/CMakeLists.txt +++ b/src/UI/toolbar/CMakeLists.txt @@ -10,6 +10,7 @@ qt_add_qml_module(ToolbarModule EscIndicatorPage.qml GCSControlIndicator.qml GimbalIndicator.qml + GPSResilienceIndicator.qml JoystickIndicator.qml ModeIndicator.qml MultiVehicleSelector.qml diff --git a/src/UI/toolbar/GPSResilienceIndicator.qml b/src/UI/toolbar/GPSResilienceIndicator.qml new file mode 100644 index 000000000000..99edc3f82ee9 --- /dev/null +++ b/src/UI/toolbar/GPSResilienceIndicator.qml @@ -0,0 +1,166 @@ +/**************************************************************************** + * + * (c) 2009-2024 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +import QtQuick +import QtQuick.Layouts + +import QGroundControl +import QGroundControl.Controls + +//------------------------------------------------------------------------- +//-- GPS Resilience Indicator +Item { + id: control + width: height + anchors.top: parent.top + anchors.bottom: parent.bottom + visible: showIndicator + + property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle + property var _gpsAggregate: _activeVehicle ? _activeVehicle.gpsAggregate : null + + property var qgcPal: QGroundControl.globalPalette + + property bool showIndicator: _activeVehicle && _gpsAggregate && ( + (_gpsAggregate.authenticationState.value > 0 && _gpsAggregate.authenticationState.value < 255) || + (_gpsAggregate.spoofingState.value > 0 && _gpsAggregate.spoofingState.value < 255) || + (_gpsAggregate.jammingState.value > 0 && _gpsAggregate.jammingState.value < 255) + ) + + // Authentication Icon (Outer/Bottom Layer) + QGCColoredImage { + id: authIcon + width: parent.height * 0.95 + height: parent.height * 0.95 + anchors.centerIn: parent + source: "/qmlimages/GpsAuthentication.svg" + fillMode: Image.PreserveAspectFit + sourceSize.height: height + color: _authColor() + visible: _gpsAggregate && _gpsAggregate.authenticationState.value > 0 && _gpsAggregate.authenticationState.value < 255 + } + + // Interference Icon (Inner/Top Layer) + QGCColoredImage { + id: interfIcon + width: parent.height * 0.55 + height: parent.height * 0.55 + anchors.centerIn: parent + source: "/qmlimages/GpsInterference.svg" + fillMode: Image.PreserveAspectFit + sourceSize.height: height + color: _interfColor() + visible: _gpsAggregate && (Math.max(_gpsAggregate.spoofingState.value, _gpsAggregate.jammingState.value) > 0) && (Math.max(_gpsAggregate.spoofingState.value, _gpsAggregate.jammingState.value) < 255) + } + + function _authColor() { + if (!_gpsAggregate) return qgcPal.colorGrey; + switch (_gpsAggregate.authenticationState.value) { + case 1: return qgcPal.colorYellow; // Initializing + case 2: return qgcPal.colorRed; // Error + case 3: return qgcPal.colorGreen; // OK + default: return qgcPal.colorGrey; // Unknown or Disabled + } + } + + function _interfColor() { + if (!_gpsAggregate) return qgcPal.colorGrey; + let maxState = Math.max(_gpsAggregate.spoofingState.value, _gpsAggregate.jammingState.value); + switch (maxState) { + case 1: return qgcPal.colorGreen; // Not spoofed/jammed + case 2: return qgcPal.colorOrange; // Mitigated + case 3: return qgcPal.colorRed; // Detected + default: return qgcPal.colorGrey; // Unknown + } + } + + MouseArea { + anchors.fill: parent + onClicked: mainWindow.showIndicatorDrawer(resiliencePopup, control) + } + + Component { + id: resiliencePopup + ToolIndicatorPage { + showExpand: expandedComponent ? true : false + contentComponent: resilienceContent + } + } + + Component { + id: resilienceContent + ColumnLayout { + spacing: ScreenTools.defaultFontPixelHeight / 2 + + // Unified GPS Resilience Status + SettingsGroupLayout { + heading: qsTr("GPS Resilience Status") + showDividers: true + + LabelledLabel { + label: qsTr("GPS Jamming") + labelText: _gpsAggregate ? (_gpsAggregate.jammingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + visible: _gpsAggregate && _gpsAggregate.jammingState.value > 0 && _gpsAggregate.jammingState.value < 255 + } + + LabelledLabel { + label: qsTr("GPS Spoofing") + labelText: _gpsAggregate ? (_gpsAggregate.spoofingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + visible: _gpsAggregate && _gpsAggregate.spoofingState.value > 0 && _gpsAggregate.spoofingState.value < 255 + } + + LabelledLabel { + label: qsTr("GPS Authentication") + labelText: _gpsAggregate ? (_gpsAggregate.authenticationState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + visible: _gpsAggregate && _gpsAggregate.authenticationState.value > 0 && _gpsAggregate.authenticationState.value < 255 + } + } + + // GPS 1 Details + SettingsGroupLayout { + heading: qsTr("GPS 1 Details") + showDividers: true + visible: _activeVehicle && _activeVehicle.gps && _activeVehicle.gps.lock.value > 0 + + LabelledLabel { + label: qsTr("Jamming") + labelText: (_activeVehicle && _activeVehicle.gps) ? (_activeVehicle.gps.jammingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + } + LabelledLabel { + label: qsTr("Spoofing") + labelText: (_activeVehicle && _activeVehicle.gps) ? (_activeVehicle.gps.spoofingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + } + LabelledLabel { + label: qsTr("Authentication") + labelText: (_activeVehicle && _activeVehicle.gps) ? (_activeVehicle.gps.authenticationState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + } + } + + // GPS 2 Details + SettingsGroupLayout { + heading: qsTr("GPS 2 Details") + showDividers: true + visible: _activeVehicle && _activeVehicle.gps2 && _activeVehicle.gps2.lock.value > 0 + + LabelledLabel { + label: qsTr("Jamming") + labelText: (_activeVehicle && _activeVehicle.gps2) ? (_activeVehicle.gps2.jammingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + } + LabelledLabel { + label: qsTr("Spoofing") + labelText: (_activeVehicle && _activeVehicle.gps2) ? (_activeVehicle.gps2.spoofingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + } + LabelledLabel { + label: qsTr("Authentication") + labelText: (_activeVehicle && _activeVehicle.gps2) ? (_activeVehicle.gps2.authenticationState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + } + } + } + } +} From f8c97ad2d569d8cbfe7f79156a384de9e20002a8 Mon Sep 17 00:00:00 2001 From: Tory9 Date: Thu, 25 Dec 2025 15:52:47 +0100 Subject: [PATCH 07/17] Add GPS system errors to existing GPS indicator page --- src/QmlControls/GPSIndicatorPage.qml | 30 ++++++++++++++++++++++++++++ 1 file changed, 30 insertions(+) diff --git a/src/QmlControls/GPSIndicatorPage.qml b/src/QmlControls/GPSIndicatorPage.qml index 152d5a74a1ec..cf8a4786bfc2 100644 --- a/src/QmlControls/GPSIndicatorPage.qml +++ b/src/QmlControls/GPSIndicatorPage.qml @@ -63,6 +63,30 @@ ToolIndicatorPage { updateSettingsDisplayId() } + function errorText() { + if (!_activeVehicle) { + return qsTr("Disconnected"); + } + + switch (_activeVehicle.gps.systemErrors.value) { + case 1: + return qsTr("Incoming correction"); + case 2: + return qsTr("Configuration"); + case 4: + return qsTr("Software"); + case 8: + return qsTr("Antenna"); + case 16: + return qsTr("Event congestion"); + case 32: + return qsTr("CPU overload"); + case 64: + return qsTr("Output congestion"); + default: + return qsTr("Multiple errors"); + } + } contentComponent: Component { ColumnLayout { @@ -96,6 +120,12 @@ ToolIndicatorPage { label: qsTr("Course Over Ground") labelText: activeVehicle ? activeVehicle.gps.courseOverGround.valueString : valueNA } + + LabelledLabel { + label: qsTr("GPS Error") + labelText: errorText() + visible: activeVehicle && activeVehicle.gps.systemErrors.value > 0 + } } SettingsGroupLayout { From ebf3a91cf4ae148137b745f41cc36e8604ccbd1c Mon Sep 17 00:00:00 2001 From: Tory9 Date: Thu, 25 Dec 2025 16:02:13 +0100 Subject: [PATCH 08/17] Copilot review follow-up: Remove trailing whitespace --- src/UI/toolbar/CMakeLists.txt | 2 +- src/Vehicle/FactGroups/VehicleGPS2FactGroup.cc | 4 ++-- src/Vehicle/FactGroups/VehicleGPSFactGroup.h | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/UI/toolbar/CMakeLists.txt b/src/UI/toolbar/CMakeLists.txt index fc891995d2b1..547d24baecca 100644 --- a/src/UI/toolbar/CMakeLists.txt +++ b/src/UI/toolbar/CMakeLists.txt @@ -10,7 +10,7 @@ qt_add_qml_module(ToolbarModule EscIndicatorPage.qml GCSControlIndicator.qml GimbalIndicator.qml - GPSResilienceIndicator.qml + GPSResilienceIndicator.qml JoystickIndicator.qml ModeIndicator.qml MultiVehicleSelector.qml diff --git a/src/Vehicle/FactGroups/VehicleGPS2FactGroup.cc b/src/Vehicle/FactGroups/VehicleGPS2FactGroup.cc index 8f5017b5a372..ce5004d638fa 100644 --- a/src/Vehicle/FactGroups/VehicleGPS2FactGroup.cc +++ b/src/Vehicle/FactGroups/VehicleGPS2FactGroup.cc @@ -23,13 +23,13 @@ void VehicleGPS2FactGroup::handleMessage(Vehicle *vehicle, const mavlink_message _handleGps2Raw(message); break; case MAVLINK_MSG_ID_GNSS_INTEGRITY: - _handleGnssIntegrity(message); + _handleGnssIntegrity(message); break; default: break; } } - + void VehicleGPS2FactGroup::_handleGps2Raw(const mavlink_message_t &message) { mavlink_gps2_raw_t gps2Raw{}; diff --git a/src/Vehicle/FactGroups/VehicleGPSFactGroup.h b/src/Vehicle/FactGroups/VehicleGPSFactGroup.h index b3a3ac2daf42..31fd482b006f 100644 --- a/src/Vehicle/FactGroups/VehicleGPSFactGroup.h +++ b/src/Vehicle/FactGroups/VehicleGPSFactGroup.h @@ -83,5 +83,5 @@ class VehicleGPSFactGroup : public FactGroup Fact _postProcessingQualityFact = Fact(0, QStringLiteral("postProcessingQuality"), FactMetaData::valueTypeUint8); uint8_t _gnssIntegrityId; - QString _gnssLogPrefix; + QString _gnssLogPrefix; }; From 4c5332f6780466bad8d2ad46f1238e21ab33a34b Mon Sep 17 00:00:00 2001 From: Tory9 Date: Thu, 25 Dec 2025 16:14:02 +0100 Subject: [PATCH 09/17] Copilot review follow-up: Remove redundant code in GPS aggregate handling --- src/Vehicle/FactGroups/VehicleGPS2FactGroup.h | 2 +- .../FactGroups/VehicleGPSAggregateFactGroup.cc | 16 +++++++--------- src/Vehicle/FactGroups/VehicleGPSFactGroup.cc | 5 ++--- src/Vehicle/FactGroups/VehicleGPSFactGroup.h | 4 +--- 4 files changed, 11 insertions(+), 16 deletions(-) diff --git a/src/Vehicle/FactGroups/VehicleGPS2FactGroup.h b/src/Vehicle/FactGroups/VehicleGPS2FactGroup.h index 1a1142cbc854..889c251e1869 100644 --- a/src/Vehicle/FactGroups/VehicleGPS2FactGroup.h +++ b/src/Vehicle/FactGroups/VehicleGPS2FactGroup.h @@ -19,7 +19,7 @@ class VehicleGPS2FactGroup : public VehicleGPSFactGroup explicit VehicleGPS2FactGroup(QObject *parent = nullptr) : VehicleGPSFactGroup(parent) { - _setGnssIntegrityContext(1, QStringLiteral("GPS2")); + _setGnssIntegrityContext(1); } // Overrides from VehicleGPSFactGroup diff --git a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc index 5f0807d7fe58..742d533bbcdf 100644 --- a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc +++ b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc @@ -56,22 +56,21 @@ void VehicleGPSAggregateFactGroup::bindToGps(VehicleGPSFactGroup* gps1, VehicleG _gps1 = gps1; _gps2 = gps2; - auto connectFact = [this](Fact* fact, const QString& name) { + auto connectFact = [this](Fact* fact) { if (fact) { - Q_UNUSED(name); _connections << connect(fact, &Fact::valueChanged, this, &VehicleGPSAggregateFactGroup::_onIntegrityUpdated); } }; if (_gps1) { - connectFact(_gps1->spoofingState(), "GPS1 spoofingState"); - connectFact(_gps1->jammingState(), "GPS1 jammingState"); - connectFact(_gps1->authenticationState(), "GPS1 authenticationState"); + connectFact(_gps1->spoofingState()); + connectFact(_gps1->jammingState()); + connectFact(_gps1->authenticationState()); } if (_gps2) { - connectFact(_gps2->spoofingState(), "GPS2 spoofingState"); - connectFact(_gps2->jammingState(), "GPS2 jammingState"); - connectFact(_gps2->authenticationState(), "GPS2 authenticationState"); + connectFact(_gps2->spoofingState()); + connectFact(_gps2->jammingState()); + connectFact(_gps2->authenticationState()); } _updateAggregates(); } @@ -94,7 +93,6 @@ void VehicleGPSAggregateFactGroup::_onStaleTimeout() _jammingStateFact.setRawValue(255); _authenticationStateFact.setRawValue(255); _isStaleFact.setRawValue(true); - _updateAggregates(); } void VehicleGPSAggregateFactGroup::_clearConnections() diff --git a/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc b/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc index ad2e5c8985eb..4ea94870c277 100644 --- a/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc +++ b/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc @@ -51,13 +51,12 @@ VehicleGPSFactGroup::VehicleGPSFactGroup(QObject *parent) _gnssSignalQualityFact.setRawValue(255); _postProcessingQualityFact.setRawValue(255); - _setGnssIntegrityContext(0, QStringLiteral("GPS1")); + _setGnssIntegrityContext(0); } -void VehicleGPSFactGroup::_setGnssIntegrityContext(uint8_t id, const QString& logPrefix) +void VehicleGPSFactGroup::_setGnssIntegrityContext(uint8_t id) { _gnssIntegrityId = id; - _gnssLogPrefix = logPrefix; } void VehicleGPSFactGroup::handleMessage(Vehicle *vehicle, const mavlink_message_t &message) diff --git a/src/Vehicle/FactGroups/VehicleGPSFactGroup.h b/src/Vehicle/FactGroups/VehicleGPSFactGroup.h index 31fd482b006f..427fbf85f6fd 100644 --- a/src/Vehicle/FactGroups/VehicleGPSFactGroup.h +++ b/src/Vehicle/FactGroups/VehicleGPSFactGroup.h @@ -55,8 +55,7 @@ class VehicleGPSFactGroup : public FactGroup // Overrides from FactGroup void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) override; - - void _setGnssIntegrityContext(uint8_t id, const QString& logPrefix); + void _setGnssIntegrityContext(uint8_t id); protected: void _handleGpsRawInt(const mavlink_message_t &message); @@ -83,5 +82,4 @@ class VehicleGPSFactGroup : public FactGroup Fact _postProcessingQualityFact = Fact(0, QStringLiteral("postProcessingQuality"), FactMetaData::valueTypeUint8); uint8_t _gnssIntegrityId; - QString _gnssLogPrefix; }; From 20b869ec310a343da1d85031c7a9df6fb46db360 Mon Sep 17 00:00:00 2001 From: Tory9 Date: Thu, 25 Dec 2025 16:22:41 +0100 Subject: [PATCH 10/17] Copilot review follow-up: Improve GPS resilience code clarity --- src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc | 2 +- src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.h | 2 ++ 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc index 742d533bbcdf..51c6fb4edc45 100644 --- a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc +++ b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc @@ -46,7 +46,7 @@ VehicleGPSAggregateFactGroup::VehicleGPSAggregateFactGroup(QObject *parent) _isStaleFact.setRawValue(true); _staleTimer.setSingleShot(true); - _staleTimer.setInterval(5000); + _staleTimer.setInterval(GNSS_INTEGRITY_STALE_TIMEOUT_MS); connect(&_staleTimer, &QTimer::timeout, this, &VehicleGPSAggregateFactGroup::_onStaleTimeout); } diff --git a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.h b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.h index f868603f2d0f..7233cb6ed37e 100644 --- a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.h +++ b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.h @@ -40,6 +40,8 @@ private slots: void _onStaleTimeout(); private: + static constexpr int GNSS_INTEGRITY_STALE_TIMEOUT_MS = 5000; + static int _mergeWorst(int a, int b); static int _mergeAuthentication(int a, int b); static int _valueOrInvalid(Fact* fact); From 4af4e38ff19dd858454442658c53959ee6037adc Mon Sep 17 00:00:00 2001 From: Tory9 Date: Thu, 25 Dec 2025 20:17:08 +0100 Subject: [PATCH 11/17] Add signal emission on GNSS_INTEGRITY message receipt for stale timer --- src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc | 2 ++ src/Vehicle/FactGroups/VehicleGPSFactGroup.cc | 2 ++ src/Vehicle/FactGroups/VehicleGPSFactGroup.h | 3 +++ 3 files changed, 7 insertions(+) diff --git a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc index 51c6fb4edc45..ba3453b5f0c9 100644 --- a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc +++ b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc @@ -66,11 +66,13 @@ void VehicleGPSAggregateFactGroup::bindToGps(VehicleGPSFactGroup* gps1, VehicleG connectFact(_gps1->spoofingState()); connectFact(_gps1->jammingState()); connectFact(_gps1->authenticationState()); + _connections << connect(_gps1, &VehicleGPSFactGroup::gnssIntegrityReceived, this, &VehicleGPSAggregateFactGroup::_onIntegrityUpdated); } if (_gps2) { connectFact(_gps2->spoofingState()); connectFact(_gps2->jammingState()); connectFact(_gps2->authenticationState()); + _connections << connect(_gps2, &VehicleGPSFactGroup::gnssIntegrityReceived, this, &VehicleGPSAggregateFactGroup::_onIntegrityUpdated); } _updateAggregates(); } diff --git a/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc b/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc index 4ea94870c277..a95a94ac7780 100644 --- a/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc +++ b/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc @@ -144,4 +144,6 @@ void VehicleGPSFactGroup::_handleGnssIntegrity(const mavlink_message_t& message) systemQuality()->setRawValue (gnssIntegrity.system_status_summary); gnssSignalQuality()->setRawValue (gnssIntegrity.gnss_signal_quality); postProcessingQuality()->setRawValue(gnssIntegrity.post_processing_quality); + + emit gnssIntegrityReceived(); } diff --git a/src/Vehicle/FactGroups/VehicleGPSFactGroup.h b/src/Vehicle/FactGroups/VehicleGPSFactGroup.h index 427fbf85f6fd..2e42af613c33 100644 --- a/src/Vehicle/FactGroups/VehicleGPSFactGroup.h +++ b/src/Vehicle/FactGroups/VehicleGPSFactGroup.h @@ -57,6 +57,9 @@ class VehicleGPSFactGroup : public FactGroup void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) override; void _setGnssIntegrityContext(uint8_t id); +signals: + void gnssIntegrityReceived(); + protected: void _handleGpsRawInt(const mavlink_message_t &message); void _handleHighLatency(const mavlink_message_t &message); From 74b49e8065d44c4b3ecb007abf7446d9cb5c5acb Mon Sep 17 00:00:00 2001 From: Tory9 Date: Thu, 25 Dec 2025 20:42:19 +0100 Subject: [PATCH 12/17] Refine GPS resilience details visibility --- src/UI/toolbar/GPSResilienceIndicator.qml | 18 ++++++++++++++++-- 1 file changed, 16 insertions(+), 2 deletions(-) diff --git a/src/UI/toolbar/GPSResilienceIndicator.qml b/src/UI/toolbar/GPSResilienceIndicator.qml index 99edc3f82ee9..a5124e75b246 100644 --- a/src/UI/toolbar/GPSResilienceIndicator.qml +++ b/src/UI/toolbar/GPSResilienceIndicator.qml @@ -126,19 +126,26 @@ Item { SettingsGroupLayout { heading: qsTr("GPS 1 Details") showDividers: true - visible: _activeVehicle && _activeVehicle.gps && _activeVehicle.gps.lock.value > 0 + visible: _activeVehicle && _activeVehicle.gps && ( + _activeVehicle.gps.jammingState.value < 255 || + _activeVehicle.gps.spoofingState.value < 255 || + _activeVehicle.gps.authenticationState.value < 255 + ) LabelledLabel { label: qsTr("Jamming") labelText: (_activeVehicle && _activeVehicle.gps) ? (_activeVehicle.gps.jammingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + visible: _activeVehicle.gps.jammingState.value < 255 } LabelledLabel { label: qsTr("Spoofing") labelText: (_activeVehicle && _activeVehicle.gps) ? (_activeVehicle.gps.spoofingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + visible: _activeVehicle.gps.spoofingState.value < 255 } LabelledLabel { label: qsTr("Authentication") labelText: (_activeVehicle && _activeVehicle.gps) ? (_activeVehicle.gps.authenticationState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + visible: _activeVehicle.gps.authenticationState.value < 255 } } @@ -146,19 +153,26 @@ Item { SettingsGroupLayout { heading: qsTr("GPS 2 Details") showDividers: true - visible: _activeVehicle && _activeVehicle.gps2 && _activeVehicle.gps2.lock.value > 0 + visible: _activeVehicle && _activeVehicle.gps2 && ( + _activeVehicle.gps2.jammingState.value < 255 || + _activeVehicle.gps2.spoofingState.value < 255 || + _activeVehicle.gps2.authenticationState.value < 255 + ) LabelledLabel { label: qsTr("Jamming") labelText: (_activeVehicle && _activeVehicle.gps2) ? (_activeVehicle.gps2.jammingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + visible: _activeVehicle.gps2.jammingState.value < 255 } LabelledLabel { label: qsTr("Spoofing") labelText: (_activeVehicle && _activeVehicle.gps2) ? (_activeVehicle.gps2.spoofingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + visible: _activeVehicle.gps2.spoofingState.value < 255 } LabelledLabel { label: qsTr("Authentication") labelText: (_activeVehicle && _activeVehicle.gps2) ? (_activeVehicle.gps2.authenticationState.enumStringValue || qsTr("n/a")) : qsTr("n/a") + visible: _activeVehicle.gps2.authenticationState.value < 255 } } } From b9c531e1958fb49f3c922f125f250dee0b7756a5 Mon Sep 17 00:00:00 2001 From: Tory9 Date: Mon, 29 Dec 2025 19:42:04 +0100 Subject: [PATCH 13/17] Simplify GNSS Integrity ID handling --- src/Vehicle/FactGroups/VehicleGPS2FactGroup.h | 2 +- src/Vehicle/FactGroups/VehicleGPSFactGroup.cc | 7 ------- src/Vehicle/FactGroups/VehicleGPSFactGroup.h | 3 +-- 3 files changed, 2 insertions(+), 10 deletions(-) diff --git a/src/Vehicle/FactGroups/VehicleGPS2FactGroup.h b/src/Vehicle/FactGroups/VehicleGPS2FactGroup.h index 889c251e1869..dcfb3595690c 100644 --- a/src/Vehicle/FactGroups/VehicleGPS2FactGroup.h +++ b/src/Vehicle/FactGroups/VehicleGPS2FactGroup.h @@ -19,7 +19,7 @@ class VehicleGPS2FactGroup : public VehicleGPSFactGroup explicit VehicleGPS2FactGroup(QObject *parent = nullptr) : VehicleGPSFactGroup(parent) { - _setGnssIntegrityContext(1); + _gnssIntegrityId = 1; } // Overrides from VehicleGPSFactGroup diff --git a/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc b/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc index a95a94ac7780..f7a734e15dd2 100644 --- a/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc +++ b/src/Vehicle/FactGroups/VehicleGPSFactGroup.cc @@ -50,13 +50,6 @@ VehicleGPSFactGroup::VehicleGPSFactGroup(QObject *parent) _systemQualityFact.setRawValue(255); _gnssSignalQualityFact.setRawValue(255); _postProcessingQualityFact.setRawValue(255); - - _setGnssIntegrityContext(0); -} - -void VehicleGPSFactGroup::_setGnssIntegrityContext(uint8_t id) -{ - _gnssIntegrityId = id; } void VehicleGPSFactGroup::handleMessage(Vehicle *vehicle, const mavlink_message_t &message) diff --git a/src/Vehicle/FactGroups/VehicleGPSFactGroup.h b/src/Vehicle/FactGroups/VehicleGPSFactGroup.h index 2e42af613c33..b7d0c891d463 100644 --- a/src/Vehicle/FactGroups/VehicleGPSFactGroup.h +++ b/src/Vehicle/FactGroups/VehicleGPSFactGroup.h @@ -55,7 +55,6 @@ class VehicleGPSFactGroup : public FactGroup // Overrides from FactGroup void handleMessage(Vehicle *vehicle, const mavlink_message_t &message) override; - void _setGnssIntegrityContext(uint8_t id); signals: void gnssIntegrityReceived(); @@ -84,5 +83,5 @@ class VehicleGPSFactGroup : public FactGroup Fact _gnssSignalQualityFact = Fact(0, QStringLiteral("gnssSignalQuality"), FactMetaData::valueTypeUint8); Fact _postProcessingQualityFact = Fact(0, QStringLiteral("postProcessingQuality"), FactMetaData::valueTypeUint8); - uint8_t _gnssIntegrityId; + uint8_t _gnssIntegrityId {}; }; From 34a7f52e9e7c9c7b84a4c6bf4ce57e44fc7e1ed3 Mon Sep 17 00:00:00 2001 From: Tory9 Date: Mon, 29 Dec 2025 19:43:09 +0100 Subject: [PATCH 14/17] Switch to using JSON metadata for facts --- .../VehicleGPSAggregateFactGroup.cc | 21 +------------------ 1 file changed, 1 insertion(+), 20 deletions(-) diff --git a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc index ba3453b5f0c9..017ab3d4abbb 100644 --- a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc +++ b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc @@ -14,27 +14,8 @@ #include VehicleGPSAggregateFactGroup::VehicleGPSAggregateFactGroup(QObject *parent) - : FactGroup(0, parent) - , _spoofingStateFact (0, "spoofingState", FactMetaData::valueTypeUint8, this) - , _jammingStateFact (0, "jammingState", FactMetaData::valueTypeUint8, this) - , _authenticationStateFact(0, "authenticationState", FactMetaData::valueTypeUint8, this) - , _isStaleFact (0, "isStale", FactMetaData::valueTypeBool, this) + : FactGroup(1000, ":/json/Vehicle/GPSFact.json", parent) { - _spoofingStateFact.setEnumInfo( - QStringList({ "Unknown", "Not spoofed", "Mitigated", "Ongoing" }), - QVariantList({ 0, 1, 2, 3 }) - ); - - _jammingStateFact.setEnumInfo( - QStringList({ "Unknown", "Not jammed", "Mitigated", "Ongoing" }), - QVariantList({ 0, 1, 2, 3 }) - ); - - _authenticationStateFact.setEnumInfo( - QStringList({ "Unknown", "Initializing", "Error", "Ok", "Disabled" }), - QVariantList({ 0, 1, 2, 3, 4 }) - ); - _addFact(&_spoofingStateFact); _addFact(&_jammingStateFact); _addFact(&_authenticationStateFact); From 64eae2a8d3d5fc536a338c3d7a3bdc8ca5b00b6c Mon Sep 17 00:00:00 2001 From: Tory9 Date: Mon, 29 Dec 2025 19:43:54 +0100 Subject: [PATCH 15/17] Simplify signal connections --- .../FactGroups/VehicleGPSAggregateFactGroup.cc | 12 ------------ 1 file changed, 12 deletions(-) diff --git a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc index 017ab3d4abbb..94c43996282b 100644 --- a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc +++ b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc @@ -37,22 +37,10 @@ void VehicleGPSAggregateFactGroup::bindToGps(VehicleGPSFactGroup* gps1, VehicleG _gps1 = gps1; _gps2 = gps2; - auto connectFact = [this](Fact* fact) { - if (fact) { - _connections << connect(fact, &Fact::valueChanged, this, &VehicleGPSAggregateFactGroup::_onIntegrityUpdated); - } - }; - if (_gps1) { - connectFact(_gps1->spoofingState()); - connectFact(_gps1->jammingState()); - connectFact(_gps1->authenticationState()); _connections << connect(_gps1, &VehicleGPSFactGroup::gnssIntegrityReceived, this, &VehicleGPSAggregateFactGroup::_onIntegrityUpdated); } if (_gps2) { - connectFact(_gps2->spoofingState()); - connectFact(_gps2->jammingState()); - connectFact(_gps2->authenticationState()); _connections << connect(_gps2, &VehicleGPSFactGroup::gnssIntegrityReceived, this, &VehicleGPSAggregateFactGroup::_onIntegrityUpdated); } _updateAggregates(); From 507556e8a19addfbf74ba6582de79a2c723e0061 Mon Sep 17 00:00:00 2001 From: Tory9 Date: Mon, 29 Dec 2025 19:44:51 +0100 Subject: [PATCH 16/17] Introduce AuthState enum for clearer authentication merge logic --- .../FactGroups/VehicleGPSAggregateFactGroup.cc | 17 ++++++++--------- .../FactGroups/VehicleGPSAggregateFactGroup.h | 9 +++++++++ 2 files changed, 17 insertions(+), 9 deletions(-) diff --git a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc index 94c43996282b..ec0c4a5192d3 100644 --- a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc +++ b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.cc @@ -9,7 +9,6 @@ #include "VehicleGPSAggregateFactGroup.h" #include "VehicleGPSFactGroup.h" -#include "VehicleGPS2FactGroup.h" #include "QGCLoggingCategory.h" #include @@ -98,16 +97,16 @@ int VehicleGPSAggregateFactGroup::_mergeWorst(int a, int b) int VehicleGPSAggregateFactGroup::_mergeAuthentication(int a, int b) { - //Priority: 0 (Unknown) < 4 (Disabled) < 1 (Initializing) < 3 (OK) < 2 (Error) + // Priority: Unknown < Disabled < Initializing < OK < Error auto getWeight = [](int val) { switch (val) { - case -1: return -1; - case 0: return 0; - case 4: return 1; - case 1: return 2; - case 3: return 3; - case 2: return 4; - default: return -1; + case AUTH_INVALID: return -1; + case AUTH_UNKNOWN: return 0; // lowest priority) + case AUTH_DISABLED: return 1; + case AUTH_INITIALIZING: return 2; + case AUTH_OK: return 3; + case AUTH_ERROR: return 4; // highest priority + default: return -1; } }; diff --git a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.h b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.h index 7233cb6ed37e..bd8d364b552f 100644 --- a/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.h +++ b/src/Vehicle/FactGroups/VehicleGPSAggregateFactGroup.h @@ -24,6 +24,15 @@ class VehicleGPSAggregateFactGroup : public FactGroup Q_PROPERTY(Fact* authenticationState READ authenticationState CONSTANT) Q_PROPERTY(Fact* isStale READ isStale CONSTANT) public: + enum AuthState { + AUTH_UNKNOWN = 0, + AUTH_INITIALIZING = 1, + AUTH_ERROR = 2, + AUTH_OK = 3, + AUTH_DISABLED = 4, + AUTH_INVALID = -1 + }; + explicit VehicleGPSAggregateFactGroup(QObject *parent = nullptr); Fact* spoofingState() { return &_spoofingStateFact; } From 5b5eb526823a2a7891ad4ff7caf5b7a56b28bf98 Mon Sep 17 00:00:00 2001 From: Tory9 Date: Mon, 29 Dec 2025 21:06:22 +0100 Subject: [PATCH 17/17] Updated GPS detail visibility --- src/UI/toolbar/GPSResilienceIndicator.qml | 24 +++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/src/UI/toolbar/GPSResilienceIndicator.qml b/src/UI/toolbar/GPSResilienceIndicator.qml index a5124e75b246..2d11446eb5f8 100644 --- a/src/UI/toolbar/GPSResilienceIndicator.qml +++ b/src/UI/toolbar/GPSResilienceIndicator.qml @@ -127,25 +127,25 @@ Item { heading: qsTr("GPS 1 Details") showDividers: true visible: _activeVehicle && _activeVehicle.gps && ( - _activeVehicle.gps.jammingState.value < 255 || - _activeVehicle.gps.spoofingState.value < 255 || - _activeVehicle.gps.authenticationState.value < 255 + (_activeVehicle.gps.jammingState.value > 0 && _activeVehicle.gps.jammingState.value < 255) || + (_activeVehicle.gps.spoofingState.value > 0 && _activeVehicle.gps.spoofingState.value < 255) || + (_activeVehicle.gps.authenticationState.value > 0 && _activeVehicle.gps.authenticationState.value < 255) ) LabelledLabel { label: qsTr("Jamming") labelText: (_activeVehicle && _activeVehicle.gps) ? (_activeVehicle.gps.jammingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") - visible: _activeVehicle.gps.jammingState.value < 255 + visible: _activeVehicle.gps.jammingState.value > 0 && _activeVehicle.gps.jammingState.value < 255 } LabelledLabel { label: qsTr("Spoofing") labelText: (_activeVehicle && _activeVehicle.gps) ? (_activeVehicle.gps.spoofingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") - visible: _activeVehicle.gps.spoofingState.value < 255 + visible: _activeVehicle.gps.spoofingState.value > 0 && _activeVehicle.gps.spoofingState.value < 255 } LabelledLabel { label: qsTr("Authentication") labelText: (_activeVehicle && _activeVehicle.gps) ? (_activeVehicle.gps.authenticationState.enumStringValue || qsTr("n/a")) : qsTr("n/a") - visible: _activeVehicle.gps.authenticationState.value < 255 + visible: _activeVehicle.gps.authenticationState.value > 0 && _activeVehicle.gps.authenticationState.value < 255 } } @@ -154,25 +154,25 @@ Item { heading: qsTr("GPS 2 Details") showDividers: true visible: _activeVehicle && _activeVehicle.gps2 && ( - _activeVehicle.gps2.jammingState.value < 255 || - _activeVehicle.gps2.spoofingState.value < 255 || - _activeVehicle.gps2.authenticationState.value < 255 + (_activeVehicle.gps2.jammingState.value > 0 && _activeVehicle.gps2.jammingState.value < 255) || + (_activeVehicle.gps2.spoofingState.value > 0 && _activeVehicle.gps2.spoofingState.value < 255) || + (_activeVehicle.gps2.authenticationState.value > 0 && _activeVehicle.gps2.authenticationState.value < 255) ) LabelledLabel { label: qsTr("Jamming") labelText: (_activeVehicle && _activeVehicle.gps2) ? (_activeVehicle.gps2.jammingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") - visible: _activeVehicle.gps2.jammingState.value < 255 + visible: _activeVehicle.gps2.jammingState.value > 0 && _activeVehicle.gps2.jammingState.value < 255 } LabelledLabel { label: qsTr("Spoofing") labelText: (_activeVehicle && _activeVehicle.gps2) ? (_activeVehicle.gps2.spoofingState.enumStringValue || qsTr("n/a")) : qsTr("n/a") - visible: _activeVehicle.gps2.spoofingState.value < 255 + visible: _activeVehicle.gps2.spoofingState.value > 0 && _activeVehicle.gps2.spoofingState.value < 255 } LabelledLabel { label: qsTr("Authentication") labelText: (_activeVehicle && _activeVehicle.gps2) ? (_activeVehicle.gps2.authenticationState.enumStringValue || qsTr("n/a")) : qsTr("n/a") - visible: _activeVehicle.gps2.authenticationState.value < 255 + visible: _activeVehicle.gps2.authenticationState.value > 0 && _activeVehicle.gps2.authenticationState.value < 255 } } }