LinkManager.cc 36.6 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 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.
 *
 ****************************************************************************/
lm's avatar
lm committed
9

pixhawk's avatar
pixhawk committed
10 11
#include <QList>
#include <QApplication>
12
#include <QDebug>
13
#include <QSignalSpy>
dogmaphobic's avatar
dogmaphobic committed
14

Gus Grubba's avatar
Gus Grubba committed
15
#ifndef NO_SERIAL_LINK
Don Gagne's avatar
Don Gagne committed
16
#include "QGCSerialPortInfo.h"
dogmaphobic's avatar
dogmaphobic committed
17
#endif
18

19
#include "LinkManager.h"
20
#include "QGCApplication.h"
Don Gagne's avatar
Don Gagne committed
21 22
#include "UDPLink.h"
#include "TCPLink.h"
23
#include "SettingsManager.h"
dogmaphobic's avatar
dogmaphobic committed
24
#ifdef QGC_ENABLE_BLUETOOTH
dogmaphobic's avatar
dogmaphobic committed
25 26
#include "BluetoothLink.h"
#endif
27

Don Gagne's avatar
Don Gagne committed
28
#ifndef __mobile__
DonLakeFlyer's avatar
DonLakeFlyer committed
29
#include "GPSManager.h"
30
#include "PositionManager.h"
Don Gagne's avatar
Don Gagne committed
31 32
#endif

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

Don Gagne's avatar
Don Gagne committed
36
const char* LinkManager::_defaultUPDLinkName =       "UDP Link (AutoConnect)";
37

38 39 40 41 42 43 44 45
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

46 47
LinkManager::LinkManager(QGCApplication* app, QGCToolbox* toolbox)
    : QGCTool(app, toolbox)
48 49 50
    , _configUpdateSuspended(false)
    , _configurationsLoaded(false)
    , _connectionsSuspended(false)
51
    , _mavlinkChannelsUsedBitMask(1)    // We never use channel 0 to avoid sequence numbering problems
52 53
    , _autoConnectSettings(nullptr)
    , _mavlinkProtocol(nullptr)
54
#ifndef __mobile__
55
#ifndef NO_SERIAL_LINK
56
    , _nmeaPort(nullptr)
57
#endif
58
#endif
pixhawk's avatar
pixhawk committed
59
{
Don Gagne's avatar
Don Gagne committed
60 61 62 63
    qmlRegisterUncreatableType<LinkManager>         ("QGroundControl", 1, 0, "LinkManager",         "Reference only");
    qmlRegisterUncreatableType<LinkConfiguration>   ("QGroundControl", 1, 0, "LinkConfiguration",   "Reference only");
    qmlRegisterUncreatableType<LinkInterface>       ("QGroundControl", 1, 0, "LinkInterface",       "Reference only");

Gus Grubba's avatar
Gus Grubba committed
64
#ifndef NO_SERIAL_LINK
Don Gagne's avatar
Don Gagne committed
65 66 67
    _activeLinkCheckTimer.setInterval(_activeLinkCheckTimeoutMSecs);
    _activeLinkCheckTimer.setSingleShot(false);
    connect(&_activeLinkCheckTimer, &QTimer::timeout, this, &LinkManager::_activeLinkCheck);
Don Gagne's avatar
Don Gagne committed
68
#endif
pixhawk's avatar
pixhawk committed
69 70 71 72
}

LinkManager::~LinkManager()
{
73
#ifndef __mobile__
74
#ifndef NO_SERIAL_LINK
75
    delete _nmeaPort;
76
#endif
77
#endif
pixhawk's avatar
pixhawk committed
78 79
}

80 81
void LinkManager::setToolbox(QGCToolbox *toolbox)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
82
    QGCTool::setToolbox(toolbox);
83

DonLakeFlyer's avatar
DonLakeFlyer committed
84 85
    _autoConnectSettings = toolbox->settingsManager()->autoConnectSettings();
    _mavlinkProtocol = _toolbox->mavlinkProtocol();
86

87
    connect(_mavlinkProtocol, &MAVLinkProtocol::messageReceived, this, &LinkManager::_mavlinkMessageReceived);
88

Don Gagne's avatar
Don Gagne committed
89
    connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateAutoConnectLinks);
90
    _portListTimer.start(_autoconnectUpdateTimerMSecs); // timeout must be long enough to get past bootloader on second pass
91

92 93
}

Don Gagne's avatar
Don Gagne committed
94 95 96 97 98 99 100 101 102 103
// This should only be used by Qml code
void LinkManager::createConnectedLink(LinkConfiguration* config)
{
    for(int i = 0; i < _sharedConfigurations.count(); i++) {
        SharedLinkConfigurationPointer& sharedConf = _sharedConfigurations[i];
        if (sharedConf->name() == config->name())
            createConnectedLink(sharedConf);
    }
}

