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. 9
      src/Settings/RemoteID.SettingsGroup.json
  2. 3
      src/Settings/RemoteIDSettings.cc
  3. 3
      src/Settings/RemoteIDSettings.h
  4. 113
      src/Vehicle/RemoteIDManager.cc
  5. 17
      src/Vehicle/RemoteIDManager.h
  6. 52
      src/ui/preferences/RemoteIDSettings.qml

9
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",
@ -166,4 +173,4 @@ @@ -166,4 +173,4 @@
"default": 0
}
]
}
}

3
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)
@ -37,4 +38,4 @@ DECLARE_SETTINGSFACT(RemoteIDSettings, longitudeFixed) @@ -37,4 +38,4 @@ DECLARE_SETTINGSFACT(RemoteIDSettings, longitudeFixed)
DECLARE_SETTINGSFACT(RemoteIDSettings, altitudeFixed)
DECLARE_SETTINGSFACT(RemoteIDSettings, classificationType)
DECLARE_SETTINGSFACT(RemoteIDSettings, categoryEU)
DECLARE_SETTINGSFACT(RemoteIDSettings, classEU)
DECLARE_SETTINGSFACT(RemoteIDSettings, classEU)

3
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)
@ -39,4 +40,4 @@ public: @@ -39,4 +40,4 @@ public:
DEFINE_SETTINGFACT(classificationType)
DEFINE_SETTINGFACT(categoryEU)
DEFINE_SETTINGFACT(classEU)
};
};

113
src/Vehicle/RemoteIDManager.cc

