/*===================================================================== QGroundControl Open Source Ground Control Station (c) 2009, 2010 QGROUNDCONTROL PROJECT This file is part of the QGROUNDCONTROL project QGROUNDCONTROL is free software: you can redistribute it and/or modify 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. QGROUNDCONTROL is distributed in the hope that it will be useful, 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. You should have received a copy of the GNU General Public License along with QGROUNDCONTROL. If not, see . ======================================================================*/ /** * @file * @brief Brief Description * * @author Lorenz Meier * */ #include #include #include #include "LinkManager.h" #include "MainWindow.h" #include "QGCMessageBox.h" #include "QGCApplication.h" LinkManager* LinkManager::_instance = NULL; LinkManager* LinkManager::instance(void) { if(_instance == 0) { _instance = new LinkManager(qgcApp()); Q_CHECK_PTR(_instance); } Q_ASSERT(_instance); return _instance; } void LinkManager::deleteInstance(void) { _instance = NULL; delete this; } /** * @brief Private singleton constructor * * This class implements the singleton design pattern and has therefore only a private constructor. **/ LinkManager::LinkManager(QObject* parent) : QGCSingleton(parent), _connectionsSuspended(false) { _links = QList(); _protocolLinks = QMap(); } LinkManager::~LinkManager() { disconnectAll(); _dataMutex.lock(); foreach (LinkInterface* link, _links) { Q_ASSERT(link); link->deleteLater(); } _links.clear(); _dataMutex.unlock(); } void LinkManager::add(LinkInterface* link) { Q_ASSERT(link); _dataMutex.lock(); if (!_links.contains(link)) { connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeObj(QObject*))); _links.append(link); _dataMutex.unlock(); emit newLink(link); } else { _dataMutex.unlock(); } } void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol) { Q_ASSERT(link); Q_ASSERT(protocol); // Connect link to protocol // the protocol will receive new bytes from the link _dataMutex.lock(); QList linkList = _protocolLinks.values(protocol); // If protocol has not been added before (list length == 0) // OR if link has not been added to protocol, add if (!linkList.contains(link)) { // Protocol is new, add connect(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)), protocol, SLOT(receiveBytes(LinkInterface*, QByteArray))); // Add status connect(link, SIGNAL(connected(bool)), protocol, SLOT(linkStatusChanged(bool))); // Store the connection information in the protocol links map _protocolLinks.insertMulti(protocol, link); _dataMutex.unlock(); // Make sure the protocol clears its metadata for this link. protocol->resetMetadataForLink(link); } else { _dataMutex.unlock(); } //qDebug() << __FILE__ << __LINE__ << "ADDED LINK TO PROTOCOL" << link->getName() << protocol->getName() << "NEW SIZE OF LINK LIST:" << _protocolLinks.size(); } QList LinkManager::getLinksForProtocol(ProtocolInterface* protocol) { _dataMutex.lock(); QList links = _protocolLinks.values(protocol); _dataMutex.unlock(); return links; } ProtocolInterface* LinkManager::getProtocolForLink(LinkInterface* link) { _dataMutex.lock(); ProtocolInterface* protocol = _protocolLinks.key(link); _dataMutex.unlock(); return protocol; } bool LinkManager::connectAll() { if (_connectionsSuspendedMsg()) { return false; } bool allConnected = true; _dataMutex.lock(); foreach (LinkInterface* link, _links) { Q_ASSERT(link); if (!link->_connect()) { allConnected = false; } } _dataMutex.unlock(); return allConnected; } bool LinkManager::disconnectAll() { bool allDisconnected = true; _dataMutex.lock(); foreach (LinkInterface* link, _links) { Q_ASSERT(link); if (!link->disconnect()) { allDisconnected = false; } } _dataMutex.unlock(); return allDisconnected; } bool LinkManager::connectLink(LinkInterface* link) { Q_ASSERT(link); if (_connectionsSuspendedMsg()) { return false; } return link->_connect(); } bool LinkManager::disconnectLink(LinkInterface* link) { Q_ASSERT(link); return link->_disconnect(); } void LinkManager::removeObj(QObject* link) { // Be careful of the fact that by the time this signal makes it through the queue // the link object has already been destructed. removeLink((LinkInterface*)link); } bool LinkManager::removeLink(LinkInterface* link) { if(link) { _dataMutex.lock(); for (int i=0; i < _links.size(); i++) { if(link==_links.at(i)) { _links.removeAt(i); //remove from link list } } // Remove link from protocol map QList protocols = _protocolLinks.keys(link); foreach (ProtocolInterface* proto, protocols) { _protocolLinks.remove(proto, link); } _dataMutex.unlock(); // Emit removal of link emit linkRemoved(link); return true; } return false; } /** * The access time is linear in the number of links. * * @param id link identifier to search for * @return A pointer to the link or NULL if not found */ LinkInterface* LinkManager::getLinkForId(int id) { _dataMutex.lock(); LinkInterface* linkret = NULL; foreach (LinkInterface* link, _links) { Q_ASSERT(link); if (link->getId() == id) { linkret = link; } } _dataMutex.unlock(); return linkret; } /** * */ const QList LinkManager::getLinks() { _dataMutex.lock(); QList ret(_links); _dataMutex.unlock(); return ret; } const QList LinkManager::getSerialLinks() { _dataMutex.lock(); QList s; foreach (LinkInterface* link, _links) { Q_ASSERT(link); SerialLink* serialLink = qobject_cast(link); if (serialLink) s.append(serialLink); } _dataMutex.unlock(); return s; } /// @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) { QGCMessageBox::information(tr("Connect not allowed"), tr("Connect not allowed: %1").arg(_connectionsSuspendedReason)); return true; } else { return false; } } void LinkManager::setConnectionsSuspended(QString reason) { _connectionsSuspended = true; _connectionsSuspendedReason = reason; Q_ASSERT(!reason.isEmpty()); }