104
LinkInterface* LinkManager::createConnectedLink(SharedLinkConfigurationPointer& config, bool isPX4Flow)
105
{
106
    if (!config) {
107 108
        qWarning() << "LinkManager::createConnectedLink called with nullptr config";
        return nullptr;
109 110
    }

111
    LinkInterface* pLink = nullptr;
112
    switch(config->type()) {
Gus Grubba's avatar
Gus Grubba committed
113
#ifndef NO_SERIAL_LINK
DonLakeFlyer's avatar
DonLakeFlyer committed
114 115 116 117
    case LinkConfiguration::TypeSerial:
    {
        SerialConfiguration* serialConfig = dynamic_cast<SerialConfiguration*>(config.data());
        if (serialConfig) {
118
            pLink = new SerialLink(config, isPX4Flow);
DonLakeFlyer's avatar
DonLakeFlyer committed
119
            if (serialConfig->usbDirect()) {
120
                _activeLinkCheckList.append(dynamic_cast<SerialLink*>(pLink));
DonLakeFlyer's avatar
DonLakeFlyer committed
121 122
                if (!_activeLinkCheckTimer.isActive()) {
                    _activeLinkCheckTimer.start();
Don Gagne's avatar
Don Gagne committed
123 124 125
                }
            }
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
126
    }
Don Gagne's avatar
Don Gagne committed
127
        break;
DonLakeFlyer's avatar
DonLakeFlyer committed
128 129
#else
    Q_UNUSED(isPX4Flow)
dogmaphobic's avatar
dogmaphobic committed
130
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
131 132 133 134 135 136
    case LinkConfiguration::TypeUdp:
        pLink = new UDPLink(config);
        break;
    case LinkConfiguration::TypeTcp:
        pLink = new TCPLink(config);
        break;
dogmaphobic's avatar
dogmaphobic committed
137
#ifdef QGC_ENABLE_BLUETOOTH
DonLakeFlyer's avatar
DonLakeFlyer committed
138 139 140
    case LinkConfiguration::TypeBluetooth:
        pLink = new BluetoothLink(config);
        break;
dogmaphobic's avatar
dogmaphobic committed
141
#endif
dogmaphobic's avatar
dogmaphobic committed
142
#ifndef __mobile__
DonLakeFlyer's avatar
DonLakeFlyer committed
143 144 145
    case LinkConfiguration::TypeLogReplay:
        pLink = new LogReplayLink(config);
        break;
dogmaphobic's avatar
dogmaphobic committed
146
#endif
147
#ifdef QT_DEBUG
DonLakeFlyer's avatar
DonLakeFlyer committed
148 149 150
    case LinkConfiguration::TypeMock:
        pLink = new MockLink(config);
        break;
151
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
152 153
    case LinkConfiguration::TypeLast:
        break;
154
    }
155
    if (pLink) {
156 157
        _addLink(pLink);
        connectLink(pLink);
158 159 160 161
    }
    return pLink;
}

Don Gagne's avatar
Don Gagne committed
162
LinkInterface* LinkManager::createConnectedLink(const QString& name)
163
{
DonLakeFlyer's avatar
DonLakeFlyer committed
164 165 166 167 168 169 170 171 172
    if (name.isEmpty()) {
        qWarning() << "Internal error";
    } else {
        for(int i = 0; i < _sharedConfigurations.count(); i++) {
            SharedLinkConfigurationPointer& conf = _sharedConfigurations[i];
            if (conf->name() == name) {
                return createConnectedLink(conf);
            }
        }
173
    }
174
    return nullptr;
175 176
}

177
void LinkManager::_addLink(LinkInterface* link)
pixhawk's avatar
pixhawk committed
178
{
Don Gagne's avatar
Don Gagne committed
179
    if (thread() != QThread::currentThread()) {
180
        qWarning() << "_addLink called from incorrect thread";
Don Gagne's avatar
Don Gagne committed
181 182
        return;
    }
183

Don Gagne's avatar
Don Gagne committed
184 185 186
    if (!link) {
        return;
    }
187

188
    if (!containsLink(link)) {
189 190 191 192
        int mavlinkChannel = _reserveMavlinkChannel();
        if (mavlinkChannel != 0) {
            link->_setMavlinkChannel(mavlinkChannel);
        } else {
193
            qWarning() << "Ran out of mavlink channels";
194
            return;
195 196
        }

197
        _sharedLinks.append(SharedLinkInterfacePointer(link));
198 199
        emit newLink(link);
    }
200

Don Gagne's avatar
Don Gagne committed
201 202
    connect(link, &LinkInterface::communicationError,   _app,               &QGCApplication::criticalMessageBoxOnMainThread);
    connect(link, &LinkInterface::bytesReceived,        _mavlinkProtocol,   &MAVLinkProtocol::receiveBytes);
203

204
    _mavlinkProtocol->resetMetadataForLink(link);
205
    _mavlinkProtocol->setVersion(_mavlinkProtocol->getCurrentVersion());
206

207 208 209 210 211 212
    connect(link, &LinkInterface::connected,            this, &LinkManager::_linkConnected);
    connect(link, &LinkInterface::disconnected,         this, &LinkManager::_linkDisconnected);

    // This connection is queued since it will cloe the link. So we want the link emitter to return otherwise we would
    // close the link our from under itself.
    connect(link, &LinkInterface::connectionRemoved,    this, &LinkManager::_linkConnectionRemoved, Qt::QueuedConnection);
213
}
pixhawk's avatar
pixhawk committed
214

Don Gagne's avatar
Don Gagne committed
215
void LinkManager::disconnectAll(void)
pixhawk's avatar
pixhawk committed
216
{
Don Gagne's avatar
Don Gagne committed
217
    // Walk list in reverse order to preserve indices during delete
218 219
    for (int i=_sharedLinks.count()-1; i>=0; i--) {
        disconnectLink(_sharedLinks[i].data());
220
    }
pixhawk's avatar
pixhawk committed
221 222 223 224
}

bool LinkManager::connectLink(LinkInterface* link)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
225 226 227 228 229 230 231
    if (link) {
        if (_connectionsSuspendedMsg()) {
            return false;
        }
        return link->_connect();
    } else {
        qWarning() << "Internal error";
232 233
        return false;
    }
pixhawk's avatar
pixhawk committed
234 235
}

