QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RemoteIDManager.cc
Go to the documentation of this file.
1#include "RemoteIDManager.h"
2#include "SettingsManager.h"
3#include "RemoteIDSettings.h"
4#include "PositionManager.h"
5#include "Vehicle.h"
6#include "MAVLinkProtocol.h"
8
9QGC_LOGGING_CATEGORY(RemoteIDManagerLog, "Vehicle.RemoteIDManager")
10
11#define AREA_COUNT 1
12#define AREA_RADIUS 0
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 // Messages should be arriving at 1 Hz, so we set a 2 second timeout
19
20const uint8_t* RemoteIDManager::_id_or_mac_unknown = new uint8_t[MAVLINK_MSG_OPEN_DRONE_ID_OPERATOR_ID_FIELD_ID_OR_MAC_LEN]();
21
23 : QObject (vehicle)
24 , _vehicle (vehicle)
25 , _settings (nullptr)
26 , _armStatusGood (false)
27 , _commsGood (false)
28 , _gcsGPSGood (false)
29 , _basicIDGood (true)
30 , _GCSBasicIDValid (false)
31 , _operatorIDGood (false)
32 , _emergencyDeclared (false)
33 , _targetSystem (0) // By default 0 means broadcast
34 , _targetComponent (0) // By default 0 means broadcast
35 , _enforceSendingSelfID (false)
36{
37 _settings = SettingsManager::instance()->remoteIDSettings();
38
39 // Timer to track a healthy RID device. When expired we let the operator know
40 _odidTimeoutTimer.setSingleShot(true);
41 _odidTimeoutTimer.setInterval(RID_TIMEOUT);
42 connect(&_odidTimeoutTimer, &QTimer::timeout, this, &RemoteIDManager::_odidTimeout);
43
44 // Timer to send messages at a constant rate
45 _sendMessagesTimer.setInterval(SENDING_RATE_MSEC);
46 connect(&_sendMessagesTimer, &QTimer::timeout, this, &RemoteIDManager::_sendMessages);
47
48 // GCS GPS position updates to track the health of the GPS data
49 connect(QGCPositionManager::instance(), &QGCPositionManager::positionInfoUpdated, this, &RemoteIDManager::_updateLastGCSPositionInfo);
50
51 // Check changes in basic id settings as long as they are modified
52 connect(_settings->basicID(), &Fact::rawValueChanged, this, &RemoteIDManager::_checkGCSBasicID);
53 connect(_settings->basicIDType(), &Fact::rawValueChanged, this, &RemoteIDManager::_checkGCSBasicID);
54 connect(_settings->basicIDUaType(), &Fact::rawValueChanged, this, &RemoteIDManager::_checkGCSBasicID);
55
56 // Assign vehicle sysid and compid. GCS must target these messages to autopilot, and autopilot will redirect them to RID device
57 _targetSystem = _vehicle->id();
58 _targetComponent = _vehicle->compId();
59
60 if (_settings->operatorIDValid()->rawValue() == true || (_settings->region()->rawValue().toInt() != Region::EU && _settings->operatorID()->rawValue().toString().length() > 0)) {
61 // If it was already checked, we can flag this as good to go.
62 // We don't do a fresh verification because we don't store the private part of the ID.
63 _operatorIDGood = true;
65 }
66}
67
69{
70 switch (message.msgid) {
71 // So far we are only listening to this one, as heartbeat won't be sent if connected by CAN
72 case MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS:
73 _handleArmStatus(message);
74 default:
75 break;
76 }
77}
78
79// This slot will be called if we stop receiving heartbeats for more than RID_TIMEOUT seconds
80void RemoteIDManager::_odidTimeout()
81{
82 _commsGood = false;
83 _sendMessagesTimer.stop(); // We stop sending messages if the communication with the RID device is down
84 emit commsGoodChanged();
85 qCDebug(RemoteIDManagerLog) << "We stopped receiving heartbeat from RID device.";
86}
87
88// Parsing of the ARM_STATUS message comming from the RID device
89void RemoteIDManager::_handleArmStatus(mavlink_message_t& message)
90{
91 // Compid must be ODID_TXRX_X
92 if ( (message.compid < MAV_COMP_ID_ODID_TXRX_1) || (message.compid > MAV_COMP_ID_ODID_TXRX_3) ) {
93 // or same as autopilot, in the case of Ardupilot and CAN RID modules
94 if (message.compid != MAV_COMP_ID_AUTOPILOT1) {
95 return;
96 }
97 }
98
99 // Sanity check, only get messages from same sysid
100 if (_vehicle->id() != message.sysid) {
101 return;
102 }
103
104 if (!_available) {
105 _available = true;
106 emit availableChanged();
107 qCDebug(RemoteIDManagerLog) << "Receiving ODID_ARM_STATUS for first time. Mavlink Open Drone ID support is available.";
108 }
109
110 // We set the targetsystem
111 if (_targetSystem != message.sysid) {
112 _targetSystem = message.sysid;
113 qCDebug(RemoteIDManagerLog) << "Subscribing to ODID messages coming from system " << _targetSystem;
114 }
115
116 if (!_commsGood) {
117 _commsGood = true;
118 _sendMessagesTimer.start(); // Start sending our messages
119 _checkGCSBasicID(); // Check if basicID is good to send
120 emit commsGoodChanged();
121 qCDebug(RemoteIDManagerLog) << "Receiving ODID_ARM_STATUS from RID device";
122 }
123
124 // Restart the timeout
125 _odidTimeoutTimer.start();
126
127 // CompId and sysId are correct, we can proceed
128 mavlink_open_drone_id_arm_status_t armStatus;
129 mavlink_msg_open_drone_id_arm_status_decode(&message, &armStatus);
130
131 if (armStatus.status == MAV_ODID_ARM_STATUS_GOOD_TO_ARM && !_armStatusGood) {
132 // If good to arm, even if basic ID is not set on GCS, it was set by remoteID parameters, so GCS one would be optional in this case
133 if (!_basicIDGood) {
134 _basicIDGood = true;
135 emit basicIDGoodChanged();
136 }
137 _armStatusGood = true;
139 qCDebug(RemoteIDManagerLog) << "Arm status GOOD TO ARM.";
140 }
141
142 if (armStatus.status == MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC) {
143 _armStatusGood = false;
144 _armStatusError = QString::fromLocal8Bit(armStatus.error);
145 // Check if the error is because of missing basic id
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!";
149 emit basicIDGoodChanged();
150 }
153 qCDebug(RemoteIDManagerLog) << "Arm status error:" << _armStatusError;
154 }
155}
156
157// Function that sends messages periodically
158void RemoteIDManager::_sendMessages()
159{
160 // We always try to send System
161 _sendSystem();
162
163 // only send it if the information is correct and the tickbox in settings is set
164 if (_GCSBasicIDValid && _settings->sendBasicID()->rawValue().toBool()) {
165 _sendBasicID();
166 }
167
168 // We only send selfID if the pilot wants it or in case of a declared emergency. If an emergency is cleared
169 // we also keep sending the message, to be sure the non emergency state makes it up to the vehicle
170 if (_settings->sendSelfID()->rawValue().toBool() || _emergencyDeclared || _enforceSendingSelfID) {
171 _sendSelfIDMsg();
172 }
173
174 // We only send the OperatorID if the pilot wants it or if the region we have set is europe.
175 // To be able to send it, it needs to be filled correclty
176 if ((_settings->sendOperatorID()->rawValue().toBool() || (_settings->region()->rawValue().toInt() == Region::EU)) && _operatorIDGood) {
177 _sendOperatorID();
178 }
179
180}
181
182void RemoteIDManager::_sendSelfIDMsg()
183{
184 WeakLinkInterfacePtr weakLink = _vehicle->vehicleLinkManager()->primaryLink();
185 SharedLinkInterfacePtr sharedLink = weakLink.lock();
186
187 if (sharedLink) {
189 const QByteArray selfIdDescription = _getSelfIDDescription();
190
191 mavlink_msg_open_drone_id_self_id_pack_chan(MAVLinkProtocol::instance()->getSystemId(),
193 sharedLink->mavlinkChannel(),
194 &msg,
195 _targetSystem,
196 _targetComponent,
197 _id_or_mac_unknown,
198 _emergencyDeclared ? 1 : _settings->selfIDType()->rawValue().toInt(), // If emergency is delcared we send directly a 1 (1 = EMERGENCY)
199 selfIdDescription.constData()); // Depending on the type of SelfID we send a different description
200 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
201 }
202}
203
204// We need to return the correct description for the self ID type we have selected
205QByteArray RemoteIDManager::_getSelfIDDescription() const
206{
207 QString descriptionToSend;
208
209 if (_emergencyDeclared) {
210 // If emergency is declared we dont care about the settings and we send emergency directly
211 descriptionToSend = _settings->selfIDEmergency()->rawValue().toString();
212 } else {
213 switch (_settings->selfIDType()->rawValue().toInt()) {
214 case 0:
215 descriptionToSend = _settings->selfIDFree()->rawValue().toString();
216 break;
217 case 1:
218 descriptionToSend = _settings->selfIDEmergency()->rawValue().toString();
219 break;
220 case 2:
221 descriptionToSend = _settings->selfIDExtended()->rawValue().toString();
222 break;
223 default:
224 descriptionToSend = _settings->selfIDEmergency()->rawValue().toString();
225 }
226 }
227
228 QByteArray descriptionBuffer = descriptionToSend.toLocal8Bit();
229 descriptionBuffer.resize(MAVLINK_MSG_OPEN_DRONE_ID_SELF_ID_FIELD_DESCRIPTION_LEN);
230 return descriptionBuffer;
231}
232
233void RemoteIDManager::_sendOperatorID()
234{
235 WeakLinkInterfacePtr weakLink = _vehicle->vehicleLinkManager()->primaryLink();
236 SharedLinkInterfacePtr sharedLink = weakLink.lock();
237
238 if (sharedLink) {
240
241 QByteArray bytesOperatorID = (_settings->operatorID()->rawValue().toString()).toLocal8Bit();
242 bytesOperatorID.resize(MAVLINK_MSG_OPEN_DRONE_ID_OPERATOR_ID_FIELD_OPERATOR_ID_LEN);
243
244 mavlink_msg_open_drone_id_operator_id_pack_chan(
245 MAVLinkProtocol::instance()->getSystemId(),
247 sharedLink->mavlinkChannel(),
248 &msg,
249 _targetSystem,
250 _targetComponent,
251 _id_or_mac_unknown,
252 _settings->operatorIDType()->rawValue().toInt(),
253 bytesOperatorID.constData());
254
255 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
256 }
257}
258
259void RemoteIDManager::_sendSystem()
260{
261 QGeoCoordinate gcsPosition;
262 QGeoPositionInfo geoPositionInfo;
263 // Location types:
264 // 0 -> TAKEOFF (not supported yet)
265 // 1 -> LIVE GNNS
266 // 2 -> FIXED
267 if (_settings->locationType()->rawValue().toUInt() == LocationTypes::FIXED) {
268 // For FIXED location, we first check that the values are valid. Then we populate our position
269 if (_settings->latitudeFixed()->rawValue().toFloat() >= -90 && _settings->latitudeFixed()->rawValue().toFloat() <= 90 && _settings->longitudeFixed()->rawValue().toFloat() >= -180 && _settings->longitudeFixed()->rawValue().toFloat() <= 180) {
270 gcsPosition = QGeoCoordinate(_settings->latitudeFixed()->rawValue().toFloat(), _settings->longitudeFixed()->rawValue().toFloat(), _settings->altitudeFixed()->rawValue().toFloat());
271 geoPositionInfo = QGeoPositionInfo(gcsPosition, QDateTime::currentDateTime().currentDateTimeUtc());
272 if (!_gcsGPSGood) {
273 _gcsGPSGood = true;
274 emit gcsGPSGoodChanged();
275 }
276 } else {
277 gcsPosition = QGeoCoordinate(0,0,0);
278 geoPositionInfo = QGeoPositionInfo(gcsPosition, QDateTime::currentDateTime().currentDateTimeUtc());
279 if (_gcsGPSGood) {
280 _gcsGPSGood = false;
281 emit gcsGPSGoodChanged();
282 qCDebug(RemoteIDManagerLog) << "The provided coordinates for FIXED position are invalid.";
283 }
284 }
285 } else {
286 // For Live GNSS we take QGC GPS data
287 gcsPosition = QGCPositionManager::instance()->gcsPosition();
288 geoPositionInfo = QGCPositionManager::instance()->geoPositionInfo();
289
290 // GPS position needs to be valid before checking other stuff
291 if (geoPositionInfo.isValid()) {
292 // If we dont have altitude for FAA then the GPS data is no good
293 if ((_settings->region()->rawValue().toInt() == Region::FAA) && !(gcsPosition.altitude() >= 0) && _gcsGPSGood) {
294 _gcsGPSGood = false;
295 emit gcsGPSGoodChanged();
296 qCDebug(RemoteIDManagerLog) << "GCS GPS data error (no altitude): Altitude data is mandatory for GCS GPS data in FAA regions.";
297 return;
298 }
299
300 // If the GPS data is older than ALLOWED_GPS_DELAY we cannot use this data
301 if (_lastGeoPositionTimeStamp.msecsTo(QDateTime::currentDateTime().currentDateTimeUtc()) > ALLOWED_GPS_DELAY) {
302 if (_gcsGPSGood) {
303 _gcsGPSGood = false;
304 emit gcsGPSGoodChanged();
305 qCDebug(RemoteIDManagerLog) << "GCS GPS data is older than 5 seconds";
306 }
307 } else {
308 if (!_gcsGPSGood) {
309 _gcsGPSGood = true;
310 emit gcsGPSGoodChanged();
311 }
312 }
313 } else {
314 _gcsGPSGood = false;
315 emit gcsGPSGoodChanged();
316 qCDebug(RemoteIDManagerLog) << "GCS GPS data is not valid.";
317 }
318
319 }
320
321 WeakLinkInterfacePtr weakLink = _vehicle->vehicleLinkManager()->primaryLink();
322 SharedLinkInterfacePtr sharedLink = weakLink.lock();
323
324 if (sharedLink) {
326
327 mavlink_msg_open_drone_id_system_pack_chan(MAVLinkProtocol::instance()->getSystemId(),
329 sharedLink->mavlinkChannel(),
330 &msg,
331 _targetSystem,
332 _targetComponent,
333 _id_or_mac_unknown,
334 _settings->locationType()->rawValue().toUInt(),
335 _settings->classificationType()->rawValue().toUInt(),
336 _gcsGPSGood ? ( gcsPosition.latitude() * 1.0e7 ) : MAVLINK_UNKNOWN_LAT,
337 _gcsGPSGood ? ( gcsPosition.longitude() * 1.0e7 ) : MAVLINK_UNKNOWN_LON,
342 _settings->categoryEU()->rawValue().toUInt(),
343 _settings->classEU()->rawValue().toUInt(),
344 _gcsGPSGood ? gcsPosition.altitude() : MAVLINK_UNKNOWN_METERS,
345 _timestamp2019()), // Time stamp needs to be since 00:00:00 1/1/2019
346 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
347 }
348}
349
350// Returns seconds elapsed since 00:00:00 1/1/2019
351uint32_t RemoteIDManager::_timestamp2019()
352{
353 uint32_t secsSinceEpoch2019 = 1546300800; // Secs elapsed since epoch to 1-1-2019
354
355 return ((QDateTime::currentDateTime().currentSecsSinceEpoch()) - secsSinceEpoch2019);
356}
357
358void RemoteIDManager::_sendBasicID()
359{
360 WeakLinkInterfacePtr weakLink = _vehicle->vehicleLinkManager()->primaryLink();
361 SharedLinkInterfacePtr sharedLink = weakLink.lock();
362
363 if (sharedLink) {
365
366 QString basicIDTemp = _settings->basicID()->rawValue().toString();
367 QByteArray ba = basicIDTemp.toLocal8Bit();
368 // 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
369 ba.resize(MAVLINK_MSG_OPEN_DRONE_ID_BASIC_ID_FIELD_UAS_ID_LEN);
370
371 mavlink_msg_open_drone_id_basic_id_pack_chan(MAVLinkProtocol::instance()->getSystemId(),
373 sharedLink->mavlinkChannel(),
374 &msg,
375 _targetSystem,
376 _targetComponent,
377 _id_or_mac_unknown,
378 _settings->basicIDType()->rawValue().toUInt(),
379 _settings->basicIDUaType()->rawValue().toUInt(),
380 reinterpret_cast<const unsigned char*>(ba.constData())),
381
382 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
383 }
384}
385
386void RemoteIDManager::_checkGCSBasicID()
387{
388 QString basicID = _settings->basicID()->rawValue().toString();
389
390 if (!basicID.isEmpty() && (_settings->basicIDType()->rawValue().toInt() >= 0) && (_settings->basicIDUaType()->rawValue().toInt() >= 0)) {
391 _GCSBasicIDValid = true;
392 } else {
393 _GCSBasicIDValid = false;
394 }
395}
396
397void RemoteIDManager::checkOperatorID(const QString& operatorID)
398{
399 // We overwrite the fact that is also set by the text input but we want to update
400 // after every letter rather than when editing is done.
401 // We check whether it actually changed to avoid triggering this on startup.
402 if (operatorID != _settings->operatorID()->rawValueString()) {
403 _settings->operatorIDValid()->setRawValue(_isEUOperatorIDValid(operatorID));
404 }
405}
406
408{
409 QString operatorID = _settings->operatorID()->rawValue().toString();
410
411 if (_settings->region()->rawValue().toInt() == Region::EU) {
412 // Save for next time because we don't save the private part,
413 // so we can't re-verify next time and just trust the value
414 // in the settings.
415 _operatorIDGood = _settings->operatorIDValid()->rawValue() == true;
416 if (_operatorIDGood) {
417 // Strip private part
418 _settings->operatorID()->setRawValue(operatorID.sliced(0, 16));
419 }
420
421 } else {
422 // Otherwise, we just check if there is anything entered
423 _operatorIDGood =
424 (!operatorID.isEmpty() && (_settings->operatorIDType()->rawValue().toInt() >= 0));
425 }
426
428}
429
430bool RemoteIDManager::_isEUOperatorIDValid(const QString& operatorID) const
431{
432 const bool containsDash = operatorID.contains('-');
433 if (!(operatorID.length() == 20 && containsDash) && !(operatorID.length() == 19 && !containsDash)) {
434 qCDebug(RemoteIDManagerLog) << "OperatorID not long enough";
435 return false;
436 }
437
438 const QString countryCode = operatorID.sliced(0,3);
439 if (!countryCode.isUpper()) {
440 qCDebug(RemoteIDManagerLog) << "OperatorID country code not uppercase";
441 return false;
442 }
443
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;
448
449 const QChar result = _calculateLuhnMod36(combination);
450
451 const bool valid = (result == checksum);
452 qCDebug(RemoteIDManagerLog) << "Operator ID checksum " << (valid ? "valid" : "invalid");
453 return valid;
454}
455
456QChar RemoteIDManager::_calculateLuhnMod36(const QString& input) const {
457 const int n = 36;
458 const QString alphabet = "0123456789abcdefghijklmnopqrstuvwxyz";
459
460 int sum = 0;
461 int factor = 2;
462
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);
468 sum += addend;
469 }
470
471 int remainder = sum % n;
472 int checkCodePoint = (n - remainder) % n;
473 return alphabet.at(checkCodePoint);
474}
475
477{
478 _emergencyDeclared = declare;
480 // Wether we are starting an emergency or cancelling it, we need to enforce sending
481 // this message. Otherwise, if non optimal connection quality, vehicle RID device
482 // could remain in the wrong state. It is clarified to the user in remoteidsettings.qml
483 _enforceSendingSelfID = true;
484
485 qCDebug(RemoteIDManagerLog) << ( declare ? "Emergency declared." : "Emergency cleared.");
486}
487
488void RemoteIDManager::_updateLastGCSPositionInfo(QGeoPositionInfo update)
489{
490 if (update.isValid()) {
491 _lastGeoPositionTimeStamp = update.timestamp().toUTC();
492 }
493}
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 AREA_COUNT
#define MAVLINK_UNKNOWN_METERS
#define ALLOWED_GPS_DELAY
#define AREA_RADIUS
#define RID_TIMEOUT
#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 availableChanged()
void mavlinkMessageReceived(mavlink_message_t &message)
void commsGoodChanged()
void operatorIDGoodChanged()
void setEmergency(bool declare)
void armStatusErrorChanged()
void basicIDGoodChanged()
void emergencyDeclaredChanged()
void armStatusGoodChanged()
RemoteIDManager(Vehicle *vehicle)
void gcsGPSGoodChanged()
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()
Definition Vehicle.h:580
int id() const
Definition Vehicle.h:425
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1470
int compId() const
Definition Vehicle.h:426