@@ -461,81 +461,6 @@ void LinkManager::_addMAVLinkForwardingLink()
461461 _createDynamicForwardLink (_mavlinkForwardingLinkName, hostName);
462462}
463463
464- #ifdef QGC_ZEROCONF_ENABLED
465- void LinkManager::_addZeroConfAutoConnectLink ()
466- {
467- if (!_autoConnectSettings->autoConnectZeroConf ()->rawValue ().toBool ()) {
468- return ;
469- }
470-
471- static QSharedPointer<QMdnsEngine::Server> server;
472- static QSharedPointer<QMdnsEngine::Browser> browser;
473- server.reset (new QMdnsEngine::Server ());
474- browser.reset (new QMdnsEngine::Browser (server.get (), QMdnsEngine::MdnsBrowseType));
475-
476- const auto checkIfConnectionLinkExist = [this ](LinkConfiguration::LinkType linkType, const QString &linkName) {
477- QMutexLocker locker (&_linksMutex);
478- for (const SharedLinkInterfacePtr &link : std::as_const (_rgLinks)) {
479- const SharedLinkConfigurationPtr linkConfig = link->linkConfiguration ();
480- if (linkConfig && (linkConfig->type () == linkType) && (linkConfig->name () == linkName)) {
481- return true ;
482- }
483- }
484-
485- return false ;
486- };
487-
488- (void ) connect (browser.get (), &QMdnsEngine::Browser::serviceAdded, this , [checkIfConnectionLinkExist, this ](const QMdnsEngine::Service &service) {
489- qCDebug (LinkManagerLog) << " Found Zero-Conf:" << service.type () << service.name () << service.hostname () << service.port () << service.attributes ();
490-
491- if (!service.type ().startsWith (" _mavlink" )) {
492- qCWarning (LinkManagerLog) << " Invalid ZeroConf SericeType" << service.type ();
493- return ;
494- }
495-
496- // Windows doesnt accept trailling dots in mdns
497- // http://www.dns-sd.org/trailingdotsindomainnames.html
498- QString hostname = service.hostname ();
499- if (hostname.endsWith (' .' )) {
500- hostname.chop (1 );
501- }
502-
503- if (service.type ().startsWith (" _mavlink._udp" )) {
504- static const QString udpName = QStringLiteral (" ZeroConf UDP" );
505- if (checkIfConnectionLinkExist (LinkConfiguration::TypeUdp, udpName)) {
506- qCDebug (LinkManagerLog) << " Connection already exist" ;
507- return ;
508- }
509-
510- UDPConfiguration *const link = new UDPConfiguration (udpName);
511- link->addHost (hostname, service.port ());
512- link->setAutoConnect (true );
513- link->setDynamic (true );
514- SharedLinkConfigurationPtr config = addConfiguration (link);
515- if (!createConnectedLink (config)) {
516- qCWarning (LinkManagerLog) << " Failed to create" << udpName;
517- }
518- } else if (service.type ().startsWith (" _mavlink._tcp" )) {
519- static QString tcpName = QStringLiteral (" ZeroConf TCP" );
520- if (checkIfConnectionLinkExist (LinkConfiguration::TypeTcp, tcpName)) {
521- qCDebug (LinkManagerLog) << " Connection already exist" ;
522- return ;
523- }
524-
525- TCPConfiguration *const link = new TCPConfiguration (tcpName);
526- link->setHost (hostname);
527- link->setPort (service.port ());
528- link->setAutoConnect (true );
529- link->setDynamic (true );
530- SharedLinkConfigurationPtr config = addConfiguration (link);
531- if (!createConnectedLink (config)) {
532- qCWarning (LinkManagerLog) << " Failed to create" << tcpName;
533- }
534- }
535- });
536- }
537- #endif
538-
539464void LinkManager::_updateAutoConnectLinks ()
540465{
541466 if (_connectionsSuspended) {
@@ -798,6 +723,97 @@ void LinkManager::_createDynamicForwardLink(const char *linkName, const QString
798723 qCDebug (LinkManagerLog) << " New dynamic MAVLink forwarding port added:" << linkName << " hostname:" << hostName;
799724}
800725
726+ void LinkManager::resetMavlinkSigning ()
727+ {
728+ // Make a copy under mutex protection to avoid holding lock during signing initialization
729+ QList<SharedLinkInterfacePtr> links;
730+ {
731+ QMutexLocker locker (&_linksMutex);
732+ links = _rgLinks;
733+ }
734+
735+ for (const SharedLinkInterfacePtr &sharedLink: links) {
736+ sharedLink->initMavlinkSigning ();
737+ }
738+ }
739+
740+ #ifdef QGC_ZEROCONF_ENABLED
741+
742+ void LinkManager::_addZeroConfAutoConnectLink ()
743+ {
744+ if (!_autoConnectSettings->autoConnectZeroConf ()->rawValue ().toBool ()) {
745+ return ;
746+ }
747+
748+ static QSharedPointer<QMdnsEngine::Server> server;
749+ static QSharedPointer<QMdnsEngine::Browser> browser;
750+ server.reset (new QMdnsEngine::Server ());
751+ browser.reset (new QMdnsEngine::Browser (server.get (), QMdnsEngine::MdnsBrowseType));
752+
753+ const auto checkIfConnectionLinkExist = [this ](LinkConfiguration::LinkType linkType, const QString &linkName) {
754+ QMutexLocker locker (&_linksMutex);
755+ for (const SharedLinkInterfacePtr &link : std::as_const (_rgLinks)) {
756+ const SharedLinkConfigurationPtr linkConfig = link->linkConfiguration ();
757+ if (linkConfig && (linkConfig->type () == linkType) && (linkConfig->name () == linkName)) {
758+ return true ;
759+ }
760+ }
761+
762+ return false ;
763+ };
764+
765+ (void ) connect (browser.get (), &QMdnsEngine::Browser::serviceAdded, this , [checkIfConnectionLinkExist, this ](const QMdnsEngine::Service &service) {
766+ qCDebug (LinkManagerLog) << " Found Zero-Conf:" << service.type () << service.name () << service.hostname () << service.port () << service.attributes ();
767+
768+ if (!service.type ().startsWith (" _mavlink" )) {
769+ qCWarning (LinkManagerLog) << " Invalid ZeroConf SericeType" << service.type ();
770+ return ;
771+ }
772+
773+ // Windows doesnt accept trailling dots in mdns
774+ // http://www.dns-sd.org/trailingdotsindomainnames.html
775+ QString hostname = service.hostname ();
776+ if (hostname.endsWith (' .' )) {
777+ hostname.chop (1 );
778+ }
779+
780+ if (service.type ().startsWith (" _mavlink._udp" )) {
781+ static const QString udpName = QStringLiteral (" ZeroConf UDP" );
782+ if (checkIfConnectionLinkExist (LinkConfiguration::TypeUdp, udpName)) {
783+ qCDebug (LinkManagerLog) << " Connection already exist" ;
784+ return ;
785+ }
786+
787+ UDPConfiguration *const link = new UDPConfiguration (udpName);
788+ link->addHost (hostname, service.port ());
789+ link->setAutoConnect (true );
790+ link->setDynamic (true );
791+ SharedLinkConfigurationPtr config = addConfiguration (link);
792+ if (!createConnectedLink (config)) {
793+ qCWarning (LinkManagerLog) << " Failed to create" << udpName;
794+ }
795+ } else if (service.type ().startsWith (" _mavlink._tcp" )) {
796+ static QString tcpName = QStringLiteral (" ZeroConf TCP" );
797+ if (checkIfConnectionLinkExist (LinkConfiguration::TypeTcp, tcpName)) {
798+ qCDebug (LinkManagerLog) << " Connection already exist" ;
799+ return ;
800+ }
801+
802+ TCPConfiguration *const link = new TCPConfiguration (tcpName);
803+ link->setHost (hostname);
804+ link->setPort (service.port ());
805+ link->setAutoConnect (true );
806+ link->setDynamic (true );
807+ SharedLinkConfigurationPtr config = addConfiguration (link);
808+ if (!createConnectedLink (config)) {
809+ qCWarning (LinkManagerLog) << " Failed to create" << tcpName;
810+ }
811+ }
812+ });
813+ }
814+
815+ #endif // QGC_ZEROCONF_ENABLED
816+
801817bool LinkManager::isLinkUSBDirect (const LinkInterface *link)
802818{
803819#ifndef QGC_NO_SERIAL_LINK
@@ -820,20 +836,6 @@ bool LinkManager::isLinkUSBDirect(const LinkInterface *link)
820836 return false ;
821837}
822838
823- void LinkManager::resetMavlinkSigning ()
824- {
825- // Make a copy under mutex protection to avoid holding lock during signing initialization
826- QList<SharedLinkInterfacePtr> links;
827- {
828- QMutexLocker locker (&_linksMutex);
829- links = _rgLinks;
830- }
831-
832- for (const SharedLinkInterfacePtr &sharedLink: links) {
833- sharedLink->initMavlinkSigning ();
834- }
835- }
836-
837839#ifndef QGC_NO_SERIAL_LINK // Serial Only Functions
838840
839841void LinkManager::_filterCompositePorts (QList<QGCSerialPortInfo> &portList)
0 commit comments