Browse Source

RemoteID: validate EU operator ID (#10970)

This implements the validation of the operator ID as required for the EU remote ID spec.

The way it works is that:

1. The user enters the operator ID including the checksum and secret.
2. The ID is validated using the secret against the checksum.
3. The secret is removed and the public ID is saved, as well as a flag signalling that the ID has been checked.

This work is sponsored by bluemark.io., https://github.com/BluemarkInnovations.

Signed-off-by: Julian Oes <julian@oes.ch>
QGC4.4
Julian Oes 1 year ago
parent
commit
a8dd833217
No known key found for this signature in database
GPG Key ID: F0ED380FEA56DE41
  1. 7
      src/Settings/RemoteID.SettingsGroup.json
  2. 1
      src/Settings/RemoteIDSettings.cc
  3. 1
      src/Settings/RemoteIDSettings.h
  4. 83
      src/Vehicle/RemoteIDManager.cc
  5. 9
      src/Vehicle/RemoteIDManager.h
  6. 30
      src/ui/preferences/RemoteIDSettings.qml

7
src/Settings/RemoteID.SettingsGroup.json

@ -17,6 +17,13 @@ @@ -17,6 +17,13 @@
"default": ""
},
{
"name": "operatorIDValid",
"shortDesc": "Operator ID is valid",
"longDesc": "Operator ID has been checked using checksum.",
"type": "bool",
"default": false
},
{
"name": "operatorIDType",
"shortDesc": "Operator ID type",
"type": "uint8",

1
src/Settings/RemoteIDSettings.cc

@ -19,6 +19,7 @@ DECLARE_SETTINGGROUP(RemoteID, "RemoteID") @@ -19,6 +19,7 @@ DECLARE_SETTINGGROUP(RemoteID, "RemoteID")
DECLARE_SETTINGSFACT(RemoteIDSettings, enable)
DECLARE_SETTINGSFACT(RemoteIDSettings, operatorID)
DECLARE_SETTINGSFACT(RemoteIDSettings, operatorIDValid)
DECLARE_SETTINGSFACT(RemoteIDSettings, operatorIDType)
DECLARE_SETTINGSFACT(RemoteIDSettings, sendOperatorID)
DECLARE_SETTINGSFACT(RemoteIDSettings, selfIDFree)

1
src/Settings/RemoteIDSettings.h

@ -20,6 +20,7 @@ public: @@ -20,6 +20,7 @@ public:
DEFINE_SETTINGFACT(enable)
DEFINE_SETTINGFACT(operatorID)
DEFINE_SETTINGFACT(operatorIDValid)
DEFINE_SETTINGFACT(operatorIDType)
DEFINE_SETTINGFACT(sendOperatorID)
DEFINE_SETTINGFACT(selfIDFree)

83
src/Vehicle/RemoteIDManager.cc

@ -66,6 +66,13 @@ RemoteIDManager::RemoteIDManager(Vehicle* vehicle) @@ -66,6 +66,13 @@ RemoteIDManager::RemoteIDManager(Vehicle* vehicle)
// 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) {
// 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;
operatorIDGoodChanged();
}
}
void RemoteIDManager::mavlinkMessageReceived(mavlink_message_t& message )
@ -114,7 +121,6 @@ void RemoteIDManager::_handleArmStatus(mavlink_message_t& message) @@ -114,7 +121,6 @@ void RemoteIDManager::_handleArmStatus(mavlink_message_t& message)
_commsGood = true;
_sendMessagesTimer.start(); // Start sending our messages
_checkGCSBasicID(); // Check if basicID is good to send
checkOperatorID(); // Check if OperatorID is good in case we want to send it from start because of the settings
emit commsGoodChanged();
qCDebug(RemoteIDManagerLog) << "Receiving ODID_ARM_STATUS from RID device";
}
@ -398,18 +404,85 @@ void RemoteIDManager::_checkGCSBasicID() @@ -398,18 +404,85 @@ void RemoteIDManager::_checkGCSBasicID()
}
}
void RemoteIDManager::checkOperatorID()
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));
}
}
void RemoteIDManager::setOperatorID()
{
QString operatorID = _settings->operatorID()->rawValue().toString();
if (!operatorID.isEmpty() && (_settings->operatorIDType()->rawValue().toInt() >= 0)) {
_operatorIDGood = true;
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));
}
} else {
_operatorIDGood = false;
// Otherwise, we just check if there is anything entered
_operatorIDGood =
(!operatorID.isEmpty() && (_settings->operatorIDType()->rawValue().toInt() >= 0));
}
emit operatorIDGoodChanged();
}
bool RemoteIDManager::_isEUOperatorIDValid(const QString& operatorID) const
{
const bool containsDash = operatorID.contains('-');
if (!(operatorID.length() == 20 && containsDash) && !(operatorID.length() == 19 && !containsDash)) {
qCDebug(RemoteIDManagerLog) << "OperatorID not long enough";
return false;
}
const QString countryCode = operatorID.sliced(0,3);
if (!countryCode.isUpper()) {
qCDebug(RemoteIDManagerLog) << "OperatorID country code not uppercase";
return false;
}
const QString number = operatorID.sliced(3, 12);
const QChar checksum = operatorID.at(15);
const QString secret = containsDash ? operatorID.sliced(17, 3) : operatorID.sliced(16, 3);
const QString combination = number + secret;
const QChar result = _calculateLuhnMod36(combination);
const bool valid = (result == checksum);
qCDebug(RemoteIDManagerLog) << "Operator ID checksum " << (valid ? "valid" : "invalid");
return valid;
}
QChar RemoteIDManager::_calculateLuhnMod36(const QString& input) const {
const int n = 36;
const QString alphabet = "0123456789abcdefghijklmnopqrstuvwxyz";
int sum = 0;
int factor = 2;
for (int i = input.length() - 1; i >= 0; i--) {
int codePoint = alphabet.indexOf(input[i]);
int addend = factor * codePoint;
factor = (factor == 2) ? 1 : 2;
addend = (addend / n) + (addend % n);
sum += addend;
}
int remainder = sum % n;
int checkCodePoint = (n - remainder) % n;
return alphabet.at(checkCodePoint);
}
void RemoteIDManager::setEmergency(bool declare)
{
_emergencyDeclared = declare;

9
src/Vehicle/RemoteIDManager.h

@ -22,7 +22,7 @@ Q_DECLARE_LOGGING_CATEGORY(RemoteIDManagerLog) @@ -22,7 +22,7 @@ Q_DECLARE_LOGGING_CATEGORY(RemoteIDManagerLog)
class RemoteIDSettings;
class QGCPositionManager;
// Supporting Opend Dron ID protocol
// Supporting Open Drone ID protocol
class RemoteIDManager : public QObject
{
Q_OBJECT
@ -39,8 +39,8 @@ public: @@ -39,8 +39,8 @@ public:
Q_PROPERTY (bool operatorIDGood READ operatorIDGood NOTIFY operatorIDGoodChanged)
// Check that the information filled by the pilot operatorID is good
Q_INVOKABLE void checkOperatorID();
Q_INVOKABLE void checkOperatorID(const QString& operatorID);
Q_INVOKABLE void setOperatorID();
// Declare emergency
Q_INVOKABLE void setEmergency(bool declare);
@ -98,6 +98,9 @@ private: @@ -98,6 +98,9 @@ private:
// Basic ID
void _sendBasicID();
bool _isEUOperatorIDValid(const QString& operatorID) const;
QChar _calculateLuhnMod36(const QString& input) const;
MAVLinkProtocol* _mavlink;
Vehicle* _vehicle;
RemoteIDSettings* _settings;

30
src/ui/preferences/RemoteIDSettings.qml

@ -47,6 +47,7 @@ Rectangle { @@ -47,6 +47,7 @@ Rectangle {
// General properties
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property var _offlineVehicle: QGroundControl.multiVehicleManager.offlineEditingVehicle
property int _regionOperation: QGroundControl.settingsManager.remoteIDSettings.region.value
property int _locationType: QGroundControl.settingsManager.remoteIDSettings.locationType.value
property int _classificationType: QGroundControl.settingsManager.remoteIDSettings.classificationType.value
@ -239,7 +240,7 @@ Rectangle { @@ -239,7 +240,7 @@ Rectangle {
}
Rectangle {
id: operaotrIDFlag
id: operatorIDFlag
Layout.preferredHeight: flagsHeight
Layout.preferredWidth: flagsWidth
color: _activeRID ? (_activeVehicle.remoteIDManager.operatorIDGood ? qgcPal.colorGreen : qgcPal.colorRed) : qgcPal.colorGrey
@ -814,12 +815,35 @@ Rectangle { @@ -814,12 +815,35 @@ Rectangle {
visible: QGroundControl.settingsManager.remoteIDSettings.operatorID.visible
Layout.fillWidth: true
maximumLength: 20 // Maximum defined by Mavlink definition of OPEN_DRONE_ID_OPERATOR_ID message
onTextChanged: {
if (_activeVehicle) {
_activeVehicle.remoteIDManager.checkOperatorID(text)
} else {
_offlineVehicle.remoteIDManager.checkOperatorID(text)
}
}
onEditingFinished: {
if (_activeVehicle) {
_activeVehicle.remoteIDManager.checkOperatorID()
_activeVehicle.remoteIDManager.setOperatorID()
} else {
_offlineVehicle.remoteIDManager.setOperatorID()
}
}
}
// Spacer
QGCLabel {
text: ""
visible: _regionOperation == RemoteIDSettings.RegionOperation.EU
Layout.alignment: Qt.AlignHCenter
Layout.fillWidth: true
}
QGCLabel {
text: QGroundControl.settingsManager.remoteIDSettings.operatorID.shortDescription + qsTr(QGroundControl.settingsManager.remoteIDSettings.operatorIDValid.rawValue == true ? " valid" : " invalid")
visible: _regionOperation == RemoteIDSettings.RegionOperation.EU
Layout.alignment: Qt.AlignHCenter
Layout.fillWidth: true
}
QGCLabel {
@ -833,7 +857,7 @@ Rectangle { @@ -833,7 +857,7 @@ Rectangle {
onClicked: {
if (checked) {
if (_activeVehicle) {
_activeVehicle.remoteIDManager.checkOperatorID()
_activeVehicle.remoteIDManager.setOperatorID()
}
}
}

Loading…
Cancel
Save