Commit 5b3e8eb2 authored by Lorenz Meier's avatar Lorenz Meier

More cleanup on threading

parent eaf61cb1
...@@ -64,7 +64,7 @@ MAVLinkProtocol::MAVLinkProtocol() : ...@@ -64,7 +64,7 @@ MAVLinkProtocol::MAVLinkProtocol() :
m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx"; m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
loadSettings(); loadSettings();
//start(QThread::LowPriority); moveToThread(this);
// Start heartbeat timer, emitting a heartbeat at the configured rate // Start heartbeat timer, emitting a heartbeat at the configured rate
connect(heartbeatTimer, SIGNAL(timeout()), this, SLOT(sendHeartbeat())); connect(heartbeatTimer, SIGNAL(timeout()), this, SLOT(sendHeartbeat()));
heartbeatTimer->start(1000/heartbeatRate); heartbeatTimer->start(1000/heartbeatRate);
...@@ -81,6 +81,8 @@ MAVLinkProtocol::MAVLinkProtocol() : ...@@ -81,6 +81,8 @@ MAVLinkProtocol::MAVLinkProtocol() :
} }
} }
start(QThread::HighPriority);
emit versionCheckChanged(m_enable_version_check); emit versionCheckChanged(m_enable_version_check);
} }
...@@ -166,6 +168,20 @@ MAVLinkProtocol::~MAVLinkProtocol() ...@@ -166,6 +168,20 @@ MAVLinkProtocol::~MAVLinkProtocol()
delete m_logfile; delete m_logfile;
m_logfile = NULL; m_logfile = NULL;
} }
// Tell the thread to exit
quit();
// Wait for it to exit
wait();
}
/**
* @brief Runs the thread
*
**/
void MAVLinkProtocol::run()
{
exec();
} }
QString MAVLinkProtocol::getLogfileName() QString MAVLinkProtocol::getLogfileName()
......
...@@ -150,6 +150,8 @@ public: ...@@ -150,6 +150,8 @@ public:
*/ */
virtual void resetMetadataForLink(const LinkInterface *link); virtual void resetMetadataForLink(const LinkInterface *link);
void run();
public slots: public slots:
/** @brief Receive bytes from a communication interface */ /** @brief Receive bytes from a communication interface */
void receiveBytes(LinkInterface* link, QByteArray b); void receiveBytes(LinkInterface* link, QByteArray b);
......
...@@ -46,7 +46,7 @@ This file is part of the PIXHAWK project ...@@ -46,7 +46,7 @@ This file is part of the PIXHAWK project
* @see LinkManager. * @see LinkManager.
* *
**/ **/
class ProtocolInterface : public QObject class ProtocolInterface : public QThread
{ {
Q_OBJECT Q_OBJECT
public: public:
......
...@@ -74,6 +74,11 @@ QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress ...@@ -74,6 +74,11 @@ QGCXPlaneLink::QGCXPlaneLink(UASInterface* mav, QString remoteHost, QHostAddress
QGCXPlaneLink::~QGCXPlaneLink() QGCXPlaneLink::~QGCXPlaneLink()
{ {
storeSettings(); storeSettings();
// Tell the thread to exit
quit();
// Wait for it to exit
wait();
// if(connectState) { // if(connectState) {
// disconnectSimulation(); // disconnectSimulation();
// } // }
......
...@@ -87,6 +87,11 @@ SerialLink::~SerialLink() ...@@ -87,6 +87,11 @@ SerialLink::~SerialLink()
disconnect(); disconnect();
if(m_port) delete m_port; if(m_port) delete m_port;
m_port = NULL; m_port = NULL;
// Tell the thread to exit
quit();
// Wait for it to exit
wait();
} }
QList<QString> SerialLink::getCurrentPorts() QList<QString> SerialLink::getCurrentPorts()
...@@ -455,6 +460,7 @@ bool SerialLink::hardwareConnect(QString &type) ...@@ -455,6 +460,7 @@ bool SerialLink::hardwareConnect(QString &type)
qDebug() << "SerialLink: hardwareConnect to " << m_portName; qDebug() << "SerialLink: hardwareConnect to " << m_portName;
m_port = new QSerialPort(m_portName); m_port = new QSerialPort(m_portName);
m_port->moveToThread(this);
if (!m_port) { if (!m_port) {
emit communicationUpdate(getName(),"Error opening port: " + m_portName); emit communicationUpdate(getName(),"Error opening port: " + m_portName);
......
...@@ -56,6 +56,12 @@ TCPLink::TCPLink(QHostAddress hostAddress, quint16 socketPort) : ...@@ -56,6 +56,12 @@ TCPLink::TCPLink(QHostAddress hostAddress, quint16 socketPort) :
TCPLink::~TCPLink() TCPLink::~TCPLink()
{ {
disconnect(); disconnect();
// Tell the thread to exit
quit();
// Wait for it to exit
wait();
deleteLater(); deleteLater();
} }
......
...@@ -60,6 +60,12 @@ UDPLink::UDPLink(QHostAddress host, quint16 port) : ...@@ -60,6 +60,12 @@ UDPLink::UDPLink(QHostAddress host, quint16 port) :
UDPLink::~UDPLink() UDPLink::~UDPLink()
{ {
disconnect(); disconnect();
// Tell the thread to exit
quit();
// Wait for it to exit
wait();
this->deleteLater(); this->deleteLater();
} }
......
...@@ -132,6 +132,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -132,6 +132,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
UASManager::instance()->addUAS(uas); UASManager::instance()->addUAS(uas);
worker->start(QThread::HighPriority); worker->start(QThread::HighPriority);
connect(uas, SIGNAL(destroyed()), worker, SLOT(quit()));
return uas; return uas;
} }
...@@ -172,7 +172,6 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), ...@@ -172,7 +172,6 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
componentMulti[i] = false; componentMulti[i] = false;
} }
// Store a list of available actions for this UAS. // Store a list of available actions for this UAS.
// Basically everything exposted as a SLOT with no return value or arguments. // Basically everything exposted as a SLOT with no return value or arguments.
......
...@@ -2,7 +2,7 @@ ...@@ -2,7 +2,7 @@
#include "UASManager.h" #include "UASManager.h"
MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) : MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
QThread(parent) QThread()
{ {
// We're doing it wrong - because the Qt folks got the API wrong: // We're doing it wrong - because the Qt folks got the API wrong:
// http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/ // http://blog.qt.digia.com/blog/2010/06/17/youre-doing-it-wrong/
......
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