LinkManager.cc 37 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"
24
#include "LogReplayLink.h"
dogmaphobic's avatar
dogmaphobic committed
25
#ifdef QGC_ENABLE_BLUETOOTH
dogmaphobic's avatar
dogmaphobic committed
26 27
#include "BluetoothLink.h"
#endif
28

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

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

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

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

47 48
LinkManager::LinkManager(QGCApplication* app, QGCToolbox* toolbox)
    : QGCTool(app, toolbox)
49 50 51
    , _configUpdateSuspended(false)
    , _configurationsLoaded(false)
    , _connectionsSuspended(false)
52
    , _mavlinkChannelsUsedBitMask(1)    // We never use channel 0 to avoid sequence numbering problems
53 54
    , _autoConnectSettings(nullptr)
    , _mavlinkProtocol(nullptr)
55
#ifndef __mobile__
56
#ifndef NO_SERIAL_LINK
57
    , _nmeaPort(nullptr)
58
#endif
59
#endif
pixhawk's avatar
pixhawk committed
60
{
Don Gagne's avatar
Don Gagne committed
61 62 63 64
    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
65
#ifndef NO_SERIAL_LINK
Don Gagne's avatar
Don Gagne committed
66 67 68
    _activeLinkCheckTimer.setInterval(_activeLinkCheckTimeoutMSecs);
    _activeLinkCheckTimer.setSingleShot(false);
    connect(&_activeLinkCheckTimer, &QTimer::timeout, this, &LinkManager::_activeLinkCheck);
Don Gagne's avatar
Don Gagne committed
69
#endif
pixhawk's avatar
pixhawk committed
70 71 72 73
}

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

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

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

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

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

93 94
}

Don Gagne's avatar
Don Gagne committed
95 96 97 98 99 100 101 102 103 104
// 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);
    }
}

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

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

Don Gagne's avatar
Don Gagne committed
161
LinkInterface* LinkManager::createConnectedLink(const QString& name)
162
{
DonLakeFlyer's avatar
DonLakeFlyer committed
163 164 165 166 167 168 169 170 171
    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);
            }
        }
172
    }
173
    return nullptr;
174 175
}

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

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

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

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

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

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

206 207 208 209 210 211
    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);
212
}
pixhawk's avatar
pixhawk committed
213

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

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

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

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

Don Gagne's avatar
Don Gagne committed
243
    LinkConfiguration* config = link->getLinkConfiguration();
244 245 246 247 248
    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;
249
        }
250
    }
251

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

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

    if (!link) {
        return;
    }
265

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

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

531 532
        QGCSerialPortInfo::BoardType_t boardType;
        QString boardName;
Don Gagne's avatar
Don Gagne committed
533

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

623 624 625
#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
626
    // bug after we connect the first serial port we stop probing for additional ports. That means we must rely on
627 628 629
    // 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
630 631
    // Now we go through the current configuration list and make sure any dynamic config has gone away
    QList<LinkConfiguration*>  _confToDelete;
632 633 634 635 636 637 638
    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()) {
639 640 641 642 643 644
                            // 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
645
                }
646
                _confToDelete.append(serialConfig);
dogmaphobic's avatar
dogmaphobic committed
647
            }
Don Gagne's avatar
Don Gagne committed
648 649
        } else {
            qWarning() << "Internal error";
dogmaphobic's avatar
dogmaphobic committed
650 651
        }
    }
Don Gagne's avatar
Don Gagne committed
652

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

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

676
#endif
Gus Grubba's avatar
Gus Grubba committed
677
#endif // NO_SERIAL_LINK
678 679
}

Don Gagne's avatar
Don Gagne committed
680 681
void LinkManager::shutdown(void)
{
682
    setConnectionsSuspended(tr("Shutdown"));
Don Gagne's avatar
Don Gagne committed
683
    disconnectAll();
Don Gagne's avatar
Don Gagne committed
684 685
}

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

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

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

QStringList LinkManager::serialPorts(void)
{
    if(!_commPortList.size())
    {
        _updateSerialPorts();
    }
743 744 745 746 747
    return _commPortList;
}

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

bool LinkManager::endConfigurationEditing(LinkConfiguration* config, LinkConfiguration* editedConfig)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
758 759 760 761 762 763 764 765 766 767 768
    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";
    }
769 770 771 772 773
    return true;
}

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

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

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

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

void LinkManager::removeConfiguration(LinkConfiguration* config)
{
DonLakeFlyer's avatar
DonLakeFlyer committed
870 871 872 873 874
    if (config) {
        LinkInterface* iface = config->link();
        if(iface) {
            disconnectLink(iface);
        }
875

DonLakeFlyer's avatar
DonLakeFlyer committed
876 877 878 879 880
        _removeConfiguration(config);
        saveLinkConfigurationList();
    } else {
        qWarning() << "Internal error";
    }
881
}
882

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

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

Gus Grubba's avatar
Gus Grubba committed
898
#ifndef NO_SERIAL_LINK
Don Gagne's avatar
Don Gagne committed
899 900
void LinkManager::_activeLinkCheck(void)
{
901
    SerialLink* link = nullptr;
Don Gagne's avatar
Don Gagne committed
902 903
    bool found = false;
    if (_activeLinkCheckList.count() != 0) {
904
        link = _activeLinkCheckList.takeFirst();
905
        if (containsLink(link) && link->isConnected()) {
Don Gagne's avatar
Don Gagne committed
906 907 908 909 910 911 912 913 914
            // 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;
                }
            }
915
        } else {
916
            link = nullptr;
Don Gagne's avatar
Don Gagne committed
917 918 919 920 921
        }
    }
    if (_activeLinkCheckList.count() == 0) {
        _activeLinkCheckTimer.stop();
    }
922 923 924
    if (!found && link) {
        // See if we can get an NSH prompt on this link
        bool foundNSHPrompt = false;
925
        link->writeBytesSafe("\r", 1);
926 927 928
        QSignalSpy spy(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)));
        if (spy.wait(100)) {
            QList<QVariant> arguments = spy.takeFirst();
929
            if (arguments[1].toByteArray().contains("nsh>")) {
930 931 932
                foundNSHPrompt = true;
            }
        }
933 934 935 936
        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
937 938
    }
}
Don Gagne's avatar
Don Gagne committed
939
#endif
940 941 942 943 944 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

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;
}
978 979 980 981 982 983 984 985 986 987

void LinkManager::startAutoConnectedLinks(void)
{
    SharedLinkConfigurationPointer conf;
    for(int i = 0; i < _sharedConfigurations.count(); i++) {
        conf = _sharedConfigurations[i];
        if (conf->isAutoConnect())
            createConnectedLink(conf);
    }
}
988 989 990 991

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

1010 1011
void LinkManager::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message) {
    link->startMavlinkMessagesTimer(message.sysid);
1012
}
1013 1014 1015 1016 1017 1018 1019 1020 1021 1022

LogReplayLink* LinkManager::startLogReplay(const QString& logFile)
{
    LogReplayLinkConfiguration* linkConfig = new LogReplayLinkConfiguration(tr("Log Replay"));
    linkConfig->setLogFilename(logFile);
    linkConfig->setName(linkConfig->logFilenameShort());

    SharedLinkConfigurationPointer sharedConfig = addConfiguration(linkConfig);
    return qobject_cast<LogReplayLink*>(createConnectedLink(sharedConfig));
}