20#ifndef QGC_NO_SERIAL_LINK
30#include <QtCore/QApplicationStatic>
31#include <QtCore/QTimer>
40 , _portListTimer(new QTimer(this))
44 qCDebug(LinkManagerLog) <<
this;
46 (void) qRegisterMetaType<QAbstractSocket::SocketError>(
"QAbstractSocket::SocketError");
47 (void) qRegisterMetaType<LinkInterface*>(
"LinkInterface*");
48#ifndef QGC_NO_SERIAL_LINK
49 (void) qRegisterMetaType<QGCSerialPortInfo>(
"QGCSerialPortInfo");
55 qCDebug(LinkManagerLog) <<
this;
60 return _linkManagerInstance();
68 (void) connect(_portListTimer, &QTimer::timeout,
this, &LinkManager::_updateAutoConnectLinks);
69 _portListTimer->start(_autoconnectUpdateTimerMSecs);
75 QMutexLocker locker(&_linksMutex);
81 return _qmlConfigurations;
87 if (sharedConfig.get() == config) {
97 switch(config->type()) {
98#ifndef QGC_NO_SERIAL_LINK
100 link = std::make_shared<SerialLink>(config);
104 link = std::make_shared<UDPLink>(config);
107 link = std::make_shared<TCPLink>(config);
110 link = std::make_shared<BluetoothLink>(config);
113 link = std::make_shared<LogReplayLink>(config);
116 case LinkConfiguration::TypeMock:
117 link = std::make_shared<MockLink>(config);
129 if (!link->_allocateMavlinkChannel()) {
130 qCWarning(LinkManagerLog) <<
"Link failed to setup mavlink channels";
143 if (!link->_connect()) {
148 link->_freeMavlinkChannel();
149 config->setLink(
nullptr);
154 QMutexLocker locker(&_linksMutex);
155 _rgLinks.append(link);
157 config->setLink(link);
162void LinkManager::_communicationError(
const QString &title,
const QString &
error)
169 QMutexLocker locker(&_linksMutex);
183 QMutexLocker locker(&_linksMutex);
187 if (linkConfig && (linkConfig->type() ==
LinkConfiguration::TypeUdp) && (linkConfig->name() == _mavlinkForwardingSupportLinkName)) {
197 QList<SharedLinkInterfacePtr>
links;
199 QMutexLocker locker(&_linksMutex);
204 sharedLink->disconnect();
208void LinkManager::_linkDisconnected()
210 LinkInterface*
const link = qobject_cast<LinkInterface*>(sender());
219 QMutexLocker locker(&_linksMutex);
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();
227 (void) _rgLinks.erase(it);
233 if (!linkToCleanup) {
234 qCDebug(LinkManagerLog) <<
"link already removed";
239 config->setLink(
nullptr);
252 QMutexLocker locker(&_linksMutex);
255 if (sharedLink.get() == link) {
262 qCDebug(LinkManagerLog) <<
"link not in list (likely disconnected)";
266bool LinkManager::_connectionsSuspendedMsg()
const
268 if (_connectionsSuspended) {
282 for (
int i = 0; i < _rgLinkConfigs.count(); i++) {
285 qCWarning(LinkManagerLog) <<
"Internal error for link configuration in LinkManager";
289 if (linkConfig->isDynamic()) {
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);
302 settings.setValue(root +
"/count", trueCount);
312 for (
int i = 0; i < count; i++) {
314 if (!settings.contains(root +
"/type")) {
315 qCWarning(LinkManagerLog) <<
"Link Configuration" << root <<
"has no type.";
321 qCWarning(LinkManagerLog) <<
"Link Configuration" << root <<
"an invalid type:" << type;
325 if (!settings.contains(root +
"/name")) {
326 qCWarning(LinkManagerLog) <<
"Link Configuration" << root <<
"has no name.";
330 const QString name = settings.value(root +
"/name").toString();
331 if (name.isEmpty()) {
332 qCWarning(LinkManagerLog) <<
"Link Configuration" << root <<
"has an empty name.";
338#ifndef QGC_NO_SERIAL_LINK
356 case LinkConfiguration::TypeMock:
366 const bool autoConnect = settings.value(root +
"/auto").toBool();
368 const bool highLatency = settings.value(root +
"/high_latency").toBool();
377 _configurationsLoaded =
true;
380void LinkManager::_addUDPAutoConnectLink()
382 if (!_autoConnectSettings->autoConnectUDP()->rawValue().toBool()) {
387 QMutexLocker locker(&_linksMutex);
396 qCDebug(LinkManagerLog) <<
"New auto-connect UDP port added";
404void LinkManager::_addMAVLinkForwardingLink()
411 QMutexLocker locker(&_linksMutex);
422 _createDynamicForwardLink(_mavlinkForwardingLinkName, hostName);
425void LinkManager::_updateAutoConnectLinks()
427 if (_connectionsSuspended) {
431 _addUDPAutoConnectLink();
432 _addMAVLinkForwardingLink();
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());
442#ifndef QGC_NO_SERIAL_LINK
447 _nmeaDeviceName =
"";
451 _nmeaSocket->close();
454#ifndef QGC_NO_SERIAL_LINK
455 _addSerialAutoConnectLink();
466 QCoreApplication::processEvents(QEventLoop::ExcludeUserInputEvents);
473 static QStringList list;
474 if (!list.isEmpty()) {
478#ifndef QGC_NO_SERIAL_LINK
479 list += tr(
"Serial");
483 list += tr(
"Bluetooth");
485 list += tr(
"Mock Link");
487 list += tr(
"Log Replay");
490 qCWarning(LinkManagerLog) <<
"Internal error";
498 if (!config || !editedConfig) {
499 qCWarning(LinkManagerLog) <<
"Internal error";
513 qCWarning(LinkManagerLog) <<
"Internal error";
523#ifndef QGC_NO_SERIAL_LINK
525 _updateSerialPorts();
535 qCWarning(LinkManagerLog) <<
"Internal error";
539#ifndef QGC_NO_SERIAL_LINK
541 _updateSerialPorts();
551 qCWarning(LinkManagerLog) <<
"Internal error";
560 _removeConfiguration(config);
567 _createDynamicForwardLink(_mavlinkForwardingSupportLinkName, hostName);
568 _mavlinkSupportForwardingEnabled =
true;
574 (void) _qmlConfigurations->
removeOne(config);
576 for (
auto it = _rgLinkConfigs.begin(); it != _rgLinkConfigs.end(); ++it) {
577 if (it->get() == config) {
578 (void) _rgLinkConfigs.erase(it);
583 qCWarning(LinkManagerLog) <<
"called with unknown config";
593 QMutexLocker locker(&_linksMutex);
596 if (sharedLink.get() == link) {
606 (void) _qmlConfigurations->
append(config);
609 return _rgLinkConfigs.last();
615 if (sharedConfig->isAutoConnect()) {
624 if (_mavlinkChannelsUsedBitMask & (1 << mavlinkChannel)) {
628 mavlink_reset_channel_status(mavlinkChannel);
630 mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
631 _mavlinkChannelsUsedBitMask |= (1 << mavlinkChannel);
632 qCDebug(LinkManagerLog) <<
"allocateMavlinkChannel" << mavlinkChannel;
633 return mavlinkChannel;
636 qWarning(LinkManagerLog) <<
"allocateMavlinkChannel: all channels reserved!";
642 qCDebug(LinkManagerLog) <<
"freeMavlinkChannel" << channel;
648 _mavlinkChannelsUsedBitMask &= ~(1 << channel);
659 return qobject_cast<LogReplayLink*>(sharedConfig->link());
665void LinkManager::_createDynamicForwardLink(
const char *linkName,
const QString &hostName)
676 qCDebug(LinkManagerLog) <<
"New dynamic MAVLink forwarding port added:" << linkName <<
" hostname:" << hostName;
681#ifndef QGC_NO_SERIAL_LINK
682 const SerialLink*
const serialLink = qobject_cast<const SerialLink*>(link);
692 const SerialConfiguration*
const serialConfig = qobject_cast<const SerialConfiguration*>(config.get());
693 if (serialConfig && serialConfig->
usbDirect()) {
701#ifndef QGC_NO_SERIAL_LINK
703void LinkManager::_filterCompositePorts(QList<QGCSerialPortInfo> &portList)
705 typedef QPair<quint16, quint16> VidPidPair_t;
707 QMap<VidPidPair_t, QStringList> seenSerialNumbers;
709 for (
auto it = portList.begin(); it != portList.end();) {
713 if (seenSerialNumbers.contains(vidPid) && seenSerialNumbers[vidPid].contains(portInfo.
serialNumber())) {
718 it = portList.erase(it);
722 seenSerialNumbers[vidPid].append(portInfo.
serialNumber());
728void LinkManager::_addSerialAutoConnectLink()
730 QList<QGCSerialPortInfo> portList;
735 if (!_isSerialPortConnected()) {
742 _filterCompositePorts(portList);
744 QStringList currentPorts;
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();
761 if (portInfo.
systemLocation().trimmed() == _autoConnectSettings->autoConnectNmeaPort()->cookedValueString()) {
764 qCDebug(LinkManagerLog) <<
"Configuring nmea port" << _nmeaDeviceName;
766 _nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt();
767 newPort->
setBaudRate(
static_cast<qint32
>(_nmeaBaud));
768 qCDebug(LinkManagerLog) <<
"Configuring nmea baudrate" << _nmeaBaud;
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;
780 }
else if (portInfo.
getBoardInfo(boardType, boardName)) {
782 if (!_allowAutoConnectToBoard(boardType)) {
788 qCDebug(LinkManagerLog) <<
"Waiting for bootloader to finish" << portInfo.
systemLocation();
792 qCDebug(LinkManagerVerboseLog) <<
"Skipping existing autoconnect" << portInfo.
systemLocation();
793 }
else if (!_autoconnectPortWaitList.contains(portInfo.
systemLocation())) {
797 qCDebug(LinkManagerLog) <<
"Waiting for next autoconnect pass" << portInfo.
systemLocation() << boardName;
799 }
else if ((++_autoconnectPortWaitList[portInfo.
systemLocation()] * _autoconnectUpdateTimerMSecs) > _autoconnectConnectDelayMSecs) {
814 qCDebug(LinkManagerLog) <<
"RTK GPS auto-connected" << portInfo.
portName().trimmed();
819 qCWarning(LinkManagerLog) <<
"Internal error: Unknown board type" << boardType;
824 qCDebug(LinkManagerLog) <<
"New auto-connect port added: " << pSerialConfig->
name() << portInfo.
systemLocation();
838 if (!_autoConnectRTKPort.isEmpty() && !currentPorts.contains(_autoConnectRTKPort)) {
839 qCDebug(LinkManagerLog) <<
"RTK GPS disconnected" << _autoConnectRTKPort;
841 _autoConnectRTKPort.clear();
849 if (_autoConnectSettings->autoConnectPixhawk()->rawValue().toBool()) {
854 if (_autoConnectSettings->autoConnectSiKRadio()->rawValue().toBool()) {
859 if (_autoConnectSettings->autoConnectLibrePilot()->rawValue().toBool()) {
869 qCWarning(LinkManagerLog) <<
"Internal error: Unknown board type" << boardType;
876bool LinkManager::_portAlreadyConnected(
const QString &portName)
878 QMutexLocker locker(&_linksMutex);
880 const QString searchPort = portName.trimmed();
883 const SerialConfiguration*
const serialConfig = qobject_cast<const SerialConfiguration*>(linkConfig.get());
884 if (serialConfig && (serialConfig->
portName() == searchPort)) {
892void LinkManager::_updateSerialPorts()
894 _commPortList.clear();
895 _commPortDisplayList.clear();
898 const QString port = info.systemLocation().trimmed();
899 _commPortList += port;
906 if (_commPortDisplayList.isEmpty()) {
907 _updateSerialPorts();
910 return _commPortDisplayList;
915 if (_commPortList.isEmpty()) {
916 _updateSerialPorts();
919 return _commPortList;
927bool LinkManager::_isSerialPortConnected()
929 QMutexLocker locker(&_linksMutex);
932 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)
static GPSManager * instance()
void connectGPS(const QString &device, QStringView gps_type)
Interface holding link specific settings.
@ 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)
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)
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...
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)
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 isBootloader() const
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.
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)
static QStringList supportedBaudRates()
void setUsbDirect(bool usbDirect)
static QString cleanPortDisplayName(const QString &name)
void setPortName(const QString &name)
AutoConnectSettings * autoConnectSettings() const
static SettingsManager * instance()
MavlinkSettings * mavlinkSettings() const
void setAutoConnect(bool autoc=true) override
Set if this is this an Auto Connect configuration.
Q_INVOKABLE void addHost(const QString &host)
UdpIODevice provides a QIODevice interface over a QUdpSocket in server mode.
bool isBluetoothAvailable()
Check if Bluetooth is available on this device.
void showAppMessage(const QString &message, const QString &title)
Modal application message. Queued if the UI isn't ready yet.