diff --git a/src/comm/LinkInterface.h b/src/comm/LinkInterface.h index 8f691ccec73889054630523f72d9a64b3d4f6d3b..c177b4737410afc99e7ac9ffb55a71ab6c86a269 100644 --- a/src/comm/LinkInterface.h +++ b/src/comm/LinkInterface.h @@ -38,6 +38,8 @@ along with PIXHAWK. If not, see . #include #include +class LinkManager; + /** * The link interface defines the interface for all links used to communicate * with the groundstation application. @@ -46,6 +48,10 @@ along with PIXHAWK. If not, see . class LinkInterface : public QThread { Q_OBJECT + + // Only LinkManager is allowed to _connect or _disconnect a link + friend class LinkManager; + public: LinkInterface() : QThread(0) @@ -133,20 +139,6 @@ public: return getCurrentDataRate(outDataIndex, outDataWriteTimes, outDataWriteAmounts); } - /** - * @brief Connect this interface logically - * - * @return True if connection could be established, false otherwise - **/ - virtual bool connect() = 0; - - /** - * @brief Disconnect this interface logically - * - * @return True if connection could be terminated, false otherwise - **/ - virtual bool disconnect() = 0; - public slots: /** @@ -323,6 +315,20 @@ protected slots: **/ virtual void readBytes() = 0; +private: + /** + * @brief Connect this interface logically + * + * @return True if connection could be established, false otherwise + **/ + virtual bool _connect(void) = 0; + + /** + * @brief Disconnect this interface logically + * + * @return True if connection could be terminated, false otherwise + **/ + virtual bool _disconnect(void) = 0; }; #endif // _LINKINTERFACE_H_ diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index eecf5a5825bf4d468dffd24a081318c084e59647..4e824360d81442c5581f839d5b19f72add7437d5 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -31,11 +31,12 @@ This file is part of the QGROUNDCONTROL project #include #include -#include "LinkManager.h" -#include - +#include #include +#include "LinkManager.h" +#include "MainWindow.h" + LinkManager* LinkManager::instance() { static LinkManager* _instance = 0; @@ -54,46 +55,52 @@ LinkManager* LinkManager::instance() * * This class implements the singleton design pattern and has therefore only a private constructor. **/ -LinkManager::LinkManager() +LinkManager::LinkManager() : + _connectionsSuspended(false) { - links = QList(); - protocolLinks = QMap(); + _links = QList(); + _protocolLinks = QMap(); } LinkManager::~LinkManager() { disconnectAll(); - dataMutex.lock(); - foreach (LinkInterface* link, links) - { - if(link) link->deleteLater(); + + _dataMutex.lock(); + foreach (LinkInterface* link, _links) { + Q_ASSERT(link); + link->deleteLater(); } - dataMutex.unlock(); + _links.clear(); + _dataMutex.unlock(); } void LinkManager::add(LinkInterface* link) { - dataMutex.lock(); - if (!links.contains(link)) + Q_ASSERT(link); + + _dataMutex.lock(); + + if (!_links.contains(link)) { - if(!link) return; connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeObj(QObject*))); - links.append(link); - dataMutex.unlock(); + _links.append(link); + _dataMutex.unlock(); emit newLink(link); } else { - dataMutex.unlock(); + _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 - if (!link || !protocol) return; - - dataMutex.lock(); - QList linkList = protocolLinks.values(protocol); + _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 @@ -104,43 +111,48 @@ void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol) // 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(); + _protocolLinks.insertMulti(protocol, link); + _dataMutex.unlock(); // Make sure the protocol clears its metadata for this link. protocol->resetMetadataForLink(link); } else { - dataMutex.unlock(); + _dataMutex.unlock(); } - //qDebug() << __FILE__ << __LINE__ << "ADDED LINK TO PROTOCOL" << link->getName() << protocol->getName() << "NEW SIZE OF LINK LIST:" << protocolLinks.size(); + //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(); + _dataMutex.lock(); + QList links = _protocolLinks.values(protocol); + _dataMutex.unlock(); return links; } ProtocolInterface* LinkManager::getProtocolForLink(LinkInterface* link) { - dataMutex.lock(); - ProtocolInterface* interface = protocolLinks.key(link); - dataMutex.unlock(); + _dataMutex.lock(); + ProtocolInterface* interface = _protocolLinks.key(link); + _dataMutex.unlock(); return interface; } bool LinkManager::connectAll() { + if (_connectionsSuspendedMsg()) { + return false; + } + bool allConnected = true; - dataMutex.lock(); - foreach (LinkInterface* link, links) - { - if(!link) {} - else if(!link->connect()) allConnected = false; + _dataMutex.lock(); + foreach (LinkInterface* link, _links) { + Q_ASSERT(link); + if (!link->_connect()) { + allConnected = false; + } } - dataMutex.unlock(); + _dataMutex.unlock(); return allConnected; } @@ -149,58 +161,62 @@ bool LinkManager::disconnectAll() { bool allDisconnected = true; - dataMutex.lock(); - foreach (LinkInterface* link, links) + _dataMutex.lock(); + foreach (LinkInterface* link, _links) { - //static int i=0; - if(!link) {} - else if(!link->disconnect()) allDisconnected = false; + Q_ASSERT(link); + if (!link->disconnect()) { + allDisconnected = false; + } } - dataMutex.unlock(); + _dataMutex.unlock(); return allDisconnected; } bool LinkManager::connectLink(LinkInterface* link) { - if(!link) return false; - return link->connect(); + Q_ASSERT(link); + + if (_connectionsSuspendedMsg()) { + return false; + } + + return link->_connect(); } bool LinkManager::disconnectLink(LinkInterface* link) { - if(!link) return false; - return link->disconnect(); + Q_ASSERT(link); + return link->_disconnect(); } void LinkManager::removeObj(QObject* link) { - LinkInterface* linkInterface = dynamic_cast(link); - if (linkInterface) - { - removeLink(linkInterface); - } + // 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 < QList(links).size(); i++) + _dataMutex.lock(); + for (int i=0; i < _links.size(); i++) { - if(link==links.at(i)) + if(link==_links.at(i)) { - links.removeAt(i); //remove from link list + _links.removeAt(i); //remove from link list } } // Remove link from protocol map - QList protocols = protocolLinks.keys(link); + QList protocols = _protocolLinks.keys(link); foreach (ProtocolInterface* proto, protocols) { - protocolLinks.remove(proto, link); + _protocolLinks.remove(proto, link); } - dataMutex.unlock(); + _dataMutex.unlock(); // Emit removal of link emit linkRemoved(link); @@ -218,16 +234,18 @@ bool LinkManager::removeLink(LinkInterface* link) */ LinkInterface* LinkManager::getLinkForId(int id) { - dataMutex.lock(); + _dataMutex.lock(); LinkInterface* linkret = NULL; - foreach (LinkInterface* link, links) + foreach (LinkInterface* link, _links) { + Q_ASSERT(link); + if (link->getId() == id) { linkret = link; } } - dataMutex.unlock(); + _dataMutex.unlock(); return linkret; } @@ -236,25 +254,49 @@ LinkInterface* LinkManager::getLinkForId(int id) */ const QList LinkManager::getLinks() { - dataMutex.lock(); - QList ret(links); - dataMutex.unlock(); + _dataMutex.lock(); + QList ret(_links); + _dataMutex.unlock(); return ret; } const QList LinkManager::getSerialLinks() { - dataMutex.lock(); + _dataMutex.lock(); QList s; - foreach (LinkInterface* i, links) + foreach (LinkInterface* link, _links) { - SerialLink* link = qobject_cast(i); + Q_ASSERT(link); + + SerialLink* serialLink = qobject_cast(link); - if (link) - s.append(link); + if (serialLink) + s.append(serialLink); } - dataMutex.unlock(); + _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) { + QMessageBox::information(MainWindow::instance(), + 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()); +} + diff --git a/src/comm/LinkManager.h b/src/comm/LinkManager.h index 6c38b6492c0eb5a9eac11d184dee2d81569a1c03..7f6df39d3374e0ca86cc5e071f978e941e80fbf8 100644 --- a/src/comm/LinkManager.h +++ b/src/comm/LinkManager.h @@ -71,8 +71,15 @@ public: /** @brief Get a list of all protocols */ const QList getProtocols() { - return protocolLinks.uniqueKeys(); + return _protocolLinks.uniqueKeys(); } + + /// @brief Sets the lag to suspend the all new connections + /// @param reason User visible reason to suspend connections + void setConnectionsSuspended(QString reason); + + /// @brief Sets the flag to allow new connections to be made + void setConnectionsAllowed(void) { _connectionsSuspended = false; } public slots: @@ -88,19 +95,22 @@ public slots: bool disconnectAll(); bool disconnectLink(LinkInterface* link); -protected: - LinkManager(); - QList links; - QMultiMap protocolLinks; - QMutex dataMutex; - -private: - static LinkManager* _instance; - signals: void newLink(LinkInterface* link); void linkRemoved(LinkInterface* link); - + +private: + LinkManager(void); + + QList _links; + QMultiMap _protocolLinks; + QMutex _dataMutex; + + bool _connectionsSuspendedMsg(void); + static LinkManager* _instance; + + bool _connectionsSuspended; ///< true: all new connections should not be allowed + QString _connectionsSuspendedReason; ///< User visible reason for suspension }; -#endif // _LINKMANAGER_H_ +#endif diff --git a/src/comm/OpalLink.cc b/src/comm/OpalLink.cc index 7a1d5ed7ea0538fe6fddbeb9c361a657c6d75895..f4a12168b40af5c4c7642b82503985517bdb0620 100644 --- a/src/comm/OpalLink.cc +++ b/src/comm/OpalLink.cc @@ -457,7 +457,7 @@ int8_t OpalLink::rescaleControllerOutput(double raw) return static_cast((raw>=0?raw*127:raw*128)); } -bool OpalLink::connect() +bool OpalLink::_connect(void) { short modelState; @@ -480,7 +480,7 @@ bool OpalLink::connect() return connectState; } -bool OpalLink::disconnect() +bool OpalLink::_disconnect(void) { // OpalDisconnect returns void so its success or failure cannot be tested OpalDisconnect(); diff --git a/src/comm/OpalLink.h b/src/comm/OpalLink.h index f658c8f0e080c885c02073bfe041915ff3958b4b..5f17ea0b7b8307c5db9744f4dab82b646f561226 100644 --- a/src/comm/OpalLink.h +++ b/src/comm/OpalLink.h @@ -79,15 +79,16 @@ public: qint64 getCurrentInDataRate() const; qint64 getCurrentOutDataRate() const; - bool connect(); - - bool disconnect(); - void run(); int getOpalInstID() { return static_cast(opalInstID); } + + // These are left unimplemented in order to cause linker errors which indicate incorrect usage of + // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager. + bool connect(void); + bool disconnect(void); public slots: @@ -144,6 +145,11 @@ protected: bool sendRCValues; bool sendRawController; bool sendPosition; + +private: + // From LinkInterface + virtual bool _connect(void); + virtual bool _disconnect(void); }; #endif // OPALLINK_H diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 957079eeacc7a9ac9ba50b07dc4f99796829f21a..26dce932a80b4b0e8103dfed0c8d23ba523898e4 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -85,7 +85,7 @@ void SerialLink::requestReset() SerialLink::~SerialLink() { - disconnect(); + _disconnect(); if(m_port) delete m_port; m_port = NULL; @@ -395,7 +395,7 @@ void SerialLink::readBytes() * * @return True if connection has been disconnected, false if connection couldn't be disconnected. **/ -bool SerialLink::disconnect() +bool SerialLink::_disconnect(void) { if (isRunning()) { @@ -405,8 +405,6 @@ bool SerialLink::disconnect() } wait(); // This will terminate the thread and close the serial port - emit connected(false); - emit disconnected(); return true; } @@ -421,11 +419,11 @@ bool SerialLink::disconnect() * * @return True if connection has been established, false if connection couldn't be established. **/ -bool SerialLink::connect() +bool SerialLink::_connect(void) { qDebug() << "CONNECT CALLED"; if (isRunning()) - disconnect(); + _disconnect(); { QMutexLocker locker(&this->m_stoppMutex); m_stopp = false; @@ -436,12 +434,12 @@ bool SerialLink::connect() } /** - * @brief This function is called indirectly by the connect() call. + * @brief This function is called indirectly by the _connect() call. * - * The connect() function starts the thread and indirectly calls this method. + * The _connect() function starts the thread and indirectly calls this method. * * @return True if the connection could be established, false otherwise - * @see connect() For the right function to establish the connection. + * @see _connect() For the right function to establish the connection. **/ bool SerialLink::hardwareConnect(QString &type) { diff --git a/src/comm/SerialLink.h b/src/comm/SerialLink.h index 84adde2fafe271a5f56203cb55753e2f65a74d9a..3368991cabbc8002c45c4e08078273f04b183544 100644 --- a/src/comm/SerialLink.h +++ b/src/comm/SerialLink.h @@ -111,6 +111,11 @@ public: void run2(); int getId() const; + + // These are left unimplemented in order to cause linker errors which indicate incorrect usage of + // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager. + bool connect(void); + bool disconnect(void); signals: //[TODO] Refactor to Linkinterface void updateLink(LinkInterface*); @@ -139,8 +144,6 @@ public slots: * @param size The size of the bytes array **/ void writeBytes(const char* data, qint64 length); - bool connect(); - bool disconnect(); void linkError(QSerialPort::SerialPortError error); @@ -161,6 +164,10 @@ protected: bool m_is_cdc; private: + // From LinkInterface + virtual bool _connect(void); + virtual bool _disconnect(void); + volatile bool m_stopp; volatile bool m_reqReset; QMutex m_stoppMutex; // Mutex for accessing m_stopp diff --git a/src/comm/TCPLink.cc b/src/comm/TCPLink.cc index a09a90d73f1d15a10d56c60b1b60e00afea96aa3..df3366740bbbd2943ae3258b7ee4e44de1c621e6 100644 --- a/src/comm/TCPLink.cc +++ b/src/comm/TCPLink.cc @@ -55,7 +55,7 @@ TCPLink::TCPLink(QHostAddress hostAddress, quint16 socketPort) : TCPLink::~TCPLink() { - disconnect(); + _disconnect(); // Tell the thread to exit quit(); @@ -77,7 +77,7 @@ void TCPLink::setHostAddress(QHostAddress hostAddress) bool reconnect = false; if (this->isConnected()) { - disconnect(); + _disconnect(); reconnect = true; } @@ -85,7 +85,7 @@ void TCPLink::setHostAddress(QHostAddress hostAddress) _resetName(); if (reconnect) { - connect(); + _connect(); } } @@ -99,7 +99,7 @@ void TCPLink::setPort(int port) bool reconnect = false; if (this->isConnected()) { - disconnect(); + _disconnect(); reconnect = true; } @@ -107,7 +107,7 @@ void TCPLink::setPort(int port) _resetName(); if (reconnect) { - connect(); + _connect(); } } @@ -181,7 +181,7 @@ void TCPLink::readBytes() * * @return True if connection has been disconnected, false if connection couldn't be disconnected. **/ -bool TCPLink::disconnect() +bool TCPLink::_disconnect(void) { quit(); wait(); @@ -204,7 +204,7 @@ bool TCPLink::disconnect() * * @return True if connection has been established, false if connection couldn't be established. **/ -bool TCPLink::connect() +bool TCPLink::_connect(void) { if (isRunning()) { diff --git a/src/comm/TCPLink.h b/src/comm/TCPLink.h index c78922f749ed001c4e9c3360c3160fafaaab6169..0b6e592698ce7bfd63b59d044bc911a80c41d06c 100644 --- a/src/comm/TCPLink.h +++ b/src/comm/TCPLink.h @@ -45,10 +45,14 @@ //#define TCPLINK_READWRITE_DEBUG // Use to debug data reads/writes +class TCPLinkUnitTest; + class TCPLink : public LinkInterface { Q_OBJECT + friend class TCPLinkUnitTest; + public: TCPLink(QHostAddress hostAddress = QHostAddress::LocalHost, quint16 socketPort = 5760); ~TCPLink(); @@ -65,8 +69,6 @@ public: virtual int getId(void) const; virtual QString getName(void) const; virtual bool isConnected(void) const; - virtual bool connect(void); - virtual bool disconnect(void); virtual void requestReset(void) {}; // Extensive statistics for scientific purposes @@ -74,6 +76,11 @@ public: qint64 getCurrentInDataRate() const; qint64 getCurrentOutDataRate() const; + // These are left unimplemented in order to cause linker errors which indicate incorrect usage of + // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager. + bool connect(void); + bool disconnect(void); + public slots: void setHostAddress(const QString& hostAddress); void setPort(int port); @@ -95,6 +102,10 @@ protected: virtual void run(void); private: + // From LinkInterface + virtual bool _connect(void); + virtual bool _disconnect(void); + void _resetName(void); bool _hardwareConnect(void); #ifdef TCPLINK_READWRITE_DEBUG diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index 57f6859e58d59eaaab265f35cddd99f81a2285ae..7af36edc011787218c1c94643989b39a60b5abea 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -59,7 +59,7 @@ UDPLink::UDPLink(QHostAddress host, quint16 port) : UDPLink::~UDPLink() { - disconnect(); + _disconnect(); // Tell the thread to exit quit(); @@ -85,13 +85,13 @@ void UDPLink::setAddress(QHostAddress host) bool reconnect(false); if(this->isConnected()) { - disconnect(); + _disconnect(); reconnect = true; } this->host = host; if(reconnect) { - connect(); + _connect(); } } @@ -100,7 +100,7 @@ void UDPLink::setPort(int port) bool reconnect(false); if(this->isConnected()) { - disconnect(); + _disconnect(); reconnect = true; } this->port = port; @@ -108,7 +108,7 @@ void UDPLink::setPort(int port) emit nameChanged(this->name); if(reconnect) { - connect(); + _connect(); } } @@ -272,7 +272,7 @@ void UDPLink::readBytes() * * @return True if connection has been disconnected, false if connection couldn't be disconnected. **/ -bool UDPLink::disconnect() +bool UDPLink::_disconnect(void) { this->quit(); this->wait(); @@ -296,7 +296,7 @@ bool UDPLink::disconnect() * * @return True if connection has been established, false if connection couldn't be established. **/ -bool UDPLink::connect() +bool UDPLink::_connect(void) { if(this->isRunning()) { diff --git a/src/comm/UDPLink.h b/src/comm/UDPLink.h index 48a8aa54d4b0b353dd24a45c5bb4f93c99d5cb4c..6a60f7c6203c9b972e6385aa2fce49b23c3de158 100644 --- a/src/comm/UDPLink.h +++ b/src/comm/UDPLink.h @@ -78,6 +78,11 @@ public: void run(); int getId() const; + + // These are left unimplemented in order to cause linker errors which indicate incorrect usage of + // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager. + bool connect(void); + bool disconnect(void); public slots: void setAddress(QHostAddress host); @@ -96,8 +101,6 @@ public slots: * @param size The size of the bytes array **/ void writeBytes(const char* data, qint64 length); - bool connect(); - bool disconnect(); protected: QString name; @@ -114,6 +117,10 @@ protected: void setName(QString name); private: + // From LinkInterface + virtual bool _connect(void); + virtual bool _disconnect(void); + bool hardwareConnect(void); signals: diff --git a/src/comm/XbeeLink.cpp b/src/comm/XbeeLink.cpp index 31ad736c01c1ca89c87aea6bcde031ee5b672d84..e730b7ec2859b14d64dd5c0d9f1f3d6de8e8aca9 100644 --- a/src/comm/XbeeLink.cpp +++ b/src/comm/XbeeLink.cpp @@ -35,7 +35,7 @@ XbeeLink::~XbeeLink() delete m_portName; m_portName = NULL; } - this->disconnect(); + _disconnect(); } QString XbeeLink::getPortName() const @@ -58,7 +58,7 @@ bool XbeeLink::setPortName(QString portName) bool reconnect(false); if(this->m_connected) { - this->disconnect(); + _disconnect(); reconnect = true; } if(m_portName) @@ -87,7 +87,7 @@ bool XbeeLink::setPortName(QString portName) bool retVal(true); if(reconnect) { - retVal = this->connect(); + retVal = _connect(); } return retVal; @@ -98,14 +98,14 @@ bool XbeeLink::setBaudRate(int rate) bool reconnect(false); if(this->m_connected) { - this->disconnect(); + _disconnect(); reconnect = true; } bool retVal(true); this->m_baudRate = rate; if(reconnect) { - retVal = this->connect(); + retVal = _connect(); } return retVal; } @@ -145,7 +145,7 @@ bool XbeeLink::hardwareConnect() emit tryConnectBegin(true); if(this->isConnected()) { - this->disconnect(); + _disconnect(); } if (*this->m_portName == '\0') { @@ -166,14 +166,14 @@ bool XbeeLink::hardwareConnect() return true; } -bool XbeeLink::connect() +bool XbeeLink::_connect(void) { if (this->isRunning()) this->disconnect(); this->start(LowPriority); return true; } -bool XbeeLink::disconnect() +bool XbeeLink::_disconnect(void) { if(this->isRunning()) this->terminate(); //stop running the thread, restart it upon connect diff --git a/src/comm/XbeeLink.h b/src/comm/XbeeLink.h index f7dfbf00daa5ea62222ae8b9003e64b9d4ec9ae7..58df73386f87f45cf3fc51b670578f9d384be2fd 100644 --- a/src/comm/XbeeLink.h +++ b/src/comm/XbeeLink.h @@ -23,6 +23,11 @@ public: // virtual functions from XbeeLinkInterface QString getPortName() const; void requestReset() { } int getBaudRate() const; + + // These are left unimplemented in order to cause linker errors which indicate incorrect usage of + // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager. + bool connect(void); + bool disconnect(void); public slots: // virtual functions from XbeeLinkInterface bool setPortName(QString portName); @@ -63,7 +68,11 @@ protected: quint32 m_addrLow; private: - bool hardwareConnect(); + // From LinkInterface + virtual bool _connect(void); + virtual bool _disconnect(void); + + bool hardwareConnect(); //void CALLTYPE portCallback(xbee_con *XbeeCon, xbee_pkt *XbeePkt); }; diff --git a/src/qgcunittest/MockLink.cc b/src/qgcunittest/MockLink.cc index 143c5cf630525ac2db7f692d2079230c18a59aad..a28a7e47737ad569ef821b4fc6f6a974fa113ab9 100644 --- a/src/qgcunittest/MockLink.cc +++ b/src/qgcunittest/MockLink.cc @@ -58,7 +58,7 @@ MockLink::MockLink(void) : MockLink::~MockLink(void) { - disconnect(); + _disconnect(); deleteLater(); } @@ -67,7 +67,7 @@ void MockLink::readBytes(void) // FIXME: This is a bad virtual from LinkInterface? } -bool MockLink::connect(void) +bool MockLink::_connect(void) { _connected = true; @@ -79,7 +79,7 @@ bool MockLink::connect(void) return true; } -bool MockLink::disconnect(void) +bool MockLink::_disconnect(void) { _connected = false; exit(); diff --git a/src/qgcunittest/MockLink.h b/src/qgcunittest/MockLink.h index 0c8da2646033092d4103cea2df8d07646e54a007..d8849715f92f5c707a0756a9adbc5d15c98e77a2 100644 --- a/src/qgcunittest/MockLink.h +++ b/src/qgcunittest/MockLink.h @@ -49,10 +49,13 @@ public: virtual void requestReset(void){ } virtual bool isConnected(void) const { return _connected; } virtual qint64 getConnectionSpeed(void) const { return 100000000; } - virtual bool connect(void); - virtual bool disconnect(void); virtual qint64 bytesAvailable(void) { return 0; } + // These are left unimplemented in order to cause linker errors which indicate incorrect usage of + // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager. + bool connect(void); + bool disconnect(void); + signals: void error(const QString& errorMsg); @@ -72,6 +75,10 @@ private slots: void _run50HzTasks(void); private: + // From LinkInterface + virtual bool _connect(void); + virtual bool _disconnect(void); + // QThread override virtual void run(void); diff --git a/src/qgcunittest/TCPLinkTest.cc b/src/qgcunittest/TCPLinkTest.cc index b18a93e788d464b0bebaf58c1441736141c522cd..4bf04a8c8adce555fc1b3974c6cc224b5df67f77 100644 --- a/src/qgcunittest/TCPLinkTest.cc +++ b/src/qgcunittest/TCPLinkTest.cc @@ -113,7 +113,7 @@ void TCPLinkUnitTest::_connectFail_test(void) // With the new threading model connect will always succeed. We only get an error signal // for a failed connected. - QCOMPARE(_link->connect(), true); + QCOMPARE(_link->_connect(), true); // Make sure we get a linkError signal with the right link name QCOMPARE(_multiSpy->waitForSignalByIndex(communicationErrorSignalIndex, 1000), true); @@ -122,11 +122,11 @@ void TCPLinkUnitTest::_connectFail_test(void) QCOMPARE(arguments.at(0).toString(), _link->getName()); _multiSpy->clearSignalByIndex(communicationErrorSignalIndex); - _link->disconnect(); + _link->_disconnect(); // Try to connect again to make sure everything was cleaned up correctly from previous failed connection - QCOMPARE(_link->connect(), true); + QCOMPARE(_link->_connect(), true); // Make sure we get a linkError signal with the right link name QCOMPARE(_multiSpy->waitForSignalByIndex(communicationErrorSignalIndex, 1000), true); @@ -147,7 +147,7 @@ void TCPLinkUnitTest::_connectSucceed_test(void) Q_CHECK_PTR(server); // Connect to the server - QCOMPARE(_link->connect(), true); + QCOMPARE(_link->_connect(), true); // Make sure we get the two different connected signals QCOMPARE(_multiSpy->waitForSignalByIndex(connectedSignalIndex, 10000), true); @@ -184,7 +184,7 @@ void TCPLinkUnitTest::_connectSucceed_test(void) _multiSpy->clearAllSignals(); // Disconnect the link - _link->disconnect(); + _link->_disconnect(); // Make sure we get the disconnected signals on link side QCOMPARE(_multiSpy->waitForSignalByIndex(disconnectedSignalIndex, 1000), true); @@ -196,7 +196,7 @@ void TCPLinkUnitTest::_connectSucceed_test(void) // Try to connect again to make sure everything was cleaned up correctly from previous connection // Connect to the server - QCOMPARE(_link->connect(), true); + QCOMPARE(_link->_connect(), true); // Make sure we get the two different connected signals QCOMPARE(_multiSpy->waitForSignalByIndex(connectedSignalIndex, 1000), true);