QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
MAVLinkProtocol.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QByteArray>
4#include <QtCore/QLoggingCategory>
5#include <QtCore/QObject>
6#include <QtCore/QString>
7
8#include "LinkInterface.h"
9#include "MAVLinkLib.h"
10
11class QFile;
12
13Q_DECLARE_LOGGING_CATEGORY(MAVLinkProtocolLog)
14
15
18class MAVLinkProtocol : public QObject
19{
20 Q_OBJECT
21
22public:
25 explicit MAVLinkProtocol(QObject *parent = nullptr);
26
29
32 static MAVLinkProtocol *instance();
33
34 void init();
35
37 static QString getName() { return QStringLiteral("MAVLink protocol"); }
38
40 int getSystemId() const;
41
43 static int getComponentId() { return MAV_COMP_ID_MISSIONPLANNER; }
44
46 void resetMetadataForLink(LinkInterface *link);
47
49 void suspendLogForReplay(bool suspend) { _logSuspendReplay = suspend; }
50
54 void checkForLostLogFiles();
55
56signals:
58 void vehicleHeartbeatInfo(LinkInterface *link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType);
59
61 void messageReceived(LinkInterface *link, const mavlink_message_t &message);
62
63 void mavlinkMessageStatus(int sysid, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent);
64
65public slots:
68 void receiveBytes(LinkInterface *link, const QByteArray &data);
69
73 void logSentBytes(const LinkInterface *link, const QByteArray &data);
74
76 static void deleteTempLogFiles();
77
78private slots:
79 void _vehicleCountChanged();
80
81private:
82 void _logData(LinkInterface *link, const mavlink_message_t &message);
83 bool _closeLogFile();
84 void _startLogging();
85 void _stopLogging();
86
87 void _forward(const mavlink_message_t &message);
88 void _forwardSupport(const mavlink_message_t &message);
89
90 void _updateCounters(uint8_t mavlinkChannel, const mavlink_message_t &message);
91 bool _updateStatus(LinkInterface *link, const SharedLinkInterfacePtr linkPtr, uint8_t mavlinkChannel, const mavlink_message_t &message);
92
93 void _saveTelemetryLog(const QString &tempLogfile);
94 bool _checkTelemetrySavePath();
95
96 QFile *_tempLogFile = nullptr;
97
98 bool _logSuspendError = false;
99 bool _logSuspendReplay = false;
100 bool _vehicleWasArmed = false;
101
102 uint8_t _lastIndex[256][256]{};
103 QSet<QPair<uint8_t,uint8_t>> _firstMessageSeen;
104 uint64_t _totalReceiveCounter[MAVLINK_COMM_NUM_BUFFERS]{};
105 uint64_t _totalLossCounter[MAVLINK_COMM_NUM_BUFFERS]{};
106 float _runningLossPercent[MAVLINK_COMM_NUM_BUFFERS]{};
107
108 bool _initialized = false;
109
110 static constexpr const char *_tempLogFileTemplate = "FlightDataXXXXXX";
111 static constexpr const char *_logFileExtension = "mavlink";
112
113 static constexpr uint8_t kMaxCompId = MAV_COMPONENT_ENUM_END - 1;
114};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
#define MAVLINK_COMM_NUM_BUFFERS
Definition MAVLinkLib.h:27
struct __mavlink_message mavlink_message_t
The link interface defines the interface for all links used to communicate with the ground station ap...
static int getComponentId()
Get the component id of this application.
void mavlinkMessageStatus(int sysid, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent)
void messageReceived(LinkInterface *link, const mavlink_message_t &message)
Message received and directly copied via signal.
void vehicleHeartbeatInfo(LinkInterface *link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType)
Heartbeat received on link.
void suspendLogForReplay(bool suspend)
Suspend/Restart logging during replay.
static QString getName()
Get the human-friendly name of this protocol.