diff --git a/src/Vehicle/RemoteIDManager.cc b/src/Vehicle/RemoteIDManager.cc index 4be36403c952..722dabda7c88 100644 --- a/src/Vehicle/RemoteIDManager.cc +++ b/src/Vehicle/RemoteIDManager.cc @@ -53,17 +53,14 @@ RemoteIDManager::RemoteIDManager(Vehicle* vehicle) connect(_settings->basicID(), &Fact::rawValueChanged, this, &RemoteIDManager::_checkGCSBasicID); connect(_settings->basicIDType(), &Fact::rawValueChanged, this, &RemoteIDManager::_checkGCSBasicID); connect(_settings->basicIDUaType(), &Fact::rawValueChanged, this, &RemoteIDManager::_checkGCSBasicID); + connect(_settings->operatorID(), &Fact::rawValueChanged, this, &RemoteIDManager::_handleOperatorIDChanged); + connect(_settings->operatorIDType(), &Fact::rawValueChanged, this, [this]() { _refreshOperatorIDState(); }); + connect(_settings->region(), &Fact::rawValueChanged, this, [this]() { _refreshOperatorIDState(); }); // Assign vehicle sysid and compid. GCS must target these messages to autopilot, and autopilot will redirect them to RID device _targetSystem = _vehicle->id(); _targetComponent = _vehicle->compId(); - - if (_settings->operatorIDValid()->rawValue() == true || (_settings->region()->rawValue().toInt() != Region::EU && _settings->operatorID()->rawValue().toString().length() > 0)) { - // If it was already checked, we can flag this as good to go. - // We don't do a fresh verification because we don't store the private part of the ID. - _operatorIDGood = true; - emit operatorIDGoodChanged(); - } + _refreshOperatorIDState(); } void RemoteIDManager::mavlinkMessageReceived(mavlink_message_t& message ) @@ -391,34 +388,59 @@ void RemoteIDManager::_checkGCSBasicID() void RemoteIDManager::checkOperatorID(const QString& operatorID) { - // We overwrite the fact that is also set by the text input but we want to update - // after every letter rather than when editing is done. - // We check whether it actually changed to avoid triggering this on startup. - if (operatorID != _settings->operatorID()->rawValueString()) { - _settings->operatorIDValid()->setRawValue(_isEUOperatorIDValid(operatorID)); + const bool operatorIDValid = (operatorID.length() > 16) && _isEUOperatorIDValid(operatorID); + if (_settings->operatorIDValid()->rawValue().toBool() != operatorIDValid) { + _settings->operatorIDValid()->setRawValue(operatorIDValid); } } void RemoteIDManager::setOperatorID() { - QString operatorID = _settings->operatorID()->rawValue().toString(); - - if (_settings->region()->rawValue().toInt() == Region::EU) { - // Save for next time because we don't save the private part, - // so we can't re-verify next time and just trust the value - // in the settings. - _operatorIDGood = _settings->operatorIDValid()->rawValue() == true; - if (_operatorIDGood) { - // Strip private part - _settings->operatorID()->setRawValue(operatorID.sliced(0, 16)); - } + _refreshOperatorIDState(); +} - } else { - // Otherwise, we just check if there is anything entered - _operatorIDGood = - (!operatorID.isEmpty() && (_settings->operatorIDType()->rawValue().toInt() >= 0)); +void RemoteIDManager::_handleOperatorIDChanged(const QVariant& value) +{ + if (_updatingOperatorID) { + return; + } + + const QString operatorID = value.toString(); + const bool operatorIDValid = (operatorID.length() > 16) && _isEUOperatorIDValid(operatorID); + if (_settings->operatorIDValid()->rawValue().toBool() != operatorIDValid) { + _settings->operatorIDValid()->setRawValue(operatorIDValid); + } + + _refreshOperatorIDState(); +} + +void RemoteIDManager::_refreshOperatorIDState() +{ + const QString operatorID = _settings->operatorID()->rawValue().toString(); + const bool isEURegion = (_settings->region()->rawValue().toInt() == Region::EU); + const bool operatorIDValid = _settings->operatorIDValid()->rawValue().toBool(); + + if (isEURegion && operatorIDValid && (operatorID.length() > 16)) { + // Keep only the public 16-character EU operator ID once a full value has been validated. + _updatingOperatorID = true; + _settings->operatorID()->setRawValue(operatorID.sliced(0, 16)); + _updatingOperatorID = false; + } + + const bool operatorIDGood = isEURegion + ? operatorIDValid + : (!operatorID.isEmpty() && (_settings->operatorIDType()->rawValue().toInt() >= 0)); + + _setOperatorIDGood(operatorIDGood); +} + +void RemoteIDManager::_setOperatorIDGood(bool operatorIDGood) +{ + if (_operatorIDGood == operatorIDGood) { + return; } + _operatorIDGood = operatorIDGood; emit operatorIDGoodChanged(); } diff --git a/src/Vehicle/RemoteIDManager.h b/src/Vehicle/RemoteIDManager.h index f8a413c99948..b249272c366f 100644 --- a/src/Vehicle/RemoteIDManager.h +++ b/src/Vehicle/RemoteIDManager.h @@ -79,6 +79,9 @@ private slots: private: void _handleArmStatus(mavlink_message_t& message); + void _handleOperatorIDChanged(const QVariant& value); + void _refreshOperatorIDState(); + void _setOperatorIDGood(bool operatorIDGood); // Self ID void _sendSelfIDMsg (); @@ -113,6 +116,7 @@ private slots: bool _basicIDGood; bool _GCSBasicIDValid; bool _operatorIDGood; + bool _updatingOperatorID = false; bool _emergencyDeclared; QDateTime _lastGeoPositionTimeStamp; diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index cc492e2aed87..98a56ad6c5c0 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -310,6 +310,7 @@ add_qgc_test(FirmwareUpgradeControllerTest LABELS Unit Vehicle) add_qgc_test(InitialConnectTest LABELS Integration Vehicle RESOURCE_LOCK MockLink) add_qgc_test(InitialConnectPeripheralStartupTest LABELS Integration Vehicle RESOURCE_LOCK MockLink) add_qgc_test(MAVLinkLogManagerTest LABELS Integration Vehicle RESOURCE_LOCK MockLink) +add_qgc_test(RemoteIDManagerTest LABELS Integration Vehicle RESOURCE_LOCK MockLink) add_qgc_test(RequestMessageTest LABELS Integration Vehicle RESOURCE_LOCK MockLink TIMEOUT ${QGC_TEST_TIMEOUT_EXTENDED}) add_qgc_test(RequestMetaDataTypeStateMachineTest LABELS Integration Vehicle RESOURCE_LOCK MockLink) add_qgc_test(SendMavCommandWithHandlerTest LABELS Integration Vehicle RESOURCE_LOCK MockLink) diff --git a/test/Vehicle/CMakeLists.txt b/test/Vehicle/CMakeLists.txt index 2f0589fb2be3..95ee99b5f5b7 100644 --- a/test/Vehicle/CMakeLists.txt +++ b/test/Vehicle/CMakeLists.txt @@ -19,6 +19,8 @@ target_sources(${CMAKE_PROJECT_NAME} MAVLinkLogManagerTest.h APMAirframeComponentControllerTest.cc APMAirframeComponentControllerTest.h + RemoteIDManagerTest.cc + RemoteIDManagerTest.h RequestMessageTest.cc RequestMessageTest.h SendMavCommandWithHandlerTest.cc diff --git a/test/Vehicle/RemoteIDManagerTest.cc b/test/Vehicle/RemoteIDManagerTest.cc new file mode 100644 index 000000000000..0ed00f34c8fb --- /dev/null +++ b/test/Vehicle/RemoteIDManagerTest.cc @@ -0,0 +1,82 @@ +#include "RemoteIDManagerTest.h" + +#include "RemoteIDManager.h" +#include "RemoteIDSettings.h" +#include "SettingsManager.h" +#include "Vehicle.h" + +namespace { + +constexpr const char* kValidFullOperatorID = "FIN87astrdge12k8-xyz"; +constexpr const char* kValidPublicOperatorID = "FIN87astrdge12k8"; +constexpr const char* kInvalidOperatorID = "DEADBEEFDEADBEEF"; + +} // namespace + +void RemoteIDManagerTest::init() +{ + VehicleTestNoInitialConnect::init(); + + RemoteIDSettings* settings = SettingsManager::instance()->remoteIDSettings(); + QVERIFY(settings); + QVERIFY(vehicle()); + QVERIFY(vehicle()->remoteIDManager()); + + _savedOperatorID = settings->operatorID()->rawValue(); + _savedOperatorIDType = settings->operatorIDType()->rawValue(); + _savedOperatorIDValid = settings->operatorIDValid()->rawValue(); + _savedRegion = settings->region()->rawValue(); +} + +void RemoteIDManagerTest::cleanup() +{ + RemoteIDSettings* settings = SettingsManager::instance()->remoteIDSettings(); + QVERIFY(settings); + + settings->region()->setRawValue(RemoteIDManager::FAA); + settings->operatorID()->setRawValue(_savedOperatorID); + settings->operatorIDValid()->setRawValue(_savedOperatorIDValid); + settings->operatorIDType()->setRawValue(_savedOperatorIDType); + settings->region()->setRawValue(_savedRegion); + + VehicleTestNoInitialConnect::cleanup(); +} + +void RemoteIDManagerTest::_validEUOperatorIDIsSanitized() +{ + RemoteIDSettings* settings = SettingsManager::instance()->remoteIDSettings(); + RemoteIDManager* manager = vehicle()->remoteIDManager(); + + settings->region()->setRawValue(RemoteIDManager::EU); + settings->operatorIDType()->setRawValue(0); + settings->operatorIDValid()->setRawValue(false); + settings->operatorID()->setRawValue(QString()); + + settings->operatorID()->setRawValue(QString::fromLatin1(kValidFullOperatorID)); + + QVERIFY(settings->operatorIDValid()->rawValue().toBool()); + QCOMPARE(settings->operatorID()->rawValue().toString(), QString::fromLatin1(kValidPublicOperatorID)); + QVERIFY(manager->operatorIDGood()); +} + +void RemoteIDManagerTest::_invalidEUOperatorIDClearsTrustedState() +{ + RemoteIDSettings* settings = SettingsManager::instance()->remoteIDSettings(); + RemoteIDManager* manager = vehicle()->remoteIDManager(); + + settings->region()->setRawValue(RemoteIDManager::EU); + settings->operatorIDType()->setRawValue(0); + settings->operatorIDValid()->setRawValue(false); + settings->operatorID()->setRawValue(QString::fromLatin1(kValidFullOperatorID)); + + QVERIFY(settings->operatorIDValid()->rawValue().toBool()); + QVERIFY(manager->operatorIDGood()); + + settings->operatorID()->setRawValue(QString::fromLatin1(kInvalidOperatorID)); + + QVERIFY(!settings->operatorIDValid()->rawValue().toBool()); + QCOMPARE(settings->operatorID()->rawValue().toString(), QString::fromLatin1(kInvalidOperatorID)); + QVERIFY(!manager->operatorIDGood()); +} + +UT_REGISTER_TEST(RemoteIDManagerTest, TestLabel::Integration, TestLabel::Vehicle) diff --git a/test/Vehicle/RemoteIDManagerTest.h b/test/Vehicle/RemoteIDManagerTest.h new file mode 100644 index 000000000000..a48922cbd731 --- /dev/null +++ b/test/Vehicle/RemoteIDManagerTest.h @@ -0,0 +1,29 @@ +#pragma once + +#include + +#include "BaseClasses/VehicleTest.h" + +class RemoteIDManagerTest : public VehicleTestNoInitialConnect +{ + Q_OBJECT + +public: + explicit RemoteIDManagerTest(QObject* parent = nullptr) + : VehicleTestNoInitialConnect(parent) + { + } + +private slots: + void init() override; + void cleanup() override; + + void _validEUOperatorIDIsSanitized(); + void _invalidEUOperatorIDClearsTrustedState(); + +private: + QVariant _savedOperatorID; + QVariant _savedOperatorIDType; + QVariant _savedOperatorIDValid; + QVariant _savedRegion; +};