Don Gagne's avatar
Don Gagne committed
236
void LinkManager::disconnectLink(LinkInterface* link)
pixhawk's avatar
pixhawk committed
237
{
238
    if (!link || !containsLink(link)) {
239 240
        return;
    }
Don Gagne's avatar
Don Gagne committed
241

Don Gagne's avatar
Don Gagne committed
242
    link->_disconnect();
243

Don Gagne's avatar
Don Gagne committed
244
    LinkConfiguration* config = link->getLinkConfiguration();
245 246 247 248 249
    for (int i=0; i<_sharedAutoconnectConfigurations.count(); i++) {
        if (_sharedAutoconnectConfigurations[i].data() == config) {
            qCDebug(LinkManagerLog) << "Removing disconnected autoconnect config" << config->name();
            _sharedAutoconnectConfigurations.removeAt(i);
            break;
250
        }
251
    }
252

Don Gagne's avatar
Don Gagne committed
253
    _deleteLink(link);
pixhawk's avatar
pixhawk committed
254 255
}

256
void LinkManager::_deleteLink(LinkInterface* link)
257
{
Don Gagne's avatar
Don Gagne committed
258 259 260 261 262 263 264 265
    if (thread() != QThread::currentThread()) {
        qWarning() << "_deleteLink called from incorrect thread";
        return;
    }

    if (!link) {
        return;
    }
266

267
    // Free up the mavlink channel associated with this link
268
    _freeMavlinkChannel(link->mavlinkChannel());
269

270 271 272 273 274 275
    for (int i=0; i<_sharedLinks.count(); i++) {
        if (_sharedLinks[i].data() == link) {
            _sharedLinks.removeAt(i);
            break;
        }
    }
276

Don Gagne's avatar
Don Gagne committed
277
    // Emit removal of link
278
    emit linkDeleted(link);
pixhawk's avatar
pixhawk committed
279 280
}

281 282 283 284 285 286 287 288
SharedLinkInterfacePointer LinkManager::sharedLinkInterfacePointerForLink(LinkInterface* link)
{
    for (int i=0; i<_sharedLinks.count(); i++) {
        if (_sharedLinks[i].data() == link) {
            return _sharedLinks[i];
        }
    }

289 290
    qWarning() << "LinkManager::sharedLinkInterfaceForLink returning nullptr";
    return SharedLinkInterfacePointer(nullptr);
291 292
}

293 294 295 296 297
/// @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) {
298
        qgcApp()->showMessage(tr("Connect not allowed: %1").arg(_connectionsSuspendedReason));
299 300 301 302 303 304 305 306 307 308 309
        return true;
    } else {
        return false;
    }
}

void LinkManager::setConnectionsSuspended(QString reason)
{
    _connectionsSuspended = true;
    _connectionsSuspendedReason = reason;
}
310

311 312 313 314 315 316 317 318 319
void LinkManager::_linkConnected(void)
{
    emit linkConnected((LinkInterface*)sender());
}

void LinkManager::_linkDisconnected(void)
{
    emit linkDisconnected((LinkInterface*)sender());
}
320

321 322 323 324 325 326
void LinkManager::_linkConnectionRemoved(LinkInterface* link)
{
    // Link has been removed from system, disconnect it automatically
    disconnectLink(link);
}

327 328 329 330 331 332 333 334 335
void LinkManager::suspendConfigurationUpdates(bool suspend)
{
    _configUpdateSuspended = suspend;
}

void LinkManager::saveLinkConfigurationList()
{
    QSettings settings;
    settings.remove(LinkConfiguration::settingsRoot());
336
    int trueCount = 0;
337 338
    for (int i = 0; i < _sharedConfigurations.count(); i++) {
        SharedLinkConfigurationPointer linkConfig = _sharedConfigurations[i];
Don Gagne's avatar
Don Gagne committed
339
        if (linkConfig) {
340
            if (!linkConfig->isDynamic()) {
Don Gagne's avatar
Don Gagne committed
341
                QString root = LinkConfiguration::settingsRoot();
342
                root += QString("/Link%1").arg(trueCount++);
Don Gagne's avatar
Don Gagne committed
343 344
                settings.setValue(root + "/name", linkConfig->name());
                settings.setValue(root + "/type", linkConfig->type());
345
                settings.setValue(root + "/auto", linkConfig->isAutoConnect());
346
                settings.setValue(root + "/high_latency", linkConfig->isHighLatency());
Don Gagne's avatar
Don Gagne committed
347 348 349 350
                // Have the instance save its own values
                linkConfig->saveSettings(settings, root);
            }
        } else {
351
            qWarning() << "Internal error for link configuration in LinkManager";
dogmaphobic's avatar
dogmaphobic committed
352
        }
353
    }
dogmaphobic's avatar
dogmaphobic committed
354
    QString root(LinkConfiguration::settingsRoot());
355 356
    settings.setValue(root + "/count", trueCount);
    emit linkConfigurationsChanged();
357 358 359 360
}