@ -66,13 +66,20 @@ RemoteIDManager::RemoteIDManager(Vehicle* vehicle) @@ -66,13 +66,20 @@ 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 )
{
switch (message.msgid) {
// So far we are only listening to this one, as heartbeat won't be sent if connected by CAN
case MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS:
case MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS:
_handleArmStatus(message);
default:
break;
@ -99,7 +106,7 @@ void RemoteIDManager::_handleArmStatus(mavlink_message_t& message) @@ -99,7 +106,7 @@ void RemoteIDManager::_handleArmStatus(mavlink_message_t& message)
}
}
// Sanity check, only get messages from same sysid
// Sanity check, only get messages from same sysid
if (_vehicle->id() != message.sysid) {
return;
}
@ -113,8 +120,7 @@ void RemoteIDManager::_handleArmStatus(mavlink_message_t& message) @@ -113,8 +120,7 @@ void RemoteIDManager::_handleArmStatus(mavlink_message_t& message)
if (!_commsGood) {
_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
_checkGCSBasicID(); // Check if basicID is good to send
emit commsGoodChanged();
qCDebug(RemoteIDManagerLog) << "Receiving ODID_ARM_STATUS from RID device";
}
@ -159,22 +165,22 @@ void RemoteIDManager::_sendMessages() @@ -159,22 +165,22 @@ void RemoteIDManager::_sendMessages()
if (!_settings->enable()->rawValue().toBool()) {
return;
}
// We always try to send System
_sendSystem();
// only send it if the information is correct and the tickbox in settings is set
if (_GCSBasicIDValid && _settings->sendBasicID()->rawValue().toBool()) {
_sendBasicID();
}
// We only send selfID if the pilot wants it or in case of a declared emergency. If an emergency is cleared
// we also keep sending the message, to be sure the non emergency state makes it up to the vehicle
if (_settings->sendSelfID()->rawValue().toBool() || _emergencyDeclared || _enforceSendingSelfID) {
_sendSelfIDMsg();
}
// We only send the OperatorID if the pilot wants it or if the region we have set is europe.
// We only send the OperatorID if the pilot wants it or if the region we have set is europe.
// To be able to send it, it needs to be filled correclty
if ((_settings->sendOperatorID()->rawValue().toBool() || (_settings->region()->rawValue().toInt() == Region::EU)) && _operatorIDGood) {
_sendOperatorID();
@ -230,7 +236,7 @@ const char* RemoteIDManager::_getSelfIDDescription() @@ -230,7 +236,7 @@ const char* RemoteIDManager::_getSelfIDDescription()
descriptionToSend = bytesEmergency.data();
}
}
return descriptionToSend;
}
@ -266,7 +272,7 @@ void RemoteIDManager::_sendSystem() @@ -266,7 +272,7 @@ void RemoteIDManager::_sendSystem()
QGeoPositionInfo geoPositionInfo;
// Location types:
// 0 -> TAKEOFF (not supported yet)
// 1 -> LIVE GNNS
// 1 -> LIVE GNNS
// 2 -> FIXED
if (_settings->locationType()->rawValue().toUInt() == LocationTypes::FIXED) {
// For FIXED location, we first check that the values are valid. Then we populate our position
@ -301,7 +307,7 @@ void RemoteIDManager::_sendSystem() @@ -301,7 +307,7 @@ void RemoteIDManager::_sendSystem()
return;
}
// If the GPS data is older than ALLOWED_GPS_DELAY we cannot use this data
// If the GPS data is older than ALLOWED_GPS_DELAY we cannot use this data
if (_lastGeoPositionTimeStamp.msecsTo(QDateTime::currentDateTime().currentDateTimeUtc()) > ALLOWED_GPS_DELAY) {
if (_gcsGPSGood) {
_gcsGPSGood = false;
@ -319,12 +325,12 @@ void RemoteIDManager::_sendSystem() @@ -319,12 +325,12 @@ void RemoteIDManager::_sendSystem()
emit gcsGPSGoodChanged();
qCDebug(RemoteIDManagerLog) << "GCS GPS data is not valid.";
}
}
WeakLinkInterfacePtr weakLink = _vehicle->vehicleLinkManager()->primaryLink();
SharedLinkInterfacePtr sharedLink = weakLink.lock();
if (sharedLink) {
mavlink_message_t msg;
@ -366,10 +372,10 @@ void RemoteIDManager::_sendBasicID() @@ -366,10 +372,10 @@ void RemoteIDManager::_sendBasicID()
if (sharedLink) {
mavlink_message_t msg;
QString basicIDTemp = _settings->basicID()->rawValue().toString();
QByteArray ba = basicIDTemp.toLocal8Bit();
// To make sure the buffer is large enough to fit the message. It will add padding bytes if smaller, or exclude the extra ones if bigger
// To make sure the buffer is large enough to fit the message. It will add padding bytes if smaller, or exclude the extra ones if bigger
ba.resize(MAVLINK_MSG_OPEN_DRONE_ID_BASIC_ID_FIELD_UAS_ID_LEN);
mavlink_msg_open_drone_id_basic_id_pack_chan(_mavlink->getSystemId(),
@ -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;
@ -427,4 +500,4 @@ void RemoteIDManager::_updateLastGCSPositionInfo(QGeoPositionInfo update) @@ -427,4 +500,4 @@ void RemoteIDManager::_updateLastGCSPositionInfo(QGeoPositionInfo update)
if (update.isValid()) {
_lastGeoPositionTimeStamp = update.timestamp().toUTC();
}
}
}

17
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);
@ -84,7 +84,7 @@ private slots: @@ -84,7 +84,7 @@ private slots:
private:
void _handleArmStatus(mavlink_message_t& message);
// Self ID
// Self ID
void _sendSelfIDMsg ();
const char* _getSelfIDDescription();
@ -97,7 +97,10 @@ private: @@ -97,7 +97,10 @@ private:
// Basic ID
void _sendBasicID();
bool _isEUOperatorIDValid(const QString& operatorID) const;
QChar _calculateLuhnMod36(const QString& input) const;
MAVLinkProtocol* _mavlink;
Vehicle* _vehicle;
RemoteIDSettings* _settings;
@ -119,10 +122,10 @@ private: @@ -119,10 +122,10 @@ private:
// After emergency cleared, this makes sure the non emergency selfID message makes it to the vehicle
bool _enforceSendingSelfID;
static const uint8_t* _id_or_mac_unknown;
// Timers
QTimer _odidTimeoutTimer;
QTimer _sendMessagesTimer;
};
};

