QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
LinkManager.cc
Go to the documentation of this file.
1#include "LinkManager.h"
2#include "LogReplayLink.h"
3#include "QGCNetworkHelper.h"
4#include "MAVLinkProtocol.h"
6#include "QGCApplication.h"
9#include "SettingsManager.h"
10#include "MavlinkSettings.h"
11#include "AutoConnectSettings.h"
12#include "TCPLink.h"
13#include "UDPLink.h"
14
15#include "BluetoothLink.h"
16
17#ifndef QGC_NO_SERIAL_LINK
18#include "SerialLink.h"
19#include "GPSManager.h"
20#include "PositionManager.h"
21#include "UdpIODevice.h"
22#include "GPSRtk.h"
23#endif
24
25#ifdef QT_DEBUG
26#include "MockLink.h"
27#endif
28
29#ifdef QGC_ZEROCONF_ENABLED
30#include <qmdnsengine/browser.h>
31#include <qmdnsengine/cache.h>
32#include <qmdnsengine/mdns.h>
33#include <qmdnsengine/server.h>
34#include <qmdnsengine/service.h>
35#endif
36
37#include <QtCore/QApplicationStatic>
38#include <QtCore/QTimer>
39
40QGC_LOGGING_CATEGORY(LinkManagerLog, "Comms.LinkManager")
41QGC_LOGGING_CATEGORY(LinkManagerVerboseLog, "Comms.LinkManager:verbose")
42
43Q_APPLICATION_STATIC(LinkManager, _linkManagerInstance);
44
45LinkManager::LinkManager(QObject *parent)
46 : QObject(parent)
47 , _portListTimer(new QTimer(this))
48 , _qmlConfigurations(new QmlObjectListModel(this))
49#ifndef QGC_NO_SERIAL_LINK
50 , _nmeaSocket(new UdpIODevice(this))
51#endif
52{
53 qCDebug(LinkManagerLog) << this;
54
55 (void) qRegisterMetaType<QAbstractSocket::SocketError>("QAbstractSocket::SocketError");
56 (void) qRegisterMetaType<LinkInterface*>("LinkInterface*");
57#ifndef QGC_NO_SERIAL_LINK
58 (void) qRegisterMetaType<QGCSerialPortInfo>("QGCSerialPortInfo");
59#endif
60}
61
62LinkManager::~LinkManager()
63{
64 qCDebug(LinkManagerLog) << this;
65}
66
67LinkManager *LinkManager::instance()
68{
69 return _linkManagerInstance();
70}
71
72void LinkManager::init()
73{
74 _autoConnectSettings = SettingsManager::instance()->autoConnectSettings();
75
76 if (!qgcApp()->runningUnitTests()) {
77 (void) connect(_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks);
78 _portListTimer->start(_autoconnectUpdateTimerMSecs); // timeout must be long enough to get past bootloader on second pass
79 }
80}
81
82QList<SharedLinkInterfacePtr> LinkManager::links()
83{
84 QMutexLocker locker(&_linksMutex);
85 return _rgLinks;
86}
87
88QmlObjectListModel *LinkManager::_qmlLinkConfigurations()
89{
90 return _qmlConfigurations;
91}
92
93void LinkManager::createConnectedLink(const LinkConfiguration *config)
94{
95 for (SharedLinkConfigurationPtr &sharedConfig : _rgLinkConfigs) {
96 if (sharedConfig.get() == config) {
97 createConnectedLink(sharedConfig);
98 }
99 }
100}
101
102bool LinkManager::createConnectedLink(SharedLinkConfigurationPtr &config)
103{
104 SharedLinkInterfacePtr link = nullptr;
105
106 switch(config->type()) {
107#ifndef QGC_NO_SERIAL_LINK
108 case LinkConfiguration::TypeSerial:
109 link = std::make_shared<SerialLink>(config);
110 break;
111#endif
112 case LinkConfiguration::TypeUdp:
113 link = std::make_shared<UDPLink>(config);
114 break;
115 case LinkConfiguration::TypeTcp:
116 link = std::make_shared<TCPLink>(config);
117 break;
118 case LinkConfiguration::TypeBluetooth:
119 link = std::make_shared<BluetoothLink>(config);
120 break;
121 case LinkConfiguration::TypeLogReplay:
122 link = std::make_shared<LogReplayLink>(config);
123 break;
124#ifdef QT_DEBUG
125 case LinkConfiguration::TypeMock:
126 link = std::make_shared<MockLink>(config);
127 break;
128#endif
129 case LinkConfiguration::TypeLast:
130 default:
131 break;
132 }
133
134 if (!link) {
135 return false;
136 }
137
138 if (!link->_allocateMavlinkChannel()) {
139 qCWarning(LinkManagerLog) << "Link failed to setup mavlink channels";
140 return false;
141 }
142
143 // Set up signal connections before adding to list, so link is fully initialized
144 (void) connect(link.get(), &LinkInterface::communicationError, this, &LinkManager::_communicationError);
147 (void) connect(link.get(), &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);
148
150
151 // Try to connect before adding to active links list
152 if (!link->_connect()) {
153 (void) disconnect(link.get(), &LinkInterface::communicationError, this, &LinkManager::_communicationError);
156 (void) disconnect(link.get(), &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);
157 link->_freeMavlinkChannel();
158 config->setLink(nullptr);
159 return false;
160 }
161
162 {
163 QMutexLocker locker(&_linksMutex);
164 _rgLinks.append(link);
165 }
166 config->setLink(link);
167
168 return true;
169}
170
171void LinkManager::_communicationError(const QString &title, const QString &error)
172{
173 qgcApp()->showAppMessage(error, title);
174}
175
176SharedLinkInterfacePtr LinkManager::mavlinkForwardingLink()
177{
178 QMutexLocker locker(&_linksMutex);
179
180 for (const SharedLinkInterfacePtr &link : _rgLinks) {
181 const SharedLinkConfigurationPtr linkConfig = link->linkConfiguration();
182 if (linkConfig && (linkConfig->type() == LinkConfiguration::TypeUdp) && (linkConfig->name() == _mavlinkForwardingLinkName)) {
183 return link;
184 }
185 }
186
187 return nullptr;
188}
189
190SharedLinkInterfacePtr LinkManager::mavlinkForwardingSupportLink()
191{
192 QMutexLocker locker(&_linksMutex);
193
194 for (const SharedLinkInterfacePtr &link : _rgLinks) {
195 const SharedLinkConfigurationPtr linkConfig = link->linkConfiguration();
196 if (linkConfig && (linkConfig->type() == LinkConfiguration::TypeUdp) && (linkConfig->name() == _mavlinkForwardingSupportLinkName)) {
197 return link;
198 }
199 }
200
201 return nullptr;
202}
203
204void LinkManager::disconnectAll()
205{
206 QList<SharedLinkInterfacePtr> links;
207 {
208 QMutexLocker locker(&_linksMutex);
209 links = _rgLinks;
210 }
211
212 for (const SharedLinkInterfacePtr &sharedLink: links) {
213 sharedLink->disconnect();
214 }
215}
216
217void LinkManager::_linkDisconnected()
218{
219 LinkInterface* const link = qobject_cast<LinkInterface*>(sender());
220
221 if (!link) {
222 return;
223 }
224
225 SharedLinkInterfacePtr linkToCleanup;
227 {
228 QMutexLocker locker(&_linksMutex);
229
230 for (auto it = _rgLinks.begin(); it != _rgLinks.end(); ++it) {
231 if (it->get() == link) {
232 config = it->get()->linkConfiguration();
233 const QString linkName = config ? config->name() : QStringLiteral("<null config>");
234 qCDebug(LinkManagerLog) << linkName << "use_count:" << it->use_count();
235 linkToCleanup = *it;
236 (void) _rgLinks.erase(it);
237 break;
238 }
239 }
240 }
241
242 if (!linkToCleanup) {
243 qCDebug(LinkManagerLog) << "link already removed";
244 return;
245 }
246
247 if (config) {
248 config->setLink(nullptr);
249 }
250
251 (void) disconnect(link, &LinkInterface::communicationError, this, &LinkManager::_communicationError);
254 (void) disconnect(link, &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);
255
256 link->_freeMavlinkChannel();
257}
258
259SharedLinkInterfacePtr LinkManager::sharedLinkInterfacePointerForLink(const LinkInterface *link)
260{
261 QMutexLocker locker(&_linksMutex);
262
263 for (const SharedLinkInterfacePtr &sharedLink: _rgLinks) {
264 if (sharedLink.get() == link) {
265 return sharedLink;
266 }
267 }
268
269 // Link not found - this is normal during disconnect when queued signals are still processing.
270 // Callers should check for nullptr return value.
271 qCDebug(LinkManagerLog) << "link not in list (likely disconnected)";
272 return SharedLinkInterfacePtr(nullptr);
273}
274
275bool LinkManager::_connectionsSuspendedMsg() const
276{
277 if (_connectionsSuspended) {
278 qgcApp()->showAppMessage(tr("Connect not allowed: %1").arg(_connectionsSuspendedReason));
279 return true;
280 }
281
282 return false;
283}
284
285void LinkManager::saveLinkConfigurationList()
286{
287 QSettings settings;
288 settings.remove(LinkConfiguration::settingsRoot());
289
290 int trueCount = 0;
291 for (int i = 0; i < _rgLinkConfigs.count(); i++) {
292 SharedLinkConfigurationPtr linkConfig = _rgLinkConfigs[i];
293 if (!linkConfig) {
294 qCWarning(LinkManagerLog) << "Internal error for link configuration in LinkManager";
295 continue;
296 }
297
298 if (linkConfig->isDynamic()) {
299 continue;
300 }
301
302 const QString root = LinkConfiguration::settingsRoot() + QStringLiteral("/Link%1").arg(trueCount++);
303 settings.setValue(root + "/name", linkConfig->name());
304 settings.setValue(root + "/type", linkConfig->type());
305 settings.setValue(root + "/auto", linkConfig->isAutoConnect());
306 settings.setValue(root + "/high_latency", linkConfig->isHighLatency());
307 linkConfig->saveSettings(settings, root);
308 }
309
310 const QString root = QString(LinkConfiguration::settingsRoot());
311 settings.setValue(root + "/count", trueCount);
312}
313
314void LinkManager::loadLinkConfigurationList()
315{
316 QSettings settings;
317 // Is the group even there?
318 if (settings.contains(LinkConfiguration::settingsRoot() + "/count")) {
319 // Find out how many configurations we have
320 const int count = settings.value(LinkConfiguration::settingsRoot() + "/count").toInt();
321 for (int i = 0; i < count; i++) {
322 const QString root = LinkConfiguration::settingsRoot() + QStringLiteral("/Link%1").arg(i);
323 if (!settings.contains(root + "/type")) {
324 qCWarning(LinkManagerLog) << "Link Configuration" << root << "has no type.";
325 continue;
326 }
327
328 LinkConfiguration::LinkType type = static_cast<LinkConfiguration::LinkType>(settings.value(root + "/type").toInt());
329 if (type >= LinkConfiguration::TypeLast) {
330 qCWarning(LinkManagerLog) << "Link Configuration" << root << "an invalid type:" << type;
331 continue;
332 }
333
334 if (!settings.contains(root + "/name")) {
335 qCWarning(LinkManagerLog) << "Link Configuration" << root << "has no name.";
336 continue;
337 }
338
339 const QString name = settings.value(root + "/name").toString();
340 if (name.isEmpty()) {
341 qCWarning(LinkManagerLog) << "Link Configuration" << root << "has an empty name.";
342 continue;
343 }
344
345 LinkConfiguration* link = nullptr;
346 switch(type) {
347#ifndef QGC_NO_SERIAL_LINK
348 case LinkConfiguration::TypeSerial:
349 link = new SerialConfiguration(name);
350 break;
351#endif
352 case LinkConfiguration::TypeUdp:
353 link = new UDPConfiguration(name);
354 break;
355 case LinkConfiguration::TypeTcp:
356 link = new TCPConfiguration(name);
357 break;
358 case LinkConfiguration::TypeBluetooth:
359 link = new BluetoothConfiguration(name);
360 break;
361 case LinkConfiguration::TypeLogReplay:
362 link = new LogReplayConfiguration(name);
363 break;
364#ifdef QT_DEBUG
365 case LinkConfiguration::TypeMock:
366 link = new MockConfiguration(name);
367 break;
368#endif
369 case LinkConfiguration::TypeLast:
370 default:
371 break;
372 }
373
374 if (link) {
375 const bool autoConnect = settings.value(root + "/auto").toBool();
376 link->setAutoConnect(autoConnect);
377 const bool highLatency = settings.value(root + "/high_latency").toBool();
378 link->setHighLatency(highLatency);
379 link->loadSettings(settings, root);
380 addConfiguration(link);
381 }
382 }
383 }
384
385 // Enable automatic Serial PX4/3DR Radio hunting
386 _configurationsLoaded = true;
387}
388
389void LinkManager::_addUDPAutoConnectLink()
390{
391 if (!_autoConnectSettings->autoConnectUDP()->rawValue().toBool()) {
392 return;
393 }
394
395 {
396 QMutexLocker locker(&_linksMutex);
397 for (const SharedLinkInterfacePtr &link : _rgLinks) {
398 const SharedLinkConfigurationPtr linkConfig = link->linkConfiguration();
399 if (linkConfig && (linkConfig->type() == LinkConfiguration::TypeUdp) && (linkConfig->name() == _defaultUDPLinkName)) {
400 return;
401 }
402 }
403 }
404
405 qCDebug(LinkManagerLog) << "New auto-connect UDP port added";
406 UDPConfiguration* const udpConfig = new UDPConfiguration(_defaultUDPLinkName);
407 udpConfig->setDynamic(true);
408 udpConfig->setAutoConnect(true);
409 SharedLinkConfigurationPtr config = addConfiguration(udpConfig);
410 createConnectedLink(config);
411}
412
413void LinkManager::_addMAVLinkForwardingLink()
414{
415 if (!SettingsManager::instance()->mavlinkSettings()->forwardMavlink()->rawValue().toBool()) {
416 return;
417 }
418
419 {
420 QMutexLocker locker(&_linksMutex);
421 for (const SharedLinkInterfacePtr &link : _rgLinks) {
422 const SharedLinkConfigurationPtr linkConfig = link->linkConfiguration();
423 if (linkConfig && (linkConfig->type() == LinkConfiguration::TypeUdp) && (linkConfig->name() == _mavlinkForwardingLinkName)) {
424 // TODO: should we check if the host/port matches the mavlinkForwardHostName setting and update if it does not match?
425 return;
426 }
427 }
428 }
429
430 const QString hostName = SettingsManager::instance()->mavlinkSettings()->forwardMavlinkHostName()->rawValue().toString();
431 _createDynamicForwardLink(_mavlinkForwardingLinkName, hostName);
432}
433
434#ifdef QGC_ZEROCONF_ENABLED
435void LinkManager::_addZeroConfAutoConnectLink()
436{
437 if (!_autoConnectSettings->autoConnectZeroConf()->rawValue().toBool()) {
438 return;
439 }
440
441 static QSharedPointer<QMdnsEngine::Server> server;
442 static QSharedPointer<QMdnsEngine::Browser> browser;
443 server.reset(new QMdnsEngine::Server());
444 browser.reset(new QMdnsEngine::Browser(server.get(), QMdnsEngine::MdnsBrowseType));
445
446 const auto checkIfConnectionLinkExist = [this](LinkConfiguration::LinkType linkType, const QString &linkName) {
447 QMutexLocker locker(&_linksMutex);
448 for (const SharedLinkInterfacePtr &link : std::as_const(_rgLinks)) {
449 const SharedLinkConfigurationPtr linkConfig = link->linkConfiguration();
450 if (linkConfig && (linkConfig->type() == linkType) && (linkConfig->name() == linkName)) {
451 return true;
452 }
453 }
454
455 return false;
456 };
457
458 (void) connect(browser.get(), &QMdnsEngine::Browser::serviceAdded, this, [checkIfConnectionLinkExist, this](const QMdnsEngine::Service &service) {
459 qCDebug(LinkManagerLog) << "Found Zero-Conf:" << service.type() << service.name() << service.hostname() << service.port() << service.attributes();
460
461 if (!service.type().startsWith("_mavlink")) {
462 qCWarning(LinkManagerLog) << "Invalid ZeroConf SericeType" << service.type();
463 return;
464 }
465
466 // Windows doesnt accept trailling dots in mdns
467 // http://www.dns-sd.org/trailingdotsindomainnames.html
468 QString hostname = service.hostname();
469 if (hostname.endsWith('.')) {
470 hostname.chop(1);
471 }
472
473 if (service.type().startsWith("_mavlink._udp")) {
474 static const QString udpName = QStringLiteral("ZeroConf UDP");
475 if (checkIfConnectionLinkExist(LinkConfiguration::TypeUdp, udpName)) {
476 qCDebug(LinkManagerLog) << "Connection already exist";
477 return;
478 }
479
480 UDPConfiguration *const link = new UDPConfiguration(udpName);
481 link->addHost(hostname, service.port());
482 link->setAutoConnect(true);
483 link->setDynamic(true);
484 SharedLinkConfigurationPtr config = addConfiguration(link);
485 if (!createConnectedLink(config)) {
486 qCWarning(LinkManagerLog) << "Failed to create" << udpName;
487 }
488 } else if (service.type().startsWith("_mavlink._tcp")) {
489 static QString tcpName = QStringLiteral("ZeroConf TCP");
490 if (checkIfConnectionLinkExist(LinkConfiguration::TypeTcp, tcpName)) {
491 qCDebug(LinkManagerLog) << "Connection already exist";
492 return;
493 }
494
495 TCPConfiguration *const link = new TCPConfiguration(tcpName);
496 link->setHost(hostname);
497 link->setPort(service.port());
498 link->setAutoConnect(true);
499 link->setDynamic(true);
500 SharedLinkConfigurationPtr config = addConfiguration(link);
501 if (!createConnectedLink(config)) {
502 qCWarning(LinkManagerLog) << "Failed to create" << tcpName;
503 }
504 }
505 });
506}
507#endif
508
509void LinkManager::_updateAutoConnectLinks()
510{
511 if (_connectionsSuspended) {
512 return;
513 }
514
515 _addUDPAutoConnectLink();
516 _addMAVLinkForwardingLink();
517#ifdef QGC_ZEROCONF_ENABLED
518 _addZeroConfAutoConnectLink();
519#endif
520
521 // check to see if nmea gps is configured for UDP input, if so, set it up to connect
522 if (_autoConnectSettings->autoConnectNmeaPort()->cookedValueString() == "UDP Port") {
523 if ((_nmeaSocket->localPort() != _autoConnectSettings->nmeaUdpPort()->rawValue().toUInt()) || (_nmeaSocket->state() != UdpIODevice::BoundState)) {
524 qCDebug(LinkManagerLog) << "Changing port for UDP NMEA stream";
525 _nmeaSocket->close();
526 _nmeaSocket->bind(QHostAddress::AnyIPv4, _autoConnectSettings->nmeaUdpPort()->rawValue().toUInt());
527 QGCPositionManager::instance()->setNmeaSourceDevice(_nmeaSocket);
528 }
529#ifndef QGC_NO_SERIAL_LINK
530 if (_nmeaPort) {
531 _nmeaPort->close();
532 delete _nmeaPort;
533 _nmeaPort = nullptr;
534 _nmeaDeviceName = "";
535 }
536#endif
537 } else {
538 _nmeaSocket->close();
539 }
540
541#ifndef QGC_NO_SERIAL_LINK
542 _addSerialAutoConnectLink();
543#endif
544}
545
546void LinkManager::shutdown()
547{
548 setConnectionsSuspended(tr("Shutdown"));
549 disconnectAll();
550
551 // Wait for all the vehicles to go away to ensure an orderly shutdown and deletion of all objects
552 while (MultiVehicleManager::instance()->vehicles()->count()) {
553 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
554 }
555}
556
557QStringList LinkManager::linkTypeStrings() const
558{
559 //-- Must follow same order as enum LinkType in LinkConfiguration.h
560 static QStringList list;
561 if (!list.isEmpty()) {
562 return list;
563 }
564
565#ifndef QGC_NO_SERIAL_LINK
566 list += tr("Serial");
567#endif
568 list += tr("UDP");
569 list += tr("TCP");
570 list += tr("Bluetooth");
571#ifdef QT_DEBUG
572 list += tr("Mock Link");
573#endif
574 list += tr("Log Replay");
575
576 if (list.size() != static_cast<int>(LinkConfiguration::TypeLast)) {
577 qCWarning(LinkManagerLog) << "Internal error";
578 }
579
580 return list;
581}
582
583void LinkManager::endConfigurationEditing(LinkConfiguration *config, LinkConfiguration *editedConfig)
584{
585 if (!config || !editedConfig) {
586 qCWarning(LinkManagerLog) << "Internal error";
587 return;
588 }
589
590 config->copyFrom(editedConfig);
591 saveLinkConfigurationList();
592 emit config->nameChanged(config->name());
593 // Discard temporary duplicate
594 delete editedConfig;
595}
596
597void LinkManager::endCreateConfiguration(LinkConfiguration *config)
598{
599 if (!config) {
600 qCWarning(LinkManagerLog) << "Internal error";
601 return;
602 }
603
604 addConfiguration(config);
605 saveLinkConfigurationList();
606}
607
608LinkConfiguration *LinkManager::createConfiguration(int type, const QString &name)
609{
610#ifndef QGC_NO_SERIAL_LINK
611 if (static_cast<LinkConfiguration::LinkType>(type) == LinkConfiguration::TypeSerial) {
612 _updateSerialPorts();
613 }
614#endif
615
616 return LinkConfiguration::createSettings(type, name);
617}
618
619LinkConfiguration *LinkManager::startConfigurationEditing(LinkConfiguration *config)
620{
621 if (!config) {
622 qCWarning(LinkManagerLog) << "Internal error";
623 return nullptr;
624 }
625
626#ifndef QGC_NO_SERIAL_LINK
627 if (config->type() == LinkConfiguration::TypeSerial) {
628 _updateSerialPorts();
629 }
630#endif
631
632 return LinkConfiguration::duplicateSettings(config);
633}
634
635void LinkManager::removeConfiguration(LinkConfiguration *config)
636{
637 if (!config) {
638 qCWarning(LinkManagerLog) << "Internal error";
639 return;
640 }
641
642 LinkInterface* const link = config->link();
643 if (link) {
644 link->disconnect();
645 }
646
647 _removeConfiguration(config);
648 saveLinkConfigurationList();
649}
650
651void LinkManager::createMavlinkForwardingSupportLink()
652{
653 const QString hostName = SettingsManager::instance()->mavlinkSettings()->forwardMavlinkAPMSupportHostName()->rawValue().toString();
654 _createDynamicForwardLink(_mavlinkForwardingSupportLinkName, hostName);
655 _mavlinkSupportForwardingEnabled = true;
657}
658
659void LinkManager::_removeConfiguration(const LinkConfiguration *config)
660{
661 (void) _qmlConfigurations->removeOne(config);
662
663 for (auto it = _rgLinkConfigs.begin(); it != _rgLinkConfigs.end(); ++it) {
664 if (it->get() == config) {
665 (void) _rgLinkConfigs.erase(it);
666 return;
667 }
668 }
669
670 qCWarning(LinkManagerLog) << "called with unknown config";
671}
672
673bool LinkManager::isBluetoothAvailable()
674{
676}
677
678bool LinkManager::containsLink(const LinkInterface *link)
679{
680 QMutexLocker locker(&_linksMutex);
681
682 for (const SharedLinkInterfacePtr &sharedLink : _rgLinks) {
683 if (sharedLink.get() == link) {
684 return true;
685 }
686 }
687
688 return false;
689}
690
691SharedLinkConfigurationPtr LinkManager::addConfiguration(LinkConfiguration *config)
692{
693 (void) _qmlConfigurations->append(config);
694 (void) _rgLinkConfigs.append(SharedLinkConfigurationPtr(config));
695
696 return _rgLinkConfigs.last();
697}
698
699void LinkManager::startAutoConnectedLinks()
700{
701 for (SharedLinkConfigurationPtr &sharedConfig : _rgLinkConfigs) {
702 if (sharedConfig->isAutoConnect()) {
703 createConnectedLink(sharedConfig);
704 }
705 }
706}
707
708uint8_t LinkManager::allocateMavlinkChannel()
709{
710 for (uint8_t mavlinkChannel = 0; mavlinkChannel < MAVLINK_COMM_NUM_BUFFERS; mavlinkChannel++) {
711 if (_mavlinkChannelsUsedBitMask & (1 << mavlinkChannel)) {
712 continue;
713 }
714
715 mavlink_reset_channel_status(mavlinkChannel);
716 mavlink_status_t* const mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);
717 mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
718 _mavlinkChannelsUsedBitMask |= (1 << mavlinkChannel);
719 qCDebug(LinkManagerLog) << "allocateMavlinkChannel" << mavlinkChannel;
720 return mavlinkChannel;
721 }
722
723 qWarning(LinkManagerLog) << "allocateMavlinkChannel: all channels reserved!";
724 return invalidMavlinkChannel();
725}
726
727void LinkManager::freeMavlinkChannel(uint8_t channel)
728{
729 qCDebug(LinkManagerLog) << "freeMavlinkChannel" << channel;
730
731 if (invalidMavlinkChannel() == channel) {
732 return;
733 }
734
735 _mavlinkChannelsUsedBitMask &= ~(1 << channel);
736}
737
738LogReplayLink *LinkManager::startLogReplay(const QString &logFile)
739{
740 LogReplayConfiguration* const linkConfig = new LogReplayConfiguration(tr("Log Replay"));
741 linkConfig->setLogFilename(logFile);
742 linkConfig->setName(linkConfig->logFilenameShort());
743
744 SharedLinkConfigurationPtr sharedConfig = addConfiguration(linkConfig);
745 if (createConnectedLink(sharedConfig)) {
746 return qobject_cast<LogReplayLink*>(sharedConfig->link());
747 }
748
749 return nullptr;
750}
751
752void LinkManager::_createDynamicForwardLink(const char *linkName, const QString &hostName)
753{
754 UDPConfiguration* const udpConfig = new UDPConfiguration(linkName);
755
756 udpConfig->setDynamic(true);
757 udpConfig->setForwarding(true);
758 udpConfig->addHost(hostName);
759
760 SharedLinkConfigurationPtr config = addConfiguration(udpConfig);
761 createConnectedLink(config);
762
763 qCDebug(LinkManagerLog) << "New dynamic MAVLink forwarding port added:" << linkName << " hostname:" << hostName;
764}
765
766bool LinkManager::isLinkUSBDirect(const LinkInterface *link)
767{
768#ifndef QGC_NO_SERIAL_LINK
769 const SerialLink* const serialLink = qobject_cast<const SerialLink*>(link);
770 if (!serialLink) {
771 return false;
772 }
773
774 const SharedLinkConfigurationPtr config = serialLink->linkConfiguration();
775 if (!config) {
776 return false;
777 }
778
779 const SerialConfiguration* const serialConfig = qobject_cast<const SerialConfiguration*>(config.get());
780 if (serialConfig && serialConfig->usbDirect()) {
781 return link;
782 }
783#endif
784
785 return false;
786}
787
788void LinkManager::resetMavlinkSigning()
789{
790 // Make a copy under mutex protection to avoid holding lock during signing initialization
791 QList<SharedLinkInterfacePtr> links;
792 {
793 QMutexLocker locker(&_linksMutex);
794 links = _rgLinks;
795 }
796
797 for (const SharedLinkInterfacePtr &sharedLink: links) {
798 sharedLink->initMavlinkSigning();
799 }
800}
801
802#ifndef QGC_NO_SERIAL_LINK // Serial Only Functions
803
804void LinkManager::_filterCompositePorts(QList<QGCSerialPortInfo> &portList)
805{
806 typedef QPair<quint16, quint16> VidPidPair_t;
807
808 QMap<VidPidPair_t, QStringList> seenSerialNumbers;
809
810 for (auto it = portList.begin(); it != portList.end();) {
811 const QGCSerialPortInfo &portInfo = *it;
812 if (portInfo.hasVendorIdentifier() && portInfo.hasProductIdentifier() && !portInfo.serialNumber().isEmpty() && portInfo.serialNumber() != "0") {
813 VidPidPair_t vidPid(portInfo.vendorIdentifier(), portInfo.productIdentifier());
814 if (seenSerialNumbers.contains(vidPid) && seenSerialNumbers[vidPid].contains(portInfo.serialNumber())) {
815 // Some boards are a composite USB device, with the first port being mavlink and the second something else. We only expose to first mavlink port.
816 // However internal NMEA devices can present like this, so dont skip anything with NMEA in description
817 if(!portInfo.description().contains("NMEA")) {
818 qCDebug(LinkManagerVerboseLog) << QStringLiteral("Removing secondary port on same device - port:%1 vid:%2 pid%3 sn:%4").arg(portInfo.portName()).arg(portInfo.vendorIdentifier()).arg(portInfo.productIdentifier()).arg(portInfo.serialNumber());
819 it = portList.erase(it);
820 continue;
821 }
822 }
823 seenSerialNumbers[vidPid].append(portInfo.serialNumber());
824 }
825 it++;
826 }
827}
828
829void LinkManager::_addSerialAutoConnectLink()
830{
831 QList<QGCSerialPortInfo> portList;
832#ifdef Q_OS_ANDROID
833 // Android builds only support a single serial connection. Repeatedly calling availablePorts after that one serial
834 // port is connected leaks file handles due to a bug somewhere in android serial code. In order to work around that
835 // bug after we connect the first serial port we stop probing for additional ports.
836 if (!_isSerialPortConnected()) {
838 }
839#else
841#endif
842
843 _filterCompositePorts(portList);
844
845 QStringList currentPorts;
846 for (const QGCSerialPortInfo &portInfo: portList) {
847 qCDebug(LinkManagerVerboseLog) << "-----------------------------------------------------";
848 qCDebug(LinkManagerVerboseLog) << "portName: " << portInfo.portName();
849 qCDebug(LinkManagerVerboseLog) << "systemLocation: " << portInfo.systemLocation();
850 qCDebug(LinkManagerVerboseLog) << "description: " << portInfo.description();
851 qCDebug(LinkManagerVerboseLog) << "manufacturer: " << portInfo.manufacturer();
852 qCDebug(LinkManagerVerboseLog) << "serialNumber: " << portInfo.serialNumber();
853 qCDebug(LinkManagerVerboseLog) << "vendorIdentifier: " << portInfo.vendorIdentifier();
854 qCDebug(LinkManagerVerboseLog) << "productIdentifier: " << portInfo.productIdentifier();
855
856 currentPorts << portInfo.systemLocation();
857
859 QString boardName;
860
861 // check to see if nmea gps is configured for current Serial port, if so, set it up to connect
862 if (portInfo.systemLocation().trimmed() == _autoConnectSettings->autoConnectNmeaPort()->cookedValueString()) {
863 if (portInfo.systemLocation().trimmed() != _nmeaDeviceName) {
864 _nmeaDeviceName = portInfo.systemLocation().trimmed();
865 qCDebug(LinkManagerLog) << "Configuring nmea port" << _nmeaDeviceName;
866 QSerialPort* newPort = new QSerialPort(portInfo, this);
867 _nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt();
868 newPort->setBaudRate(static_cast<qint32>(_nmeaBaud));
869 qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud;
870 // This will stop polling old device if previously set
871 QGCPositionManager::instance()->setNmeaSourceDevice(newPort);
872 if (_nmeaPort) {
873 delete _nmeaPort;
874 }
875 _nmeaPort = newPort;
876 } else if (_autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt() != _nmeaBaud) {
877 _nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt();
878 _nmeaPort->setBaudRate(static_cast<qint32>(_nmeaBaud));
879 qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud;
880 }
881 } else if (portInfo.getBoardInfo(boardType, boardName)) {
882 // Should we be auto-connecting to this board type?
883 if (!_allowAutoConnectToBoard(boardType)) {
884 continue;
885 }
886
887 if (portInfo.isBootloader()) {
888 // Don't connect to bootloader
889 qCDebug(LinkManagerLog) << "Waiting for bootloader to finish" << portInfo.systemLocation();
890 continue;
891 }
892 if (_portAlreadyConnected(portInfo.systemLocation()) || (_autoConnectRTKPort == portInfo.systemLocation())) {
893 qCDebug(LinkManagerVerboseLog) << "Skipping existing autoconnect" << portInfo.systemLocation();
894 } else if (!_autoconnectPortWaitList.contains(portInfo.systemLocation())) {
895 // We don't connect to the port the first time we see it. The ability to correctly detect whether we
896 // are in the bootloader is flaky from a cross-platform standpoint. So by putting it on a wait list
897 // and only connect on the second pass we leave enough time for the board to boot up.
898 qCDebug(LinkManagerLog) << "Waiting for next autoconnect pass" << portInfo.systemLocation() << boardName;
899 _autoconnectPortWaitList[portInfo.systemLocation()] = 1;
900 } else if ((++_autoconnectPortWaitList[portInfo.systemLocation()] * _autoconnectUpdateTimerMSecs) > _autoconnectConnectDelayMSecs) {
901 SerialConfiguration* pSerialConfig = nullptr;
902 _autoconnectPortWaitList.remove(portInfo.systemLocation());
903 switch (boardType) {
905 pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName, portInfo.portName().trimmed()));
906 pSerialConfig->setUsbDirect(true);
907 break;
909 pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName, portInfo.portName().trimmed()));
910 break;
912 pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName, portInfo.portName().trimmed()));
913 break;
915 qCDebug(LinkManagerLog) << "RTK GPS auto-connected" << portInfo.portName().trimmed();
916 _autoConnectRTKPort = portInfo.systemLocation();
917 GPSManager::instance()->gpsRtk()->connectGPS(portInfo.systemLocation(), boardName);
918 break;
919 default:
920 qCWarning(LinkManagerLog) << "Internal error: Unknown board type" << boardType;
921 continue;
922 }
923
924 if (pSerialConfig) {
925 qCDebug(LinkManagerLog) << "New auto-connect port added: " << pSerialConfig->name() << portInfo.systemLocation();
926 pSerialConfig->setBaud((boardType == QGCSerialPortInfo::BoardTypeSiKRadio) ? 57600 : 115200);
927 pSerialConfig->setDynamic(true);
928 pSerialConfig->setPortName(portInfo.systemLocation());
929 pSerialConfig->setAutoConnect(true);
930
931 SharedLinkConfigurationPtr sharedConfig(pSerialConfig);
932 createConnectedLink(sharedConfig);
933 }
934 }
935 }
936 }
937
938 // Check for RTK GPS connection gone
939 if (!_autoConnectRTKPort.isEmpty() && !currentPorts.contains(_autoConnectRTKPort)) {
940 qCDebug(LinkManagerLog) << "RTK GPS disconnected" << _autoConnectRTKPort;
942 _autoConnectRTKPort.clear();
943 }
944}
945
946bool LinkManager::_allowAutoConnectToBoard(QGCSerialPortInfo::BoardType_t boardType) const
947{
948 switch (boardType) {
950 if (_autoConnectSettings->autoConnectPixhawk()->rawValue().toBool()) {
951 return true;
952 }
953 break;
955 if (_autoConnectSettings->autoConnectSiKRadio()->rawValue().toBool()) {
956 return true;
957 }
958 break;
960 if (_autoConnectSettings->autoConnectLibrePilot()->rawValue().toBool()) {
961 return true;
962 }
963 break;
965 if (_autoConnectSettings->autoConnectRTKGPS()->rawValue().toBool() && !GPSManager::instance()->gpsRtk()->connected()) {
966 return true;
967 }
968 break;
969 default:
970 qCWarning(LinkManagerLog) << "Internal error: Unknown board type" << boardType;
971 return false;
972 }
973
974 return false;
975}
976
977bool LinkManager::_portAlreadyConnected(const QString &portName)
978{
979 QMutexLocker locker(&_linksMutex);
980
981 const QString searchPort = portName.trimmed();
982 for (const SharedLinkInterfacePtr &linkInterface : _rgLinks) {
983 const SharedLinkConfigurationPtr linkConfig = linkInterface->linkConfiguration();
984 const SerialConfiguration* const serialConfig = qobject_cast<const SerialConfiguration*>(linkConfig.get());
985 if (serialConfig && (serialConfig->portName() == searchPort)) {
986 return true;
987 }
988 }
989
990 return false;
991}
992
993void LinkManager::_updateSerialPorts()
994{
995 _commPortList.clear();
996 _commPortDisplayList.clear();
997 const QList<QGCSerialPortInfo> portList = QGCSerialPortInfo::availablePorts();
998 for (const QGCSerialPortInfo &info: portList) {
999 const QString port = info.systemLocation().trimmed();
1000 _commPortList += port;
1001 _commPortDisplayList += SerialConfiguration::cleanPortDisplayName(port);
1002 }
1003}
1004
1005QStringList LinkManager::serialPortStrings()
1006{
1007 if (_commPortDisplayList.isEmpty()) {
1008 _updateSerialPorts();
1009 }
1010
1011 return _commPortDisplayList;
1012}
1013
1014QStringList LinkManager::serialPorts()
1015{
1016 if (_commPortList.isEmpty()) {
1017 _updateSerialPorts();
1018 }
1019
1020 return _commPortList;
1021}
1022
1023QStringList LinkManager::serialBaudRates()
1024{
1025 return SerialConfiguration::supportedBaudRates();
1026}
1027
1028bool LinkManager::_isSerialPortConnected()
1029{
1030 QMutexLocker locker(&_linksMutex);
1031
1032 for (const SharedLinkInterfacePtr &link: _rgLinks) {
1033 if (qobject_cast<const SerialLink*>(link.get())) {
1034 return true;
1035 }
1036 }
1037
1038 return false;
1039}
1040
1041#endif // QGC_NO_SERIAL_LINK
std::shared_ptr< LinkConfiguration > SharedLinkConfigurationPtr
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
Q_APPLICATION_STATIC(LinkManager, _linkManagerInstance)
mavlink_status_t * mavlink_get_channel_status(uint8_t chan)
Definition QGCMAVLink.cc:50
#define MAVLINK_COMM_NUM_BUFFERS
Definition MAVLinkLib.h:27
#define qgcApp()
Error error
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Fact *autoConnectLibrePilot READ autoConnectLibrePilot CONSTANT Fact * autoConnectLibrePilot()
Fact *autoConnectPixhawk READ autoConnectPixhawk CONSTANT Fact * autoConnectPixhawk()
Fact *autoConnectUDP READ autoConnectUDP CONSTANT Fact * autoConnectUDP()
Fact *autoConnectSiKRadio READ autoConnectSiKRadio CONSTANT Fact * autoConnectSiKRadio()
Fact *autoConnectNmeaPort READ autoConnectNmeaPort CONSTANT Fact * autoConnectNmeaPort()
Fact *autoConnectRTKGPS READ autoConnectRTKGPS CONSTANT Fact * autoConnectRTKGPS()
Fact *autoConnectNmeaBaud READ autoConnectNmeaBaud CONSTANT Fact * autoConnectNmeaBaud()
Fact *nmeaUdpPort READ nmeaUdpPort CONSTANT Fact * nmeaUdpPort()
Fact *autoConnectZeroConf READ autoConnectZeroConf CONSTANT Fact * autoConnectZeroConf()
GPSRtk * gpsRtk()
Definition GPSManager.h:20
static GPSManager * instance()
Definition GPSManager.cc:23
void disconnectGPS()
Definition GPSRtk.cc:112
void connectGPS(const QString &device, QStringView gps_type)
Definition GPSRtk.cc:50
bool connected() const
Definition GPSRtk.cc:130
Interface holding link specific settings.
void nameChanged(const QString &name)
The link interface defines the interface for all links used to communicate with the ground station ap...
void bytesReceived(LinkInterface *link, const QByteArray &data)
void disconnected()
virtual void _freeMavlinkChannel()
virtual void disconnect()=0
void communicationError(const QString &title, const QString &error)
void bytesSent(LinkInterface *link, const QByteArray &data)
SharedLinkConfigurationPtr linkConfiguration()
Manage communication links The Link Manager organizes the physical Links. It can manage arbitrary lin...
Definition LinkManager.h:35
void mavlinkSupportForwardingEnabledChanged()
void receiveBytes(LinkInterface *link, const QByteArray &data)
void logSentBytes(const LinkInterface *link, const QByteArray &data)
static MAVLinkProtocol * instance()
void resetMetadataForLink(LinkInterface *link)
Reset the counters for all metadata for this link.
Fact *forwardMavlinkHostName READ forwardMavlinkHostName CONSTANT Fact * forwardMavlinkHostName()
Fact *forwardMavlinkAPMSupportHostName READ forwardMavlinkAPMSupportHostName CONSTANT Fact * forwardMavlinkAPMSupportHostName()
bool getBoardInfo(BoardType_t &boardType, QString &name) const
static QList< QGCSerialPortInfo > availablePorts()
Override of QSerialPortInfo::availablePorts.
quint16 productIdentifier() const
QString manufacturer() const
QString portName() const
bool hasVendorIdentifier() const
QString serialNumber() const
QString systemLocation() const
QString description() const
quint16 vendorIdentifier() const
bool hasProductIdentifier() const
Provides functions to access serial ports.
Definition qserialport.h:17
void close() override
bool setBaudRate(qint32 baudRate, Directions directions=AllDirections)
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
QObject * removeOne(const QObject *object) override final
bool isBluetoothAvailable()
Check if Bluetooth is available on this device.