void LinkManager::loadLinkConfigurationList()
{
361
    bool linksChanged = false;
362 363 364 365 366 367 368 369 370
    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")) {
371 372
                LinkConfiguration::LinkType type = static_cast<LinkConfiguration::LinkType>(settings.value(root + "/type").toInt());
                if(type < LinkConfiguration::TypeLast) {
373 374 375
                    if(settings.contains(root + "/name")) {
                        QString name = settings.value(root + "/name").toString();
                        if(!name.isEmpty()) {
376
                            LinkConfiguration* pLink = nullptr;
377
                            bool autoConnect = settings.value(root + "/auto").toBool();
378
                            bool highLatency = settings.value(root + "/high_latency").toBool();
379
                            switch(type) {
Gus Grubba's avatar
Gus Grubba committed
380
#ifndef NO_SERIAL_LINK
DonLakeFlyer's avatar
DonLakeFlyer committed
381
                            case LinkConfiguration::TypeSerial:
382
                                pLink = dynamic_cast<LinkConfiguration*>(new SerialConfiguration(name));
DonLakeFlyer's avatar
DonLakeFlyer committed
383
                                break;
dogmaphobic's avatar
dogmaphobic committed
384
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
385
                            case LinkConfiguration::TypeUdp:
386
                                pLink = dynamic_cast<LinkConfiguration*>(new UDPConfiguration(name));
DonLakeFlyer's avatar
DonLakeFlyer committed
387 388
                                break;
                            case LinkConfiguration::TypeTcp:
389
                                pLink = dynamic_cast<LinkConfiguration*>(new TCPConfiguration(name));
DonLakeFlyer's avatar
DonLakeFlyer committed
390
                                break;
dogmaphobic's avatar
dogmaphobic committed
391
#ifdef QGC_ENABLE_BLUETOOTH
DonLakeFlyer's avatar
DonLakeFlyer committed
392
                            case LinkConfiguration::TypeBluetooth:
393
                                pLink = dynamic_cast<LinkConfiguration*>(new BluetoothConfiguration(name));
DonLakeFlyer's avatar
DonLakeFlyer committed
394
                                break;
dogmaphobic's avatar
dogmaphobic committed
395
#endif
dogmaphobic's avatar
dogmaphobic committed
396
#ifndef __mobile__
DonLakeFlyer's avatar
DonLakeFlyer committed
397
                            case LinkConfiguration::TypeLogReplay:
398
                                pLink = dynamic_cast<LinkConfiguration*>(new LogReplayLinkConfiguration(name));
DonLakeFlyer's avatar
DonLakeFlyer committed
399
                                break;
dogmaphobic's avatar
dogmaphobic committed
400
#endif
401
#ifdef QT_DEBUG
DonLakeFlyer's avatar
DonLakeFlyer committed
402
                            case LinkConfiguration::TypeMock:
403 404
                                pLink = dynamic_cast<LinkConfiguration*>(new MockConfiguration(name));
                                break;
405
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
406 407
                            case LinkConfiguration::TypeLast:
                                break;
408 409
                            }
                            if(pLink) {
410 411
                                //-- Have the instance load its own values
                                pLink->setAutoConnect(autoConnect);
412
                                pLink->setHighLatency(highLatency);
413
                                pLink->loadSettings(settings, root);
414
                                addConfiguration(pLink);
415
                                linksChanged = true;
416 417
                            }
                        } else {
418
                            qWarning() << "Link Configuration" << root << "has an empty name." ;
419 420
                        }
                    } else {
421
                        qWarning() << "Link Configuration" << root << "has no name." ;
422 423
                    }
                } else {
424
                    qWarning() << "Link Configuration" << root << "an invalid type: " << type;
425 426
                }
            } else {
427
                qWarning() << "Link Configuration" << root << "has no type." ;
428 429 430
            }
        }
    }
431 432

    if(linksChanged) {
433
        emit linkConfigurationsChanged();
434 435
    }
    // Enable automatic Serial PX4/3DR Radio hunting
436 437 438
    _configurationsLoaded = true;
}

Gus Grubba's avatar
Gus Grubba committed
439
#ifndef NO_SERIAL_LINK
Don Gagne's avatar
Don Gagne committed
440
SerialConfiguration* LinkManager::_autoconnectConfigurationsContainsPort(const QString& portName)
441 442
{
    QString searchPort = portName.trimmed();
Don Gagne's avatar
Don Gagne committed
443

444 445
    for (int i=0; i<_sharedAutoconnectConfigurations.count(); i++) {
        SerialConfiguration* serialConfig = qobject_cast<SerialConfiguration*>(_sharedAutoconnectConfigurations[i].data());
Don Gagne's avatar
Don Gagne committed
446

447 448 449
        if (serialConfig) {
            if (serialConfig->portName() == searchPort) {
                return serialConfig;
450
            }
Don Gagne's avatar
Don Gagne committed
451 452
        } else {
            qWarning() << "Internal error";
453 454
        }
    }
455
    return nullptr;
456
}
dogmaphobic's avatar
dogmaphobic committed
457
#endif
458

