QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
RemoteIDManager.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QObject>
4#include <QtCore/QDateTime>
5#include <QtCore/QTimer>
6#include <QtPositioning/QGeoPositionInfo>
7#include <QtQmlIntegration/QtQmlIntegration>
8
10
12class Vehicle;
13
14// Supporting Open Drone ID protocol
15class RemoteIDManager : public QObject
16{
17 Q_OBJECT
18 QML_ELEMENT
19 QML_UNCREATABLE("")
20public:
21 RemoteIDManager(Vehicle* vehicle);
22
23 Q_PROPERTY(bool available READ available NOTIFY availableChanged)
24 Q_PROPERTY(bool armStatusGood READ armStatusGood NOTIFY armStatusGoodChanged)
25 Q_PROPERTY(QString armStatusError READ armStatusError NOTIFY armStatusErrorChanged)
26 Q_PROPERTY(bool commsGood READ commsGood NOTIFY commsGoodChanged)
27 Q_PROPERTY(bool gcsGPSGood READ gcsGPSGood NOTIFY gcsGPSGoodChanged)
28 Q_PROPERTY(bool basicIDGood READ basicIDGood NOTIFY basicIDGoodChanged)
30 Q_PROPERTY(bool operatorIDGood READ operatorIDGood NOTIFY operatorIDGoodChanged)
31
32 Q_INVOKABLE void checkOperatorID(const QString& operatorID);
33 Q_INVOKABLE void setOperatorID();
34
35 // Declare emergency
36 Q_INVOKABLE void setEmergency(bool declare);
37
38 bool available (void) const { return _available; }
39 bool armStatusGood (void) const { return _armStatusGood; }
40 QString armStatusError (void) const { return _armStatusError; }
41 bool commsGood (void) const { return _commsGood; }
42 bool gcsGPSGood (void) const { return _gcsGPSGood; }
43 bool basicIDGood (void) const { return _basicIDGood; }
44 bool emergencyDeclared (void) const { return _emergencyDeclared;}
45 bool operatorIDGood (void) const { return _operatorIDGood; }
46
48
54
55 enum Region {
57 EU
58 };
59
60signals:
69
70private slots:
71 void _odidTimeout();
72 void _sendMessages();
73 void _updateLastGCSPositionInfo(QGeoPositionInfo update);
74 void _checkGCSBasicID();
75
76private:
77 void _handleArmStatus(mavlink_message_t& message);
78
79 // Self ID
80 void _sendSelfIDMsg ();
81 QByteArray _getSelfIDDescription() const;
82
83 // Operator ID
84 void _sendOperatorID ();
85
86 // System
87 void _sendSystem();
88 uint32_t _timestamp2019();
89
90 // Basic ID
91 void _sendBasicID();
92
93 // GCS GPS status
94 void _updateGcsGpsStatus(bool gpsGood, const QString& error = QString());
95
96 bool _isEUOperatorIDValid(const QString& operatorID) const;
97 QChar _calculateLuhnMod36(const QString& input) const;
98
99 Vehicle* _vehicle;
100 RemoteIDSettings* _settings;
101
102 // Flags ODID
103 bool _available = false;
104 bool _armStatusGood;
105 QString _armStatusError;
106 bool _commsGood;
107 bool _gcsGPSGood;
108 QString _gcsGPSError;
109 bool _basicIDGood;
110 bool _GCSBasicIDValid;
111 bool _operatorIDGood;
112
113 bool _emergencyDeclared;
114 QDateTime _lastGeoPositionTimeStamp;
115 int _targetSystem;
116 int _targetComponent;
117
118 // After emergency cleared, this makes sure the non emergency selfID message makes it to the vehicle
119 bool _enforceSendingSelfID;
120
121 static const uint8_t* _id_or_mac_unknown;
122
123 // Timers
124 QTimer _odidTimeoutTimer;
125 QTimer _sendMessagesTimer;
126};
Error error
struct __mavlink_message mavlink_message_t
void availableChanged()
bool emergencyDeclared(void) const
void mavlinkMessageReceived(mavlink_message_t &message)
bool armStatusGood(void) const
void commsGoodChanged()
void operatorIDGoodChanged()
Q_INVOKABLE void setEmergency(bool declare)
void armStatusErrorChanged()
void basicIDGoodChanged()
QString armStatusError(void) const
bool commsGood(void) const
bool gcsGPSGood(void) const
Q_INVOKABLE void setOperatorID()
void emergencyDeclaredChanged()
bool operatorIDGood(void) const
void armStatusGoodChanged()
bool basicIDGood(void) const
bool available(void) const
void gcsGPSGoodChanged()
Q_INVOKABLE void checkOperatorID(const QString &operatorID)