Commit 3237dd41 authored by Nate Weibley's avatar Nate Weibley

Enforce threadsafe shutdown and deletion of MAVLinkDecoder

parent 02441ff5
......@@ -3,10 +3,9 @@
#include <QDebug>
MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
QThread()
MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol) :
QThread(), creationThread(QThread::currentThread())
{
Q_UNUSED(parent);
// 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/
moveToThread(this);
......@@ -52,6 +51,7 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
// textMessageFilter.insert(MAVLINK_MSG_ID_HIGHRES_IMU, false);
connect(protocol, &MAVLinkProtocol::messageReceived, this, &MAVLinkDecoder::receiveMessage);
connect(this, &MAVLinkDecoder::finish, this, &QThread::quit);
start(LowPriority);
}
......@@ -63,6 +63,7 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
void MAVLinkDecoder::run()
{
exec();
moveToThread(creationThread);
}
void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t message)
......
......@@ -8,13 +8,14 @@ class MAVLinkDecoder : public QThread
{
Q_OBJECT
public:
MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent = 0);
MAVLinkDecoder(MAVLinkProtocol* protocol);
void run();
signals:
void textMessageReceived(int uasid, int componentid, int severity, const QString& text);
void valueChanged(const int uasId, const QString& name, const QString& unit, const QVariant& value, const quint64 msec);
void finish(); ///< Trigger a thread safe shutdown
public slots:
/** @brief Receive one message from the protocol and decode it */
......@@ -35,6 +36,7 @@ protected:
quint64 onboardTimeOffset[cMessageIds]; ///< Offset of onboard time from Unix epoch (of the receiving GCS)
qint64 onboardToGCSUnixTimeOffsetAndDelay[cMessageIds]; ///< Offset of onboard time and GCS Unix time
quint64 firstOnboardTime[cMessageIds]; ///< First seen onboard time
QThread* creationThread; ///< QThread on which the object is created
};
#endif // MAVLINKDECODER_H
......@@ -274,6 +274,11 @@ MainWindow::MainWindow()
MainWindow::~MainWindow()
{
// Enforce thread-safe shutdown of the mavlink decoder
mavlinkDecoder->finish();
mavlinkDecoder->wait(1000);
mavlinkDecoder->deleteLater();
// This needs to happen before we get into the QWidget dtor
// otherwise the QML engine reads freed data and tries to
// destroy MainWindow a second time.
......@@ -290,8 +295,7 @@ QString MainWindow::_getWindowGeometryKey()
void MainWindow::_buildCommonWidgets(void)
{
// Add generic MAVLink decoder
// TODO: This is never deleted
mavlinkDecoder = new MAVLinkDecoder(qgcApp()->toolbox()->mavlinkProtocol(), this);
mavlinkDecoder = new MAVLinkDecoder(qgcApp()->toolbox()->mavlinkProtocol());
connect(mavlinkDecoder.data(), &MAVLinkDecoder::valueChanged, this, &MainWindow::valueChanged);
// Log player
......
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