Don Gagne's avatar
Don Gagne committed
459
void LinkManager::_updateAutoConnectLinks(void)
460
{
Don Gagne's avatar
Don Gagne committed
461
    if (_connectionsSuspended || qgcApp()->runningUnitTests()) {
462 463
        return;
    }
Don Gagne's avatar
Don Gagne committed
464 465
    // Re-add UDP if we need to
    bool foundUDP = false;
466
    for (int i = 0; i < _sharedLinks.count(); i++) {
467
        LinkConfiguration* linkConfig = _sharedLinks[i]->getLinkConfiguration();
Don Gagne's avatar
Don Gagne committed
468 469 470 471 472
        if (linkConfig->type() == LinkConfiguration::TypeUdp && linkConfig->name() == _defaultUPDLinkName) {
            foundUDP = true;
            break;
        }
    }
473
    if (!foundUDP && _autoConnectSettings->autoConnectUDP()->rawValue().toBool()) {
Don Gagne's avatar
Don Gagne committed
474
        qCDebug(LinkManagerLog) << "New auto-connect UDP port added";
475
        //-- Default UDPConfiguration is set up for autoconnect
Don Gagne's avatar
Don Gagne committed
476
        UDPConfiguration* udpConfig = new UDPConfiguration(_defaultUPDLinkName);
DonLakeFlyer's avatar
DonLakeFlyer committed
477
        udpConfig->setDynamic(true);
478 479
        SharedLinkConfigurationPointer config = addConfiguration(udpConfig);
        createConnectedLink(config);
480
        emit linkConfigurationsChanged();
Don Gagne's avatar
Don Gagne committed
481
    }
482
#ifndef __mobile__
483
#ifndef NO_SERIAL_LINK
484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503
    // 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
504
#endif
Don Gagne's avatar
Don Gagne committed
505

Gus Grubba's avatar
Gus Grubba committed
506
#ifndef NO_SERIAL_LINK
dogmaphobic's avatar
dogmaphobic committed
507
    QStringList currentPorts;
508 509 510 511 512
    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.
513
    if (!_sharedAutoconnectConfigurations.count()) {
514 515
        portList = QGCSerialPortInfo::availablePorts();
    }
516 517
#else
    portList = QGCSerialPortInfo::availablePorts();
518
#endif
Don Gagne's avatar
Don Gagne committed
519

520
    // Iterate Comm Ports
521
    for (QGCSerialPortInfo portInfo: portList) {
Don Gagne's avatar
Don Gagne committed
522 523 524 525 526 527 528 529 530
        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
531 532
        // Save port name
        currentPorts << portInfo.systemLocation();
Don Gagne's avatar
Don Gagne committed
533

534 535
        QGCSerialPortInfo::BoardType_t boardType;
        QString boardName;
Don Gagne's avatar
Don Gagne committed
536

537
#ifndef NO_SERIAL_LINK
538
#ifndef __mobile__
539
        // check to see if nmea gps is configured for current Serial port, if so, set it up to connect
540 541 542 543 544 545
        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();
546
                newPort->setBaudRate(static_cast<qint32>(_nmeaBaud));
547 548 549 550 551 552 553 554 555
                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();
556
                _nmeaPort->setBaudRate(static_cast<qint32>(_nmeaBaud));
557 558
                qCDebug(LinkManagerLog) << "Configuring nmea baudrate" << _nmeaBaud;
            }
559
        } else
560
#endif
561 562
#endif
        if (portInfo.getBoardInfo(boardType, boardName)) {
Don Gagne's avatar
Don Gagne committed
563 564
            if (portInfo.isBootloader()) {
                // Don't connect to bootloader
565
                qCDebug(LinkManagerLog) << "Waiting for bootloader to finish" << portInfo.systemLocation();
Don Gagne's avatar
Don Gagne committed
566 567
                continue;
            }
568
            if (_autoconnectConfigurationsContainsPort(portInfo.systemLocation()) || _autoConnectRTKPort == portInfo.systemLocation()) {
569 570 571 572 573 574
                qCDebug(LinkManagerVerboseLog) << "Skipping existing autoconnect" << portInfo.systemLocation();
            } else if (!_autoconnectWaitList.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();
575 576
                _autoconnectWaitList[portInfo.systemLocation()] = 1;
            } else if (++_autoconnectWaitList[portInfo.systemLocation()] * _autoconnectUpdateTimerMSecs > _autoconnectConnectDelayMSecs) {
577
                SerialConfiguration* pSerialConfig = nullptr;
578
                _autoconnectWaitList.remove(portInfo.systemLocation());
Don Gagne's avatar
Don Gagne committed
579
                switch (boardType) {
580
                case QGCSerialPortInfo::BoardTypePixhawk:
581
                    if (_autoConnectSettings->autoConnectPixhawk()->rawValue().toBool()) {
582
                        pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName).arg(portInfo.portName().trimmed()));
583 584 585
                        pSerialConfig->setUsbDirect(true);
                    }
                    break;
Don Gagne's avatar
Don Gagne committed
586
                case QGCSerialPortInfo::BoardTypePX4Flow:
587
                    if (_autoConnectSettings->autoConnectPX4Flow()->rawValue().toBool()) {
588
                        pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName).arg(portInfo.portName().trimmed()));
Don Gagne's avatar
Don Gagne committed
589
                    }
Don Gagne's avatar
Don Gagne committed
590
                    break;
591
                case QGCSerialPortInfo::BoardTypeSiKRadio:
592
                    if (_autoConnectSettings->autoConnectSiKRadio()->rawValue().toBool()) {
593
                        pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName).arg(portInfo.portName().trimmed()));
Don Gagne's avatar
Don Gagne committed
594 595
                    }
                    break;
596
                case QGCSerialPortInfo::BoardTypeOpenPilot:
597
                    if (_autoConnectSettings->autoConnectLibrePilot()->rawValue().toBool()) {
598
                        pSerialConfig = new SerialConfiguration(tr("%1 on %2 (AutoConnect)").arg(boardName).arg(portInfo.portName().trimmed()));
599 600
                    }
                    break;
Don Gagne's avatar
Don Gagne committed
601 602
#ifndef __mobile__
                case QGCSerialPortInfo::BoardTypeRTKGPS:
603
                    if (_autoConnectSettings->autoConnectRTKGPS()->rawValue().toBool() && !_toolbox->gpsManager()->connected()) {
604 605
                        qCDebug(LinkManagerLog) << "RTK GPS auto-connected" << portInfo.portName().trimmed();
                        _autoConnectRTKPort = portInfo.systemLocation();
606
                        _toolbox->gpsManager()->connectGPS(portInfo.systemLocation(), boardName);
Don Gagne's avatar
Don Gagne committed
607 608 609
                    }
                    break;
