LinkManager.cc 19.9 KB
Newer Older
pixhawk's avatar
pixhawk committed
1
/*=====================================================================
lm's avatar
lm committed
2 3 4

QGroundControl Open Source Ground Control Station

5
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
lm's avatar
lm committed
6 7 8 9

This file is part of the QGROUNDCONTROL project

    QGROUNDCONTROL is free software: you can redistribute it and/or modify
pixhawk's avatar
pixhawk committed
10 11 12
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.
lm's avatar
lm committed
13 14

    QGROUNDCONTROL is distributed in the hope that it will be useful,
pixhawk's avatar
pixhawk committed
15 16 17
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.
lm's avatar
lm committed
18

pixhawk's avatar
pixhawk committed
19
    You should have received a copy of the GNU General Public License
lm's avatar
lm committed
20 21
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.

pixhawk's avatar
pixhawk committed
22
======================================================================*/
23

pixhawk's avatar
pixhawk committed
24 25 26 27 28 29 30 31 32 33
/**
 * @file
 *   @brief Brief Description
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#include <QList>
#include <QApplication>
34
#include <QDebug>
dogmaphobic's avatar
dogmaphobic committed
35 36

#ifndef __ios__
dogmaphobic's avatar
dogmaphobic committed
37 38 39
#ifdef __android__
#include "qserialportinfo.h"
#else
40
#include <QSerialPortInfo>
dogmaphobic's avatar
dogmaphobic committed
41
#endif
dogmaphobic's avatar
dogmaphobic committed
42
#endif
43

44 45
#include "LinkManager.h"
#include "MainWindow.h"
Don Gagne's avatar
Don Gagne committed
46
#include "QGCMessageBox.h"
47
#include "QGCApplication.h"
48
#include "SerialPortIds.h"
49

Don Gagne's avatar
Don Gagne committed
50
IMPLEMENT_QGC_SINGLETON(LinkManager, LinkManager)
Don Gagne's avatar
Don Gagne committed
51
QGC_LOGGING_CATEGORY(LinkManagerLog, "LinkManagerLog")
52

pixhawk's avatar
pixhawk committed
53 54
/**
 * @brief Private singleton constructor
55
 *
pixhawk's avatar
pixhawk committed
56 57
 * This class implements the singleton design pattern and has therefore only a private constructor.
 **/
58 59 60 61 62
LinkManager::LinkManager(QObject* parent)
    : QGCSingleton(parent)
    , _configUpdateSuspended(false)
    , _configurationsLoaded(false)
    , _connectionsSuspended(false)
63
    , _mavlinkChannelsUsedBitMask(0)
64
    , _nullSharedLink(NULL)
pixhawk's avatar
pixhawk committed
65
{
dogmaphobic's avatar
dogmaphobic committed
66
#ifndef __ios__
67 68
    connect(&_portListTimer, &QTimer::timeout, this, &LinkManager::_updateConfigurationList);
    _portListTimer.start(1000);
dogmaphobic's avatar
dogmaphobic committed
69
#endif
pixhawk's avatar
pixhawk committed
70 71 72 73
}

LinkManager::~LinkManager()
{
74 75 76 77 78 79
    // Clear configuration list
    while(_linkConfigurations.count()) {
        LinkConfiguration* pLink = _linkConfigurations.at(0);
        if(pLink) delete pLink;
        _linkConfigurations.removeAt(0);
    }
80
    Q_ASSERT_X(_links.count() == 0, "LinkManager", "LinkManager::_shutdown should have been called previously");
pixhawk's avatar
pixhawk committed
81 82
}

