Commit 765dfbbd authored by dogmaphobic's avatar dogmaphobic

Make the fix dependent on the Qt version.

parent ac7e80d6
...@@ -28,6 +28,13 @@ This file is part of the QGROUNDCONTROL project ...@@ -28,6 +28,13 @@ This file is part of the QGROUNDCONTROL project
* *
*/ */
#include <QtGlobal>
#if QT_VERSION > 0x050401
#define UDP_BROKEN_SIGNAL 1
#else
#define UDP_BROKEN_SIGNAL 0
#endif
#include <QTimer> #include <QTimer>
#include <QList> #include <QList>
#include <QDebug> #include <QDebug>
...@@ -100,6 +107,7 @@ UDPLink::~UDPLink() ...@@ -100,6 +107,7 @@ UDPLink::~UDPLink()
_disconnect(); _disconnect();
// Tell the thread to exit // Tell the thread to exit
_running = false; _running = false;
quit();
// Wait for it to exit // Wait for it to exit
wait(); wait();
while(_outQueue.count() > 0) { while(_outQueue.count() > 0) {
...@@ -115,13 +123,24 @@ UDPLink::~UDPLink() ...@@ -115,13 +123,24 @@ UDPLink::~UDPLink()
void UDPLink::run() void UDPLink::run()
{ {
if(_hardwareConnect()) { if(_hardwareConnect()) {
while(true) { if(UDP_BROKEN_SIGNAL) {
readBytes(); bool loop = false;
if(_writeBytes() && _running) while(true) {
continue; //-- Anything to read?
if(!_running) loop = _socket->hasPendingDatagrams();
break; if(loop) {
this->msleep(50); readBytes();
}
//-- Loop right away if busy
if((_dequeBytes() || loop) && _running)
continue;
if(!_running)
break;
//-- Settle down (it gets here if there is nothing to read or write)
this->msleep(50);
}
} else {
exec();
} }
} }
if (_socket) { if (_socket) {
...@@ -154,51 +173,58 @@ void UDPLink::removeHost(const QString& host) ...@@ -154,51 +173,58 @@ void UDPLink::removeHost(const QString& host)
_config->removeHost(host); _config->removeHost(host);
} }
#define UDPLINK_DEBUG 0
void UDPLink::writeBytes(const char* data, qint64 size) void UDPLink::writeBytes(const char* data, qint64 size)
{ {
if (!_socket) { if (!_socket) {
return; return;
} }
QByteArray* qdata = new QByteArray(data, size); if(UDP_BROKEN_SIGNAL) {
QMutexLocker lock(&_mutex); QByteArray* qdata = new QByteArray(data, size);
_outQueue.enqueue(qdata); QMutexLocker lock(&_mutex);
_outQueue.enqueue(qdata);
} else {
_sendBytes(data, size);
}
} }
bool UDPLink::_writeBytes() bool UDPLink::_dequeBytes()
{ {
QMutexLocker lock(&_mutex); QMutexLocker lock(&_mutex);
if(_outQueue.count() > 0) { if(_outQueue.count() > 0) {
QByteArray* qdata = _outQueue.dequeue(); QByteArray* qdata = _outQueue.dequeue();
lock.unlock(); lock.unlock();
QStringList goneHosts; _sendBytes(qdata->data(), qdata->size());
// Send to all connected systems
QString host;
int port;
if(_config->firstHost(host, port)) {
do {
QHostAddress currentHost(host);
if(_socket->writeDatagram(qdata->data(), qdata->size(), currentHost, (quint16)port) < 0) {
// This host is gone. Add to list to be removed
goneHosts.append(host);
}
// Log the amount and time written out for future data rate calculations.
QMutexLocker dataRateLocker(&dataRateMutex);
logDataRateToBuffer(outDataWriteAmounts, outDataWriteTimes, &outDataIndex, qdata->size(), QDateTime::currentMSecsSinceEpoch());
} while (_config->nextHost(host, port));
//-- Remove hosts that are no longer there
foreach (QString ghost, goneHosts) {
_config->removeHost(ghost);
}
}
delete qdata; delete qdata;
lock.relock(); lock.relock();
} }
return (_outQueue.count() > 0); return (_outQueue.count() > 0);
} }
void UDPLink::_sendBytes(const char* data, qint64 size)
{
QStringList goneHosts;
// Send to all connected systems
QString host;
int port;
if(_config->firstHost(host, port)) {
do {
QHostAddress currentHost(host);
if(_socket->writeDatagram(data, size, currentHost, (quint16)port) < 0) {
// This host is gone. Add to list to be removed
goneHosts.append(host);
}
// Log the amount and time written out for future data rate calculations.
QMutexLocker dataRateLocker(&dataRateMutex);
logDataRateToBuffer(outDataWriteAmounts, outDataWriteTimes, &outDataIndex, size, QDateTime::currentMSecsSinceEpoch());
} while (_config->nextHost(host, port));
//-- Remove hosts that are no longer there
foreach (QString ghost, goneHosts) {
_config->removeHost(ghost);
}
}
}
/** /**
* @brief Read a number of bytes from the interface. * @brief Read a number of bytes from the interface.
**/ **/
...@@ -235,7 +261,7 @@ void UDPLink::readBytes() ...@@ -235,7 +261,7 @@ void UDPLink::readBytes()
// would trigger this. // would trigger this.
// Add host to broadcast list if not yet present, or update its port // Add host to broadcast list if not yet present, or update its port
_config->addHost(sender.toString(), (int)senderPort); _config->addHost(sender.toString(), (int)senderPort);
if(!_running) if(UDP_BROKEN_SIGNAL && !_running)
break; break;
} }
} }
...@@ -248,6 +274,7 @@ void UDPLink::readBytes() ...@@ -248,6 +274,7 @@ void UDPLink::readBytes()
bool UDPLink::_disconnect(void) bool UDPLink::_disconnect(void)
{ {
_running = false; _running = false;
quit();
wait(); wait();
if (_socket) { if (_socket) {
// Make sure delete happen on correct thread // Make sure delete happen on correct thread
...@@ -255,9 +282,8 @@ bool UDPLink::_disconnect(void) ...@@ -255,9 +282,8 @@ bool UDPLink::_disconnect(void)
_socket = NULL; _socket = NULL;
emit disconnected(); emit disconnected();
} }
// TODO When would this ever return false?
_connectState = false; _connectState = false;
return !_connectState; return true;
} }
/** /**
...@@ -267,17 +293,15 @@ bool UDPLink::_disconnect(void) ...@@ -267,17 +293,15 @@ bool UDPLink::_disconnect(void)
**/ **/
bool UDPLink::_connect(void) bool UDPLink::_connect(void)
{ {
if(this->isRunning()) if(this->isRunning() || _running)
{ {
_running = false; _running = false;
quit();
wait(); wait();
} }
// TODO When would this ever return false?
bool connected = true;
// I see no reason to run this in "HighPriority"
_running = true; _running = true;
start(NormalPriority); start(NormalPriority);
return connected; return true;
} }
bool UDPLink::_hardwareConnect() bool UDPLink::_hardwareConnect()
...@@ -292,6 +316,10 @@ bool UDPLink::_hardwareConnect() ...@@ -292,6 +316,10 @@ bool UDPLink::_hardwareConnect()
_connectState = _socket->bind(host, _config->localPort(), QAbstractSocket::ReuseAddressHint); _connectState = _socket->bind(host, _config->localPort(), QAbstractSocket::ReuseAddressHint);
if (_connectState) { if (_connectState) {
_registerZeroconf(_config->localPort(), kZeroconfRegistration); _registerZeroconf(_config->localPort(), kZeroconfRegistration);
//-- Connect signal if this version of Qt is not broken
if(!UDP_BROKEN_SIGNAL) {
QObject::connect(_socket, SIGNAL(readyRead()), this, SLOT(readBytes()));
}
emit connected(); emit connected();
} else { } else {
emit communicationError("UDP Link Error", "Error binding UDP port"); emit communicationError("UDP Link Error", "Error binding UDP port");
......
...@@ -219,7 +219,8 @@ private: ...@@ -219,7 +219,8 @@ private:
QMutex _mutex; QMutex _mutex;
QQueue<QByteArray*> _outQueue; QQueue<QByteArray*> _outQueue;
bool _writeBytes (); bool _dequeBytes ();
void _sendBytes (const char* data, qint64 size);
}; };
......
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