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