13#define MAVLINK_UNKNOWN_METERS -1000.0f
14#define MAVLINK_UNKNOWN_LAT 0
15#define MAVLINK_UNKNOWN_LON 0
16#define SENDING_RATE_MSEC 1000
17#define ALLOWED_GPS_DELAY 5000
18#define RID_TIMEOUT 2500
20const uint8_t* RemoteIDManager::_id_or_mac_unknown =
new uint8_t[MAVLINK_MSG_OPEN_DRONE_ID_OPERATOR_ID_FIELD_ID_OR_MAC_LEN]();
26 , _armStatusGood (false)
30 , _GCSBasicIDValid (false)
31 , _operatorIDGood (false)
32 , _emergencyDeclared (false)
34 , _targetComponent (0)
35 , _enforceSendingSelfID (false)
37 _settings = SettingsManager::instance()->remoteIDSettings();
40 _odidTimeoutTimer.setSingleShot(
true);
42 connect(&_odidTimeoutTimer, &QTimer::timeout,
this, &RemoteIDManager::_odidTimeout);
46 connect(&_sendMessagesTimer, &QTimer::timeout,
this, &RemoteIDManager::_sendMessages);
57 _targetSystem = _vehicle->
id();
58 _targetComponent = _vehicle->
compId();
63 _operatorIDGood =
true;
70 switch (message.msgid) {
72 case MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS:
73 _handleArmStatus(message);
80void RemoteIDManager::_odidTimeout()
83 _sendMessagesTimer.stop();
85 qCDebug(RemoteIDManagerLog) <<
"We stopped receiving heartbeat from RID device.";
92 if ( (message.compid < MAV_COMP_ID_ODID_TXRX_1) || (message.compid > MAV_COMP_ID_ODID_TXRX_3) ) {
94 if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
100 if (_vehicle->
id() != message.sysid) {
107 qCDebug(RemoteIDManagerLog) <<
"Receiving ODID_ARM_STATUS for first time. Mavlink Open Drone ID support is available.";
111 if (_targetSystem != message.sysid) {
112 _targetSystem = message.sysid;
113 qCDebug(RemoteIDManagerLog) <<
"Subscribing to ODID messages coming from system " << _targetSystem;
118 _sendMessagesTimer.start();
121 qCDebug(RemoteIDManagerLog) <<
"Receiving ODID_ARM_STATUS from RID device";
125 _odidTimeoutTimer.start();
128 mavlink_open_drone_id_arm_status_t armStatus;
129 mavlink_msg_open_drone_id_arm_status_decode(&message, &armStatus);
131 if (armStatus.status == MAV_ODID_ARM_STATUS_GOOD_TO_ARM && !_armStatusGood) {
137 _armStatusGood =
true;
139 qCDebug(RemoteIDManagerLog) <<
"Arm status GOOD TO ARM.";
142 if (armStatus.status == MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC) {
143 _armStatusGood =
false;
144 _armStatusError = QString::fromLocal8Bit(armStatus.error);
146 if (armStatus.error == QString(
"missing basic_id message")) {
147 _basicIDGood =
false;
148 qCDebug(RemoteIDManagerLog) <<
"Arm status error, basic_id is not set in RID device nor in GCS!";
153 qCDebug(RemoteIDManagerLog) <<
"Arm status error:" << _armStatusError;
158void RemoteIDManager::_sendMessages()
164 if (_GCSBasicIDValid && _settings->
sendBasicID()->rawValue().toBool()) {
170 if (_settings->
sendSelfID()->rawValue().toBool() || _emergencyDeclared || _enforceSendingSelfID) {
182void RemoteIDManager::_sendSelfIDMsg()
189 const QByteArray selfIdDescription = _getSelfIDDescription();
193 sharedLink->mavlinkChannel(),
198 _emergencyDeclared ? 1 : _settings->selfIDType()->rawValue().toInt(),
199 selfIdDescription.constData());
205QByteArray RemoteIDManager::_getSelfIDDescription()
const
207 QString descriptionToSend;
209 if (_emergencyDeclared) {
211 descriptionToSend = _settings->
selfIDEmergency()->rawValue().toString();
213 switch (_settings->
selfIDType()->rawValue().toInt()) {
215 descriptionToSend = _settings->
selfIDFree()->rawValue().toString();
218 descriptionToSend = _settings->
selfIDEmergency()->rawValue().toString();
221 descriptionToSend = _settings->
selfIDExtended()->rawValue().toString();
224 descriptionToSend = _settings->
selfIDEmergency()->rawValue().toString();
228 QByteArray descriptionBuffer = descriptionToSend.toLocal8Bit();
229 descriptionBuffer.resize(MAVLINK_MSG_OPEN_DRONE_ID_SELF_ID_FIELD_DESCRIPTION_LEN);
230 return descriptionBuffer;
233void RemoteIDManager::_sendOperatorID()
241 QByteArray bytesOperatorID = (_settings->
operatorID()->rawValue().toString()).toLocal8Bit();
242 bytesOperatorID.resize(MAVLINK_MSG_OPEN_DRONE_ID_OPERATOR_ID_FIELD_OPERATOR_ID_LEN);
244 mavlink_msg_open_drone_id_operator_id_pack_chan(
247 sharedLink->mavlinkChannel(),
253 bytesOperatorID.constData());
259void RemoteIDManager::_sendSystem()
261 QGeoCoordinate gcsPosition;
262 QGeoPositionInfo geoPositionInfo;
271 geoPositionInfo = QGeoPositionInfo(gcsPosition, QDateTime::currentDateTime().currentDateTimeUtc());
277 gcsPosition = QGeoCoordinate(0,0,0);
278 geoPositionInfo = QGeoPositionInfo(gcsPosition, QDateTime::currentDateTime().currentDateTimeUtc());
282 qCDebug(RemoteIDManagerLog) <<
"The provided coordinates for FIXED position are invalid.";
287 gcsPosition = QGCPositionManager::instance()->gcsPosition();
288 geoPositionInfo = QGCPositionManager::instance()->geoPositionInfo();
291 if (geoPositionInfo.isValid()) {
293 if ((_settings->
region()->rawValue().toInt() ==
Region::FAA) && !(gcsPosition.altitude() >= 0) && _gcsGPSGood) {
296 qCDebug(RemoteIDManagerLog) <<
"GCS GPS data error (no altitude): Altitude data is mandatory for GCS GPS data in FAA regions.";
301 if (_lastGeoPositionTimeStamp.msecsTo(QDateTime::currentDateTime().currentDateTimeUtc()) >
ALLOWED_GPS_DELAY) {
305 qCDebug(RemoteIDManagerLog) <<
"GCS GPS data is older than 5 seconds";
316 qCDebug(RemoteIDManagerLog) <<
"GCS GPS data is not valid.";
329 sharedLink->mavlinkChannel(),
342 _settings->categoryEU()->rawValue().toUInt(),
343 _settings->classEU()->rawValue().toUInt(),
346 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
351uint32_t RemoteIDManager::_timestamp2019()
353 uint32_t secsSinceEpoch2019 = 1546300800;
355 return ((QDateTime::currentDateTime().currentSecsSinceEpoch()) - secsSinceEpoch2019);
358void RemoteIDManager::_sendBasicID()
366 QString basicIDTemp = _settings->
basicID()->rawValue().toString();
367 QByteArray ba = basicIDTemp.toLocal8Bit();
369 ba.resize(MAVLINK_MSG_OPEN_DRONE_ID_BASIC_ID_FIELD_UAS_ID_LEN);
373 sharedLink->mavlinkChannel(),
380 reinterpret_cast<const unsigned char*
>(ba.constData())),
386void RemoteIDManager::_checkGCSBasicID()
388 QString basicID = _settings->
basicID()->rawValue().toString();
390 if (!basicID.isEmpty() && (_settings->
basicIDType()->rawValue().toInt() >= 0) && (_settings->
basicIDUaType()->rawValue().toInt() >= 0)) {
391 _GCSBasicIDValid =
true;
393 _GCSBasicIDValid =
false;
397void RemoteIDManager::checkOperatorID(
const QString& operatorID)
402 if (operatorID != _settings->
operatorID()->rawValueString()) {
403 _settings->
operatorIDValid()->setRawValue(_isEUOperatorIDValid(operatorID));
409 QString operatorID = _settings->
operatorID()->rawValue().toString();
416 if (_operatorIDGood) {
418 _settings->
operatorID()->setRawValue(operatorID.sliced(0, 16));
424 (!operatorID.isEmpty() && (_settings->
operatorIDType()->rawValue().toInt() >= 0));
430bool RemoteIDManager::_isEUOperatorIDValid(
const QString& operatorID)
const
432 const bool containsDash = operatorID.contains(
'-');
433 if (!(operatorID.length() == 20 && containsDash) && !(operatorID.length() == 19 && !containsDash)) {
434 qCDebug(RemoteIDManagerLog) <<
"OperatorID not long enough";
438 const QString countryCode = operatorID.sliced(0,3);
439 if (!countryCode.isUpper()) {
440 qCDebug(RemoteIDManagerLog) <<
"OperatorID country code not uppercase";
444 const QString number = operatorID.sliced(3, 12);
445 const QChar checksum = operatorID.at(15);
446 const QString secret = containsDash ? operatorID.sliced(17, 3) : operatorID.sliced(16, 3);
447 const QString combination = number + secret;
449 const QChar result = _calculateLuhnMod36(combination);
451 const bool valid = (result == checksum);
452 qCDebug(RemoteIDManagerLog) <<
"Operator ID checksum " << (valid ?
"valid" :
"invalid");
456QChar RemoteIDManager::_calculateLuhnMod36(
const QString& input)
const {
458 const QString alphabet =
"0123456789abcdefghijklmnopqrstuvwxyz";
463 for (
int i = input.length() - 1; i >= 0; i--) {
464 int codePoint = alphabet.indexOf(input[i]);
465 int addend = factor * codePoint;
466 factor = (factor == 2) ? 1 : 2;
467 addend = (addend / n) + (addend % n);
471 int remainder = sum % n;
472 int checkCodePoint = (n - remainder) % n;
473 return alphabet.at(checkCodePoint);
478 _emergencyDeclared = declare;
483 _enforceSendingSelfID =
true;
485 qCDebug(RemoteIDManagerLog) << ( declare ?
"Emergency declared." :
"Emergency cleared.");
488void RemoteIDManager::_updateLastGCSPositionInfo(QGeoPositionInfo update)
490 if (update.isValid()) {
491 _lastGeoPositionTimeStamp = update.timestamp().toUTC();
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
std::weak_ptr< LinkInterface > WeakLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
#define MAVLINK_UNKNOWN_LAT
#define SENDING_RATE_MSEC
#define MAVLINK_UNKNOWN_METERS
#define ALLOWED_GPS_DELAY
#define MAVLINK_UNKNOWN_LON
void rawValueChanged(const QVariant &value)
static int getComponentId()
Get the component id of this application.
static MAVLinkProtocol * instance()
void positionInfoUpdated(QGeoPositionInfo update)
void mavlinkMessageReceived(mavlink_message_t &message)
void operatorIDGoodChanged()
void setEmergency(bool declare)
void armStatusErrorChanged()
void basicIDGoodChanged()
void emergencyDeclaredChanged()
void armStatusGoodChanged()
RemoteIDManager(Vehicle *vehicle)
Fact *basicIDType READ basicIDType CONSTANT Fact * basicIDType()
Fact *basicID READ basicID CONSTANT Fact * basicID()
Fact *latitudeFixed READ latitudeFixed CONSTANT Fact * latitudeFixed()
Fact *selfIDType READ selfIDType CONSTANT Fact * selfIDType()
Fact *sendBasicID READ sendBasicID CONSTANT Fact * sendBasicID()
Fact *locationType READ locationType CONSTANT Fact * locationType()
Fact *operatorID READ operatorID CONSTANT Fact * operatorID()
Fact *selfIDExtended READ selfIDExtended CONSTANT Fact * selfIDExtended()
Fact *selfIDEmergency READ selfIDEmergency CONSTANT Fact * selfIDEmergency()
Fact *operatorIDType READ operatorIDType CONSTANT Fact * operatorIDType()
Fact *operatorIDValid READ operatorIDValid CONSTANT Fact * operatorIDValid()
Fact *basicIDUaType READ basicIDUaType CONSTANT Fact * basicIDUaType()
Fact *classificationType READ classificationType CONSTANT Fact * classificationType()
Fact *selfIDFree READ selfIDFree CONSTANT Fact * selfIDFree()
Fact *region READ region CONSTANT Fact * region()
Fact *sendSelfID READ sendSelfID CONSTANT Fact * sendSelfID()
Fact *longitudeFixed READ longitudeFixed CONSTANT Fact * longitudeFixed()
Fact *altitudeFixed READ altitudeFixed CONSTANT Fact * altitudeFixed()
Fact *sendOperatorID READ sendOperatorID CONSTANT Fact * sendOperatorID()
WeakLinkInterfacePtr primaryLink() const
VehicleLinkManager * vehicleLinkManager()
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)