#endif
Don Gagne's avatar
Don Gagne committed
610 611
                default:
                    qWarning() << "Internal error";
Don Gagne's avatar
Don Gagne committed
612
                    continue;
dogmaphobic's avatar
dogmaphobic committed
613
                }
Don Gagne's avatar
Don Gagne committed
614 615
                if (pSerialConfig) {
                    qCDebug(LinkManagerLog) << "New auto-connect port added: " << pSerialConfig->name() << portInfo.systemLocation();
616
                    pSerialConfig->setBaud(boardType == QGCSerialPortInfo::BoardTypeSiKRadio ? 57600 : 115200);
Don Gagne's avatar
Don Gagne committed
617 618
                    pSerialConfig->setDynamic(true);
                    pSerialConfig->setPortName(portInfo.systemLocation());
619
                    _sharedAutoconnectConfigurations.append(SharedLinkConfigurationPointer(pSerialConfig));
620
                    createConnectedLink(_sharedAutoconnectConfigurations.last(), boardType == QGCSerialPortInfo::BoardTypePX4Flow);
Don Gagne's avatar
Don Gagne committed
621
                }
dogmaphobic's avatar
dogmaphobic committed
622 623 624
            }
        }
    }
Don Gagne's avatar
Don Gagne committed
625

626 627 628
#ifndef __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
629
    // bug after we connect the first serial port we stop probing for additional ports. That means we must rely on
630 631 632
    // the port disconnecting itself when the radio is pulled to signal communication list as opposed to automatically
    // closing the Link.

dogmaphobic's avatar
dogmaphobic committed
633 634
    // Now we go through the current configuration list and make sure any dynamic config has gone away
    QList<LinkConfiguration*>  _confToDelete;
635 636 637 638 639 640 641
    for (int i=0; i<_sharedAutoconnectConfigurations.count(); i++) {
        SerialConfiguration* serialConfig = qobject_cast<SerialConfiguration*>(_sharedAutoconnectConfigurations[i].data());
        if (serialConfig) {
            if (!currentPorts.contains(serialConfig->portName())) {
                if (serialConfig->link()) {
                    if (serialConfig->link()->isConnected()) {
                        if (serialConfig->link()->active()) {
642 643 644 645 646 647
                            // We don't remove links which are still connected which have been active with a vehicle on them
                            // even though at this point the cable may have been pulled. Instead we wait for the user to
                            // Disconnect. Once the user disconnects, the link will be removed.
                            continue;
                        }
                    }
Don Gagne's avatar
Don Gagne committed
648
                }
649
                _confToDelete.append(serialConfig);
dogmaphobic's avatar
dogmaphobic committed
650
            }
Don Gagne's avatar
Don Gagne committed
651 652
        } else {
            qWarning() << "Internal error";
dogmaphobic's avatar
dogmaphobic committed
653 654
        }
    }
Don Gagne's avatar
Don Gagne committed
655

Don Gagne's avatar
Don Gagne committed
656
    // Now remove all configs that are gone
657
    for (LinkConfiguration* pDeleteConfig: _confToDelete) {
Don Gagne's avatar
Don Gagne committed
658
        qCDebug(LinkManagerLog) << "Removing unused autoconnect config" << pDeleteConfig->name();
Don Gagne's avatar
Don Gagne committed
659 660 661
        if (pDeleteConfig->link()) {
            disconnectLink(pDeleteConfig->link());
        }
662 663 664 665 666 667
        for (int i=0; i<_sharedAutoconnectConfigurations.count(); i++) {
            if (_sharedAutoconnectConfigurations[i].data() == pDeleteConfig) {
                _sharedAutoconnectConfigurations.removeAt(i);
                break;
            }
        }
668
    }
669 670

    // Check for RTK GPS connection gone
671
#if !defined(__mobile__)
672 673 674 675 676
    if (!_autoConnectRTKPort.isEmpty() && !currentPorts.contains(_autoConnectRTKPort)) {
        qCDebug(LinkManagerLog) << "RTK GPS disconnected" << _autoConnectRTKPort;
        _toolbox->gpsManager()->disconnectGPS();
        _autoConnectRTKPort.clear();
    }
677
#endif
678

679
#endif
Gus Grubba's avatar
Gus Grubba committed
680
#endif // NO_SERIAL_LINK
681 682
}

Don Gagne's avatar
Don Gagne committed
683 684
void LinkManager::shutdown(void)
{
685
    setConnectionsSuspended(tr("Shutdown"));
Don Gagne's avatar
Don Gagne committed
686
    disconnectAll();
Don Gagne's avatar
Don Gagne committed
687 688
}

689 690 691 692 693 694
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
695
#ifndef NO_SERIAL_LINK
696 697 698 699
        list += tr("Serial");
#endif
        list += tr("UDP");
        list += tr("TCP");
dogmaphobic's avatar
dogmaphobic committed
700
#ifdef QGC_ENABLE_BLUETOOTH
dogmaphobic's avatar
dogmaphobic committed
701 702
        list += "Bluetooth";
#endif
dogmaphobic's avatar
dogmaphobic committed
703
#ifdef QT_DEBUG
704
        list += tr("Mock Link");
dogmaphobic's avatar
dogmaphobic committed
705 706
#endif
#ifndef __mobile__
707
        list += tr("Log Replay");
dogmaphobic's avatar
dogmaphobic committed
708
#endif
709
        if (list.size() != static_cast<int>(LinkConfiguration::TypeLast)) {
DonLakeFlyer's avatar
DonLakeFlyer committed
710 711
            qWarning() << "Internal error";
        }