83
LinkInterface* LinkManager::createConnectedLink(LinkConfiguration* config)
84 85 86 87
{
    Q_ASSERT(config);
    LinkInterface* pLink = NULL;
    switch(config->type()) {
dogmaphobic's avatar
dogmaphobic committed
88
#ifndef __ios__
89 90 91
        case LinkConfiguration::TypeSerial:
            pLink = new SerialLink(dynamic_cast<SerialConfiguration*>(config));
            break;
dogmaphobic's avatar
dogmaphobic committed
92
#endif
93 94 95
        case LinkConfiguration::TypeUdp:
            pLink = new UDPLink(dynamic_cast<UDPConfiguration*>(config));
            break;
96 97 98
        case LinkConfiguration::TypeTcp:
            pLink = new TCPLink(dynamic_cast<TCPConfiguration*>(config));
            break;
99
#ifdef QT_DEBUG
100 101 102
        case LinkConfiguration::TypeMock:
            pLink = new MockLink(dynamic_cast<MockConfiguration*>(config));
            break;
103
#endif
104 105
    }
    if(pLink) {
106 107
        _addLink(pLink);
        connectLink(pLink);
108 109 110 111
    }
    return pLink;
}

112
LinkInterface* LinkManager::createConnectedLink(const QString& name)
113 114 115 116 117
{
    Q_ASSERT(name.isEmpty() == false);
    for(int i = 0; i < _linkConfigurations.count(); i++) {
        LinkConfiguration* conf = _linkConfigurations.at(i);
        if(conf && conf->name() == name)
118
            return createConnectedLink(conf);
119 120 121 122
    }
    return NULL;
}

123
void LinkManager::_addLink(LinkInterface* link)
pixhawk's avatar
pixhawk committed
124
{
125
    Q_ASSERT(link);
126

127
    _linkListMutex.lock();
128

129
    if (!containsLink(link)) {
130 131 132
        // Find a mavlink channel to use for this link
        for (int i=0; i<32; i++) {
            if (!(_mavlinkChannelsUsedBitMask && 1 << i)) {
133
                mavlink_reset_channel_status(i);
134 135 136 137 138 139
                link->_setMavlinkChannel(i);
                _mavlinkChannelsUsedBitMask |= i << i;
                break;
            }
        }
        
140
        _links.append(QSharedPointer<LinkInterface>(link));
141
        _linkListMutex.unlock();
142
        emit newLink(link);
143
    } else {
144
        _linkListMutex.unlock();
145
    }
146

147 148
    // MainWindow may be around when doing things like running unit tests
    if (MainWindow::instance()) {
149
        connect(link, &LinkInterface::communicationError, qgcApp(), &QGCApplication::criticalMessageBoxOnMainThread);
150
    }
151

152 153 154 155 156
    MAVLinkProtocol* mavlink = MAVLinkProtocol::instance();
    connect(link, &LinkInterface::bytesReceived, mavlink, &MAVLinkProtocol::receiveBytes);
    connect(link, &LinkInterface::connected, mavlink, &MAVLinkProtocol::linkConnected);
    connect(link, &LinkInterface::disconnected, mavlink, &MAVLinkProtocol::linkDisconnected);
    mavlink->resetMetadataForLink(link);
157

158 159
    connect(link, &LinkInterface::connected, this, &LinkManager::_linkConnected);
    connect(link, &LinkInterface::disconnected, this, &LinkManager::_linkDisconnected);
160
}
pixhawk's avatar
pixhawk committed
161 162 163

bool LinkManager::connectAll()
{
164 165 166
    if (_connectionsSuspendedMsg()) {
        return false;
    }
167

168 169
    bool allConnected = true;

170 171 172
    foreach (SharedLinkInterface sharedLink, _links) {
        Q_ASSERT(sharedLink.data());
        if (!sharedLink.data()->_connect()) {
173 174
            allConnected = false;
        }
175 176 177
    }

    return allConnected;
pixhawk's avatar
pixhawk committed
178 179 180 181
}

bool LinkManager::disconnectAll()
{
182 183
    bool allDisconnected = true;

184 185 186 187
    // Make a copy so the list is modified out from under us
    QList<SharedLinkInterface> links = _links;

    foreach (SharedLinkInterface sharedLink, links) {
188
        Q_ASSERT(sharedLink.data());
189
        if (!disconnectLink(sharedLink.data())) {
190 191
            allDisconnected = false;
        }
192 193 194
    }

    return allDisconnected;
pixhawk's avatar
pixhawk committed
195 196 197 198
}

