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/QLoggingCategory>
6#include <QtCore/QTimer>
7#include <QtPositioning/QGeoPositionInfo>
8#include <QtQmlIntegration/QtQmlIntegration>
9
10#include "MAVLinkLib.h"
11
12Q_DECLARE_LOGGING_CATEGORY(RemoteIDManagerLog)
13
15class Vehicle;
16
17// Supporting Open Drone ID protocol
18class RemoteIDManager : public QObject
19{
20 Q_OBJECT
21 QML_ELEMENT
22 QML_UNCREATABLE("")
23public:
24 RemoteIDManager(Vehicle* vehicle);
25
26 Q_PROPERTY(bool available READ available NOTIFY availableChanged)
27 Q_PROPERTY(bool armStatusGood READ armStatusGood NOTIFY armStatusGoodChanged)
28 Q_PROPERTY(QString armStatusError READ armStatusError NOTIFY armStatusErrorChanged)
29 Q_PROPERTY(bool commsGood READ commsGood NOTIFY commsGoodChanged)
30 Q_PROPERTY(bool gcsGPSGood READ gcsGPSGood NOTIFY gcsGPSGoodChanged)
31 Q_PROPERTY(bool basicIDGood READ basicIDGood NOTIFY basicIDGoodChanged)
33 Q_PROPERTY(bool operatorIDGood READ operatorIDGood NOTIFY operatorIDGoodChanged)
34
35
36 Q_INVOKABLE void checkOperatorID(const QString& operatorID);
37 Q_INVOKABLE void setOperatorID();
38
39 // Declare emergency
40 Q_INVOKABLE void setEmergency(bool declare);
41
42 bool available (void) const { return _available; }
43 bool armStatusGood (void) const { return _armStatusGood; }
44 QString armStatusError (void) const { return _armStatusError; }
45 bool commsGood (void) const { return _commsGood; }
46 bool gcsGPSGood (void) const { return _gcsGPSGood; }
47 bool basicIDGood (void) const { return _basicIDGood; }
48 bool emergencyDeclared (void) const { return _emergencyDeclared;}
49 bool operatorIDGood (void) const { return _operatorIDGood; }
50
52
58
59 enum Region {
61 EU
62 };
63
64signals:
73
74private slots:
75 void _odidTimeout();
76 void _sendMessages();
77 void _updateLastGCSPositionInfo(QGeoPositionInfo update);
78 void _checkGCSBasicID();
79
80private:
81 void _handleArmStatus(mavlink_message_t& message);
82
83 // Self ID
84 void _sendSelfIDMsg ();
85 QByteArray _getSelfIDDescription() const;
86
87 // Operator ID
88 void _sendOperatorID ();
89
90 // System
91 void _sendSystem();
92 uint32_t _timestamp2019();
93
94 // Basic ID
95 void _sendBasicID();
96
97 bool _isEUOperatorIDValid(const QString& operatorID) const;
98 QChar _calculateLuhnMod36(const QString& input) const;
99
100 Vehicle* _vehicle;
101 RemoteIDSettings* _settings;
102
103 // Flags ODID
104 bool _available = false;
105 bool _armStatusGood;
106 QString _armStatusError;
107 bool _commsGood;
108 bool _gcsGPSGood;
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};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
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()
void setEmergency(bool declare)
void armStatusErrorChanged()
void basicIDGoodChanged()
QString armStatusError(void) const
bool commsGood(void) const
bool gcsGPSGood(void) const
void emergencyDeclaredChanged()
bool operatorIDGood(void) const
void armStatusGoodChanged()
bool basicIDGood(void) const
bool available(void) const
void gcsGPSGoodChanged()