52
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
@ -189,7 +190,7 @@ Rectangle { @@ -189,7 +190,7 @@ Rectangle {
font.bold: true
}
}
Rectangle {
id: gpsFlag
Layout.preferredHeight: flagsHeight
@ -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
@ -423,7 +424,7 @@ Rectangle { @@ -423,7 +424,7 @@ Rectangle {
// -----------------------------------------------------------------------------------------
// ----------------------------------------- GPS -------------------------------------------
// Data representation and connection options for GCS GPS.
// Data representation and connection options for GCS GPS.
QGCLabel {
id: gpsLabel
text: qsTr("GPS GCS")
@ -478,7 +479,7 @@ Rectangle { @@ -478,7 +479,7 @@ Rectangle {
if (_regionOperation == RemoteIDSettings.RegionOperation.FAA) {
if (currentIndex != 1) {
QGroundControl.settingsManager.remoteIDSettings.locationType.value = 1
currentIndex = 1
currentIndex = 1
}
} else {
// TODO: this lines below efectively disable TAKEOFF option. Uncoment when we add support for it
@ -526,7 +527,7 @@ Rectangle { @@ -526,7 +527,7 @@ Rectangle {
Layout.fillWidth: true
fact: QGroundControl.settingsManager.remoteIDSettings.altitudeFixed
}
QGCLabel {
text: qsTr("Latitude")
Layout.fillWidth: true
@ -550,7 +551,7 @@ Rectangle { @@ -550,7 +551,7 @@ Rectangle {
}
QGCLabel {
text: _regionOperation == RemoteIDSettings.RegionOperation.FAA ?
text: _regionOperation == RemoteIDSettings.RegionOperation.FAA ?
qsTr("Altitude") + qsTr(" (Mandatory)") :
qsTr("Altitude")
Layout.fillWidth: true
@ -693,7 +694,7 @@ Rectangle { @@ -693,7 +694,7 @@ Rectangle {
visible: QGroundControl.settingsManager.remoteIDSettings.basicIDType.visible
}
GridLayout {
id: basicIDGrid
anchors.margins: _margins
@ -784,13 +785,13 @@ Rectangle { @@ -784,13 +785,13 @@ Rectangle {
QGCLabel {
text: QGroundControl.settingsManager.remoteIDSettings.operatorIDType.shortDescription
visible: QGroundControl.settingsManager.remoteIDSettings.operatorIDType.visible
visible: QGroundControl.settingsManager.remoteIDSettings.operatorIDType.visible
Layout.fillWidth: true
}
FactComboBox {
id: operatorIDFactComboBox
fact: QGroundControl.settingsManager.remoteIDSettings.operatorIDType
visible: QGroundControl.settingsManager.remoteIDSettings.operatorIDType.visible && (QGroundControl.settingsManager.remoteIDSettings.operatorIDType.enumValues.length > 1)
visible: QGroundControl.settingsManager.remoteIDSettings.operatorIDType.visible && (QGroundControl.settingsManager.remoteIDSettings.operatorIDType.enumValues.length > 1)
Layout.fillWidth: true
sizeToContents: true
}
@ -801,7 +802,7 @@ Rectangle { @@ -801,7 +802,7 @@ Rectangle {
}
QGCLabel {
text: _regionOperation == RemoteIDSettings.RegionOperation.FAA ?
text: _regionOperation == RemoteIDSettings.RegionOperation.FAA ?
QGroundControl.settingsManager.remoteIDSettings.operatorID.shortDescription :
QGroundControl.settingsManager.remoteIDSettings.operatorID.shortDescription + qsTr(" (Mandatory)")
visible: QGroundControl.settingsManager.remoteIDSettings.operatorID.visible
@ -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()
}
}
}
@ -899,7 +923,7 @@ Rectangle { @@ -899,7 +923,7 @@ Rectangle {
visible: QGroundControl.settingsManager.remoteIDSettings.sendSelfID.visible
}
}
QGCLabel {
id: selfIDnote
width: selfIDGrid.width

Loading…
Cancel
Save