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/QObject>
5#include <QtCore/QPair>
6#include <QtCore/QSet>
7#include <QtCore/QString>
8
9#include "LinkInterface.h"
10#include "MAVLinkEnums.h"
11#include "MAVLinkMessageType.h"
12
13class QFile;
14
17class MAVLinkProtocol : public QObject
18{
19 Q_OBJECT
20
21public:
22 explicit MAVLinkProtocol(QObject* parent = nullptr);
23
25
26 static MAVLinkProtocol* instance();
27
28 void init();
29
30 static QString getName() { return QStringLiteral("MAVLink protocol"); }
31
32 int getSystemId() const;
33
34 static int getComponentId() { return MAV_COMP_ID_MISSIONPLANNER; }
35
37
40
41 void suspendLogForReplay(bool suspend) { _logSuspendReplay = suspend; }
42
44
45signals:
46 void vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType,
47 int vehicleType);
48
49 void messageReceived(LinkInterface* link, const mavlink_message_t& message);
50
51 void mavlinkMessageStatus(int sysid, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss,
52 float lossPercent);
53
54public slots:
55 void receiveBytes(LinkInterface* link, const QByteArray& data);
56
57 void logSentBytes(const LinkInterface* link, const QByteArray& data);
58
59 static void deleteTempLogFiles();
60
61private slots:
62 void _vehicleCountChanged();
63
64private:
65 void _logData(LinkInterface* link, const mavlink_message_t& message);
66 bool _closeLogFile();
67 void _startLogging();
68 void _stopLogging();
69
70 void _forward(const mavlink_message_t& message);
71 void _forwardSupport(const mavlink_message_t& message);
72
73 void _updateCounters(uint8_t mavlinkChannel, const mavlink_message_t& message);
74 bool _updateStatus(LinkInterface* link, const SharedLinkInterfacePtr linkPtr, uint8_t mavlinkChannel,
75 const mavlink_message_t& message);
76
77 void _saveTelemetryLog(const QString& tempLogfile);
78 bool _checkTelemetrySavePath();
79
80 QFile* _tempLogFile = nullptr;
81
82 bool _logSuspendError = false;
83 bool _logSuspendReplay = false;
84 bool _vehicleWasArmed = false;
85
88 uint8_t _lastIndex[MAVLINK_COMM_NUM_BUFFERS][256][256]{};
89
90 QSet<QPair<uint8_t, uint8_t>> _firstMessageSeen[MAVLINK_COMM_NUM_BUFFERS];
91 uint64_t _totalReceiveCounter[MAVLINK_COMM_NUM_BUFFERS]{};
92 uint64_t _totalLossCounter[MAVLINK_COMM_NUM_BUFFERS]{};
93 float _runningLossPercent[MAVLINK_COMM_NUM_BUFFERS]{};
94
95 bool _initialized = false;
96
97 static constexpr const char* _tempLogFileTemplate = "FlightDataXXXXXX";
98 static constexpr const char* _logFileExtension = "mavlink";
99
100 static constexpr uint8_t kMaxCompId = MAV_COMPONENT_ENUM_END - 1;
101};
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
#define MAVLINK_COMM_NUM_BUFFERS
struct __mavlink_message mavlink_message_t
The link interface defines the interface for all links used to communicate with the ground station ap...
MAVLink micro air vehicle protocol reference implementation.
void receiveBytes(LinkInterface *link, const QByteArray &data)
static int getComponentId()
void mavlinkMessageStatus(int sysid, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent)
void messageReceived(LinkInterface *link, const mavlink_message_t &message)
void vehicleHeartbeatInfo(LinkInterface *link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType)
void resetSequenceTracking(LinkInterface *link)
Reset sequence tracking so signing transitions don't inflate loss counters.
void logSentBytes(const LinkInterface *link, const QByteArray &data)
static MAVLinkProtocol * instance()
int getSystemId() const
void resetMetadataForLink(LinkInterface *link)
void suspendLogForReplay(bool suspend)
static QString getName()
static void deleteTempLogFiles()