Commit d7dbdf08 authored by Lorenz Meier's avatar Lorenz Meier

Move MAVLink decoder in its own low priority thread

parent 5e06a09c
......@@ -2,8 +2,12 @@
#include "UASManager.h"
MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
QObject(parent)
QThread(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);
mavlink_message_info_t msg[256] = MAVLINK_MESSAGE_INFO;
memcpy(messageInfo, msg, sizeof(mavlink_message_info_t)*256);
memset(receivedMessages, 0, sizeof(mavlink_message_t)*256);
......@@ -46,6 +50,17 @@ MAVLinkDecoder::MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent) :
// textMessageFilter.insert(MAVLINK_MSG_ID_HIGHRES_IMU, false);
connect(protocol, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), this, SLOT(receiveMessage(LinkInterface*,mavlink_message_t)));
start(LowPriority);
}
/**
* @brief Runs the thread
*
**/
void MAVLinkDecoder::run()
{
exec();
}
void MAVLinkDecoder::receiveMessage(LinkInterface* link,mavlink_message_t message)
......
......@@ -4,12 +4,14 @@
#include <QObject>
#include "MAVLinkProtocol.h"
class MAVLinkDecoder : public QObject
class MAVLinkDecoder : public QThread
{
Q_OBJECT
public:
MAVLinkDecoder(MAVLinkProtocol* protocol, QObject *parent = 0);
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);
......
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