712 713 714 715
    }
    return list;
}

716
void LinkManager::_updateSerialPorts()
717
{
718 719
    _commPortList.clear();
    _commPortDisplayList.clear();
Gus Grubba's avatar
Gus Grubba committed
720
#ifndef NO_SERIAL_LINK
721
    QList<QSerialPortInfo> portList = QSerialPortInfo::availablePorts();
722
    for (const QSerialPortInfo &info: portList)
723
    {
724 725 726
        QString port = info.systemLocation().trimmed();
        _commPortList += port;
        _commPortDisplayList += SerialConfiguration::cleanPortDisplayname(port);
727 728
    }
#endif
729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745
}

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

QStringList LinkManager::serialPorts(void)
{
    if(!_commPortList.size())
    {
        _updateSerialPorts();
    }
746 747 748 749 750
    return _commPortList;
}

QStringList LinkManager::serialBaudRates(void)
{
Gus Grubba's avatar
Gus Grubba committed
751
#ifdef NO_SERIAL_LINK
752 753 754 755 756 757
    QStringList foo;
    return foo;
#else
    return SerialConfiguration::supportedBaudRates();
#endif
}
758 759 760

bool LinkManager::endConfigurationEditing(LinkConfiguration* config, LinkConfiguration* editedConfig)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
761 762 763 764 765 766 767 768 769 770 771
    if (config && editedConfig) {
        _fixUnnamed(editedConfig);
        config->copyFrom(editedConfig);
        saveLinkConfigurationList();
        // Tell link about changes (if any)
        config->updateSettings();
        // Discard temporary duplicate
        delete editedConfig;
    } else {
        qWarning() << "Internal error";
    }
772 773 774 775 776
    return true;
}

bool LinkManager::endCreateConfiguration(LinkConfiguration* config)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
777 778 779 780 781 782 783
    if (config) {
        _fixUnnamed(config);
        addConfiguration(config);
        saveLinkConfigurationList();
    } else {
        qWarning() << "Internal error";
    }
784 785 786 787 788
    return true;
}

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

LinkConfiguration* LinkManager::startConfigurationEditing(LinkConfiguration* config)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
798
    if (config) {
Gus Grubba's avatar
Gus Grubba committed
799
#ifndef NO_SERIAL_LINK
DonLakeFlyer's avatar
DonLakeFlyer committed
800 801
        if(config->type() == LinkConfiguration::TypeSerial)
            _updateSerialPorts();
dogmaphobic's avatar
dogmaphobic committed
802
#endif
DonLakeFlyer's avatar
DonLakeFlyer committed
803 804 805
        return LinkConfiguration::duplicateSettings(config);
    } else {
        qWarning() << "Internal error";
806
        return nullptr;
DonLakeFlyer's avatar
DonLakeFlyer committed
807
    }
808 809 810 811
}

void LinkManager::_fixUnnamed(LinkConfiguration* config)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
812 813 814 815
    if (config) {
        //-- Check for "Unnamed"
        if (config->name() == "Unnamed") {
            switch(config->type()) {
Gus Grubba's avatar
Gus Grubba committed
816
#ifndef NO_SERIAL_LINK
817 818
            case LinkConfiguration::TypeSerial: {
                QString tname = dynamic_cast<SerialConfiguration*>(config)->portName();
819
#ifdef Q_OS_WIN
820 821 822 823 824 825 826
                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
827
            }
828 829 830
#endif
            case LinkConfiguration::TypeUdp:
                config->setName(
831
                    QString("UDP Link on Port %1").arg(dynamic_cast<UDPConfiguration*>(config)->localPort()));
832 833
                break;
            case LinkConfiguration::TypeTcp: {
DonLakeFlyer's avatar
DonLakeFlyer committed
834 835 836
                TCPConfiguration* tconfig = dynamic_cast<TCPConfiguration*>(config);
                if(tconfig) {
                    config->setName(
837
                        QString("TCP Link %1:%2").arg(tconfig->address().toString()).arg(static_cast<int>(tconfig->port())));
838
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
839
            }
840
                break;
dogmaphobic's avatar
dogmaphobic committed
841
#ifdef QGC_ENABLE_BLUETOOTH
dogmaphobic's avatar
dogmaphobic committed
842
            case LinkConfiguration::TypeBluetooth: {
DonLakeFlyer's avatar
DonLakeFlyer committed
843 844 845
                BluetoothConfiguration* tconfig = dynamic_cast<BluetoothConfiguration*>(config);
                if(tconfig) {
                    config->setName(QString("%1 (Bluetooth Device)").arg(tconfig->device().name));
dogmaphobic's avatar
dogmaphobic committed
846
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
847
            }
dogmaphobic's avatar
dogmaphobic committed
848 849
                break;
#endif
dogmaphobic's avatar
dogmaphobic committed
850
#ifndef __mobile__
851
            case LinkConfiguration::TypeLogReplay: {
DonLakeFlyer's avatar
DonLakeFlyer committed
852 853 854
                LogReplayLinkConfiguration* tconfig = dynamic_cast<LogReplayLinkConfiguration*>(config);
                if(tconfig) {
                    config->setName(QString("Log Replay %1").arg(tconfig->logFilenameShort()));
855
                }
DonLakeFlyer's avatar
DonLakeFlyer committed
856
            }
857
                break;
dogmaphobic's avatar
dogmaphobic committed
858
#endif
859 860
#ifdef QT_DEBUG
            case LinkConfiguration::TypeMock:
861
                config->setName(QString("Mock Link"));
862 863 864 865
                break;
#endif
            case LinkConfiguration::TypeLast:
                break;
DonLakeFlyer's avatar
DonLakeFlyer committed
866
            }
867
        }
DonLakeFlyer's avatar
DonLakeFlyer committed
868 869
    } else {
        qWarning() << "Internal error";
870 871 872 873 874
    }
}

void LinkManager::removeConfiguration(LinkConfiguration* config)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
875 876 877 878 879
    if (config) {
        LinkInterface* iface = config->link();
        if(iface) {
            disconnectLink(iface);
        }
880

DonLakeFlyer's avatar
DonLakeFlyer committed
881 882 883 884 885
        _removeConfiguration(config);
        saveLinkConfigurationList();
    } else {
        qWarning() << "Internal error";
    }
886
}
887

