LinkManager.cc 19.7 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

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

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

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

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

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

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

126
    _linkListMutex.lock();
127

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

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

151 152 153 154 155
    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);
156

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

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

167 168
    bool allConnected = true;

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

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

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

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

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

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

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

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

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

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

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

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

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

246
    _linkListMutex.unlock();
247

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

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

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

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

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

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

void LinkManager::_linkDisconnected(void)
{
    emit linkDisconnected((LinkInterface*)sender());
}
302 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

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
342 343 344 345 346 347 348 349 350 351
        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);
        }
352
    }
dogmaphobic's avatar
dogmaphobic committed
353
    QString root(LinkConfiguration::settingsRoot());
354
    settings.setValue(root + "/count", index);
355 356 357 358 359
    emit linkConfigurationChanged();
}

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

    //-- 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;
    }
447
    
448 449 450 451
    if(linksChanged) {
        emit linkConfigurationChanged();
    }
    // Enable automatic Serial PX4/3DR Radio hunting
452 453 454
    _configurationsLoaded = true;
}

dogmaphobic's avatar
dogmaphobic committed
455
#ifndef __ios__
456 457 458 459 460 461 462 463 464 465 466 467 468 469
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
470
#endif
471

dogmaphobic's avatar
dogmaphobic committed
472
#ifndef __ios__
473 474 475 476 477 478
void LinkManager::_updateConfigurationList(void)
{
    if (_configUpdateSuspended || !_configurationsLoaded) {
        return;
    }
    bool saveList = false;
dogmaphobic's avatar
dogmaphobic committed
479
    QStringList currentPorts;
480 481 482
    QList<QSerialPortInfo> portList = QSerialPortInfo::availablePorts();
    // Iterate Comm Ports
    foreach (QSerialPortInfo portInfo, portList) {
Don Gagne's avatar
Don Gagne committed
483 484
#if 0
        // Too noisy for most logging, so turn on as needed
Don Gagne's avatar
Don Gagne committed
485 486 487 488 489 490 491
        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
492
#endif
dogmaphobic's avatar
dogmaphobic committed
493 494
        // Save port name
        currentPorts << portInfo.systemLocation();
495 496
        // Is this a PX4 and NOT in bootloader mode?
        if (portInfo.vendorIdentifier() == 9900 && !portInfo.description().contains("BL")) {
497
            SerialConfiguration* pSerial = _findSerialConfiguration(portInfo.systemLocation());
498 499 500 501 502 503 504 505
            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
506 507
                if (portInfo.description() == "AeroCore") {
                    pSerial = new SerialConfiguration(QString("AeroCore on %1").arg(portInfo.portName().trimmed()));
Don Gagne's avatar
Don Gagne committed
508 509
                } else if (portInfo.description().contains("PX4Flow")) {
                    pSerial = new SerialConfiguration(QString("PX4Flow on %1").arg(portInfo.portName().trimmed()));
dogmaphobic's avatar
dogmaphobic committed
510 511 512 513 514
                } else if (portInfo.description().contains("PX4")) {
                    pSerial = new SerialConfiguration(QString("Pixhawk on %1").arg(portInfo.portName().trimmed()));
                } else {
                    continue;
                }
dogmaphobic's avatar
dogmaphobic committed
515
                pSerial->setDynamic(true);
516 517
                pSerial->setPreferred(true);
                pSerial->setBaud(115200);
518
                pSerial->setPortName(portInfo.systemLocation());
519 520 521 522
                addLinkConfiguration(pSerial);
                saveList = true;
            }
        }
dogmaphobic's avatar
dogmaphobic committed
523 524 525 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
        // Is this an FTDI Chip? It could be a 3DR Modem
        if (portInfo.vendorIdentifier() == 1027) {
            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) {
551 552 553 554 555 556
                // 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
557 558 559 560 561 562 563 564
                }
            }
        }
    }
    // Now remove all links that are gone
    foreach (LinkConfiguration* pDelete, _confToDelete) {
        removeLinkConfiguration(pDelete);
        saveList = true;
565 566 567 568 569 570
    }
    // Save configuration list, which will also trigger a signal for the UI
    if(saveList) {
        saveLinkConfigurationList();
    }
}
dogmaphobic's avatar
dogmaphobic committed
571
#endif
572

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
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;
}