From dc0c3f3db346aa12e04be94351505e182282e496 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 2 Nov 2014 20:10:35 -0800 Subject: [PATCH] LinkInterface::bytesAvailable api removal MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit This api doesn’t make any sense given the fact that LinkInterface signals bytesReceived with the bytes in the signal. Also the reason why it is never called! --- src/comm/LinkInterface.h | 7 ------- src/comm/MAVLinkSimulationLink.cc | 8 -------- src/comm/MAVLinkSimulationLink.h | 1 - src/comm/OpalLink.cc | 12 ------------ src/comm/OpalLink.h | 2 -- src/comm/SerialLink.cc | 15 --------------- src/comm/SerialLink.h | 1 - src/comm/TCPLink.cc | 10 ---------- src/comm/TCPLink.h | 1 - src/comm/UDPLink.cc | 11 ----------- src/comm/UDPLink.h | 1 - src/comm/XbeeLink.cpp | 5 ----- src/comm/XbeeLink.h | 1 - 13 files changed, 75 deletions(-) diff --git a/src/comm/LinkInterface.h b/src/comm/LinkInterface.h index 333567752..8f691ccec 100644 --- a/src/comm/LinkInterface.h +++ b/src/comm/LinkInterface.h @@ -147,13 +147,6 @@ public: **/ virtual bool disconnect() = 0; - /** - * @brief Get the current number of bytes in buffer. - * - * @return The number of bytes ready to read - **/ - virtual qint64 bytesAvailable() = 0; - public slots: /** diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index de09f956f..ce9eb79b0 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -632,14 +632,6 @@ void MAVLinkSimulationLink::mainloop() } -qint64 MAVLinkSimulationLink::bytesAvailable() -{ - readyBufferMutex.lock(); - qint64 size = readyBuffer.size(); - readyBufferMutex.unlock(); - return size; -} - void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) { // Parse bytes diff --git a/src/comm/MAVLinkSimulationLink.h b/src/comm/MAVLinkSimulationLink.h index 912c5201d..b360d37df 100644 --- a/src/comm/MAVLinkSimulationLink.h +++ b/src/comm/MAVLinkSimulationLink.h @@ -51,7 +51,6 @@ public: MAVLinkSimulationLink(QString readFile="", QString writeFile="", int rate=5); ~MAVLinkSimulationLink(); bool isConnected() const; - qint64 bytesAvailable(); void run(); void requestReset() { } diff --git a/src/comm/OpalLink.cc b/src/comm/OpalLink.cc index 9850feefe..7a1d5ed7e 100644 --- a/src/comm/OpalLink.cc +++ b/src/comm/OpalLink.cc @@ -58,18 +58,6 @@ OpalLink::OpalLink() : QObject::connect(getSignalsTimer, SIGNAL(timeout()), this, SLOT(getSignals())); } - -/* - * - Communication - * - */ - -qint64 OpalLink::bytesAvailable() -{ - return 0; -} - void OpalLink::writeBytes(const char *bytes, qint64 length) { /* decode the message */ diff --git a/src/comm/OpalLink.h b/src/comm/OpalLink.h index e9edbdb2a..f658c8f0e 100644 --- a/src/comm/OpalLink.h +++ b/src/comm/OpalLink.h @@ -83,8 +83,6 @@ public: bool disconnect(); - qint64 bytesAvailable(); - void run(); int getOpalInstID() { diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 96f70c4c9..957079eea 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -390,21 +390,6 @@ void SerialLink::readBytes() } } - -/** - * @brief Get the number of bytes to read. - * - * @return The number of bytes to read - **/ -qint64 SerialLink::bytesAvailable() -{ - if (m_port) { - return m_port->bytesAvailable(); - } else { - return 0; - } -} - /** * @brief Disconnect the connection. * diff --git a/src/comm/SerialLink.h b/src/comm/SerialLink.h index 75632632a..84adde2fa 100644 --- a/src/comm/SerialLink.h +++ b/src/comm/SerialLink.h @@ -78,7 +78,6 @@ public: void requestReset(); bool isConnected() const; - qint64 bytesAvailable(); /** * @brief The port handle diff --git a/src/comm/TCPLink.cc b/src/comm/TCPLink.cc index 51c222348..a09a90d73 100644 --- a/src/comm/TCPLink.cc +++ b/src/comm/TCPLink.cc @@ -176,16 +176,6 @@ void TCPLink::readBytes() } } -/** - * @brief Get the number of bytes to read. - * - * @return The number of bytes to read - **/ -qint64 TCPLink::bytesAvailable() -{ - return _socket->bytesAvailable(); -} - /** * @brief Disconnect the connection. * diff --git a/src/comm/TCPLink.h b/src/comm/TCPLink.h index f97db7fbe..c78922f74 100644 --- a/src/comm/TCPLink.h +++ b/src/comm/TCPLink.h @@ -67,7 +67,6 @@ public: virtual bool isConnected(void) const; virtual bool connect(void); virtual bool disconnect(void); - virtual qint64 bytesAvailable(void); virtual void requestReset(void) {}; // Extensive statistics for scientific purposes diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index ecf6fb90c..57f6859e5 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -267,17 +267,6 @@ void UDPLink::readBytes() } } - -/** - * @brief Get the number of bytes to read. - * - * @return The number of bytes to read - **/ -qint64 UDPLink::bytesAvailable() -{ - return socket->pendingDatagramSize(); -} - /** * @brief Disconnect the connection. * diff --git a/src/comm/UDPLink.h b/src/comm/UDPLink.h index 00cf92097..48a8aa54d 100644 --- a/src/comm/UDPLink.h +++ b/src/comm/UDPLink.h @@ -52,7 +52,6 @@ public: void requestReset() { } bool isConnected() const; - qint64 bytesAvailable(); int getPort() const { return port; } diff --git a/src/comm/XbeeLink.cpp b/src/comm/XbeeLink.cpp index 337c961fc..31ad736c0 100644 --- a/src/comm/XbeeLink.cpp +++ b/src/comm/XbeeLink.cpp @@ -189,11 +189,6 @@ bool XbeeLink::disconnect() return true; } -qint64 XbeeLink::bytesAvailable() -{ - return 0; -} - void XbeeLink::writeBytes(const char *bytes, qint64 length) // TO DO: delete the data array { char *data; diff --git a/src/comm/XbeeLink.h b/src/comm/XbeeLink.h index 4e9e43fca..f7dfbf00d 100644 --- a/src/comm/XbeeLink.h +++ b/src/comm/XbeeLink.h @@ -36,7 +36,6 @@ public: // virtual functions from LinkInterface bool isConnected() const; bool connect(); bool disconnect(); - qint64 bytesAvailable(); // Extensive statistics for scientific purposes qint64 getConnectionSpeed() const; -- 2.22.0