Commit 761fef95 authored by Don Gagne's avatar Don Gagne

Cleanup of TCPLink from unit test findings

parent b412d826
...@@ -746,10 +746,14 @@ CONFIG(debug, debug|release) { ...@@ -746,10 +746,14 @@ CONFIG(debug, debug|release) {
HEADERS += \ HEADERS += \
src/qgcunittest/AutoTest.h \ src/qgcunittest/AutoTest.h \
src/qgcunittest/UASUnitTest.h src/qgcunittest/UASUnitTest.h \
src/qgcunittest/MultiSignalSpy.h \
src/qgcunittest/TCPLinkTest.h
SOURCES += \ SOURCES += \
src/qgcunittest/UASUnitTest.cc src/qgcunittest/UASUnitTest.cc \
src/qgcunittest/MultiSignalSpy.cc \
src/qgcunittest/TCPLinkTest.cc
} }
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler # Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
......
...@@ -413,8 +413,7 @@ bool SerialLink::hardwareConnect() ...@@ -413,8 +413,7 @@ bool SerialLink::hardwareConnect()
} }
QObject::connect(m_port,SIGNAL(aboutToClose()),this,SIGNAL(disconnected())); QObject::connect(m_port,SIGNAL(aboutToClose()),this,SIGNAL(disconnected()));
QObject::connect(m_port, SIGNAL(error(SerialLinkPortError_t)), QObject::connect(m_port, SIGNAL(error(QSerialPort::SerialPortError)), this, SLOT(linkError(QSerialPort::SerialPortError)));
this, SLOT(linkError(SerialLinkPortError_t)));
// port->setCommTimeouts(QSerialPort::CtScheme_NonBlockingRead); // port->setCommTimeouts(QSerialPort::CtScheme_NonBlockingRead);
...@@ -444,7 +443,7 @@ bool SerialLink::hardwareConnect() ...@@ -444,7 +443,7 @@ bool SerialLink::hardwareConnect()
return true; // successful connection return true; // successful connection
} }
void SerialLink::linkError(SerialLinkPortError_t error) void SerialLink::linkError(QSerialPort::SerialPortError error)
{ {
qDebug() << error; qDebug() << error;
} }
......
...@@ -40,9 +40,6 @@ This file is part of the QGROUNDCONTROL project ...@@ -40,9 +40,6 @@ This file is part of the QGROUNDCONTROL project
#include <configuration.h> #include <configuration.h>
#include "SerialLinkInterface.h" #include "SerialLinkInterface.h"
// convenience type for passing errors
typedef QSerialPort::SerialPortError SerialLinkPortError_t;
/** /**
* @brief The SerialLink class provides cross-platform access to serial links. * @brief The SerialLink class provides cross-platform access to serial links.
* It takes care of the link management and provides a common API to higher * It takes care of the link management and provides a common API to higher
...@@ -137,7 +134,7 @@ public slots: ...@@ -137,7 +134,7 @@ public slots:
bool connect(); bool connect();
bool disconnect(); bool disconnect();
void linkError(SerialLinkPortError_t error); void linkError(QSerialPort::SerialPortError error);
protected: protected:
quint64 m_bytesRead; quint64 m_bytesRead;
......
...@@ -21,13 +21,6 @@ ...@@ -21,13 +21,6 @@
======================================================================*/ ======================================================================*/
/**
* @file
* @brief Definition of TCP connection (server) for unmanned vehicles
* @author Lorenz Meier <mavteam@student.ethz.ch>
*
*/
#include <QTimer> #include <QTimer>
#include <QList> #include <QList>
#include <QDebug> #include <QDebug>
...@@ -37,26 +30,29 @@ ...@@ -37,26 +30,29 @@
#include "LinkManager.h" #include "LinkManager.h"
#include "QGC.h" #include "QGC.h"
#include <QHostInfo> #include <QHostInfo>
#include <QSignalSpy>
TCPLink::TCPLink(QHostAddress hostAddress, quint16 socketPort) : /// @file
host(hostAddress), /// @brief TCP link type for SITL support
port(socketPort), ///
socket(NULL), /// @author Don Gagne <don@thegagnes.com>
socketIsConnected(false)
TCPLink::TCPLink(QHostAddress hostAddress, quint16 socketPort) :
_hostAddress(hostAddress),
_port(socketPort),
_socket(NULL),
_socketIsConnected(false)
{ {
// Set unique ID and add link to the list of links _linkId = getNextLinkId();
this->id = getNextLinkId(); _resetName();
this->name = tr("TCP Link (port:%1)").arg(this->port);
emit nameChanged(this->name);
qDebug() << "TCP Created " << this->name; qDebug() << "TCP Created " << _name;
} }
TCPLink::~TCPLink() TCPLink::~TCPLink()
{ {
disconnect(); disconnect();
this->deleteLater(); deleteLater();
} }
void TCPLink::run() void TCPLink::run()
...@@ -64,45 +60,47 @@ void TCPLink::run() ...@@ -64,45 +60,47 @@ void TCPLink::run()
exec(); exec();
} }
void TCPLink::setAddress(const QString &text) void TCPLink::setHostAddress(QHostAddress hostAddress)
{
setAddress(QHostAddress(text));
}
void TCPLink::setAddress(QHostAddress host)
{ {
bool reconnect(false); bool reconnect = false;
if (this->isConnected())
{ if (this->isConnected()) {
disconnect(); disconnect();
reconnect = true; reconnect = true;
} }
this->host = host;
if (reconnect) _hostAddress = hostAddress;
{ _resetName();
if (reconnect) {
connect(); connect();
} }
} }
void TCPLink::setHostAddress(const QString& hostAddress)
{
setHostAddress(QHostAddress(hostAddress));
}
void TCPLink::setPort(int port) void TCPLink::setPort(int port)
{ {
bool reconnect(false); bool reconnect = false;
if(this->isConnected())
{ if (this->isConnected()) {
disconnect(); disconnect();
reconnect = true; reconnect = true;
} }
this->port = port;
this->name = tr("TCP Link (port:%1)").arg(this->port); _port = port;
emit nameChanged(this->name); _resetName();
if(reconnect)
{ if (reconnect) {
connect(); connect();
} }
} }
#ifdef TCPLINK_READWRITE_DEBUG #ifdef TCPLINK_READWRITE_DEBUG
void TCPLink::writeDebugBytes(const char *data, qint16 size) void TCPLink::_writeDebugBytes(const char *data, qint16 size)
{ {
QString bytes; QString bytes;
QString ascii; QString ascii;
...@@ -119,7 +117,7 @@ void TCPLink::writeDebugBytes(const char *data, qint16 size) ...@@ -119,7 +117,7 @@ void TCPLink::writeDebugBytes(const char *data, qint16 size)
ascii.append(219); ascii.append(219);
} }
} }
qDebug() << "Sent" << size << "bytes to" << host.toString() << ":" << port << "data:"; qDebug() << "Sent" << size << "bytes to" << _hostAddress.toString() << ":" << _port << "data:";
qDebug() << bytes; qDebug() << bytes;
qDebug() << "ASCII:" << ascii; qDebug() << "ASCII:" << ascii;
} }
...@@ -128,9 +126,9 @@ void TCPLink::writeDebugBytes(const char *data, qint16 size) ...@@ -128,9 +126,9 @@ void TCPLink::writeDebugBytes(const char *data, qint16 size)
void TCPLink::writeBytes(const char* data, qint64 size) void TCPLink::writeBytes(const char* data, qint64 size)
{ {
#ifdef TCPLINK_READWRITE_DEBUG #ifdef TCPLINK_READWRITE_DEBUG
writeDebugBytes(data, size); _writeDebugBytes(data, size);
#endif #endif
socket->write(data, size); _socket->write(data, size);
// Log the amount and time written out for future data rate calculations. // Log the amount and time written out for future data rate calculations.
QMutexLocker dataRateLocker(&dataRateMutex); QMutexLocker dataRateLocker(&dataRateMutex);
...@@ -145,14 +143,14 @@ void TCPLink::writeBytes(const char* data, qint64 size) ...@@ -145,14 +143,14 @@ void TCPLink::writeBytes(const char* data, qint64 size)
**/ **/
void TCPLink::readBytes() void TCPLink::readBytes()
{ {
qint64 byteCount = socket->bytesAvailable(); qint64 byteCount = _socket->bytesAvailable();
if (byteCount) if (byteCount)
{ {
QByteArray buffer; QByteArray buffer;
buffer.resize(byteCount); buffer.resize(byteCount);
socket->read(buffer.data(), buffer.size()); _socket->read(buffer.data(), buffer.size());
emit bytesReceived(this, buffer); emit bytesReceived(this, buffer);
...@@ -166,7 +164,6 @@ void TCPLink::readBytes() ...@@ -166,7 +164,6 @@ void TCPLink::readBytes()
} }
} }
/** /**
* @brief Get the number of bytes to read. * @brief Get the number of bytes to read.
* *
...@@ -174,7 +171,7 @@ void TCPLink::readBytes() ...@@ -174,7 +171,7 @@ void TCPLink::readBytes()
**/ **/
qint64 TCPLink::bytesAvailable() qint64 TCPLink::bytesAvailable()
{ {
return socket->bytesAvailable(); return _socket->bytesAvailable();
} }
/** /**
...@@ -184,15 +181,18 @@ qint64 TCPLink::bytesAvailable() ...@@ -184,15 +181,18 @@ qint64 TCPLink::bytesAvailable()
**/ **/
bool TCPLink::disconnect() bool TCPLink::disconnect()
{ {
this->quit(); quit();
this->wait(); wait();
if (socket) if (_socket)
{ {
socket->disconnect(); _socket->disconnectFromHost();
socketIsConnected = false; _socketIsConnected = false;
delete socket; delete _socket;
socket = NULL; _socket = NULL;
emit disconnected();
emit connected(false);
} }
return true; return true;
...@@ -205,42 +205,54 @@ bool TCPLink::disconnect() ...@@ -205,42 +205,54 @@ bool TCPLink::disconnect()
**/ **/
bool TCPLink::connect() bool TCPLink::connect()
{ {
if(this->isRunning()) if (isRunning())
{ {
this->quit(); quit();
this->wait(); wait();
} }
bool connected = this->hardwareConnect(); bool connected = _hardwareConnect();
start(HighPriority); if (connected) {
start(HighPriority);
}
return connected; return connected;
} }
bool TCPLink::hardwareConnect(void) bool TCPLink::_hardwareConnect(void)
{ {
socket = new QTcpSocket(); Q_ASSERT(_socket == NULL);
_socket = new QTcpSocket();
socket->connectToHost(host, port); QSignalSpy errorSpy(_socket, SIGNAL(error(QAbstractSocket::SocketError)));
QObject::connect(socket, SIGNAL(readyRead()), this, SLOT(readBytes())); _socket->connectToHost(_hostAddress, _port);
QObject::connect(socket, SIGNAL(error(QAbstractSocket::SocketError)), this, SLOT(socketError(QAbstractSocket::SocketError)));
QObject::connect(_socket, SIGNAL(readyRead()), this, SLOT(readBytes()));
QObject::connect(_socket, SIGNAL(error(QAbstractSocket::SocketError)), this, SLOT(_socketError(QAbstractSocket::SocketError)));
// Give the socket a second to connect to the other side otherwise error out // Give the socket a second to connect to the other side otherwise error out
if (!socket->waitForConnected(1000)) if (!_socket->waitForConnected(1000))
{ {
emit communicationError(getName(), "connection failed"); // Whether a failed connection emits an error signal or not is platform specific.
// So in cases where it is not emitted, we emit one ourselves.
if (errorSpy.count() == 0) {
emit communicationError(getName(), "Connection failed");
}
delete _socket;
_socket = NULL;
return false; return false;
} }
socketIsConnected = true; _socketIsConnected = true;
emit connected(true); emit connected(true);
emit connected();
return true; return true;
} }
void TCPLink::socketError(QAbstractSocket::SocketError socketError) void TCPLink::_socketError(QAbstractSocket::SocketError socketError)
{ {
Q_UNUSED(socketError); Q_UNUSED(socketError);
emit communicationError(getName(), "Error on socket: " + socket->errorString()); emit communicationError(getName(), "Error on socket: " + _socket->errorString());
} }
/** /**
...@@ -250,26 +262,19 @@ void TCPLink::socketError(QAbstractSocket::SocketError socketError) ...@@ -250,26 +262,19 @@ void TCPLink::socketError(QAbstractSocket::SocketError socketError)
**/ **/
bool TCPLink::isConnected() const bool TCPLink::isConnected() const
{ {
return socketIsConnected; return _socketIsConnected;
} }
int TCPLink::getId() const int TCPLink::getId() const
{ {
return id; return _linkId;
} }
QString TCPLink::getName() const QString TCPLink::getName() const
{ {
return name; return _name;
}
void TCPLink::setName(QString name)
{
this->name = name;
emit nameChanged(this->name);
} }
qint64 TCPLink::getConnectionSpeed() const qint64 TCPLink::getConnectionSpeed() const
{ {
return 54000000; // 54 Mbit return 54000000; // 54 Mbit
...@@ -284,3 +289,9 @@ qint64 TCPLink::getCurrentOutDataRate() const ...@@ -284,3 +289,9 @@ qint64 TCPLink::getCurrentOutDataRate() const
{ {
return 0; return 0;
} }
void TCPLink::_resetName(void)
{
_name = QString("TCP Link (host:%1 port:%2)").arg(_hostAddress.toString()).arg(_port);
emit nameChanged(_name);
}
\ No newline at end of file
...@@ -21,12 +21,10 @@ ...@@ -21,12 +21,10 @@
======================================================================*/ ======================================================================*/
/** /// @file
* @file /// @brief TCP link type for SITL support
* @brief TCP connection (server) for unmanned vehicles ///
* @author Lorenz Meier <mavteam@student.ethz.ch> /// @author Don Gagne <don@thegagnes.com>
*
*/
#ifndef TCPLINK_H #ifndef TCPLINK_H
#define TCPLINK_H #define TCPLINK_H
...@@ -50,66 +48,65 @@ public: ...@@ -50,66 +48,65 @@ public:
TCPLink(QHostAddress hostAddress = QHostAddress::LocalHost, quint16 socketPort = 5760); TCPLink(QHostAddress hostAddress = QHostAddress::LocalHost, quint16 socketPort = 5760);
~TCPLink(); ~TCPLink();
void requestReset() { } void setHostAddress(QHostAddress hostAddress);
bool isConnected() const; QHostAddress getHostAddress(void) const { return _hostAddress; }
qint64 bytesAvailable(); quint16 getPort(void) const { return _port; }
int getPort() const { QTcpSocket* getSocket(void) { return _socket; }
return port;
}
QHostAddress getHostAddress() const {
return host;
}
QString getName() const; // LinkInterface methods
int getBaudRate() const; virtual int getId(void) const;
int getBaudRateType() const; virtual QString getName(void) const;
int getFlowType() const; virtual bool isConnected(void) const;
int getParityType() const; virtual bool connect(void);
int getDataBitsType() const; virtual bool disconnect(void);
int getStopBitsType() const; virtual qint64 bytesAvailable(void);
virtual void requestReset(void) {};
// Extensive statistics for scientific purposes // Extensive statistics for scientific purposes
qint64 getConnectionSpeed() const; qint64 getConnectionSpeed() const;
qint64 getCurrentInDataRate() const; qint64 getCurrentInDataRate() const;
qint64 getCurrentOutDataRate() const; qint64 getCurrentOutDataRate() const;
void run();
int getId() const;
public slots: public slots:
void setAddress(QHostAddress host); void setHostAddress(const QString& hostAddress);
void setPort(int port); void setPort(int port);
void readBytes();
void writeBytes(const char* data, qint64 length);
bool connect();
bool disconnect();
void socketError(QAbstractSocket::SocketError socketError);
void setAddress(const QString &text);
// From LinkInterface
virtual void writeBytes(const char* data, qint64 length);
protected slots:
void _socketError(QAbstractSocket::SocketError socketError);
// From LinkInterface
virtual void readBytes(void);
protected: protected:
QString name; // From LinkInterface->QThread
QHostAddress host; virtual void run(void);
quint16 port;
int id;
QTcpSocket* socket;
bool socketIsConnected;
QMutex dataMutex;
void setName(QString name);
private: private:
bool hardwareConnect(void); void _resetName(void);
bool _hardwareConnect(void);
#ifdef TCPLINK_READWRITE_DEBUG #ifdef TCPLINK_READWRITE_DEBUG
void writeDebugBytes(const char *data, qint16 size); void _writeDebugBytes(const char *data, qint16 size);
#endif #endif
QString _name;
QHostAddress _hostAddress;
quint16 _port;
int _linkId;
QTcpSocket* _socket;
bool _socketIsConnected;
signals: quint64 _bitsSentTotal;
//Signals are defined by LinkInterface quint64 _bitsSentCurrent;
quint64 _bitsSentMax;
quint64 _bitsReceivedTotal;
quint64 _bitsReceivedCurrent;
quint64 _bitsReceivedMax;
quint64 _connectionStartTime;
QMutex _statisticsMutex;
}; };
#endif // TCPLINK_H #endif // TCPLINK_H
...@@ -14,7 +14,7 @@ QGCTCPLinkConfiguration::QGCTCPLinkConfiguration(TCPLink* link, QWidget *parent) ...@@ -14,7 +14,7 @@ QGCTCPLinkConfiguration::QGCTCPLinkConfiguration(TCPLink* link, QWidget *parent)
QString addr = link->getHostAddress().toString(); QString addr = link->getHostAddress().toString();
ui->hostAddressLineEdit->setText(addr); ui->hostAddressLineEdit->setText(addr);
connect(ui->portSpinBox, SIGNAL(valueChanged(int)), link, SLOT(setPort(int))); connect(ui->portSpinBox, SIGNAL(valueChanged(int)), link, SLOT(setPort(int)));
connect(ui->hostAddressLineEdit, SIGNAL(textChanged (const QString &)), link, SLOT(setAddress(const QString &))); connect(ui->hostAddressLineEdit, SIGNAL(textChanged (const QString &)), link, SLOT(setHostAddress(const QString &)));
} }
QGCTCPLinkConfiguration::~QGCTCPLinkConfiguration() QGCTCPLinkConfiguration::~QGCTCPLinkConfiguration()
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment