Skip to content

Commit

Permalink
RemoteID: validate EU operator ID (mavlink#10970)
Browse files Browse the repository at this point in the history
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>
  • Loading branch information
julianoes committed Apr 11, 2024
1 parent 3902373 commit a8dd833
Show file tree
Hide file tree
Showing 6 changed files with 153 additions and 44 deletions.
9 changes: 8 additions & 1 deletion src/Settings/RemoteID.SettingsGroup.json
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,13 @@
"type": "string",
"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",
Expand Down Expand Up @@ -166,4 +173,4 @@
"default": 0
}
]
}
}
3 changes: 2 additions & 1 deletion src/Settings/RemoteIDSettings.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand All @@ -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 changes: 2 additions & 1 deletion src/Settings/RemoteIDSettings.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ class RemoteIDSettings : public SettingsGroup

DEFINE_SETTINGFACT(enable)
DEFINE_SETTINGFACT(operatorID)
DEFINE_SETTINGFACT(operatorIDValid)
DEFINE_SETTINGFACT(operatorIDType)
DEFINE_SETTINGFACT(sendOperatorID)
DEFINE_SETTINGFACT(selfIDFree)
Expand All @@ -39,4 +40,4 @@ class RemoteIDSettings : public SettingsGroup
DEFINE_SETTINGFACT(classificationType)
DEFINE_SETTINGFACT(categoryEU)
DEFINE_SETTINGFACT(classEU)
};
};
113 changes: 93 additions & 20 deletions src/Vehicle/RemoteIDManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand All @@ -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;
}
Expand All @@ -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";
}
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -230,7 +236,7 @@ const char* RemoteIDManager::_getSelfIDDescription()
descriptionToSend = bytesEmergency.data();
}
}

return descriptionToSend;
}

Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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;
Expand All @@ -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;

Expand Down Expand Up @@ -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(),
Expand Down Expand Up @@ -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;
Expand All @@ -427,4 +500,4 @@ void RemoteIDManager::_updateLastGCSPositionInfo(QGeoPositionInfo update)
if (update.isValid()) {
_lastGeoPositionTimeStamp = update.timestamp().toUTC();
}
}
}
17 changes: 10 additions & 7 deletions src/Vehicle/RemoteIDManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -39,8 +39,8 @@ class RemoteIDManager : public QObject
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);
Expand Down Expand Up @@ -84,7 +84,7 @@ private slots:
private:
void _handleArmStatus(mavlink_message_t& message);

// Self ID
// Self ID
void _sendSelfIDMsg ();
const char* _getSelfIDDescription();

Expand All @@ -97,7 +97,10 @@ private slots:

// Basic ID
void _sendBasicID();


bool _isEUOperatorIDValid(const QString& operatorID) const;
QChar _calculateLuhnMod36(const QString& input) const;

MAVLinkProtocol* _mavlink;
Vehicle* _vehicle;
RemoteIDSettings* _settings;
Expand All @@ -119,10 +122,10 @@ private slots:

// 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;
};
};
Loading

0 comments on commit a8dd833

Please sign in to comment.