3#include <QtCore/QObject>
4#include <QtCore/QDateTime>
5#include <QtCore/QTimer>
6#include <QtPositioning/QGeoPositionInfo>
7#include <QtQmlIntegration/QtQmlIntegration>
73 void _updateLastGCSPositionInfo(QGeoPositionInfo update);
74 void _checkGCSBasicID();
80 void _sendSelfIDMsg ();
81 QByteArray _getSelfIDDescription()
const;
84 void _sendOperatorID ();
88 uint32_t _timestamp2019();
94 void _updateGcsGpsStatus(
bool gpsGood,
const QString&
error = QString());
96 bool _isEUOperatorIDValid(
const QString& operatorID)
const;
97 QChar _calculateLuhnMod36(
const QString& input)
const;
103 bool _available =
false;
105 QString _armStatusError;
108 QString _gcsGPSError;
110 bool _GCSBasicIDValid;
111 bool _operatorIDGood;
113 bool _emergencyDeclared;
114 QDateTime _lastGeoPositionTimeStamp;
116 int _targetComponent;
119 bool _enforceSendingSelfID;
121 static const uint8_t* _id_or_mac_unknown;
124 QTimer _odidTimeoutTimer;
125 QTimer _sendMessagesTimer;
struct __mavlink_message mavlink_message_t
bool emergencyDeclared(void) const
void mavlinkMessageReceived(mavlink_message_t &message)
bool armStatusGood(void) const
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
Q_INVOKABLE void checkOperatorID(const QString &operatorID)