bool LinkManager::connectLink(LinkInterface* link)
{
199
    Q_ASSERT(link);
200

201 202 203 204
    if (_connectionsSuspendedMsg()) {
        return false;
    }

205 206 207 208 209
    if (link->_connect()) {
        return true;
    } else {
        return false;
    }
pixhawk's avatar
pixhawk committed
210 211 212 213
}

bool LinkManager::disconnectLink(LinkInterface* link)
{
214
    Q_ASSERT(link);
215
    if (link->_disconnect()) {
216 217 218 219
        LinkConfiguration* config = link->getLinkConfiguration();
        if(config) {
            config->setLink(NULL);
        }
220
        _deleteLink(link);
221 222 223 224
        return true;
    } else {
        return false;
    }
pixhawk's avatar
pixhawk committed
225 226
}

227
void LinkManager::_deleteLink(LinkInterface* link)
228
{
229
    Q_ASSERT(link);
230

231
    _linkListMutex.lock();
232 233 234
    
    // Free up the mavlink channel associated with this link
    _mavlinkChannelsUsedBitMask &= ~(1 << link->getMavlinkChannel());
235

236 237 238 239 240 241 242 243
    bool found = false;
    for (int i=0; i<_links.count(); i++) {
        if (_links[i].data() == link) {
            _links.removeAt(i);
            found = true;
            break;
        }
    }
244
    Q_UNUSED(found);
245
    Q_ASSERT(found);
246

247
    _linkListMutex.unlock();
248

Don Gagne's avatar
Don Gagne committed
249
    // Emit removal of link
250
    emit linkDeleted(link);
pixhawk's avatar
pixhawk committed
251 252 253 254 255 256 257
}

/**
 *
 */
const QList<LinkInterface*> LinkManager::getLinks()
{
258 259 260 261
    QList<LinkInterface*> list;
    
    foreach (SharedLinkInterface sharedLink, _links) {
        list << sharedLink.data();
262
    }
263 264
    
    return list;
265
}
266 267 268 269 270 271

/// @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) {
Don Gagne's avatar
Don Gagne committed
272 273
        QGCMessageBox::information(tr("Connect not allowed"),
                                   tr("Connect not allowed: %1").arg(_connectionsSuspendedReason));
274 275 276 277 278 279 280 281 282 283 284 285
        return true;
    } else {
        return false;
    }
}

void LinkManager::setConnectionsSuspended(QString reason)
{
    _connectionsSuspended = true;
    _connectionsSuspendedReason = reason;
    Q_ASSERT(!reason.isEmpty());
}
286 287 288

void LinkManager::_shutdown(void)
{
289 290
    while (_links.count() != 0) {
        disconnectLink(_links[0].data());
291 292
    }
}
293 294 295 296 297 298 299 300 301 302

void LinkManager::_linkConnected(void)
{
    emit linkConnected((LinkInterface*)sender());
}

void LinkManager::_linkDisconnected(void)
{
    emit linkDisconnected((LinkInterface*)sender());
}
303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342

void LinkManager::addLinkConfiguration(LinkConfiguration* link)
{
    Q_ASSERT(link != NULL);
    //-- If not there already, add it
    int idx = _linkConfigurations.indexOf(link);
    if(idx < 0)
    {
        _linkConfigurations.append(link);
    }
}

void LinkManager::removeLinkConfiguration(LinkConfiguration *link)
{
    Q_ASSERT(link != NULL);
    int idx = _linkConfigurations.indexOf(link);
    if(idx >= 0)
    {
        _linkConfigurations.removeAt(idx);
        delete link;
    }
}

const QList<LinkConfiguration*> LinkManager::getLinkConfigurationList()
{
    return _linkConfigurations;
}

void LinkManager::suspendConfigurationUpdates(bool suspend)
{
    _configUpdateSuspended = suspend;
}

