Skip to content
LinkManager.cc 32.1 KiB
Newer Older
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
pixhawk's avatar
pixhawk committed
#include <QList>
#include <QApplication>
#include <QSignalSpy>
Gus Grubba's avatar
Gus Grubba committed
#ifndef NO_SERIAL_LINK
Don Gagne's avatar
Don Gagne committed
#include "QGCSerialPortInfo.h"
dogmaphobic's avatar
dogmaphobic committed
#endif
#include "LinkManager.h"
#include "QGCApplication.h"
Don Gagne's avatar
Don Gagne committed
#include "UDPLink.h"
#include "TCPLink.h"
#include "SettingsManager.h"
Don Gagne's avatar
 
Don Gagne committed
#include "LogReplayLink.h"
dogmaphobic's avatar
dogmaphobic committed
#ifdef QGC_ENABLE_BLUETOOTH
dogmaphobic's avatar
dogmaphobic committed
#include "BluetoothLink.h"
#endif
Don Gagne's avatar
Don Gagne committed
#ifndef __mobile__
DonLakeFlyer's avatar
DonLakeFlyer committed
#include "GPSManager.h"
#include "PositionManager.h"
Don Gagne's avatar
Don Gagne committed
#endif

DonLakeFlyer's avatar
 
DonLakeFlyer committed
#ifdef QT_DEBUG
#include "MockLink.h"
#endif

Don Gagne's avatar
Don Gagne committed
QGC_LOGGING_CATEGORY(LinkManagerLog, "LinkManagerLog")
Don Gagne's avatar
Don Gagne committed
QGC_LOGGING_CATEGORY(LinkManagerVerboseLog, "LinkManagerVerboseLog")

const char* LinkManager::_defaultUDPLinkName =       "UDP Link (AutoConnect)";
const char* LinkManager::_mavlinkForwardingLinkName =       "MAVLink Forwarding Link";
const int LinkManager::_autoconnectUpdateTimerMSecs =   1000;
#ifdef Q_OS_WIN
// Have to manually let the bootloader go by on Windows to get a working connect
const int LinkManager::_autoconnectConnectDelayMSecs =  6000;
#else
const int LinkManager::_autoconnectConnectDelayMSecs =  1000;
#endif

LinkManager::LinkManager(QGCApplication* app, QGCToolbox* toolbox)
    : QGCTool(app, toolbox)
    , _configUpdateSuspended(false)
    , _configurationsLoaded(false)
    , _connectionsSuspended(false)
    , _mavlinkChannelsUsedBitMask(1)    // We never use channel 0 to avoid sequence numbering problems
    , _autoConnectSettings(nullptr)
    , _mavlinkProtocol(nullptr)
    #ifndef __mobile__
    #ifndef NO_SERIAL_LINK
    , _nmeaPort(nullptr)
pixhawk's avatar
pixhawk committed
{
Don Gagne's avatar
Don Gagne committed
    qmlRegisterUncreatableType<LinkManager>         ("QGroundControl", 1, 0, "LinkManager",         "Reference only");
    qmlRegisterUncreatableType<LinkConfiguration>   ("QGroundControl", 1, 0, "LinkConfiguration",   "Reference only");
    qmlRegisterUncreatableType<LinkInterface>       ("QGroundControl", 1, 0, "LinkInterface",       "Reference only");
pixhawk's avatar
pixhawk committed
}

LinkManager::~LinkManager()
{
#ifndef __mobile__
    delete _nmeaPort;
pixhawk's avatar
pixhawk committed
}

void LinkManager::setToolbox(QGCToolbox *toolbox)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
    QGCTool::setToolbox(toolbox);
DonLakeFlyer's avatar
DonLakeFlyer committed
    _autoConnectSettings = toolbox->settingsManager()->autoConnectSettings();
    _mavlinkProtocol = _toolbox->mavlinkProtocol();
Don Gagne's avatar
Don Gagne committed
    connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks);
    _portListTimer.start(_autoconnectUpdateTimerMSecs); // timeout must be long enough to get past bootloader on second pass
Don Gagne's avatar
Don Gagne committed
// This should only be used by Qml code
void LinkManager::createConnectedLink(LinkConfiguration* config)
{
    for(int i = 0; i < _rgLinkConfigs.count(); i++) {
        SharedLinkConfigurationPtr& sharedConfig = _rgLinkConfigs[i];
        if (sharedConfig.get() == config)
            createConnectedLink(sharedConfig);
Don Gagne's avatar
Don Gagne committed
    }
}

bool LinkManager::createConnectedLink(SharedLinkConfigurationPtr& config, bool isPX4Flow)
Gus Grubba's avatar
Gus Grubba committed
#ifndef NO_SERIAL_LINK
DonLakeFlyer's avatar
DonLakeFlyer committed
    case LinkConfiguration::TypeSerial:
        link = new SerialLink(config, isPX4Flow);
