Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
182 changes: 92 additions & 90 deletions src/Comms/LinkManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -410,80 +410,6 @@ void LinkManager::_addMAVLinkForwardingLink()
_createDynamicForwardLink(_mavlinkForwardingLinkName, hostName);
}

#ifdef QGC_ZEROCONF_ENABLED
void LinkManager::_addZeroConfAutoConnectLink()
{
if (!_autoConnectSettings->autoConnectZeroConf()->rawValue().toBool()) {
return;
}

static QSharedPointer<QMdnsEngine::Server> server;
static QSharedPointer<QMdnsEngine::Browser> browser;
server.reset(new QMdnsEngine::Server());
browser.reset(new QMdnsEngine::Browser(server.get(), QMdnsEngine::MdnsBrowseType));

const auto checkIfConnectionLinkExist = [this](LinkConfiguration::LinkType linkType, const QString &linkName) {
for (const SharedLinkInterfacePtr &link : std::as_const(_rgLinks)) {
const SharedLinkConfigurationPtr linkConfig = link->linkConfiguration();
if ((linkConfig->type() == linkType) && (linkConfig->name() == linkName)) {
return true;
}
}

return false;
};

(void) connect(browser.get(), &QMdnsEngine::Browser::serviceAdded, this, [checkIfConnectionLinkExist, this](const QMdnsEngine::Service &service) {
qCDebug(LinkManagerLog) << "Found Zero-Conf:" << service.type() << service.name() << service.hostname() << service.port() << service.attributes();

if (!service.type().startsWith("_mavlink")) {
qCWarning(LinkManagerLog) << "Invalid ZeroConf SericeType" << service.type();
return;
}

// Windows doesnt accept trailling dots in mdns
// http://www.dns-sd.org/trailingdotsindomainnames.html
QString hostname = service.hostname();
if (hostname.endsWith('.')) {
hostname.chop(1);
}

if (service.type().startsWith("_mavlink._udp")) {
static const QString udpName = QStringLiteral("ZeroConf UDP");
if (checkIfConnectionLinkExist(LinkConfiguration::TypeUdp, udpName)) {
qCDebug(LinkManagerLog) << "Connection already exist";
return;
}

UDPConfiguration *const link = new UDPConfiguration(udpName);
link->addHost(hostname, service.port());
link->setAutoConnect(true);
link->setDynamic(true);
SharedLinkConfigurationPtr config = addConfiguration(link);
if (!createConnectedLink(config)) {
qCWarning(LinkManagerLog) << "Failed to create" << udpName;
}
} else if (service.type().startsWith("_mavlink._tcp")) {
static QString tcpName = QStringLiteral("ZeroConf TCP");
if (checkIfConnectionLinkExist(LinkConfiguration::TypeTcp, tcpName)) {
qCDebug(LinkManagerLog) << "Connection already exist";
return;
}

TCPConfiguration *const link = new TCPConfiguration(tcpName);
link->setHost(hostname);
link->setPort(service.port());
link->setAutoConnect(true);
link->setDynamic(true);
SharedLinkConfigurationPtr config = addConfiguration(link);
if (!createConnectedLink(config)) {
qCWarning(LinkManagerLog) << "Failed to create" << tcpName;
}
}
});
}
#endif

