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 "AppMessages.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#include "PositionManager.h"
18#include "UdpIODevice.h"
19
20#ifndef QGC_NO_SERIAL_LINK
21#include "SerialLink.h"
22#include "GPSManager.h"
23#include "GPSRtk.h"
24#endif
25
26#ifdef QT_DEBUG
27#include "MockLink.h"
28#endif
29
30#include <QtCore/QApplicationStatic>
31#include <QtCore/QTimer>
32
33QGC_LOGGING_CATEGORY(LinkManagerLog, "Comms.LinkManager")
34QGC_LOGGING_CATEGORY(LinkManagerVerboseLog, "Comms.LinkManager:verbose")
35
36Q_APPLICATION_STATIC(LinkManager, _linkManagerInstance);
37
38LinkManager::LinkManager(QObject *parent)
39 : QObject(parent)
40 , _portListTimer(new QTimer(this))
41 , _qmlConfigurations(new QmlObjectListModel(this))
42 , _nmeaSocket(new UdpIODevice(this))
43{
44 qCDebug(LinkManagerLog) << this;
45
46 (void) qRegisterMetaType<QAbstractSocket::SocketError>("QAbstractSocket::SocketError");
47 (void) qRegisterMetaType<LinkInterface*>("LinkInterface*");
48#ifndef QGC_NO_SERIAL_LINK
49 (void) qRegisterMetaType<QGCSerialPortInfo>("QGCSerialPortInfo");
50#endif
51}
52
54{
55 qCDebug(LinkManagerLog) << this;
56}
57
59{
60 return _linkManagerInstance();
61}
62
64{
65 _autoConnectSettings = SettingsManager::instance()->autoConnectSettings();
66
67 if (!QGC::runningUnitTests()) {
68 (void) connect(_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks);
69 _portListTimer->start(_autoconnectUpdateTimerMSecs); // timeout must be long enough to get past bootloader on second pass
70 }
71}
72
73QList<SharedLinkInterfacePtr> LinkManager::links()
74{
75 QMutexLocker locker(&_linksMutex);
76 return _rgLinks;
77}
78
79QmlObjectListModel *LinkManager::_qmlLinkConfigurations()
80{
81 return _qmlConfigurations;
82}
83
85{
86 for (SharedLinkConfigurationPtr &sharedConfig : _rgLinkConfigs) {
87 if (sharedConfig.get() == config) {
88 createConnectedLink(sharedConfig);
89 }
90 }
91}
92
94{
95 SharedLinkInterfacePtr link = nullptr;
96
97 switch(config->type()) {
98#ifndef QGC_NO_SERIAL_LINK
100 link = std::make_shared<SerialLink>(config);
101 break;
102#endif
104 link = std::make_shared<UDPLink>(config);
105 break;
107 link = std::make_shared<TCPLink>(config);
108 break;
110 link = std::make_shared<BluetoothLink>(config);
111 break;
113 link = std::make_shared<LogReplayLink>(config);
114 break;
115#ifdef QT_DEBUG
116 case LinkConfiguration::TypeMock:
117 link = std::make_shared<MockLink>(config);
118 break;
119#endif
121 default:
122 break;
123 }
124
125 if (!link) {
126 return false;
127 }
128
129 if (!link->_allocateMavlinkChannel()) {
130 qCWarning(LinkManagerLog) << "Link failed to setup mavlink channels";
131 return false;
132 }
133
134 // Set up signal connections before adding to list, so link is fully initialized
135 (void) connect(link.get(), &LinkInterface::communicationError, this, &LinkManager::_communicationError);
138 (void) connect(link.get(), &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);
139
141
142 // Try to connect before adding to active links list
143 if (!link->_connect()) {
144 (void) disconnect(link.get(), &LinkInterface::communicationError, this, &LinkManager::_communicationError);
147 (void) disconnect(link.get(), &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);
148 link->_freeMavlinkChannel();
149 config->setLink(nullptr);
150 return false;
151 }
152
153 {
154 QMutexLocker locker(&_linksMutex);
155 _rgLinks.append(link);
156 }
157 config->setLink(link);
158
159 return true;
160}
161
162void LinkManager::_communicationError(const QString &title, const QString &error)
163{
165}
166
168{
169 QMutexLocker locker(&_linksMutex);
170
171 for (const SharedLinkInterfacePtr &link : _rgLinks) {
172 const SharedLinkConfigurationPtr linkConfig = link->linkConfiguration();
173 if (linkConfig && (linkConfig->type() == LinkConfiguration::TypeUdp) && (linkConfig->name() == _mavlinkForwardingLinkName)) {
174 return link;
175 }
176 }
177
178 return nullptr;
179}
180
182{
183 QMutexLocker locker(&_linksMutex);
184
185 for (const SharedLinkInterfacePtr &link : _rgLinks) {
186 const SharedLinkConfigurationPtr linkConfig = link->linkConfiguration();
187 if (linkConfig && (linkConfig->type() == LinkConfiguration::TypeUdp) && (linkConfig->name() == _mavlinkForwardingSupportLinkName)) {
188 return link;
189 }
190 }
191
192 return nullptr;
193}
194
196{
197 QList<SharedLinkInterfacePtr> links;
198 {
199 QMutexLocker locker(&_linksMutex);
200 links = _rgLinks;
201 }
202
203 for (const SharedLinkInterfacePtr &sharedLink: links) {
204 sharedLink->disconnect();
205 }
206}
207
208void LinkManager::_linkDisconnected()
209{
210 LinkInterface* const link = qobject_cast<LinkInterface*>(sender());
211
212 if (!link) {
213 return;
214 }
215
216 SharedLinkInterfacePtr linkToCleanup;
218 {
219 QMutexLocker locker(&_linksMutex);
220
221 for (auto it = _rgLinks.begin(); it != _rgLinks.end(); ++it) {
222 if (it->get() == link) {
223 config = it->get()->linkConfiguration();
224 const QString linkName = config ? config->name() : QStringLiteral("<null config>");
225 qCDebug(LinkManagerLog) << linkName << "use_count:" << it->use_count();
226 linkToCleanup = *it;
227 (void) _rgLinks.erase(it);
228 break;
229 }
230 }
231 }
232
233 if (!linkToCleanup) {
234 qCDebug(LinkManagerLog) << "link already removed";
235 return;
236 }
237
238 if (config) {
239 config->setLink(nullptr);
240 }
241
242 (void) disconnect(link, &LinkInterface::communicationError, this, &LinkManager::_communicationError);
245 (void) disconnect(link, &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);
246
247 link->_freeMavlinkChannel();
248}
249
251{
252 QMutexLocker locker(&_linksMutex);
253
254 for (const SharedLinkInterfacePtr &sharedLink: _rgLinks) {
255 if (sharedLink.get() == link) {
256 return sharedLink;
257 }
258 }
259
260 // Link not found - this is normal during disconnect when queued signals are still processing.
261 // Callers should check for nullptr return value.
262 qCDebug(LinkManagerLog) << "link not in list (likely disconnected)";
263 return SharedLinkInterfacePtr(nullptr);
264}
265
266bool LinkManager::_connectionsSuspendedMsg() const
267{
268 if (_connectionsSuspended) {
269 QGC::showAppMessage(tr("Connect not allowed: %1").arg(_connectionsSuspendedReason));
270 return true;
271 }
272
273 return false;
274}
275
277{
278 QSettings settings;
279 settings.remove(LinkConfiguration::settingsRoot());
280
281 int trueCount = 0;
282 for (int i = 0; i < _rgLinkConfigs.count(); i++) {
283 SharedLinkConfigurationPtr linkConfig = _rgLinkConfigs[i];
284 if (!linkConfig) {
285 qCWarning(LinkManagerLog) << "Internal error for link configuration in LinkManager";
286 continue;
287 }
288
289 if (linkConfig->isDynamic()) {
290 continue;
291 }
292
293 const QString root = LinkConfiguration::settingsRoot() + QStringLiteral("/Link%1").arg(trueCount++);
294 settings.setValue(root + "/name", linkConfig->name());
295 settings.setValue(root + "/type", linkConfig->type());
296 settings.setValue(root + "/auto", linkConfig->isAutoConnect());
297 settings.setValue(root + "/high_latency", linkConfig->isHighLatency());
298 linkConfig->saveSettings(settings, root);
299 }
300
301 const QString root = QString(LinkConfiguration::settingsRoot());
302 settings.setValue(root + "/count", trueCount);
303}
304
306{
307 QSettings settings;
308 // Is the group even there?
309 if (settings.contains(LinkConfiguration::settingsRoot() + "/count")) {
310 // Find out how many configurations we have
311 const int count = settings.value(LinkConfiguration::settingsRoot() + "/count").toInt();
312 for (int i = 0; i < count; i++) {
313 const QString root = LinkConfiguration::settingsRoot() + QStringLiteral("/Link%1").arg(i);
314 if (!settings.contains(root + "/type")) {
315 qCWarning(LinkManagerLog) << "Link Configuration" << root << "has no type.";
316 continue;
317 }
318
319 LinkConfiguration::LinkType type = static_cast<LinkConfiguration::LinkType>(settings.value(root + "/type").toInt());
320 if (type >= LinkConfiguration::TypeLast) {
321 qCWarning(LinkManagerLog) << "Link Configuration" << root << "an invalid type:" << type;
322 continue;
323 }
324
325 if (!settings.contains(root + "/name")) {
326 qCWarning(LinkManagerLog) << "Link Configuration" << root << "has no name.";
327 continue;
328 }
329
330 const QString name = settings.value(root + "/name").toString();
331 if (name.isEmpty()) {
332 qCWarning(LinkManagerLog) << "Link Configuration" << root << "has an empty name.";
333 continue;
334 }
335
336 LinkConfiguration* link = nullptr;
337 switch(type) {
338#ifndef QGC_NO_SERIAL_LINK
340 link = new SerialConfiguration(name);
341 break;
342#endif
344 link = new UDPConfiguration(name);
345 break;
347 link = new TCPConfiguration(name);
348 break;
350 link = new BluetoothConfiguration(name);
351 break;
353 link = new LogReplayConfiguration(name);
354 break;
355#ifdef QT_DEBUG
356 case LinkConfiguration::TypeMock:
357 link = new MockConfiguration(name);
358 break;
359#endif
361 default:
362 break;
363 }
364
365 if (link) {
366 const bool autoConnect = settings.value(root + "/auto").toBool();
367 link->setAutoConnect(autoConnect);
368 const bool highLatency = settings.value(root + "/high_latency").toBool();
369 link->setHighLatency(highLatency);
370 link->loadSettings(settings, root);
371 addConfiguration(link);
372 }
373 }
374 }
375
376 // Enable automatic Serial PX4/3DR Radio hunting
377 _configurationsLoaded = true;
378}
379
380void LinkManager::_addUDPAutoConnectLink()
381{
382 if (!_autoConnectSettings->autoConnectUDP()->rawValue().toBool()) {
383 return;
384 }
385
386 {
387 QMutexLocker locker(&_linksMutex);
388 for (const SharedLinkInterfacePtr &link : _rgLinks) {
389 const SharedLinkConfigurationPtr linkConfig = link->linkConfiguration();
390 if (linkConfig && (linkConfig->type() == LinkConfiguration::TypeUdp) && (linkConfig->name() == _defaultUDPLinkName)) {
391 return;
392 }
393 }
394 }
395
396 qCDebug(LinkManagerLog) << "New auto-connect UDP port added";
397 UDPConfiguration* const udpConfig = new UDPConfiguration(_defaultUDPLinkName);
398 udpConfig->setDynamic(true);
399 udpConfig->setAutoConnect(true);
401 createConnectedLink(config);
402}
403
404void LinkManager::_addMAVLinkForwardingLink()
405{
406 if (!SettingsManager::instance()->mavlinkSettings()->forwardMavlink()->rawValue().toBool()) {
407 return;
408 }
409
410 {
411 QMutexLocker locker(&_linksMutex);
412 for (const SharedLinkInterfacePtr &link : _rgLinks) {
413 const SharedLinkConfigurationPtr linkConfig = link->linkConfiguration();
414 if (linkConfig && (linkConfig->type() == LinkConfiguration::TypeUdp) && (linkConfig->name() == _mavlinkForwardingLinkName)) {
415 // TODO: should we check if the host/port matches the mavlinkForwardHostName setting and update if it does not match?
416 return;
417 }
418 }
419 }
420
421 const QString hostName = SettingsManager::instance()->mavlinkSettings()->forwardMavlinkHostName()->rawValue().toString();
422 _createDynamicForwardLink(_mavlinkForwardingLinkName, hostName);
423}
424
425void LinkManager::_updateAutoConnectLinks()
426{
427 if (_connectionsSuspended) {
428 return;
429 }
430
431 _addUDPAutoConnectLink();
432 _addMAVLinkForwardingLink();
433
434 // check to see if nmea gps is configured for UDP input, if so, set it up to connect
435 if (_autoConnectSettings->autoConnectNmeaPort()->cookedValueString() == "UDP Port") {
436 if ((_nmeaSocket->localPort() != _autoConnectSettings->nmeaUdpPort()->rawValue().toUInt()) || (_nmeaSocket->state() != UdpIODevice::BoundState)) {
437 qCDebug(LinkManagerLog) << "Changing port for UDP NMEA stream";
438 _nmeaSocket->close();
439 _nmeaSocket->bind(QHostAddress::AnyIPv4, _autoConnectSettings->nmeaUdpPort()->rawValue().toUInt());
441 }
442#ifndef QGC_NO_SERIAL_LINK
443 if (_nmeaPort) {
444 _nmeaPort->close();
445 delete _nmeaPort;
446 _nmeaPort = nullptr;
447 _nmeaDeviceName = "";
448 }
449#endif
450 } else {
451 _nmeaSocket->close();
452 }
453
454#ifndef QGC_NO_SERIAL_LINK
455 _addSerialAutoConnectLink();
456#endif
457}
458
460{
461 setConnectionsSuspended(tr("Shutdown"));
463
464 // Wait for all the vehicles to go away to ensure an orderly shutdown and deletion of all objects
465 while (MultiVehicleManager::instance()->vehicles()->count()) {
466 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
467 }
468}
469
471{
472 //-- Must follow same order as enum LinkType in LinkConfiguration.h
473 static QStringList list;
474 if (!list.isEmpty()) {
475 return list;
476 }
477
478#ifndef QGC_NO_SERIAL_LINK
479 list += tr("Serial");
480#endif
481 list += tr("UDP");
482 list += tr("TCP");
483 list += tr("Bluetooth");
484#ifdef QT_DEBUG
485 list += tr("Mock Link");
486#endif
487 list += tr("Log Replay");
488
489 if (list.size() != static_cast<int>(LinkConfiguration::TypeLast)) {
490 qCWarning(LinkManagerLog) << "Internal error";
491 }
492
493 return list;
494}
495
497{
498 if (!config || !editedConfig) {
499 qCWarning(LinkManagerLog) << "Internal error";
500 return;
501 }
502
503 config->copyFrom(editedConfig);
505 emit config->nameChanged(config->name());
506 // Discard temporary duplicate
507 delete editedConfig;
508}
509
511{
512 if (!config) {
513 qCWarning(LinkManagerLog) << "Internal error";
514 return;
515 }
516
517 addConfiguration(config);
519}
520
522{
523#ifndef QGC_NO_SERIAL_LINK
525 _updateSerialPorts();
526 }
527#endif
528
529 return LinkConfiguration::createSettings(type, name);
530}
531
533{
534 if (!config) {
535 qCWarning(LinkManagerLog) << "Internal error";
536 return nullptr;
537 }
538
539#ifndef QGC_NO_SERIAL_LINK
540 if (config->type() == LinkConfiguration::TypeSerial) {
541 _updateSerialPorts();
542 }
543#endif
544
546}
547
549{
550 if (!config) {
551 qCWarning(LinkManagerLog) << "Internal error";
552 return;
553 }
554
555 LinkInterface* const link = config->link();
556 if (link) {
557 link->disconnect();
558 }
559
560 _removeConfiguration(config);
562}
563
565{
566 const QString hostName = SettingsManager::instance()->mavlinkSettings()->forwardMavlinkAPMSupportHostName()->rawValue().toString();
567 _createDynamicForwardLink(_mavlinkForwardingSupportLinkName, hostName);
568 _mavlinkSupportForwardingEnabled = true;
570}
571
572void LinkManager::_removeConfiguration(const LinkConfiguration *config)
573{
574 (void) _qmlConfigurations->removeOne(config);
575
576 for (auto it = _rgLinkConfigs.begin(); it != _rgLinkConfigs.end(); ++it) {
577 if (it->get() == config) {
578 (void) _rgLinkConfigs.erase(it);
579 return;
580 }
581 }
582
583 qCWarning(LinkManagerLog) << "called with unknown config";
584}
585
590
592{
593 QMutexLocker locker(&_linksMutex);
594
595 for (const SharedLinkInterfacePtr &sharedLink : _rgLinks) {
596 if (sharedLink.get() == link) {
597 return true;
598 }
599 }
600
601 return false;
602}
603
605{
606 (void) _qmlConfigurations->append(config);
607 (void) _rgLinkConfigs.append(SharedLinkConfigurationPtr(config));
608
609 return _rgLinkConfigs.last();
610}
611
613{
614 for (SharedLinkConfigurationPtr &sharedConfig : _rgLinkConfigs) {
615 if (sharedConfig->isAutoConnect()) {
616 createConnectedLink(sharedConfig);
617 }
618 }
619}
620
622{
623 for (uint8_t mavlinkChannel = 0; mavlinkChannel < MAVLINK_COMM_NUM_BUFFERS; mavlinkChannel++) {
624 if (_mavlinkChannelsUsedBitMask & (1 << mavlinkChannel)) {
625 continue;
626 }
627
628 mavlink_reset_channel_status(mavlinkChannel);
629 mavlink_status_t* const mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);
630 mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
631 _mavlinkChannelsUsedBitMask |= (1 << mavlinkChannel);
632 qCDebug(LinkManagerLog) << "allocateMavlinkChannel" << mavlinkChannel;
633 return mavlinkChannel;
634 }
635
636 qWarning(LinkManagerLog) << "allocateMavlinkChannel: all channels reserved!";
637 return invalidMavlinkChannel();
638}
639
641{
642 qCDebug(LinkManagerLog) << "freeMavlinkChannel" << channel;
643
644 if (invalidMavlinkChannel() == channel) {
645 return;
646 }
647
648 _mavlinkChannelsUsedBitMask &= ~(1 << channel);
649}
650
652{
653 LogReplayConfiguration* const linkConfig = new LogReplayConfiguration(tr("Log Replay"));
654 linkConfig->setLogFilename(logFile);
655 linkConfig->setName(linkConfig->logFilenameShort());
656
657 SharedLinkConfigurationPtr sharedConfig = addConfiguration(linkConfig);
658 if (createConnectedLink(sharedConfig)) {
659 return qobject_cast<LogReplayLink*>(sharedConfig->link());
660 }
661
662 return nullptr;
663}
664
665void LinkManager::_createDynamicForwardLink(const char *linkName, const QString &hostName)
666{
667 UDPConfiguration* const udpConfig = new UDPConfiguration(linkName);
668
669 udpConfig->setDynamic(true);
670 udpConfig->setForwarding(true);
671 udpConfig->addHost(hostName);
672
674 createConnectedLink(config);
675
676 qCDebug(LinkManagerLog) << "New dynamic MAVLink forwarding port added:" << linkName << " hostname:" << hostName;
677}
678
679bool LinkManager::isLinkUSBDirect([[maybe_unused]] const LinkInterface *link)
680{
681#ifndef QGC_NO_SERIAL_LINK
682 const SerialLink* const serialLink = qobject_cast<const SerialLink*>(link);
683 if (!serialLink) {
684 return false;
685 }
686
687 const SharedLinkConfigurationPtr config = serialLink->linkConfiguration();
688 if (!config) {
689 return false;
690 }
691
692 const SerialConfiguration* const serialConfig = qobject_cast<const SerialConfiguration*>(config.get());
693 if (serialConfig && serialConfig->usbDirect()) {
694 return link;
695 }
696#endif
697
698 return false;
699}
700
701#ifndef QGC_NO_SERIAL_LINK // Serial Only Functions
702
703void LinkManager::_filterCompositePorts(QList<QGCSerialPortInfo> &portList)
704{
705 typedef QPair<quint16, quint16> VidPidPair_t;
706
707 QMap<VidPidPair_t, QStringList> seenSerialNumbers;
708
709 for (auto it = portList.begin(); it != portList.end();) {
710 const QGCSerialPortInfo &portInfo = *it;
711 if (portInfo.hasVendorIdentifier() && portInfo.hasProductIdentifier() && !portInfo.serialNumber().isEmpty() && portInfo.serialNumber() != "0") {
712 VidPidPair_t vidPid(portInfo.vendorIdentifier(), portInfo.productIdentifier());
713 if (seenSerialNumbers.contains(vidPid) && seenSerialNumbers[vidPid].contains(portInfo.serialNumber())) {
714 // 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.
715 // However internal NMEA devices can present like this, so dont skip anything with NMEA in description
716 if(!portInfo.description().contains("NMEA")) {
717 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());
718 it = portList.erase(it);
719 continue;
720 }
721 }
722 seenSerialNumbers[vidPid].append(portInfo.serialNumber());
723 }
724 it++;
725 }
726}
727
728void LinkManager::_addSerialAutoConnectLink()
729{
730 QList<QGCSerialPortInfo> portList;
731#ifdef Q_OS_ANDROID
732 // Android builds only support a single serial connection. Repeatedly calling availablePorts after that one serial
733 // port is connected leaks file handles due to a bug somewhere in android serial code. In order to work around that
734 // bug after we connect the first serial port we stop probing for additional ports.
735 if (!_isSerialPortConnected()) {
737 }
738#else
740#endif
741
742 _filterCompositePorts(portList);
743
744 QStringList currentPorts;
745 for (const QGCSerialPortInfo &portInfo: portList) {
746 qCDebug(LinkManagerVerboseLog) << "-----------------------------------------------------";
747 qCDebug(LinkManagerVerboseLog) << "portName: " << portInfo.portName();
748 qCDebug(LinkManagerVerboseLog) << "systemLocation: " << portInfo.systemLocation();
749 qCDebug(LinkManagerVerboseLog) << "description: " << portInfo.description();
750 qCDebug(LinkManagerVerboseLog) << "manufacturer: " << portInfo.manufacturer();
751 qCDebug(LinkManagerVerboseLog) << "serialNumber: " << portInfo.serialNumber();
752 qCDebug(LinkManagerVerboseLog) << "vendorIdentifier: " << portInfo.vendorIdentifier();
753 qCDebug(LinkManagerVerboseLog) << "productIdentifier: " << portInfo.productIdentifier();
754
755 currentPorts << portInfo.systemLocation();
756
758 QString boardName;
759
760 // check to see if nmea gps is configured for current Serial port, if so, set it up to connect
761 if (portInfo.systemLocation().trimmed() == _autoConnectSettings->autoConnectNmeaPort()->cookedValueString()) {
762 if (portInfo.systemLocation().trimmed() != _nmeaDeviceName) {
763 _nmeaDeviceName = portInfo.systemLocation().trimmed();
764 qCDebug(LinkManagerLog) << "Configuring nmea port" << _nmeaDeviceName;
765 QSerialPort* newPort = new QSerialPort(portInfo, this);
766 _nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt();
767 newPort->setBaudRate(static_cast<qint32>(_nmeaBaud));
768 qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud;
769 // This will stop polling old device if previously set
771 if (_nmeaPort) {
772 delete _nmeaPort;
773 }
774 _nmeaPort = newPort;
775 } else if (_autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt() != _nmeaBaud) {
776 _nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt();
777 _nmeaPort->setBaudRate(static_cast<qint32>(_nmeaBaud));
778 qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud;
779 }
780 } else if (portInfo.getBoardInfo(boardType, boardName)) {
781 // Should we be auto-connecting to this board type?
782 if (!_allowAutoConnectToBoard(boardType)) {
783 continue;
784 }
785
786 if (portInfo.isBootloader()) {
787 // Don't connect to bootloader
788 qCDebug(LinkManagerLog) << "Waiting for bootloader to finish" << portInfo.systemLocation();
789 continue;
790 }
791 if (_portAlreadyConnected(portInfo.systemLocation()) || (_autoConnectRTKPort == portInfo.systemLocation())) {
792 qCDebug(LinkManagerVerboseLog) << "Skipping existing autoconnect" << portInfo.systemLocation();
793 } else if (!_autoconnectPortWaitList.contains(portInfo.systemLocation())) {
794 // We don't connect to the port the first time we see it. The ability to correctly detect whether we
795 // are in the bootloader is flaky from a cross-platform standpoint. So by putting it on a wait list
796 // and only connect on the second pass we leave enough time for the board to boot up.
797 qCDebug(LinkManagerLog) << "Waiting for next autoconnect pass" << portInfo.systemLocation() << boardName;
798 _autoconnectPortWaitList[portInfo.systemLocation()] = 1;
799 } else if ((++_autoconnectPortWaitList[portInfo.systemLocation()] * _autoconnectUpdateTimerMSecs) > _autoconnectConnectDelayMSecs) {
800 SerialConfiguration* pSerialConfig = nullptr;
801 _autoconnectPortWaitList.remove(portInfo.systemLocation());
802 switch (boardType) {
804 pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName, portInfo.portName().trimmed()));
805 pSerialConfig->setUsbDirect(true);
806 break;
808 pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName, portInfo.portName().trimmed()));
809 break;
811 pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName, portInfo.portName().trimmed()));
812 break;
814 qCDebug(LinkManagerLog) << "RTK GPS auto-connected" << portInfo.portName().trimmed();
815 _autoConnectRTKPort = portInfo.systemLocation();
816 GPSManager::instance()->gpsRtk()->connectGPS(portInfo.systemLocation(), boardName);
817 break;
818 default:
819 qCWarning(LinkManagerLog) << "Internal error: Unknown board type" << boardType;
820 continue;
821 }
822
823 if (pSerialConfig) {
824 qCDebug(LinkManagerLog) << "New auto-connect port added: " << pSerialConfig->name() << portInfo.systemLocation();
825 pSerialConfig->setBaud((boardType == QGCSerialPortInfo::BoardTypeSiKRadio) ? 57600 : 115200);
826 pSerialConfig->setDynamic(true);
827 pSerialConfig->setPortName(portInfo.systemLocation());
828 pSerialConfig->setAutoConnect(true);
829
830 SharedLinkConfigurationPtr sharedConfig(pSerialConfig);
831 createConnectedLink(sharedConfig);
832 }
833 }
834 }
835 }
836
837 // Check for RTK GPS connection gone
838 if (!_autoConnectRTKPort.isEmpty() && !currentPorts.contains(_autoConnectRTKPort)) {
839 qCDebug(LinkManagerLog) << "RTK GPS disconnected" << _autoConnectRTKPort;
841 _autoConnectRTKPort.clear();
842 }
843}
844
845bool LinkManager::_allowAutoConnectToBoard(QGCSerialPortInfo::BoardType_t boardType) const
846{
847 switch (boardType) {
849 if (_autoConnectSettings->autoConnectPixhawk()->rawValue().toBool()) {
850 return true;
851 }
852 break;
854 if (_autoConnectSettings->autoConnectSiKRadio()->rawValue().toBool()) {
855 return true;
856 }
857 break;
859 if (_autoConnectSettings->autoConnectLibrePilot()->rawValue().toBool()) {
860 return true;
861 }
862 break;
864 if (_autoConnectSettings->autoConnectRTKGPS()->rawValue().toBool() && !GPSManager::instance()->gpsRtk()->connected()) {
865 return true;
866 }
867 break;
868 default:
869 qCWarning(LinkManagerLog) << "Internal error: Unknown board type" << boardType;
870 return false;
871 }
872
873 return false;
874}
875
876bool LinkManager::_portAlreadyConnected(const QString &portName)
877{
878 QMutexLocker locker(&_linksMutex);
879
880 const QString searchPort = portName.trimmed();
881 for (const SharedLinkInterfacePtr &linkInterface : _rgLinks) {
882 const SharedLinkConfigurationPtr linkConfig = linkInterface->linkConfiguration();
883 const SerialConfiguration* const serialConfig = qobject_cast<const SerialConfiguration*>(linkConfig.get());
884 if (serialConfig && (serialConfig->portName() == searchPort)) {
885 return true;
886 }
887 }
888
889 return false;
890}
891
892void LinkManager::_updateSerialPorts()
893{
894 _commPortList.clear();
895 _commPortDisplayList.clear();
896 const QList<QGCSerialPortInfo> portList = QGCSerialPortInfo::availablePorts();
897 for (const QGCSerialPortInfo &info: portList) {
898 const QString port = info.systemLocation().trimmed();
899 _commPortList += port;
900 _commPortDisplayList += SerialConfiguration::cleanPortDisplayName(port);
901 }
902}
903
905{
906 if (_commPortDisplayList.isEmpty()) {
907 _updateSerialPorts();
908 }
909
910 return _commPortDisplayList;
911}
912
914{
915 if (_commPortList.isEmpty()) {
916 _updateSerialPorts();
917 }
918
919 return _commPortList;
920}
921
926
927bool LinkManager::_isSerialPortConnected()
928{
929 QMutexLocker locker(&_linksMutex);
930
931 for (const SharedLinkInterfacePtr &link: _rgLinks) {
932 if (qobject_cast<const SerialLink*>(link.get())) {
933 return true;
934 }
935 }
936
937 return false;
938}
939
940#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:53
#define MAVLINK_COMM_NUM_BUFFERS
Error error
#define QGC_LOGGING_CATEGORY(name, categoryStr)
GPSRtk * gpsRtk()
Definition GPSManager.h:17
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.
@ TypeSerial
Serial Link.
@ TypeBluetooth
Bluetooth Link.
virtual void loadSettings(QSettings &settings, const QString &root)=0
virtual LinkType type() const =0
static LinkConfiguration * duplicateSettings(const LinkConfiguration *source)
virtual void copyFrom(const LinkConfiguration *source)
void setDynamic(bool dynamic=true)
Set if this is this a dynamic configuration. (decided at runtime)
void setHighLatency(bool hl=false)
Set if this is this an High Latency configuration.
static LinkConfiguration * createSettings(int type, const QString &name)
void setForwarding(bool forwarding=true)
Set if this is this a forwarding link configuration. (decided at runtime)
static QString settingsRoot()
LinkInterface * link() const
void nameChanged(const QString &name)
void setName(const QString &name)
QString name() const
virtual void setAutoConnect(bool autoc=true)
Set if this is this an Auto Connect configuration.
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 Q_INVOKABLE 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:32
Q_INVOKABLE void createConnectedLink(const LinkConfiguration *config)
This should only be used by Qml code.
SharedLinkInterfacePtr sharedLinkInterfacePointerForLink(const LinkInterface *link)
QStringList serialPorts()
Q_INVOKABLE void endConfigurationEditing(LinkConfiguration *config, LinkConfiguration *editedConfig)
SharedLinkConfigurationPtr addConfiguration(LinkConfiguration *config)
QStringList linkTypeStrings() const
void loadLinkConfigurationList()
static bool isLinkUSBDirect(const LinkInterface *link)
uint8_t allocateMavlinkChannel()
Q_INVOKABLE void createMavlinkForwardingSupportLink()
Q_INVOKABLE LinkConfiguration * createConfiguration(int type, const QString &name)
Create/Edit Link Configuration.
void startAutoConnectedLinks()
Q_INVOKABLE void endCreateConfiguration(LinkConfiguration *config)
Q_INVOKABLE void shutdown()
Called to signal app shutdown. Disconnects all links while turning off auto-connect.
static LinkManager * instance()
void freeMavlinkChannel(uint8_t channel)
Q_INVOKABLE void removeConfiguration(LinkConfiguration *config)
QList< SharedLinkInterfacePtr > links()
static constexpr uint8_t invalidMavlinkChannel()
void setConnectionsSuspended(const QString &reason)
Definition LinkManager.h:74
void disconnectAll()
Q_INVOKABLE LogReplayLink * startLogReplay(const QString &logFile)
QStringList serialPortStrings()
static QStringList serialBaudRates()
SharedLinkInterfacePtr mavlinkForwardingSupportLink()
Returns pointer to the mavlink support forwarding link, or nullptr if it does not exist.
Q_INVOKABLE LinkConfiguration * startConfigurationEditing(LinkConfiguration *config)
bool containsLink(const LinkInterface *link)
SharedLinkInterfacePtr mavlinkForwardingLink()
Returns pointer to the mavlink forwarding link, or nullptr if it does not exist.
static bool isBluetoothAvailable()
void saveLinkConfigurationList()
void mavlinkSupportForwardingEnabledChanged()
QString logFilenameShort() const
void setLogFilename(const QString &logFilename)
void receiveBytes(LinkInterface *link, const QByteArray &data)
void logSentBytes(const LinkInterface *link, const QByteArray &data)
static MAVLinkProtocol * instance()
void resetMetadataForLink(LinkInterface *link)
static MultiVehicleManager * instance()
static QGCPositionManager * instance()
void setNmeaSourceDevice(QIODevice *device)
QGC's version of Qt QSerialPortInfo. It provides additional information about board types that QGC ca...
bool getBoardInfo(BoardType_t &boardType, QString &name) const
static QList< QGCSerialPortInfo > availablePorts()
Override of QSerialPortInfo::availablePorts.
quint16 productIdentifier() const
Returns the 16-bit product number for the serial port, if available; otherwise returns zero.
QString manufacturer() const
Returns the manufacturer string of the serial port, if available; otherwise returns an empty string.
QString portName() const
Returns the name of the serial port.
bool hasVendorIdentifier() const
Returns true if there is a valid 16-bit vendor number present; otherwise returns false.
QString serialNumber() const
QString systemLocation() const
Returns the system location of the serial port.
QString description() const
Returns the description string of the serial port, if available; otherwise returns an empty string.
quint16 vendorIdentifier() const
Returns the 16-bit vendor number for the serial port, if available; otherwise returns zero.
bool hasProductIdentifier() const
Returns true if there is a valid 16-bit product number present; otherwise returns false.
Provides functions to access serial ports.
Definition qserialport.h:17
void close() override
\reimp
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
void setBaud(qint32 baud)
Definition SerialLink.h:46
bool usbDirect() const
Definition SerialLink.h:66
static QStringList supportedBaudRates()
QString portName() const
Definition SerialLink.h:60
void setUsbDirect(bool usbDirect)
Definition SerialLink.h:67
static QString cleanPortDisplayName(const QString &name)
void setPortName(const QString &name)
Definition SerialLink.cc:36
AutoConnectSettings * autoConnectSettings() const
static SettingsManager * instance()
MavlinkSettings * mavlinkSettings() const
void setAutoConnect(bool autoc=true) override
Set if this is this an Auto Connect configuration.
Definition UDPLink.cc:55
Q_INVOKABLE void addHost(const QString &host)
Definition UDPLink.cc:132
UdpIODevice provides a QIODevice interface over a QUdpSocket in server mode.
Definition UdpIODevice.h:11
bool isBluetoothAvailable()
Check if Bluetooth is available on this device.
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