void LinkManager::saveLinkConfigurationList()
{
    QSettings settings;
    settings.remove(LinkConfiguration::settingsRoot());
    int index = 0;
    foreach (LinkConfiguration* pLink, _linkConfigurations) {
        Q_ASSERT(pLink != NULL);
dogmaphobic's avatar
dogmaphobic committed
343 344 345 346 347 348 349 350 351 352
        if(!pLink->isDynamic())
        {
            QString root = LinkConfiguration::settingsRoot();
            root += QString("/Link%1").arg(index++);
            settings.setValue(root + "/name", pLink->name());
            settings.setValue(root + "/type", pLink->type());
            settings.setValue(root + "/preferred", pLink->isPreferred());
            // Have the instance save its own values
            pLink->saveSettings(settings, root);
        }
353
    }
dogmaphobic's avatar
dogmaphobic committed
354
    QString root(LinkConfiguration::settingsRoot());
355
    settings.setValue(root + "/count", index);
356 357 358 359 360
    emit linkConfigurationChanged();
}

void LinkManager::loadLinkConfigurationList()
{
361 362
    bool udpExists = false;
    bool linksChanged = false;
363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382
    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")) {
                int type = settings.value(root + "/type").toInt();
                if(type < LinkConfiguration::TypeLast) {
                    if(settings.contains(root + "/name")) {
                        QString name = settings.value(root + "/name").toString();
                        if(!name.isEmpty()) {
                            bool preferred = false;
                            if(settings.contains(root + "/preferred")) {
                                preferred = settings.value(root + "/preferred").toBool();
                            }
                            LinkConfiguration* pLink = NULL;
                            switch(type) {
dogmaphobic's avatar
dogmaphobic committed
383
#ifndef __ios__
384 385 386 387
                                case LinkConfiguration::TypeSerial:
                                    pLink = (LinkConfiguration*)new SerialConfiguration(name);
                                    pLink->setPreferred(preferred);
                                    break;
dogmaphobic's avatar
dogmaphobic committed
388
#endif
389 390 391 392
                                case LinkConfiguration::TypeUdp:
                                    pLink = (LinkConfiguration*)new UDPConfiguration(name);
                                    pLink->setPreferred(preferred);
                                    break;
393 394 395 396
                                case LinkConfiguration::TypeTcp:
                                    pLink = (LinkConfiguration*)new TCPConfiguration(name);
                                    pLink->setPreferred(preferred);
                                    break;
397
#ifdef QT_DEBUG
398 399 400 401
                                case LinkConfiguration::TypeMock:
                                    pLink = (LinkConfiguration*)new MockConfiguration(name);
                                    pLink->setPreferred(false);
                                    break;
402
#endif
403 404 405 406 407
                            }
                            if(pLink) {
                                // Have the instance load its own values
                                pLink->loadSettings(settings, root);
                                addLinkConfiguration(pLink);
408 409 410 411 412 413 414 415
                                linksChanged = true;
                                // Check for UDP links
                                if(pLink->type() == LinkConfiguration::TypeUdp) {
                                    UDPConfiguration* uLink = dynamic_cast<UDPConfiguration*>(pLink);
                                    if(uLink && uLink->localPort() == QGC_UDP_LOCAL_PORT) {
                                        udpExists = true;
                                    }
                                }
416 417 418 419 420 421 422 423 424 425 426 427 428 429 430
                            }
                        } else {
                            qWarning() << "Link Configuration " << root << " has an empty name." ;
                        }
                    } else {
                        qWarning() << "Link Configuration " << root << " has no name." ;
                    }
                } else {
                    qWarning() << "Link Configuration " << root << " an invalid type: " << type;
                }
            } else {
                qWarning() << "Link Configuration " << root << " has no type." ;
            }
        }
    }
431 432 433 434 435 436
    
    // Debug buids always add MockLink automatically
#ifdef QT_DEBUG
    MockConfiguration* pMock = new MockConfiguration("Mock Link");
    pMock->setDynamic(true);
    addLinkConfiguration(pMock);
