QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
VehicleLinkManager.cc
Go to the documentation of this file.
2#include "MAVLinkLib.h"
3#include "Vehicle.h"
4#include "LinkManager.h"
5#include "AppMessages.h"
6#include "AudioOutput.h"
7#ifndef QGC_NO_SERIAL_LINK
8 #include "SerialLink.h"
9#endif
10#include "QGCLoggingCategory.h"
11
12QGC_LOGGING_CATEGORY(VehicleLinkManagerLog, "Vehicle.VehicleLinkManager")
13
15 : QObject(vehicle)
16 , _vehicle(vehicle)
17 , _commLostCheckTimer(new QTimer(this))
18{
19 // qCDebug(VehicleLinkManagerLog) << Q_FUNC_INFO << this;
20
22 (void) connect(_commLostCheckTimer, &QTimer::timeout, this, &VehicleLinkManager::_commLostCheck);
23
24 _commLostCheckTimer->setSingleShot(false);
25 _commLostCheckTimer->setInterval(_commLostCheckTimeoutMSecs);
26}
27
29{
30 // qCDebug(VehicleLinkManagerLog) << Q_FUNC_INFO << this;
31}
32
34{
35 // Radio status messages come from Sik Radios directly. It doesn't indicate there is any life on the other end.
36 if (message.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
37 return;
38 }
39
40 const int linkIndex = _containsLinkIndex(link);
41 if (linkIndex == -1) {
42 _addLink(link);
43 return;
44 }
45
46 LinkInfo_t &linkInfo = _rgLinkInfo[linkIndex];
47 linkInfo.heartbeatElapsedTimer.restart();
48 if (_rgLinkInfo[linkIndex].commLost) {
49 _commRegainedOnLink(link);
50 }
51}
52
53void VehicleLinkManager::_commRegainedOnLink(LinkInterface *link)
54{
55
56 const int linkIndex = _containsLinkIndex(link);
57 if (linkIndex == -1) {
58 return;
59 }
60
61 _rgLinkInfo[linkIndex].commLost = false;
62
63 // Notify the user of communication regained
64 QString commRegainedMessage;
65 const bool isPrimaryLink = link == _primaryLink.lock().get();
66 if (_rgLinkInfo.count() > 1) {
67 commRegainedMessage = tr("%1Communication regained on %2 link").arg(_vehicle->_vehicleIdSpeech()).arg(isPrimaryLink ? tr("primary") : tr("secondary"));
68 } else {
69 commRegainedMessage = tr("%1Communication regained").arg(_vehicle->_vehicleIdSpeech());
70 }
71
72 // Try to switch to another link
73 QString primarySwitchMessage;
74 if (_updatePrimaryLink()) {
75 primarySwitchMessage = tr("%1Switching communication to new primary link").arg(_vehicle->_vehicleIdSpeech());
76 }
77
78 if (!commRegainedMessage.isEmpty()) {
79 AudioOutput::instance()->say(commRegainedMessage.toLower());
80 }
81
82 if (!primarySwitchMessage.isEmpty()) {
83 AudioOutput::instance()->say(primarySwitchMessage.toLower());
84 QGC::showAppMessage(primarySwitchMessage);
85 }
86
88
89 // Check recovery from total communication loss
90 if (!_communicationLost) {
91 return;
92 }
93
94 bool noCommunicationLoss = true;
95 for (const LinkInfo_t &linkInfo: _rgLinkInfo) {
96 if (linkInfo.commLost) {
97 noCommunicationLoss = false;
98 break;
99 }
100 }
101
102 if (noCommunicationLoss) {
103 _communicationLost = false;
104 emit communicationLostChanged(_communicationLost);
105 }
106}
107
108void VehicleLinkManager::_commLostCheck()
109{
110 if (!_communicationLostEnabled) {
111 return;
112 }
113
114 // Use much shorter heartbeat timeout in unit tests since MockLink sends heartbeats instantly
115 const int heartbeatTimeout = QGC::runningUnitTests() ? kTestHeartbeatTimeoutMs : _heartbeatMaxElpasedMSecs;
116
117 bool linkStatusChange = false;
118 for (LinkInfo_t &linkInfo: _rgLinkInfo) {
119 if (!linkInfo.commLost && !linkInfo.link->linkConfiguration()->isHighLatency() && (linkInfo.heartbeatElapsedTimer.elapsed() > heartbeatTimeout)) {
120 linkInfo.commLost = true;
121 linkStatusChange = true;
122
123 // Notify the user of individual link communication loss
124 const bool isPrimaryLink = linkInfo.link.get() == _primaryLink.lock().get();
125 if (_rgLinkInfo.count() > 1) {
126 const QString msg = tr("%1Communication lost on %2 link.").arg(_vehicle->_vehicleIdSpeech()).arg(isPrimaryLink ? tr("primary") : tr("secondary"));
127 AudioOutput::instance()->say(msg.toLower());
128 }
129 }
130 }
131
132 if (linkStatusChange) {
133 emit linkStatusesChanged();
134 }
135
136 if (_updatePrimaryLink()) {
137 QString msg = tr("%1Switching communication to secondary link.").arg(_vehicle->_vehicleIdSpeech());
138 AudioOutput::instance()->say(msg.toLower());
140 }
141
142 if (_communicationLost) {
143 return;
144 }
145
146 bool totalCommunicationLoss = true;
147 for (const LinkInfo_t &linkInfo: _rgLinkInfo) {
148 if (!linkInfo.commLost) {
149 totalCommunicationLoss = false;
150 break;
151 }
152 }
153
154 if (totalCommunicationLoss) {
155 if (_autoDisconnect) {
156 // There is only one link to the vehicle and we want to auto disconnect from it
157 closeVehicle();
158 return;
159 }
160
161 AudioOutput::instance()->say(tr("%1Communication lost").arg(_vehicle->_vehicleIdSpeech()).toLower());
162
163 _communicationLost = true;
164 emit communicationLostChanged(_communicationLost);
165 }
166}
167
168int VehicleLinkManager::_containsLinkIndex(const LinkInterface *link)
169{
170 for (int i = 0; i < _rgLinkInfo.count(); i++) {
171 if (_rgLinkInfo[i].link.get() == link) {
172 return i;
173 }
174 }
175
176 return -1;
177}
178
179void VehicleLinkManager::_addLink(LinkInterface *link)
180{
181 if (_containsLinkIndex(link) != -1) {
182 qCWarning(VehicleLinkManagerLog) << "_addLink call with link which is already in the list";
183 return;
184 }
185
187 if (!sharedLink) {
188 qCDebug(VehicleLinkManagerLog) << "_addLink stale link" << (void*)link;
189 return;
190 }
191
192 qCDebug(VehicleLinkManagerLog) << "_addLink:" << link->linkConfiguration()->name() << QString("%1").arg((qulonglong)link, 0, 16);
193
194 link->addVehicleReference();
195
196 LinkInfo_t linkInfo;
197 linkInfo.link = sharedLink;
198 if (!link->linkConfiguration()->isHighLatency()) {
199 linkInfo.heartbeatElapsedTimer.start();
200 }
201 _rgLinkInfo.append(linkInfo);
202
203 _updatePrimaryLink();
204
205 (void) connect(link, &LinkInterface::disconnected, this, &VehicleLinkManager::_linkDisconnected);
206
207 emit linkNamesChanged();
208
209 if (_rgLinkInfo.count() == 1) {
210 _commLostCheckTimer->start();
211 }
212}
213
214void VehicleLinkManager::_removeLink(LinkInterface *link)
215{
216 const int linkIndex = _containsLinkIndex(link);
217 if (linkIndex == -1) {
218 qCWarning(VehicleLinkManagerLog) << "_removeLink call with link which is already in the list";
219 return;
220 }
221
222 qCDebug(VehicleLinkManagerLog) << "_removeLink:" << QString("%1").arg((qulonglong)link, 0, 16);
223
224 if (link == _primaryLink.lock().get()) {
225 _primaryLink.reset();
226 emit primaryLinkChanged();
227 }
228
229 disconnect(link, &LinkInterface::disconnected, this, &VehicleLinkManager::_linkDisconnected);
230 link->removeVehicleReference();
231 emit linkNamesChanged();
232 _rgLinkInfo.removeAt(linkIndex); // Remove the link last since it may cause the link itself to be deleted
233
234 if (_rgLinkInfo.isEmpty()) {
235 _commLostCheckTimer->stop();
236 }
237}
238
239void VehicleLinkManager::_linkDisconnected()
240{
241 qCDebug(VehicleLinkManagerLog) << Q_FUNC_INFO << "linkCount" << _rgLinkInfo.count();
242
243 LinkInterface *link = qobject_cast<LinkInterface*>(sender());
244 if (!link) {
245 return;
246 }
247
248 _removeLink(link);
249 _updatePrimaryLink();
250 if (_rgLinkInfo.isEmpty() && !_allLinksRemovedSignalledByCloseVehicle) {
251 qCDebug(VehicleLinkManagerLog) << "signalling allLinksRemoved";
252 // Stop command processing timers immediately to prevent callbacks during the
253 // asynchronous vehicle destruction sequence
254 _vehicle->_stopCommandProcessing();
255 emit allLinksRemoved(_vehicle);
256 }
257}
258
259SharedLinkInterfacePtr VehicleLinkManager::_bestActivePrimaryLink()
260{
261#ifndef QGC_NO_SERIAL_LINK
262 // Best choice is a USB connection
263 for (const LinkInfo_t &linkInfo: _rgLinkInfo) {
264 if (linkInfo.commLost) {
265 continue;
266 }
267
268 SharedLinkInterfacePtr candidateLink = linkInfo.link;
269 auto linkInterface = candidateLink.get();
270 if (linkInterface && LinkManager::isLinkUSBDirect(linkInterface)) {
271 return candidateLink;
272 }
273 }
274#endif
275
276 // Next best is normal latency link
277 for (const LinkInfo_t &linkInfo: _rgLinkInfo) {
278 if (linkInfo.commLost) {
279 continue;
280 }
281
282 SharedLinkInterfacePtr candidateLink = linkInfo.link;
283 const SharedLinkConfigurationPtr config = candidateLink->linkConfiguration();
284 if (config && !config->isHighLatency()) {
285 return candidateLink;
286 }
287 }
288
289 // Last possible choice is a high latency link
290 SharedLinkInterfacePtr primaryLink = _primaryLink.lock();
291 if (primaryLink && primaryLink->linkConfiguration()->isHighLatency()) {
292 // Best choice continues to be the current high latency link
293 return primaryLink;
294 }
295
296 // Pick any high latency link if one exists
297 for (const LinkInfo_t &linkInfo: _rgLinkInfo) {
298 if (linkInfo.commLost) {
299 continue;
300 }
301
302 SharedLinkInterfacePtr candidateLink = linkInfo.link;
303 const SharedLinkConfigurationPtr config = candidateLink->linkConfiguration();
304 if (config && config->isHighLatency()) {
305 return candidateLink;
306 }
307 }
308
309 return {};
310}
311
312bool VehicleLinkManager::_updatePrimaryLink()
313{
314 SharedLinkInterfacePtr primaryLink = _primaryLink.lock();
315 const int linkIndex = _containsLinkIndex(primaryLink.get());
316
317 if ((linkIndex != -1) && !_rgLinkInfo[linkIndex].commLost && !primaryLink->linkConfiguration()->isHighLatency()) {
318 // Current priority link is still valid
319 return false;
320 }
321
322 SharedLinkInterfacePtr bestActivePrimaryLink = _bestActivePrimaryLink();
323 if ((linkIndex != -1) && !bestActivePrimaryLink) {
324 // Nothing better available, leave things set to current primary link
325 return false;
326 }
327
328 if (bestActivePrimaryLink == primaryLink) {
329 return false;
330 }
331
332 if (primaryLink && primaryLink->linkConfiguration()->isHighLatency()) {
333 _vehicle->sendMavCommand(
334 MAV_COMP_ID_AUTOPILOT1,
335 MAV_CMD_CONTROL_HIGH_LATENCY,
336 true,
337 0 // Stop transmission on this link
338 );
339 }
340
341 _primaryLink = bestActivePrimaryLink;
342 emit primaryLinkChanged();
343
344 if (bestActivePrimaryLink && bestActivePrimaryLink->linkConfiguration()->isHighLatency()) {
345 _vehicle->sendMavCommand(MAV_COMP_ID_AUTOPILOT1,
346 MAV_CMD_CONTROL_HIGH_LATENCY,
347 true,
348 1); // Start transmission on this link
349 }
350
351 return true;
352}
353
355{
356 // Vehicle is no longer communicating with us. Remove all link references
357
358 const QList<LinkInfo_t> rgLinkInfoCopy = _rgLinkInfo;
359 for (const LinkInfo_t &linkInfo: rgLinkInfoCopy) {
360 _removeLink(linkInfo.link.get());
361 }
362
363 _rgLinkInfo.clear();
364
365 _allLinksRemovedSignalledByCloseVehicle = true; // Prevent double signal of allLinksRemoved
366 // Stop command processing timers immediately to prevent callbacks during the
367 // asynchronous vehicle destruction sequence
368 _vehicle->_stopCommandProcessing();
369 emit allLinksRemoved(_vehicle);
370}
371
372void VehicleLinkManager::setCommunicationLostEnabled(bool communicationLostEnabled)
373{
374 if (_communicationLostEnabled != communicationLostEnabled) {
375 _communicationLostEnabled = communicationLostEnabled;
377 }
378}
379
381{
382 return (_containsLinkIndex(link) != -1);
383}
384
386{
387 if (!_primaryLink.expired()) {
388 return _primaryLink.lock()->linkConfiguration()->name();
389 }
390
391 return QString();
392}
393
395{
396 for (const LinkInfo_t& linkInfo: _rgLinkInfo) {
397 if (linkInfo.link->linkConfiguration()->name() == name) {
398 _primaryLink = linkInfo.link;
399 emit primaryLinkChanged();
400 }
401 }
402}
403
405{
406 QStringList rgNames;
407
408 for (const LinkInfo_t &linkInfo: _rgLinkInfo) {
409 rgNames.append(linkInfo.link->linkConfiguration()->name());
410 }
411
412 return rgNames;
413}
414
416{
417 QStringList rgStatuses;
418
419 for (const LinkInfo_t &linkInfo: _rgLinkInfo) {
420 rgStatuses.append(linkInfo.commLost ? tr("Comm Lost") : "");
421 }
422
423 return rgStatuses;
424}
std::shared_ptr< LinkConfiguration > SharedLinkConfigurationPtr
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
void say(const QString &text, TextMods textMods=TextMod::None)
static AudioOutput * instance()
The link interface defines the interface for all links used to communicate with the ground station ap...
void disconnected()
SharedLinkConfigurationPtr linkConfiguration()
SharedLinkInterfacePtr sharedLinkInterfacePointerForLink(const LinkInterface *link)
static bool isLinkUSBDirect(const LinkInterface *link)
static LinkManager * instance()
void communicationLostEnabledChanged(bool communicationLostEnabled)
QStringList linkNames() const
WeakLinkInterfacePtr primaryLink() const
void allLinksRemoved(Vehicle *vehicle)
QStringList linkStatuses() const
void setPrimaryLinkByName(const QString &name)
void mavlinkMessageReceived(LinkInterface *link, const mavlink_message_t &message)
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
QString primaryLinkName() const
void sendMavCommand(int compId, MAV_CMD command, bool showError, float param1=0.0f, float param2=0.0f, float param3=0.0f, float param4=0.0f, float param5=0.0f, float param6=0.0f, float param7=0.0f)
Definition Vehicle.cc:2146
bool runningUnitTests()
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.
Definition AppMessages.cc:9