void LinkManager::_updateAutoConnectLinks()
{
if (_connectionsSuspended) {
Expand Down Expand Up @@ -744,6 +670,89 @@ void LinkManager::_createDynamicForwardLink(const char *linkName, const QString
qCDebug(LinkManagerLog) << "New dynamic MAVLink forwarding port added:" << linkName << " hostname:" << hostName;
}

void LinkManager::resetMavlinkSigning()
{
for (const SharedLinkInterfacePtr &sharedLink: _rgLinks) {
sharedLink->initMavlinkSigning();
}
}

#ifdef QGC_ZEROCONF_ENABLED

void LinkManager::_addZeroConfAutoConnectLink()
{
if (!_autoConnectSettings->autoConnectZeroConf()->rawValue().toBool()) {
return;
}

static QSharedPointer<QMdnsEngine::Server> server;
static QSharedPointer<QMdnsEngine::Browser> browser;
server.reset(new QMdnsEngine::Server());
browser.reset(new QMdnsEngine::Browser(server.get(), QMdnsEngine::MdnsBrowseType));

const auto checkIfConnectionLinkExist = [this](LinkConfiguration::LinkType linkType, const QString &linkName) {
for (const SharedLinkInterfacePtr &link : std::as_const(_rgLinks)) {
const SharedLinkConfigurationPtr linkConfig = link->linkConfiguration();
if ((linkConfig->type() == linkType) && (linkConfig->name() == linkName)) {
return true;
}
}

return false;
};

(void) connect(browser.get(), &QMdnsEngine::Browser::serviceAdded, this, [checkIfConnectionLinkExist, this](const QMdnsEngine::Service &service) {
qCDebug(LinkManagerLog) << "Found Zero-Conf:" << service.type() << service.name() << service.hostname() << service.port() << service.attributes();

if (!service.type().startsWith("_mavlink")) {
qCWarning(LinkManagerLog) << "Invalid ZeroConf SericeType" << service.type();
return;
}

// Windows doesnt accept trailling dots in mdns
// http://www.dns-sd.org/trailingdotsindomainnames.html
QString hostname = service.hostname();
if (hostname.endsWith('.')) {
hostname.chop(1);
}

if (service.type().startsWith("_mavlink._udp")) {
static const QString udpName = QStringLiteral("ZeroConf UDP");
if (checkIfConnectionLinkExist(LinkConfiguration::TypeUdp, udpName)) {
qCDebug(LinkManagerLog) << "Connection already exist";
return;
}

UDPConfiguration *const link = new UDPConfiguration(udpName);
link->addHost(hostname, service.port());
link->setAutoConnect(true);
link->setDynamic(true);
SharedLinkConfigurationPtr config = addConfiguration(link);
if (!createConnectedLink(config)) {
qCWarning(LinkManagerLog) << "Failed to create" << udpName;
}
} else if (service.type().startsWith("_mavlink._tcp")) {
static QString tcpName = QStringLiteral("ZeroConf TCP");
if (checkIfConnectionLinkExist(LinkConfiguration::TypeTcp, tcpName)) {
qCDebug(LinkManagerLog) << "Connection already exist";
return;
}

TCPConfiguration *const link = new TCPConfiguration(tcpName);
link->setHost(hostname);
link->setPort(service.port());
link->setAutoConnect(true);
link->setDynamic(true);
SharedLinkConfigurationPtr config = addConfiguration(link);
if (!createConnectedLink(config)) {
qCWarning(LinkManagerLog) << "Failed to create" << tcpName;
}
}
});
}

#endif // QGC_ZEROCONF_ENABLED

bool LinkManager::isLinkUSBDirect(const LinkInterface *link)
{
#ifndef QGC_NO_SERIAL_LINK
Expand All @@ -766,14 +775,18 @@ bool LinkManager::isLinkUSBDirect(const LinkInterface *link)
return false;
}

void LinkManager::resetMavlinkSigning()
#ifndef QGC_NO_SERIAL_LINK // Serial Only Functions

bool LinkManager::_isSerialPortConnected() const
{
for (const SharedLinkInterfacePtr &sharedLink: _rgLinks) {
sharedLink->initMavlinkSigning();
for (const SharedLinkInterfacePtr &link: _rgLinks) {
if (qobject_cast<const SerialLink*>(link.get())) {
return true;
}
}
}

#ifndef QGC_NO_SERIAL_LINK // Serial Only Functions
return false;
}

void LinkManager::_filterCompositePorts(QList<QGCSerialPortInfo> &portList)
{
Expand Down Expand Up @@ -997,15 +1010,4 @@ QStringList LinkManager::serialBaudRates()
return SerialConfiguration::supportedBaudRates();
}

bool LinkManager::_isSerialPortConnected() const
{
for (const SharedLinkInterfacePtr &link: _rgLinks) {
if (qobject_cast<const SerialLink*>(link.get())) {
return true;
}
}

return false;
}

#endif // QGC_NO_SERIAL_LINK
10 changes: 5 additions & 5 deletions src/Comms/LinkManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,10 @@ class SerialLink;
class UDPConfiguration;
class UdpIODevice;

/// @brief Manage communication links
/// The Link Manager organizes the physical Links. It can manage arbitrary
/// links and takes care of connecting them as well assigning the correct
/// protocol instance to transport the link data into the application.
/// Manage communication links
/// The Link Manager organizes the physical Links. It can manage arbitrary
/// links and takes care of connecting them as well assigning the correct
/// protocol instance to transport the link data into the application.
class LinkManager : public QObject
{
Q_OBJECT
Expand Down Expand Up @@ -175,9 +175,9 @@ private slots:
Q_PROPERTY(QStringList serialPorts READ serialPorts NOTIFY commPortsChanged)

public:
static QStringList serialBaudRates();
QStringList serialPortStrings();
QStringList serialPorts();
static QStringList serialBaudRates();

signals:
void commPortStringsChanged();
Expand Down
2 changes: 1 addition & 1 deletion src/Comms/TCPLink.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@
#include <QtNetwork/QHostInfo>
#include <QtNetwork/QTcpSocket>

QGC_LOGGING_CATEGORY(TCPLinkLog, "test.comms.tcplink")
QGC_LOGGING_CATEGORY(TCPLinkLog, "qgc.comms.tcplink")

namespace {
constexpr int CONNECT_TIMEOUT_MS = 5000;
Expand Down
3 changes: 2 additions & 1 deletion src/FactSystem/ParameterManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -812,7 +812,8 @@ void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId)
QDir ParameterManager::parameterCacheDir()
{
const QString spath(QFileInfo(QSettings().fileName()).dir().absolutePath());
return (spath + QDir::separator() + QStringLiteral("ParamCache"));
const QDir cacheDir(spath + QDir::separator() + QStringLiteral("ParamCache"));
return cacheDir;
}

QString ParameterManager::parameterCacheFile(int vehicleId, int componentId)
Expand Down
Loading
Loading