437
    linksChanged = true;
438
#endif
439 440 441 442 443 444 445 446 447

    //-- If we don't have a configured UDP link, create a default one
    if(!udpExists) {
        UDPConfiguration* uLink = new UDPConfiguration("Default UDP Link");
        uLink->setLocalPort(QGC_UDP_LOCAL_PORT);
        uLink->setDynamic();
        addLinkConfiguration(uLink);
        linksChanged = true;
    }
448
    
449 450 451 452
    if(linksChanged) {
        emit linkConfigurationChanged();
    }
    // Enable automatic Serial PX4/3DR Radio hunting
453 454 455
    _configurationsLoaded = true;
}

dogmaphobic's avatar
dogmaphobic committed
456
#ifndef __ios__
457 458 459 460 461 462 463 464 465 466 467 468 469 470
SerialConfiguration* LinkManager::_findSerialConfiguration(const QString& portName)
{
    QString searchPort = portName.trimmed();
    foreach (LinkConfiguration* pLink, _linkConfigurations) {
        Q_ASSERT(pLink != NULL);
        if(pLink->type() == LinkConfiguration::TypeSerial) {
            SerialConfiguration* pSerial = dynamic_cast<SerialConfiguration*>(pLink);
            if(pSerial->portName() == searchPort) {
                return pSerial;
            }
        }
    }
    return NULL;
}
dogmaphobic's avatar
dogmaphobic committed
471
#endif
472

