Commit ebdd072e authored by Lorenz Meier's avatar Lorenz Meier

Fix up threading of UAS object, WIP

parent ae848a5e
......@@ -562,7 +562,8 @@ HEADERS += \
src/ui/designer/QGCXYPlot.h \
src/ui/menuactionhelper.h \
src/uas/UASManagerInterface.h \
src/uas/QGCUASParamManagerInterface.h
src/uas/QGCUASParamManagerInterface.h \
src/uas/QGCUASWorker.h
SOURCES += \
src/main.cc \
......@@ -745,4 +746,5 @@ SOURCES += \
src/ui/px4_configuration/QGCPX4MulticopterConfig.cc \
src/ui/px4_configuration/QGCPX4SensorCalibration.cc \
src/ui/designer/QGCXYPlot.cc \
src/ui/menuactionhelper.cpp
src/ui/menuactionhelper.cpp \
src/uas/QGCUASWorker.cc
#include "QGCMAVLinkUASFactory.h"
#include "UASManager.h"
#include "QGCUASWorker.h"
QGCMAVLinkUASFactory::QGCMAVLinkUASFactory(QObject *parent) :
QObject(parent)
......@@ -21,7 +22,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
UASInterface* uas;
QThread* worker = new QThread();
QGCUASWorker* worker = new QGCUASWorker();
switch (heartbeat->autopilot)
{
......
#include "QGCUASWorker.h"
#include <QGC.h>
QGCUASWorker::QGCUASWorker() : QThread()
{
}
void QGCUASWorker::run()
{
QGC::SLEEP::msleep(100);
}
#ifndef QGCUASWORKER_H
#define QGCUASWORKER_H
#include <QThread>
class QGCUASWorker : public QThread
{
public:
QGCUASWorker();
protected:
void run();
};
#endif // QGCUASWORKER_H
......@@ -51,7 +51,7 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
commStatus(COMM_DISCONNECTED),
receiveDropRate(0),
sendDropRate(0),
statusTimeout(new QTimer(this)),
statusTimeout(new QTimer()),
name(""),
type(MAV_TYPE_GENERIC),
......@@ -138,7 +138,7 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
airSpeed(std::numeric_limits<double>::quiet_NaN()),
groundSpeed(std::numeric_limits<double>::quiet_NaN()),
waypointManager(this),
waypointManager(),
attitudeKnown(false),
attitudeStamped(false),
......@@ -153,7 +153,7 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
paramsOnceRequested(false),
paramMgr(this),
paramMgr(),
simulation(0),
// The protected members.
......@@ -180,17 +180,17 @@ UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
// Store a list of available actions for this UAS.
// Basically everything exposed as a SLOT with no return value or arguments.
QAction* newAction = new QAction(tr("Arm"), this);
QAction* newAction = new QAction(tr("Arm"), thread);
newAction->setToolTip(tr("Enable the UAS so that all actuators are online"));
connect(newAction, SIGNAL(triggered()), this, SLOT(armSystem()));
actions.append(newAction);
newAction = new QAction(tr("Disarm"), this);
newAction = new QAction(tr("Disarm"), thread);
newAction->setToolTip(tr("Disable the UAS so that all actuators are offline"));
connect(newAction, SIGNAL(triggered()), this, SLOT(disarmSystem()));
actions.append(newAction);
newAction = new QAction(tr("Toggle armed"), this);
newAction = new QAction(tr("Toggle armed"), thread);
newAction->setToolTip(tr("Toggle between armed and disarmed"));
connect(newAction, SIGNAL(triggered()), this, SLOT(toggleAutonomy()));
actions.append(newAction);
......
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