Don Gagne's avatar
Don Gagne committed
        break;
DonLakeFlyer's avatar
DonLakeFlyer committed
#else
    Q_UNUSED(isPX4Flow)
dogmaphobic's avatar
dogmaphobic committed
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
    case LinkConfiguration::TypeUdp:
DonLakeFlyer's avatar
DonLakeFlyer committed
        break;
    case LinkConfiguration::TypeTcp:
DonLakeFlyer's avatar
DonLakeFlyer committed
        break;
dogmaphobic's avatar
dogmaphobic committed
#ifdef QGC_ENABLE_BLUETOOTH
DonLakeFlyer's avatar
DonLakeFlyer committed
    case LinkConfiguration::TypeBluetooth:
        link = new BluetoothLink(config);
DonLakeFlyer's avatar
DonLakeFlyer committed
        break;
dogmaphobic's avatar
dogmaphobic committed
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
    case LinkConfiguration::TypeLogReplay:
        link = new LogReplayLink(config);
DonLakeFlyer's avatar
DonLakeFlyer committed
        break;
#ifdef QT_DEBUG
DonLakeFlyer's avatar
DonLakeFlyer committed
    case LinkConfiguration::TypeMock:
DonLakeFlyer's avatar
DonLakeFlyer committed
        break;
DonLakeFlyer's avatar
DonLakeFlyer committed
    case LinkConfiguration::TypeLast:
        break;
    QScopedPointer<LinkInterface> scopedLink(link);
        int mavlinkChannel = _reserveMavlinkChannel();
        if (mavlinkChannel != 0) {
            link->_setMavlinkChannel(mavlinkChannel);
        } else {
            qWarning() << "Ran out of mavlink channels";
        SharedLinkInterfacePtr sharedLink(link);
        _rgLinks.append(sharedLink);
        config->setLink(sharedLink);
        connect(link, &LinkInterface::communicationError,  _app,                &QGCApplication::criticalMessageBoxOnMainThread);
        connect(link, &LinkInterface::bytesReceived,       _mavlinkProtocol,    &MAVLinkProtocol::receiveBytes);
        connect(link, &LinkInterface::bytesSent,           _mavlinkProtocol,    &MAVLinkProtocol::logSentBytes);
        connect(link, &LinkInterface::disconnected,        this,                &LinkManager::_linkDisconnected);
        _mavlinkProtocol->resetMetadataForLink(link);
        _mavlinkProtocol->setVersion(_mavlinkProtocol->getCurrentVersion());
pixhawk's avatar
pixhawk committed


    return scopedLink.take() ? true : false;
pixhawk's avatar
pixhawk committed
}