888 889
bool LinkManager::isAutoconnectLink(LinkInterface* link)
{
890 891 892 893 894 895
    for (int i=0; i<_sharedAutoconnectConfigurations.count(); i++) {
        if (_sharedAutoconnectConfigurations[i].data() == link->getLinkConfiguration()) {
            return true;
        }
    }
    return false;
896
}
dogmaphobic's avatar
dogmaphobic committed
897 898 899 900 901

bool LinkManager::isBluetoothAvailable(void)
{
    return qgcApp()->isBluetoothAvailable();
}
Don Gagne's avatar
Don Gagne committed
902

Gus Grubba's avatar
Gus Grubba committed
903
#ifndef NO_SERIAL_LINK
Don Gagne's avatar
Don Gagne committed
904 905
void LinkManager::_activeLinkCheck(void)
{
906
    SerialLink* link = nullptr;
Don Gagne's avatar
Don Gagne committed
907 908
    bool found = false;
    if (_activeLinkCheckList.count() != 0) {
909
        link = _activeLinkCheckList.takeFirst();
910
        if (containsLink(link) && link->isConnected()) {
Don Gagne's avatar
Don Gagne committed
911 912 913 914 915 916 917 918 919
            // Make sure there is a vehicle on the link
            QmlObjectListModel* vehicles = _toolbox->multiVehicleManager()->vehicles();
            for (int i=0; i<vehicles->count(); i++) {
                Vehicle* vehicle = qobject_cast<Vehicle*>(vehicles->get(i));
                if (vehicle->containsLink(link)) {
                    found = true;
                    break;
                }
            }
920
        } else {
921
            link = nullptr;
Don Gagne's avatar
Don Gagne committed
922 923 924 925 926
        }
    }
    if (_activeLinkCheckList.count() == 0) {
        _activeLinkCheckTimer.stop();
    }
927 928 929
    if (!found && link) {
        // See if we can get an NSH prompt on this link
        bool foundNSHPrompt = false;
930
        link->writeBytesSafe("\r", 1);
931 932 933 934 935 936 937
        QSignalSpy spy(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)));
        if (spy.wait(100)) {
            QList<QVariant> arguments = spy.takeFirst();
            if (arguments[1].value<QByteArray>().contains("nsh>")) {
                foundNSHPrompt = true;
            }
        }
938 939 940 941
        qgcApp()->showMessage(
            foundNSHPrompt ?
                tr("Please check to make sure you have an SD Card inserted in your Vehicle and try again.") :
                tr("Your Vehicle is not responding. If this continues, shutdown %1, restart the Vehicle letting it boot completely, then start %1.").arg(qgcApp()->applicationName()));
Don Gagne's avatar
Don Gagne committed
942 943
    }
}
Don Gagne's avatar
Don Gagne committed
944
#endif
945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982

bool LinkManager::containsLink(LinkInterface* link)
{
    for (int i=0; i<_sharedLinks.count(); i++) {
        if (_sharedLinks[i].data() == link) {
            return true;
        }
    }
    return false;
}

SharedLinkConfigurationPointer LinkManager::addConfiguration(LinkConfiguration* config)
{
    _qmlConfigurations.append(config);
    _sharedConfigurations.append(SharedLinkConfigurationPointer(config));
    return _sharedConfigurations.last();
}

void LinkManager::_removeConfiguration(LinkConfiguration* config)
{
    _qmlConfigurations.removeOne(config);
    for (int i=0; i<_sharedConfigurations.count(); i++) {
        if (_sharedConfigurations[i].data() == config) {
            _sharedConfigurations.removeAt(i);
            return;
        }
    }
    qWarning() << "LinkManager::_removeConfiguration called with unknown config";
}

QList<LinkInterface*> LinkManager::links(void)
{
    QList<LinkInterface*> rawLinks;
    for (int i=0; i<_sharedLinks.count(); i++) {
        rawLinks.append(_sharedLinks[i].data());
    }
    return rawLinks;
}
983 984 985 986 987 988 989 990 991 992

void LinkManager::startAutoConnectedLinks(void)
{
    SharedLinkConfigurationPointer conf;
    for(int i = 0; i < _sharedConfigurations.count(); i++) {
        conf = _sharedConfigurations[i];
        if (conf->isAutoConnect())
            createConnectedLink(conf);
    }
}
993 994 995 996

int LinkManager::_reserveMavlinkChannel(void)
{
    // Find a mavlink channel to use for this link, Channel 0 is reserved for internal use.
997
    for (uint8_t mavlinkChannel = 1; mavlinkChannel < MAVLINK_COMM_NUM_BUFFERS; mavlinkChannel++) {
998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013
        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);
}
1014

1015 1016
void LinkManager::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message) {
    link->startMavlinkMessagesTimer(message.sysid);
1017
}