QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleLinkManager.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QElapsedTimer>
4#include <QtCore/QLoggingCategory>
5#include <QtCore/QObject>
6#include <QtCore/QTimer>
7#include <QtQmlIntegration/QtQmlIntegration>
8
9#include "LinkInterface.h"
10#include "MAVLinkLib.h"
11
12Q_DECLARE_LOGGING_CATEGORY(VehicleLinkManagerLog)
13
14class Vehicle;
15class VehicleLinkManagerTest;
16
17class VehicleLinkManager : public QObject
18{
19 Q_OBJECT
20 QML_ELEMENT
21 QML_UNCREATABLE("")
22 Q_MOC_INCLUDE("Vehicle.h")
24 Q_PROPERTY(QStringList linkNames READ linkNames NOTIFY linkNamesChanged)
25 Q_PROPERTY(QStringList linkStatuses READ linkStatuses NOTIFY linkStatusesChanged)
28 Q_PROPERTY(bool autoDisconnect MEMBER _autoDisconnect NOTIFY autoDisconnectChanged)
29
30 friend class Vehicle;
31#ifdef QGC_UNITTEST_BUILD
32 friend class VehicleLinkManagerTest;
33#endif
34
35public:
38
39 void mavlinkMessageReceived(LinkInterface *link, const mavlink_message_t &message);
40 bool containsLink(LinkInterface *link);
41 WeakLinkInterfacePtr primaryLink() const { return _primaryLink; }
42 QString primaryLinkName() const;
43 QStringList linkNames() const;
44 QStringList linkStatuses() const;
45 bool communicationLost() const { return _communicationLost; }
46 bool communicationLostEnabled() const { return _communicationLostEnabled; }
47 void setPrimaryLinkByName(const QString &name);
49 void closeVehicle();
50
51signals:
53 void allLinksRemoved(Vehicle *vehicle);
58 void autoDisconnectChanged(bool autoDisconnect);
59
60private slots:
61 void _commLostCheck();
62
63private:
64 int _containsLinkIndex(const LinkInterface *link);
65 void _addLink(LinkInterface *link);
66 void _removeLink(LinkInterface *link);
67 void _linkDisconnected();
68 bool _updatePrimaryLink();
69 SharedLinkInterfacePtr _bestActivePrimaryLink();
70 void _commRegainedOnLink(LinkInterface *link);
71
72 struct LinkInfo_t {
74 bool commLost = false;
75 QElapsedTimer heartbeatElapsedTimer;
76 };
77
78 Vehicle *_vehicle = nullptr;
79 QTimer *_commLostCheckTimer = nullptr;
80 QList<LinkInfo_t> _rgLinkInfo;
81 WeakLinkInterfacePtr _primaryLink;
82 bool _communicationLost = false;
83 bool _communicationLostEnabled = true;
84 bool _autoDisconnect = false;
85 bool _allLinksRemovedSignalledByCloseVehicle = false;
86
87 static constexpr int _commLostCheckTimeoutMSecs = 1000;
88 static constexpr int _heartbeatMaxElpasedMSecs = 3500;
89
90public:
92 static constexpr int kTestHeartbeatTimeoutMs = 500;
93
96 static constexpr int kTestCommLostDetectionTimeoutMs = _commLostCheckTimeoutMSecs + kTestHeartbeatTimeoutMs + 500;
97};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
std::weak_ptr< LinkInterface > WeakLinkInterfacePtr
struct __mavlink_message mavlink_message_t
The link interface defines the interface for all links used to communicate with the ground station ap...
void communicationLostEnabledChanged(bool communicationLostEnabled)
QStringList linkNames() const
void autoDisconnectChanged(bool autoDisconnect)
WeakLinkInterfacePtr primaryLink() const
void allLinksRemoved(Vehicle *vehicle)
QStringList linkStatuses() const
void setPrimaryLinkByName(const QString &name)
void mavlinkMessageReceived(LinkInterface *link, const mavlink_message_t &message)
static constexpr int kTestCommLostDetectionTimeoutMs
void setCommunicationLostEnabled(bool communicationLostEnabled)
bool containsLink(LinkInterface *link)
void communicationLostChanged(bool communicationLost)
static constexpr int kTestHeartbeatTimeoutMs
Heartbeat timeout used in unit tests (much shorter for faster tests)
void linkStatusesChanged()
bool communicationLostEnabled() const
bool communicationLost() const
QString primaryLinkName() const