17#ifndef QGC_NO_SERIAL_LINK
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>
37#include <QtCore/QApplicationStatic>
38#include <QtCore/QTimer>
47 , _portListTimer(new QTimer(this))
49#ifndef QGC_NO_SERIAL_LINK
53 qCDebug(LinkManagerLog) <<
this;
55 (void) qRegisterMetaType<QAbstractSocket::SocketError>(
"QAbstractSocket::SocketError");
56 (void) qRegisterMetaType<LinkInterface*>(
"LinkInterface*");
57#ifndef QGC_NO_SERIAL_LINK
58 (void) qRegisterMetaType<QGCSerialPortInfo>(
"QGCSerialPortInfo");
62LinkManager::~LinkManager()
64 qCDebug(LinkManagerLog) <<
this;
69 return _linkManagerInstance();
72void LinkManager::init()
74 _autoConnectSettings = SettingsManager::instance()->autoConnectSettings();
76 if (!
qgcApp()->runningUnitTests()) {
77 (void) connect(_portListTimer, &QTimer::timeout,
this, &LinkManager::_updateAutoConnectLinks);
78 _portListTimer->start(_autoconnectUpdateTimerMSecs);
82QList<SharedLinkInterfacePtr> LinkManager::links()
84 QMutexLocker locker(&_linksMutex);
90 return _qmlConfigurations;
96 if (sharedConfig.get() == config) {
97 createConnectedLink(sharedConfig);
106 switch(config->type()) {
107#ifndef QGC_NO_SERIAL_LINK
108 case LinkConfiguration::TypeSerial:
109 link = std::make_shared<SerialLink>(config);
112 case LinkConfiguration::TypeUdp:
113 link = std::make_shared<UDPLink>(config);
115 case LinkConfiguration::TypeTcp:
116 link = std::make_shared<TCPLink>(config);
118 case LinkConfiguration::TypeBluetooth:
119 link = std::make_shared<BluetoothLink>(config);
121 case LinkConfiguration::TypeLogReplay:
122 link = std::make_shared<LogReplayLink>(config);
125 case LinkConfiguration::TypeMock:
126 link = std::make_shared<MockLink>(config);
129 case LinkConfiguration::TypeLast:
138 if (!link->_allocateMavlinkChannel()) {
139 qCWarning(LinkManagerLog) <<
"Link failed to setup mavlink channels";
152 if (!link->_connect()) {
157 link->_freeMavlinkChannel();
158 config->setLink(
nullptr);
163 QMutexLocker locker(&_linksMutex);
164 _rgLinks.append(link);
166 config->setLink(link);
171void LinkManager::_communicationError(
const QString &title,
const QString &
error)
178 QMutexLocker locker(&_linksMutex);
182 if (linkConfig && (linkConfig->type() == LinkConfiguration::TypeUdp) && (linkConfig->name() == _mavlinkForwardingLinkName)) {
192 QMutexLocker locker(&_linksMutex);
196 if (linkConfig && (linkConfig->type() == LinkConfiguration::TypeUdp) && (linkConfig->name() == _mavlinkForwardingSupportLinkName)) {
204void LinkManager::disconnectAll()
206 QList<SharedLinkInterfacePtr> links;
208 QMutexLocker locker(&_linksMutex);
213 sharedLink->disconnect();
217void LinkManager::_linkDisconnected()
219 LinkInterface*
const link = qobject_cast<LinkInterface*>(sender());
228 QMutexLocker locker(&_linksMutex);
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();
236 (void) _rgLinks.erase(it);
242 if (!linkToCleanup) {
243 qCDebug(LinkManagerLog) <<
"link already removed";
248 config->setLink(
nullptr);
261 QMutexLocker locker(&_linksMutex);
264 if (sharedLink.get() == link) {
271 qCDebug(LinkManagerLog) <<
"link not in list (likely disconnected)";
275bool LinkManager::_connectionsSuspendedMsg()
const
277 if (_connectionsSuspended) {
278 qgcApp()->showAppMessage(tr(
"Connect not allowed: %1").arg(_connectionsSuspendedReason));
285void LinkManager::saveLinkConfigurationList()
288 settings.remove(LinkConfiguration::settingsRoot());
291 for (
int i = 0; i < _rgLinkConfigs.count(); i++) {
294 qCWarning(LinkManagerLog) <<
"Internal error for link configuration in LinkManager";
298 if (linkConfig->isDynamic()) {
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);
310 const QString root = QString(LinkConfiguration::settingsRoot());
311 settings.setValue(root +
"/count", trueCount);
314void LinkManager::loadLinkConfigurationList()
318 if (settings.contains(LinkConfiguration::settingsRoot() +
"/count")) {
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.";
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;
334 if (!settings.contains(root +
"/name")) {
335 qCWarning(LinkManagerLog) <<
"Link Configuration" << root <<
"has no name.";
339 const QString name = settings.value(root +
"/name").toString();
340 if (name.isEmpty()) {
341 qCWarning(LinkManagerLog) <<
"Link Configuration" << root <<
"has an empty name.";
347#ifndef QGC_NO_SERIAL_LINK
348 case LinkConfiguration::TypeSerial:
352 case LinkConfiguration::TypeUdp:
355 case LinkConfiguration::TypeTcp:
358 case LinkConfiguration::TypeBluetooth:
361 case LinkConfiguration::TypeLogReplay:
365 case LinkConfiguration::TypeMock:
369 case LinkConfiguration::TypeLast:
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);
386 _configurationsLoaded =
true;
389void LinkManager::_addUDPAutoConnectLink()
391 if (!_autoConnectSettings->
autoConnectUDP()->rawValue().toBool()) {
396 QMutexLocker locker(&_linksMutex);
399 if (linkConfig && (linkConfig->type() == LinkConfiguration::TypeUdp) && (linkConfig->name() == _defaultUDPLinkName)) {
405 qCDebug(LinkManagerLog) <<
"New auto-connect UDP port added";
407 udpConfig->setDynamic(
true);
408 udpConfig->setAutoConnect(
true);
410 createConnectedLink(config);
413void LinkManager::_addMAVLinkForwardingLink()
415 if (!SettingsManager::instance()->mavlinkSettings()->forwardMavlink()->rawValue().toBool()) {
420 QMutexLocker locker(&_linksMutex);
423 if (linkConfig && (linkConfig->type() == LinkConfiguration::TypeUdp) && (linkConfig->name() == _mavlinkForwardingLinkName)) {
430 const QString hostName = SettingsManager::instance()->mavlinkSettings()->
forwardMavlinkHostName()->rawValue().toString();
431 _createDynamicForwardLink(_mavlinkForwardingLinkName, hostName);
434#ifdef QGC_ZEROCONF_ENABLED
435void LinkManager::_addZeroConfAutoConnectLink()
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));
446 const auto checkIfConnectionLinkExist = [
this](LinkConfiguration::LinkType linkType,
const QString &linkName) {
447 QMutexLocker locker(&_linksMutex);
450 if (linkConfig && (linkConfig->type() == linkType) && (linkConfig->name() == linkName)) {
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();
461 if (!service.type().startsWith(
"_mavlink")) {
462 qCWarning(LinkManagerLog) <<
"Invalid ZeroConf SericeType" << service.type();
468 QString hostname = service.hostname();
469 if (hostname.endsWith(
'.')) {
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";
481 link->addHost(hostname, service.port());
482 link->setAutoConnect(
true);
483 link->setDynamic(
true);
485 if (!createConnectedLink(config)) {
486 qCWarning(LinkManagerLog) <<
"Failed to create" << udpName;
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";
496 link->setHost(hostname);
497 link->setPort(service.port());
498 link->setAutoConnect(
true);
499 link->setDynamic(
true);
501 if (!createConnectedLink(config)) {
502 qCWarning(LinkManagerLog) <<
"Failed to create" << tcpName;
509void LinkManager::_updateAutoConnectLinks()
511 if (_connectionsSuspended) {
515 _addUDPAutoConnectLink();
516 _addMAVLinkForwardingLink();
517#ifdef QGC_ZEROCONF_ENABLED
518 _addZeroConfAutoConnectLink();
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);
529#ifndef QGC_NO_SERIAL_LINK
534 _nmeaDeviceName =
"";
538 _nmeaSocket->close();
541#ifndef QGC_NO_SERIAL_LINK
542 _addSerialAutoConnectLink();
546void LinkManager::shutdown()
548 setConnectionsSuspended(tr(
"Shutdown"));
552 while (MultiVehicleManager::instance()->vehicles()->count()) {
553 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
557QStringList LinkManager::linkTypeStrings()
const
560 static QStringList list;
561 if (!list.isEmpty()) {
565#ifndef QGC_NO_SERIAL_LINK
566 list += tr(
"Serial");
570 list += tr(
"Bluetooth");
572 list += tr(
"Mock Link");
574 list += tr(
"Log Replay");
576 if (list.size() !=
static_cast<int>(LinkConfiguration::TypeLast)) {
577 qCWarning(LinkManagerLog) <<
"Internal error";
585 if (!config || !editedConfig) {
586 qCWarning(LinkManagerLog) <<
"Internal error";
590 config->copyFrom(editedConfig);
591 saveLinkConfigurationList();
600 qCWarning(LinkManagerLog) <<
"Internal error";
604 addConfiguration(config);
605 saveLinkConfigurationList();
608LinkConfiguration *LinkManager::createConfiguration(
int type,
const QString &name)
610#ifndef QGC_NO_SERIAL_LINK
611 if (
static_cast<LinkConfiguration::LinkType
>(type) == LinkConfiguration::TypeSerial) {
612 _updateSerialPorts();
616 return LinkConfiguration::createSettings(type, name);
622 qCWarning(LinkManagerLog) <<
"Internal error";
626#ifndef QGC_NO_SERIAL_LINK
627 if (config->type() == LinkConfiguration::TypeSerial) {
628 _updateSerialPorts();
632 return LinkConfiguration::duplicateSettings(config);
638 qCWarning(LinkManagerLog) <<
"Internal error";
647 _removeConfiguration(config);
648 saveLinkConfigurationList();
651void LinkManager::createMavlinkForwardingSupportLink()
654 _createDynamicForwardLink(_mavlinkForwardingSupportLinkName, hostName);
655 _mavlinkSupportForwardingEnabled =
true;
661 (void) _qmlConfigurations->
removeOne(config);
663 for (
auto it = _rgLinkConfigs.begin(); it != _rgLinkConfigs.end(); ++it) {
664 if (it->get() == config) {
665 (void) _rgLinkConfigs.erase(it);
670 qCWarning(LinkManagerLog) <<
"called with unknown config";
673bool LinkManager::isBluetoothAvailable()
680 QMutexLocker locker(&_linksMutex);
683 if (sharedLink.get() == link) {
693 (void) _qmlConfigurations->
append(config);
696 return _rgLinkConfigs.last();
699void LinkManager::startAutoConnectedLinks()
702 if (sharedConfig->isAutoConnect()) {
703 createConnectedLink(sharedConfig);
708uint8_t LinkManager::allocateMavlinkChannel()
711 if (_mavlinkChannelsUsedBitMask & (1 << mavlinkChannel)) {
715 mavlink_reset_channel_status(mavlinkChannel);
717 mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
718 _mavlinkChannelsUsedBitMask |= (1 << mavlinkChannel);
719 qCDebug(LinkManagerLog) <<
"allocateMavlinkChannel" << mavlinkChannel;
720 return mavlinkChannel;
723 qWarning(LinkManagerLog) <<
"allocateMavlinkChannel: all channels reserved!";
724 return invalidMavlinkChannel();
727void LinkManager::freeMavlinkChannel(uint8_t channel)
729 qCDebug(LinkManagerLog) <<
"freeMavlinkChannel" << channel;
731 if (invalidMavlinkChannel() == channel) {
735 _mavlinkChannelsUsedBitMask &= ~(1 << channel);
738LogReplayLink *LinkManager::startLogReplay(
const QString &logFile)
741 linkConfig->setLogFilename(logFile);
742 linkConfig->setName(linkConfig->logFilenameShort());
745 if (createConnectedLink(sharedConfig)) {
746 return qobject_cast<LogReplayLink*>(sharedConfig->link());
752void LinkManager::_createDynamicForwardLink(
const char *linkName,
const QString &hostName)
756 udpConfig->setDynamic(
true);
757 udpConfig->setForwarding(
true);
758 udpConfig->addHost(hostName);
761 createConnectedLink(config);
763 qCDebug(LinkManagerLog) <<
"New dynamic MAVLink forwarding port added:" << linkName <<
" hostname:" << hostName;
768#ifndef QGC_NO_SERIAL_LINK
769 const SerialLink*
const serialLink = qobject_cast<const SerialLink*>(link);
779 const SerialConfiguration*
const serialConfig = qobject_cast<const SerialConfiguration*>(config.get());
780 if (serialConfig && serialConfig->usbDirect()) {
788void LinkManager::resetMavlinkSigning()
791 QList<SharedLinkInterfacePtr> links;
793 QMutexLocker locker(&_linksMutex);
798 sharedLink->initMavlinkSigning();
802#ifndef QGC_NO_SERIAL_LINK
804void LinkManager::_filterCompositePorts(QList<QGCSerialPortInfo> &portList)
806 typedef QPair<quint16, quint16> VidPidPair_t;
808 QMap<VidPidPair_t, QStringList> seenSerialNumbers;
810 for (
auto it = portList.begin(); it != portList.end();) {
814 if (seenSerialNumbers.contains(vidPid) && seenSerialNumbers[vidPid].contains(portInfo.
serialNumber())) {
819 it = portList.erase(it);
823 seenSerialNumbers[vidPid].append(portInfo.
serialNumber());
829void LinkManager::_addSerialAutoConnectLink()
831 QList<QGCSerialPortInfo> portList;
836 if (!_isSerialPortConnected()) {
843 _filterCompositePorts(portList);
845 QStringList currentPorts;
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();
865 qCDebug(LinkManagerLog) <<
"Configuring nmea port" << _nmeaDeviceName;
868 newPort->
setBaudRate(
static_cast<qint32
>(_nmeaBaud));
869 qCDebug(LinkManagerLog) <<
"Configuring nmea baudrate" << _nmeaBaud;
871 QGCPositionManager::instance()->setNmeaSourceDevice(newPort);
876 }
else if (_autoConnectSettings->
autoConnectNmeaBaud()->cookedValue().toUInt() != _nmeaBaud) {
878 _nmeaPort->
setBaudRate(
static_cast<qint32
>(_nmeaBaud));
879 qCDebug(LinkManagerLog) <<
"Configuring nmea baudrate" << _nmeaBaud;
881 }
else if (portInfo.
getBoardInfo(boardType, boardName)) {
883 if (!_allowAutoConnectToBoard(boardType)) {
889 qCDebug(LinkManagerLog) <<
"Waiting for bootloader to finish" << portInfo.
systemLocation();
893 qCDebug(LinkManagerVerboseLog) <<
"Skipping existing autoconnect" << portInfo.
systemLocation();
894 }
else if (!_autoconnectPortWaitList.contains(portInfo.
systemLocation())) {
898 qCDebug(LinkManagerLog) <<
"Waiting for next autoconnect pass" << portInfo.
systemLocation() << boardName;
900 }
else if ((++_autoconnectPortWaitList[portInfo.
systemLocation()] * _autoconnectUpdateTimerMSecs) > _autoconnectConnectDelayMSecs) {
906 pSerialConfig->setUsbDirect(
true);
915 qCDebug(LinkManagerLog) <<
"RTK GPS auto-connected" << portInfo.
portName().trimmed();
920 qCWarning(LinkManagerLog) <<
"Internal error: Unknown board type" << boardType;
925 qCDebug(LinkManagerLog) <<
"New auto-connect port added: " << pSerialConfig->name() << portInfo.
systemLocation();
927 pSerialConfig->setDynamic(
true);
929 pSerialConfig->setAutoConnect(
true);
932 createConnectedLink(sharedConfig);
939 if (!_autoConnectRTKPort.isEmpty() && !currentPorts.contains(_autoConnectRTKPort)) {
940 qCDebug(LinkManagerLog) <<
"RTK GPS disconnected" << _autoConnectRTKPort;
942 _autoConnectRTKPort.clear();
970 qCWarning(LinkManagerLog) <<
"Internal error: Unknown board type" << boardType;
977bool LinkManager::_portAlreadyConnected(
const QString &portName)
979 QMutexLocker locker(&_linksMutex);
981 const QString searchPort = portName.trimmed();
984 const SerialConfiguration*
const serialConfig = qobject_cast<const SerialConfiguration*>(linkConfig.get());
985 if (serialConfig && (serialConfig->portName() == searchPort)) {
993void LinkManager::_updateSerialPorts()
995 _commPortList.clear();
996 _commPortDisplayList.clear();
999 const QString port = info.systemLocation().trimmed();
1000 _commPortList += port;
1001 _commPortDisplayList += SerialConfiguration::cleanPortDisplayName(port);
1005QStringList LinkManager::serialPortStrings()
1007 if (_commPortDisplayList.isEmpty()) {
1008 _updateSerialPorts();
1011 return _commPortDisplayList;
1014QStringList LinkManager::serialPorts()
1016 if (_commPortList.isEmpty()) {
1017 _updateSerialPorts();
1020 return _commPortList;
1023QStringList LinkManager::serialBaudRates()
1025 return SerialConfiguration::supportedBaudRates();
1028bool LinkManager::_isSerialPortConnected()
1030 QMutexLocker locker(&_linksMutex);
1033 if (qobject_cast<const SerialLink*>(link.get())) {
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)
#define MAVLINK_COMM_NUM_BUFFERS
#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()
static GPSManager * instance()
void connectGPS(const QString &device, QStringView gps_type)
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)
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...
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 isBootloader() const
bool getBoardInfo(BoardType_t &boardType, QString &name) const
static QList< QGCSerialPortInfo > availablePorts()
Override of QSerialPortInfo::availablePorts.
quint16 productIdentifier() const
QString manufacturer() 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.
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.