SharedLinkInterfacePtr LinkManager::mavlinkForwardingLink()
pixhawk's avatar
pixhawk committed
{
    for (int i = 0; i < _rgLinks.count(); i++) {
        SharedLinkConfigurationPtr linkConfig = _rgLinks[i]->linkConfiguration();
        if (linkConfig->type() == LinkConfiguration::TypeUdp && linkConfig->name() == _mavlinkForwardingLinkName) {
            SharedLinkInterfacePtr& link = _rgLinks[i];
            return link;
DonLakeFlyer's avatar
DonLakeFlyer committed
        }
pixhawk's avatar
pixhawk committed
}

void LinkManager::disconnectAll(void)
pixhawk's avatar
pixhawk committed
{
    QList<SharedLinkInterfacePtr> links = _rgLinks;
Don Gagne's avatar
Don Gagne committed

    for (const SharedLinkInterfacePtr& sharedLink: links) {
        sharedLink->disconnect();
pixhawk's avatar
pixhawk committed
}

void LinkManager::_linkDisconnected(void)
    LinkInterface* link = qobject_cast<LinkInterface*>(sender());
Don Gagne's avatar
Don Gagne committed

    if (!link || !containsLink(link)) {
Don Gagne's avatar
Don Gagne committed
        return;
    }
Don Gagne's avatar
Don Gagne committed
    disconnect(link, &LinkInterface::communicationError,  _app,                &QGCApplication::criticalMessageBoxOnMainThread);
    disconnect(link, &LinkInterface::bytesReceived,       _mavlinkProtocol,    &MAVLinkProtocol::receiveBytes);
    disconnect(link, &LinkInterface::bytesSent,           _mavlinkProtocol,    &MAVLinkProtocol::logSentBytes);
    disconnect(link, &LinkInterface::disconnected,        this,                &LinkManager::_linkDisconnected);

    _freeMavlinkChannel(link->mavlinkChannel());
    for (int i=0; i<_rgLinks.count(); i++) {
        if (_rgLinks[i].get() == link) {
Don Gagne's avatar
Don Gagne committed
            qCDebug(LinkManagerLog) << "LinkManager::_linkDisconnected" << _rgLinks[i]->linkConfiguration()->name() << _rgLinks[i].use_count();
pixhawk's avatar
pixhawk committed
}

SharedLinkInterfacePtr LinkManager::sharedLinkInterfacePointerForLink(LinkInterface* link)
    for (int i=0; i<_rgLinks.count(); i++) {
        if (_rgLinks[i].get() == link) {
            return _rgLinks[i];
    qWarning() << "LinkManager::sharedLinkInterfaceForLink returning nullptr";
    return SharedLinkInterfacePtr(nullptr);
/// @brief If all new connections should be suspended a message is displayed to the user and true
///         is returned;
bool LinkManager::_connectionsSuspendedMsg(void)
{
    if (_connectionsSuspended) {
DoinLakeFlyer's avatar
 
DoinLakeFlyer committed
        qgcApp()->showAppMessage(tr("Connect not allowed: %1").arg(_connectionsSuspendedReason));
        return true;
    } else {
        return false;
    }
}

void LinkManager::setConnectionsSuspended(QString reason)
{
    _connectionsSuspended = true;
    _connectionsSuspendedReason = reason;
}
void LinkManager::suspendConfigurationUpdates(bool suspend)
{
    _configUpdateSuspended = suspend;
}

void LinkManager::saveLinkConfigurationList()
{
    QSettings settings;
    settings.remove(LinkConfiguration::settingsRoot());
    int trueCount = 0;
    for (int i = 0; i < _rgLinkConfigs.count(); i++) {
        SharedLinkConfigurationPtr linkConfig = _rgLinkConfigs[i];
Don Gagne's avatar
Don Gagne committed
        if (linkConfig) {
            if (!linkConfig->isDynamic()) {
Don Gagne's avatar
Don Gagne committed
                QString root = LinkConfiguration::settingsRoot();
                root += QString("/Link%1").arg(trueCount++);
Don Gagne's avatar
Don Gagne committed
                settings.setValue(root + "/name", linkConfig->name());
                settings.setValue(root + "/type", linkConfig->type());
                settings.setValue(root + "/auto", linkConfig->isAutoConnect());
                settings.setValue(root + "/high_latency", linkConfig->isHighLatency());
Don Gagne's avatar
Don Gagne committed
                // Have the instance save its own values
                linkConfig->saveSettings(settings, root);
            }
        } else {
            qWarning() << "Internal error for link configuration in LinkManager";
dogmaphobic's avatar
dogmaphobic committed
        }
dogmaphobic's avatar
dogmaphobic committed
    QString root(LinkConfiguration::settingsRoot());
    settings.setValue(root + "/count", trueCount);
}

void LinkManager::loadLinkConfigurationList()
{
    QSettings settings;
    // Is the group even there?
    if(settings.contains(LinkConfiguration::settingsRoot() + "/count")) {
        // Find out how many configurations we have
        int count = settings.value(LinkConfiguration::settingsRoot() + "/count").toInt();
        for(int i = 0; i < count; i++) {
            QString root(LinkConfiguration::settingsRoot());
            root += QString("/Link%1").arg(i);
            if(settings.contains(root + "/type")) {
                LinkConfiguration::LinkType type = static_cast<LinkConfiguration::LinkType>(settings.value(root + "/type").toInt());
                if(type < LinkConfiguration::TypeLast) {
                    if(settings.contains(root + "/name")) {
                        QString name = settings.value(root + "/name").toString();
                        if(!name.isEmpty()) {
                            LinkConfiguration* link = nullptr;
                            bool autoConnect = settings.value(root + "/auto").toBool();
                            bool highLatency = settings.value(root + "/high_latency").toBool();
                            switch(type) {
Gus Grubba's avatar
Gus Grubba committed
#ifndef NO_SERIAL_LINK
DonLakeFlyer's avatar
DonLakeFlyer committed
                            case LinkConfiguration::TypeSerial:
                                link = new SerialConfiguration(name);
DonLakeFlyer's avatar
DonLakeFlyer committed
                                break;
dogmaphobic's avatar
dogmaphobic committed
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
                            case LinkConfiguration::TypeUdp:
                                link = new UDPConfiguration(name);
DonLakeFlyer's avatar
DonLakeFlyer committed
                                break;
                            case LinkConfiguration::TypeTcp:
                                link = new TCPConfiguration(name);
DonLakeFlyer's avatar
DonLakeFlyer committed
                                break;
dogmaphobic's avatar
dogmaphobic committed
#ifdef QGC_ENABLE_BLUETOOTH
DonLakeFlyer's avatar
DonLakeFlyer committed
                            case LinkConfiguration::TypeBluetooth:
                                link = new BluetoothConfiguration(name);
DonLakeFlyer's avatar
DonLakeFlyer committed
                                break;
dogmaphobic's avatar
dogmaphobic committed
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
                            case LinkConfiguration::TypeLogReplay:
                                link = new LogReplayLinkConfiguration(name);
DonLakeFlyer's avatar
DonLakeFlyer committed
                                break;
#ifdef QT_DEBUG
DonLakeFlyer's avatar
DonLakeFlyer committed
                            case LinkConfiguration::TypeMock:
                                link = new MockConfiguration(name);
                                break;
DonLakeFlyer's avatar
DonLakeFlyer committed
                            case LinkConfiguration::TypeLast:
                                break;
                                //-- Have the instance load its own values
                                link->setAutoConnect(autoConnect);
                                link->setHighLatency(highLatency);
                                link->loadSettings(settings, root);
                                addConfiguration(link);
                            qWarning() << "Link Configuration" << root << "has an empty name." ;
                        qWarning() << "Link Configuration" << root << "has no name." ;
                    qWarning() << "Link Configuration" << root << "an invalid type: " << type;
                qWarning() << "Link Configuration" << root << "has no type." ;

    // Enable automatic Serial PX4/3DR Radio hunting
Gus Grubba's avatar
Gus Grubba committed
#ifndef NO_SERIAL_LINK
bool LinkManager::_portAlreadyConnected(const QString& portName)
Don Gagne's avatar
Don Gagne committed

    for (int i=0; i<_rgLinks.count(); i++) {
        SharedLinkConfigurationPtr linkConfig = _rgLinks[i]->linkConfiguration();
        SerialConfiguration* serialConfig = qobject_cast<SerialConfiguration*>(linkConfig.get());
        if (serialConfig) {
            if (serialConfig->portName() == searchPort) {
dogmaphobic's avatar
dogmaphobic committed
#endif
void LinkManager::_addUDPAutoConnectLink(void)
    if (_autoConnectSettings->autoConnectUDP()->rawValue().toBool()) {
        bool foundUDP = false;

        for (int i = 0; i < _rgLinks.count(); i++) {
            SharedLinkConfigurationPtr linkConfig = _rgLinks[i]->linkConfiguration();
            if (linkConfig->type() == LinkConfiguration::TypeUdp && linkConfig->name() == _defaultUDPLinkName) {
                foundUDP = true;
                break;
            }
Don Gagne's avatar
Don Gagne committed
        }
        if (!foundUDP) {
            qCDebug(LinkManagerLog) << "New auto-connect UDP port added";
            //-- Default UDPConfiguration is set up for autoconnect
            UDPConfiguration* udpConfig = new UDPConfiguration(_defaultUDPLinkName);
            udpConfig->setDynamic(true);
            SharedLinkConfigurationPtr config = addConfiguration(udpConfig);
            createConnectedLink(config);
void LinkManager::_addMAVLinkForwardingLink(void)
{
    if (_toolbox->settingsManager()->appSettings()->forwardMavlink()->rawValue().toBool()) {
        bool foundMAVLinkForwardingLink = false;
        for (int i=0; i<_rgLinks.count(); i++) {
            SharedLinkConfigurationPtr linkConfig = _rgLinks[i]->linkConfiguration();
            if (linkConfig->type() == LinkConfiguration::TypeUdp && linkConfig->name() == _mavlinkForwardingLinkName) {
                foundMAVLinkForwardingLink = true;
                // TODO: should we check if the host/port matches the mavlinkForwardHostName setting and update if it does not match?
                break;
            }
        }
        if (!foundMAVLinkForwardingLink) {
            qCDebug(LinkManagerLog) << "New MAVLink forwarding port added";
            UDPConfiguration* udpConfig = new UDPConfiguration(_mavlinkForwardingLinkName);
            udpConfig->setDynamic(true);
            QString hostName = _toolbox->settingsManager()->appSettings()->forwardMavlinkHostName()->rawValue().toString();
            udpConfig->addHost(hostName);

            SharedLinkConfigurationPtr config = addConfiguration(udpConfig);
            createConnectedLink(config);
        }
}

void LinkManager::_updateAutoConnectLinks(void)
{
    if (_connectionsSuspended || qgcApp()->runningUnitTests()) {
        return;
    }

    _addUDPAutoConnectLink();
    _addMAVLinkForwardingLink();
Don Gagne's avatar
 
Don Gagne committed
#ifndef NO_SERIAL_LINK
    // check to see if nmea gps is configured for UDP input, if so, set it up to connect
    if (_autoConnectSettings->autoConnectNmeaPort()->cookedValueString() == "UDP Port") {
        if (_nmeaSocket.localPort() != _autoConnectSettings->nmeaUdpPort()->rawValue().toUInt()
                || _nmeaSocket.state() != UdpIODevice::BoundState) {
            qCDebug(LinkManagerLog) << "Changing port for UDP NMEA stream";
            _nmeaSocket.close();
            _nmeaSocket.bind(QHostAddress::AnyIPv4, _autoConnectSettings->nmeaUdpPort()->rawValue().toUInt());
            _toolbox->qgcPositionManager()->setNmeaSourceDevice(&_nmeaSocket);
        }
        //close serial port
        if (_nmeaPort) {
            _nmeaPort->close();
            delete _nmeaPort;
            _nmeaPort = nullptr;
            _nmeaDeviceName = "";
        }
    } else {
        _nmeaSocket.close();
    }
#endif
Don Gagne's avatar
 
Don Gagne committed
#endif
Don Gagne's avatar
Don Gagne committed

Gus Grubba's avatar
Gus Grubba committed
#ifndef NO_SERIAL_LINK
    QStringList                 currentPorts;
    QList<QGCSerialPortInfo>    portList;
#ifdef __android__
    // Android builds only support a single serial connection. Repeatedly calling availablePorts after that one serial
    // port is connected leaks file handles due to a bug somewhere in android serial code. In order to work around that
    // bug after we connect the first serial port we stop probing for additional ports.
    if (!_isSerialPortConnected()) {
        portList = QGCSerialPortInfo::availablePorts();
    }
    else {
        qDebug() << "Skipping serial port list";
    }
#else
    portList = QGCSerialPortInfo::availablePorts();
Don Gagne's avatar
Don Gagne committed

    for (const QGCSerialPortInfo& portInfo: portList) {
Don Gagne's avatar
Don Gagne committed
        qCDebug(LinkManagerVerboseLog) << "-----------------------------------------------------";
        qCDebug(LinkManagerVerboseLog) << "portName:          " << portInfo.portName();
        qCDebug(LinkManagerVerboseLog) << "systemLocation:    " << portInfo.systemLocation();
        qCDebug(LinkManagerVerboseLog) << "description:       " << portInfo.description();
        qCDebug(LinkManagerVerboseLog) << "manufacturer:      " << portInfo.manufacturer();
        qCDebug(LinkManagerVerboseLog) << "serialNumber:      " << portInfo.serialNumber();
        qCDebug(LinkManagerVerboseLog) << "vendorIdentifier:  " << portInfo.vendorIdentifier();
        qCDebug(LinkManagerVerboseLog) << "productIdentifier: " << portInfo.productIdentifier();

dogmaphobic's avatar
dogmaphobic committed
        // Save port name
        currentPorts << portInfo.systemLocation();
        QGCSerialPortInfo::BoardType_t boardType;
        QString boardName;
#ifndef __mobile__
        // check to see if nmea gps is configured for current Serial port, if so, set it up to connect
        if (portInfo.systemLocation().trimmed() == _autoConnectSettings->autoConnectNmeaPort()->cookedValueString()) {
            if (portInfo.systemLocation().trimmed() != _nmeaDeviceName) {
                _nmeaDeviceName = portInfo.systemLocation().trimmed();
                qCDebug(LinkManagerLog) << "Configuring nmea port" << _nmeaDeviceName;
                QSerialPort* newPort = new QSerialPort(portInfo);
                _nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt();
                newPort->setBaudRate(static_cast<qint32>(_nmeaBaud));
                qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud;
                // This will stop polling old device if previously set
                _toolbox->qgcPositionManager()->setNmeaSourceDevice(newPort);
                if (_nmeaPort) {
                    delete _nmeaPort;
                }
                _nmeaPort = newPort;
            } else if (_autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt() != _nmeaBaud) {
                _nmeaBaud = _autoConnectSettings->autoConnectNmeaBaud()->cookedValue().toUInt();
                _nmeaPort->setBaudRate(static_cast<qint32>(_nmeaBaud));
                qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud;
            }
            if (portInfo.getBoardInfo(boardType, boardName)) {
                if (portInfo.isBootloader()) {
                    // Don't connect to bootloader
                    qCDebug(LinkManagerLog) << "Waiting for bootloader to finish" << portInfo.systemLocation();
Don Gagne's avatar
Don Gagne committed
                    continue;
dogmaphobic's avatar
dogmaphobic committed
                }
                if (_portAlreadyConnected(portInfo.systemLocation()) || _autoConnectRTKPort == portInfo.systemLocation()) {
                    qCDebug(LinkManagerVerboseLog) << "Skipping existing autoconnect" << portInfo.systemLocation();
                } else if (!_autoconnectPortWaitList.contains(portInfo.systemLocation())) {
                    // We don't connect to the port the first time we see it. The ability to correctly detect whether we
                    // are in the bootloader is flaky from a cross-platform standpoint. So by putting it on a wait list
                    // and only connect on the second pass we leave enough time for the board to boot up.
                    qCDebug(LinkManagerLog) << "Waiting for next autoconnect pass" << portInfo.systemLocation();
                    _autoconnectPortWaitList[portInfo.systemLocation()] = 1;
                } else if (++_autoconnectPortWaitList[portInfo.systemLocation()] * _autoconnectUpdateTimerMSecs > _autoconnectConnectDelayMSecs) {
                    SerialConfiguration* pSerialConfig = nullptr;
                    _autoconnectPortWaitList.remove(portInfo.systemLocation());
                    switch (boardType) {
                    case QGCSerialPortInfo::BoardTypePixhawk:
                        if (_autoConnectSettings->autoConnectPixhawk()->rawValue().toBool()) {
                            pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName).arg(portInfo.portName().trimmed()));
                            pSerialConfig->setUsbDirect(true);
                        }
                        break;
                    case QGCSerialPortInfo::BoardTypePX4Flow:
                        if (_autoConnectSettings->autoConnectPX4Flow()->rawValue().toBool()) {
                            pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName).arg(portInfo.portName().trimmed()));
                        break;
                    case QGCSerialPortInfo::BoardTypeSiKRadio:
                        if (_autoConnectSettings->autoConnectSiKRadio()->rawValue().toBool()) {
                            pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName).arg(portInfo.portName().trimmed()));
                        }
                        break;
                    case QGCSerialPortInfo::BoardTypeOpenPilot:
                        if (_autoConnectSettings->autoConnectLibrePilot()->rawValue().toBool()) {
                            pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName).arg(portInfo.portName().trimmed()));
                        }
                        break;
#ifndef __mobile__
                    case QGCSerialPortInfo::BoardTypeRTKGPS:
                        if (_autoConnectSettings->autoConnectRTKGPS()->rawValue().toBool() && !_toolbox->gpsManager()->connected()) {
                            qCDebug(LinkManagerLog) << "RTK GPS auto-connected" << portInfo.portName().trimmed();
                            _autoConnectRTKPort = portInfo.systemLocation();
                            _toolbox->gpsManager()->connectGPS(portInfo.systemLocation(), boardName);
                        }
                        break;
#endif
                    default:
                        qWarning() << "Internal error";
                        continue;
                    }
                    if (pSerialConfig) {
                        qCDebug(LinkManagerLog) << "New auto-connect port added: " << pSerialConfig->name() << portInfo.systemLocation();
                        pSerialConfig->setBaud      (boardType == QGCSerialPortInfo::BoardTypeSiKRadio ? 57600 : 115200);
                        pSerialConfig->setDynamic   (true);
                        pSerialConfig->setPortName  (portInfo.systemLocation());

                        SharedLinkConfigurationPtr  sharedConfig(pSerialConfig);
                        createConnectedLink(sharedConfig, boardType == QGCSerialPortInfo::BoardTypePX4Flow);
Don Gagne's avatar
Don Gagne committed
                }
    // Check for RTK GPS connection gone
    if (!_autoConnectRTKPort.isEmpty() && !currentPorts.contains(_autoConnectRTKPort)) {
        qCDebug(LinkManagerLog) << "RTK GPS disconnected" << _autoConnectRTKPort;
        _toolbox->gpsManager()->disconnectGPS();
        _autoConnectRTKPort.clear();
    }
Gus Grubba's avatar
Gus Grubba committed
#endif // NO_SERIAL_LINK
Don Gagne's avatar
Don Gagne committed
void LinkManager::shutdown(void)
{
    setConnectionsSuspended(tr("Shutdown"));
Don Gagne's avatar
Don Gagne committed
    disconnectAll();

    // Wait for all the vehicles to go away to ensure an orderly shutdown and deletion of all objects
    while (_toolbox->multiVehicleManager()->vehicles()->count()) {
        qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
    }
QStringList LinkManager::linkTypeStrings(void) const
{
    //-- Must follow same order as enum LinkType in LinkConfiguration.h
    static QStringList list;
    if(!list.size())
    {
Gus Grubba's avatar
Gus Grubba committed
#ifndef NO_SERIAL_LINK
        list += tr("Serial");
#endif
        list += tr("UDP");
        list += tr("TCP");
dogmaphobic's avatar
dogmaphobic committed
#ifdef QGC_ENABLE_BLUETOOTH
dogmaphobic's avatar
dogmaphobic committed
        list += "Bluetooth";
#endif
dogmaphobic's avatar
dogmaphobic committed
#ifdef QT_DEBUG
        list += tr("Mock Link");
dogmaphobic's avatar
dogmaphobic committed
#endif
#ifndef __mobile__
        list += tr("Log Replay");
dogmaphobic's avatar
dogmaphobic committed
#endif
        if (list.size() != static_cast<int>(LinkConfiguration::TypeLast)) {
DonLakeFlyer's avatar
DonLakeFlyer committed
            qWarning() << "Internal error";
        }
void LinkManager::_updateSerialPorts()
    _commPortList.clear();
    _commPortDisplayList.clear();
Gus Grubba's avatar
Gus Grubba committed
#ifndef NO_SERIAL_LINK
    QList<QSerialPortInfo> portList = QSerialPortInfo::availablePorts();
    for (const QSerialPortInfo &info: portList)
        QString port = info.systemLocation().trimmed();
        _commPortList += port;
        _commPortDisplayList += SerialConfiguration::cleanPortDisplayname(port);
}

QStringList LinkManager::serialPortStrings(void)
{
    if(!_commPortDisplayList.size())
    {
        _updateSerialPorts();
    }
    return _commPortDisplayList;
}

QStringList LinkManager::serialPorts(void)
{
    if(!_commPortList.size())
    {
        _updateSerialPorts();
    }
    return _commPortList;
}

QStringList LinkManager::serialBaudRates(void)
{
Gus Grubba's avatar
Gus Grubba committed
#ifdef NO_SERIAL_LINK
    QStringList foo;
    return foo;
#else
    return SerialConfiguration::supportedBaudRates();
#endif
}

bool LinkManager::endConfigurationEditing(LinkConfiguration* config, LinkConfiguration* editedConfig)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
    if (config && editedConfig) {
        _fixUnnamed(editedConfig);
        config->copyFrom(editedConfig);
        saveLinkConfigurationList();
        emit config->nameChanged(config->name());
DonLakeFlyer's avatar
DonLakeFlyer committed
        // Discard temporary duplicate
        delete editedConfig;
    } else {
        qWarning() << "Internal error";
    }
    return true;
}

bool LinkManager::endCreateConfiguration(LinkConfiguration* config)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
    if (config) {
        _fixUnnamed(config);
        addConfiguration(config);
        saveLinkConfigurationList();
    } else {
        qWarning() << "Internal error";
    }
    return true;
}

LinkConfiguration* LinkManager::createConfiguration(int type, const QString& name)
{
Gus Grubba's avatar
Gus Grubba committed
#ifndef NO_SERIAL_LINK
    if(static_cast<LinkConfiguration::LinkType>(type) == LinkConfiguration::TypeSerial)
        _updateSerialPorts();
dogmaphobic's avatar
dogmaphobic committed
#endif
    return LinkConfiguration::createSettings(type, name);
}

LinkConfiguration* LinkManager::startConfigurationEditing(LinkConfiguration* config)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
    if (config) {
Gus Grubba's avatar
Gus Grubba committed
#ifndef NO_SERIAL_LINK
DonLakeFlyer's avatar
DonLakeFlyer committed
        if(config->type() == LinkConfiguration::TypeSerial)
            _updateSerialPorts();
dogmaphobic's avatar
dogmaphobic committed
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
        return LinkConfiguration::duplicateSettings(config);
    } else {
        qWarning() << "Internal error";
        return nullptr;
DonLakeFlyer's avatar
DonLakeFlyer committed
    }
}

void LinkManager::_fixUnnamed(LinkConfiguration* config)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
    if (config) {
        //-- Check for "Unnamed"
        if (config->name() == "Unnamed") {
            switch(config->type()) {
Gus Grubba's avatar
Gus Grubba committed
#ifndef NO_SERIAL_LINK
            case LinkConfiguration::TypeSerial: {
                QString tname = dynamic_cast<SerialConfiguration*>(config)->portName();
#ifdef Q_OS_WIN
                tname.replace("\\\\.\\", "");
#else
                tname.replace("/dev/cu.", "");
                tname.replace("/dev/", "");
#endif
                config->setName(QString("Serial Device on %1").arg(tname));
                break;
DonLakeFlyer's avatar
DonLakeFlyer committed
            }
#endif
            case LinkConfiguration::TypeUdp:
                config->setName(
                            QString("UDP Link on Port %1").arg(dynamic_cast<UDPConfiguration*>(config)->localPort()));
                break;
            case LinkConfiguration::TypeTcp: {
DonLakeFlyer's avatar
DonLakeFlyer committed
                TCPConfiguration* tconfig = dynamic_cast<TCPConfiguration*>(config);
                if(tconfig) {
                    config->setName(
                                QString("TCP Link %1:%2").arg(tconfig->address().toString()).arg(static_cast<int>(tconfig->port())));
DonLakeFlyer's avatar
DonLakeFlyer committed
            }
dogmaphobic's avatar
dogmaphobic committed
#ifdef QGC_ENABLE_BLUETOOTH
dogmaphobic's avatar
dogmaphobic committed
            case LinkConfiguration::TypeBluetooth: {
DonLakeFlyer's avatar
DonLakeFlyer committed
                BluetoothConfiguration* tconfig = dynamic_cast<BluetoothConfiguration*>(config);
                if(tconfig) {
                    config->setName(QString("%1 (Bluetooth Device)").arg(tconfig->device().name));
dogmaphobic's avatar
dogmaphobic committed
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
            }
dogmaphobic's avatar
dogmaphobic committed
                break;
#endif
            case LinkConfiguration::TypeLogReplay: {
DonLakeFlyer's avatar
DonLakeFlyer committed
                LogReplayLinkConfiguration* tconfig = dynamic_cast<LogReplayLinkConfiguration*>(config);
                if(tconfig) {
                    config->setName(QString("Log Replay %1").arg(tconfig->logFilenameShort()));
DonLakeFlyer's avatar
DonLakeFlyer committed
            }
                break;
#ifdef QT_DEBUG
            case LinkConfiguration::TypeMock:
                config->setName(QString("Mock Link"));
                break;
#endif
            case LinkConfiguration::TypeLast:
                break;
DonLakeFlyer's avatar
DonLakeFlyer committed
            }
DonLakeFlyer's avatar
DonLakeFlyer committed
    } else {
        qWarning() << "Internal error";
    }
}

void LinkManager::removeConfiguration(LinkConfiguration* config)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
    if (config) {
        LinkInterface* link = config->link();
        if (link) {
            link->disconnect();
DonLakeFlyer's avatar
DonLakeFlyer committed
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
        _removeConfiguration(config);
        saveLinkConfigurationList();
    } else {
        qWarning() << "Internal error";
    }
void LinkManager::_removeConfiguration(LinkConfiguration* config)
    _qmlConfigurations.removeOne(config);
    for (int i=0; i<_rgLinkConfigs.count(); i++) {
        if (_rgLinkConfigs[i].get() == config) {
            _rgLinkConfigs.removeAt(i);
            return;
    qWarning() << "LinkManager::_removeConfiguration called with unknown config";
dogmaphobic's avatar
dogmaphobic committed

bool LinkManager::isBluetoothAvailable(void)
{
    return qgcApp()->isBluetoothAvailable();
}
bool LinkManager::containsLink(LinkInterface* link)
{
    for (int i=0; i<_rgLinks.count(); i++) {
        if (_rgLinks[i].get() == link) {
SharedLinkConfigurationPtr LinkManager::addConfiguration(LinkConfiguration* config)
{
    _qmlConfigurations.append(config);
    _rgLinkConfigs.append(SharedLinkConfigurationPtr(config));
    return _rgLinkConfigs.last();

void LinkManager::startAutoConnectedLinks(void)
{
    SharedLinkConfigurationPtr conf;
    for(int i = 0; i < _rgLinkConfigs.count(); i++) {
        conf = _rgLinkConfigs[i];
        if (conf->isAutoConnect())
            createConnectedLink(conf);
    }
}

int LinkManager::_reserveMavlinkChannel(void)
{
    // Find a mavlink channel to use for this link, Channel 0 is reserved for internal use.
Don Gagne's avatar
 
Don Gagne committed
    for (uint8_t mavlinkChannel = 1; mavlinkChannel < MAVLINK_COMM_NUM_BUFFERS; mavlinkChannel++) {
        if (!(_mavlinkChannelsUsedBitMask & 1 << mavlinkChannel)) {
            mavlink_reset_channel_status(mavlinkChannel);
            // Start the channel on Mav 1 protocol
            mavlink_status_t* mavlinkStatus = mavlink_get_channel_status(mavlinkChannel);
            mavlinkStatus->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
            _mavlinkChannelsUsedBitMask |= 1 << mavlinkChannel;
            return mavlinkChannel;
        }
    }
    return 0;   // All channels reserved
}

void LinkManager::_freeMavlinkChannel(int channel)
{
    _mavlinkChannelsUsedBitMask &= ~(1 << channel);
}
Don Gagne's avatar
 
Don Gagne committed
LogReplayLink* LinkManager::startLogReplay(const QString& logFile)
{
    LogReplayLinkConfiguration* linkConfig = new LogReplayLinkConfiguration(tr("Log Replay"));
    linkConfig->setLogFilename(logFile);
    linkConfig->setName(linkConfig->logFilenameShort());

    SharedLinkConfigurationPtr sharedConfig = addConfiguration(linkConfig);
    if (createConnectedLink(sharedConfig)) {
        return qobject_cast<LogReplayLink*>(sharedConfig->link());
    } else {
        return nullptr;
    }
}

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

    return false;
Don Gagne's avatar
 
Don Gagne committed
}