dogmaphobic's avatar
dogmaphobic committed
473
#ifndef __ios__
474 475 476 477 478 479
void LinkManager::_updateConfigurationList(void)
{
    if (_configUpdateSuspended || !_configurationsLoaded) {
        return;
    }
    bool saveList = false;
dogmaphobic's avatar
dogmaphobic committed
480
    QStringList currentPorts;
481 482 483
    QList<QSerialPortInfo> portList = QSerialPortInfo::availablePorts();
    // Iterate Comm Ports
    foreach (QSerialPortInfo portInfo, portList) {
Don Gagne's avatar
Don Gagne committed
484 485
#if 0
        // Too noisy for most logging, so turn on as needed
Don Gagne's avatar
Don Gagne committed
486 487 488 489 490 491 492
        qCDebug(LinkManagerLog) << "-----------------------------------------------------";
        qCDebug(LinkManagerLog) << "portName:         " << portInfo.portName();
        qCDebug(LinkManagerLog) << "systemLocation:   " << portInfo.systemLocation();
        qCDebug(LinkManagerLog) << "description:      " << portInfo.description();
        qCDebug(LinkManagerLog) << "manufacturer:     " << portInfo.manufacturer();
        qCDebug(LinkManagerLog) << "serialNumber:     " << portInfo.serialNumber();
        qCDebug(LinkManagerLog) << "vendorIdentifier: " << portInfo.vendorIdentifier();
Don Gagne's avatar
Don Gagne committed
493
#endif
dogmaphobic's avatar
dogmaphobic committed
494 495
        // Save port name
        currentPorts << portInfo.systemLocation();
496
        // Is this a PX4 and NOT in bootloader mode?
497
        if (portInfo.vendorIdentifier() == SerialPortIds::px4VendorId && !portInfo.description().contains("BL")) {
498
            SerialConfiguration* pSerial = _findSerialConfiguration(portInfo.systemLocation());
499 500 501 502 503 504 505 506
            if (pSerial) {
                //-- If this port is configured make sure it has the preferred flag set
                if(!pSerial->isPreferred()) {
                    pSerial->setPreferred(true);
                    saveList = true;
                }
            } else {
                // Lets create a new Serial configuration automatically
dogmaphobic's avatar
dogmaphobic committed
507 508
                if (portInfo.description() == "AeroCore") {
                    pSerial = new SerialConfiguration(QString("AeroCore on %1").arg(portInfo.portName().trimmed()));
Don Gagne's avatar
Don Gagne committed
509 510
                } else if (portInfo.description().contains("PX4Flow")) {
                    pSerial = new SerialConfiguration(QString("PX4Flow on %1").arg(portInfo.portName().trimmed()));
dogmaphobic's avatar
dogmaphobic committed
511 512 513 514 515
                } else if (portInfo.description().contains("PX4")) {
                    pSerial = new SerialConfiguration(QString("Pixhawk on %1").arg(portInfo.portName().trimmed()));
                } else {
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
516
                pSerial->setDynamic(true);
517 518
                pSerial->setPreferred(true);
                pSerial->setBaud(115200);
519
                pSerial->setPortName(portInfo.systemLocation());
520 521 522 523
                addLinkConfiguration(pSerial);
                saveList = true;
            }
        }
dogmaphobic's avatar
dogmaphobic committed
524
        // Is this an FTDI Chip? It could be a 3DR Modem
525
        if (portInfo.vendorIdentifier() == SerialPortIds::threeDRRadioVendorId && portInfo.productIdentifier() == SerialPortIds::threeDRRadioProductId) {
dogmaphobic's avatar
dogmaphobic committed
526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551
            SerialConfiguration* pSerial = _findSerialConfiguration(portInfo.systemLocation());
            if (pSerial) {
                //-- If this port is configured make sure it has the preferred flag set, unless someone else already has it set.
                if(!pSerial->isPreferred() && !saveList) {
                    pSerial->setPreferred(true);
                    saveList = true;
                }
            } else {
                // Lets create a new Serial configuration automatically (an assumption at best)
                pSerial = new SerialConfiguration(QString("3DR Radio on %1").arg(portInfo.portName().trimmed()));
                pSerial->setDynamic(true);
                pSerial->setPreferred(true);
                pSerial->setBaud(57600);
                pSerial->setPortName(portInfo.systemLocation());
                addLinkConfiguration(pSerial);
                saveList = true;
            }
        }
    }
    // Now we go through the current configuration list and make sure any dynamic config has gone away
    QList<LinkConfiguration*>  _confToDelete;
    foreach (LinkConfiguration* pLink, _linkConfigurations) {
        Q_ASSERT(pLink != NULL);
        // We only care about dynamic links
        if(pLink->isDynamic()) {
            if(pLink->type() == LinkConfiguration::TypeSerial) {
552 553 554 555 556 557
                // Don't mess with connected link. Let it deal with the disapearing device.
                if(pLink->getLink() == NULL) {
                    SerialConfiguration* pSerial = dynamic_cast<SerialConfiguration*>(pLink);
                    if(!currentPorts.contains(pSerial->portName())) {
                        _confToDelete.append(pSerial);
                    }
dogmaphobic's avatar
dogmaphobic committed
558 559 560 561 562 563 564 565
                }
            }
        }
    }
    // Now remove all links that are gone
    foreach (LinkConfiguration* pDelete, _confToDelete) {
        removeLinkConfiguration(pDelete);
        saveList = true;
566 567 568 569 570 571
    }
    // Save configuration list, which will also trigger a signal for the UI
    if(saveList) {
        saveLinkConfigurationList();
    }
}
dogmaphobic's avatar
dogmaphobic committed
572
#endif
573

574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608
bool LinkManager::containsLink(LinkInterface* link)
{
    bool found = false;
    foreach (SharedLinkInterface sharedLink, _links) {
        if (sharedLink.data() == link) {
            found = true;
            break;
        }
    }
    return found;
}

bool LinkManager::anyConnectedLinks(void)
{
    bool found = false;
    foreach (SharedLinkInterface sharedLink, _links) {
        if (sharedLink.data()->isConnected()) {
            found = true;
            break;
        }
    }
    return found;
}

SharedLinkInterface& LinkManager::sharedPointerForLink(LinkInterface* link)
{
    for (int i=0; i<_links.count(); i++) {
        if (_links[i].data() == link) {
            return _links[i];
        }
    }
    // This should never happen
    Q_ASSERT(false);
    return _nullSharedLink;
}