3#include <QtCore/QObject>
4#include <QtCore/QDateTime>
5#include <QtCore/QLoggingCategory>
6#include <QtCore/QTimer>
7#include <QtPositioning/QGeoPositionInfo>
8#include <QtQmlIntegration/QtQmlIntegration>
36 Q_INVOKABLE
void checkOperatorID(
const QString& operatorID);
77 void _updateLastGCSPositionInfo(QGeoPositionInfo update);
78 void _checkGCSBasicID();
84 void _sendSelfIDMsg ();
85 QByteArray _getSelfIDDescription()
const;
88 void _sendOperatorID ();
92 uint32_t _timestamp2019();
97 bool _isEUOperatorIDValid(
const QString& operatorID)
const;
98 QChar _calculateLuhnMod36(
const QString& input)
const;
104 bool _available =
false;
106 QString _armStatusError;
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;
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
struct __mavlink_message mavlink_message_t
bool emergencyDeclared(void) const
void mavlinkMessageReceived(mavlink_message_t &message)
bool armStatusGood(void) const
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