Commit 2d8796a9 authored by Lorenz Meier's avatar Lorenz Meier

UAS threading improvements

parent f6eaed25
......@@ -38,8 +38,8 @@ This file is part of the QGROUNDCONTROL project
#endif
#endif
ArduPilotMegaMAV::ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id) :
UAS(mavlink, id)//,
ArduPilotMegaMAV::ArduPilotMegaMAV(MAVLinkProtocol* mavlink, QThread* thread, int id) :
UAS(mavlink, thread, id)//,
// place other initializers here
{
//This does not seem to work. Manually request each stream type at a specified rate.
......
......@@ -29,7 +29,7 @@ class ArduPilotMegaMAV : public UAS
{
Q_OBJECT
public:
ArduPilotMegaMAV(MAVLinkProtocol* mavlink, int id = 0);
ArduPilotMegaMAV(MAVLinkProtocol* mavlink, QThread* thread, int id = 0);
/** @brief Set camera mount stabilization modes */
void setMountConfigure(unsigned char mode, bool stabilize_roll,bool stabilize_pitch,bool stabilize_yaw);
/** @brief Set camera mount control */
......
......@@ -23,8 +23,8 @@ This file is part of the QGROUNDCONTROL project
#include "PxQuadMAV.h"
#include "GAudioOutput.h"
PxQuadMAV::PxQuadMAV(MAVLinkProtocol* mavlink, int id) :
UAS(mavlink, id)
PxQuadMAV::PxQuadMAV(MAVLinkProtocol* mavlink, QThread* thread, int id) :
UAS(mavlink, thread, id)
{
}
......
......@@ -31,7 +31,7 @@ class PxQuadMAV : public UAS
Q_OBJECT
Q_INTERFACES(UASInterface)
public:
PxQuadMAV(MAVLinkProtocol* mavlink, int id);
PxQuadMAV(MAVLinkProtocol* mavlink, QThread* thread, int id);
public slots:
/** @brief Receive a MAVLink message from this MAV */
void receiveMessage(LinkInterface* link, mavlink_message_t message);
......
......@@ -27,7 +27,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
{
case MAV_AUTOPILOT_GENERIC:
{
UAS* mav = new UAS(mavlink, sysid);
UAS* mav = new UAS(mavlink, worker, sysid);
// Set the system type
mav->setSystemType((int)heartbeat->type);
......@@ -43,7 +43,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
break;
case MAV_AUTOPILOT_PIXHAWK:
{
PxQuadMAV* mav = new PxQuadMAV(mavlink, sysid);
PxQuadMAV* mav = new PxQuadMAV(mavlink, worker, sysid);
// Set the system type
mav->setSystemType((int)heartbeat->type);
......@@ -62,7 +62,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
break;
case MAV_AUTOPILOT_SLUGS:
{
SlugsMAV* mav = new SlugsMAV(mavlink, sysid);
SlugsMAV* mav = new SlugsMAV(mavlink, worker, sysid);
// Set the system type
mav->setSystemType((int)heartbeat->type);
......@@ -78,7 +78,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
break;
case MAV_AUTOPILOT_ARDUPILOTMEGA:
{
ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(mavlink, sysid);
ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(mavlink, worker, sysid);
// Set the system type
mav->setSystemType((int)heartbeat->type);
......@@ -95,7 +95,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
#ifdef QGC_USE_SENSESOAR_MESSAGES
case MAV_AUTOPILOT_SENSESOAR:
{
senseSoarMAV* mav = new senseSoarMAV(mavlink,sysid);
senseSoarMAV* mav = new senseSoarMAV(mavlink,worker, sysid);
mav->setSystemType((int)heartbeat->type);
mav->moveToThread(worker);
......@@ -107,11 +107,9 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
#endif
default:
{
UAS* mav = new UAS(mavlink, sysid);
UAS* mav = new UAS(mavlink, worker, sysid);
mav->setSystemType((int)heartbeat->type);
mav->moveToThread(worker);
// Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special
......
......@@ -2,8 +2,8 @@
#include <QDebug>
SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, int id) :
UAS(mavlink, id)
SlugsMAV::SlugsMAV(MAVLinkProtocol* mavlink, QThread* thread, int id) :
UAS(mavlink, thread, id)
{
widgetTimer = new QTimer (this);
widgetTimer->setInterval(SLUGS_UPDATE_RATE);
......
......@@ -53,7 +53,7 @@ class SlugsMAV : public UAS
public:
SlugsMAV(MAVLinkProtocol* mavlink, int id = 0);
SlugsMAV(MAVLinkProtocol* mavlink, QThread* thread, int id = 0);
public slots:
/** @brief Receive a MAVLink message from this MAV */
......
......@@ -41,7 +41,7 @@
* creating the UAS.
*/
UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
UAS::UAS(MAVLinkProtocol* protocol, QThread* thread, int id) : UASInterface(),
lipoFull(4.2f),
lipoEmpty(3.5f),
uasId(id),
......@@ -166,6 +166,11 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
lastSendTimeGPS(0),
lastSendTimeSensors(0)
{
moveToThread(thread);
waypointManager.moveToThread(thread);
paramMgr.moveToThread(thread);
statusTimeout->moveToThread(thread);
for (unsigned int i = 0; i<255;++i)
{
componentID[i] = -1;
......@@ -173,7 +178,7 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
}
// Store a list of available actions for this UAS.
// Basically everything exposted as a SLOT with no return value or arguments.
// Basically everything exposed as a SLOT with no return value or arguments.
QAction* newAction = new QAction(tr("Arm"), this);
newAction->setToolTip(tr("Enable the UAS so that all actuators are online"));
......@@ -364,34 +369,6 @@ void UAS::updateState()
GAudioOutput::instance()->notifyNegative();
}
}
//#define MAVLINK_OFFBOARD_CONTROL_MODE_NONE 0
//#define MAVLINK_OFFBOARD_CONTROL_MODE_RATES 1
//#define MAVLINK_OFFBOARD_CONTROL_MODE_ATTITUDE 2
//#define MAVLINK_OFFBOARD_CONTROL_MODE_VELOCITY 3
//#define MAVLINK_OFFBOARD_CONTROL_MODE_POSITION 4
//#define MAVLINK_OFFBOARD_CONTROL_FLAG_ARMED 0x10
//#warning THIS IS A HUGE HACK AND SHOULD NEVER SHOW UP IN ANY GIT REPOSITORY
// mavlink_message_t message;
// mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t sp;
// sp.group = 0;
// /* set rate mode, set zero rates and 20% throttle */
// sp.mode = MAVLINK_OFFBOARD_CONTROL_MODE_RATES | MAVLINK_OFFBOARD_CONTROL_FLAG_ARMED;
// sp.roll[0] = INT16_MAX * 0.0f;
// sp.pitch[0] = INT16_MAX * 0.0f;
// sp.yaw[0] = INT16_MAX * 0.0f;
// sp.thrust[0] = UINT16_MAX * 0.3f;
// /* send from system 200 and component 0 */
// mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode(200, 0, &message, &sp);
// sendMessage(message);
}
/**
......
......@@ -32,6 +32,7 @@ This file is part of the QGROUNDCONTROL project
#ifndef _UAS_H_
#define _UAS_H_
#include <QThread>
#include "UASInterface.h"
#include <MAVLinkProtocol.h>
#include <QVector3D>
......@@ -55,7 +56,7 @@ class UAS : public UASInterface
{
Q_OBJECT
public:
UAS(MAVLinkProtocol* protocol, int id = 0);
UAS(MAVLinkProtocol* protocol, QThread* thread, int id = 0);
~UAS();
float lipoFull; ///< 100% charged voltage
......
......@@ -2,8 +2,8 @@
#include <cmath>
#include <qmath.h>
senseSoarMAV::senseSoarMAV(MAVLinkProtocol* mavlink, int id)
: UAS(mavlink, id), senseSoarState(0)
senseSoarMAV::senseSoarMAV(MAVLinkProtocol* mavlink, QThread* thread, int id)
: UAS(mavlink, thread, id), senseSoarState(0)
{
}
......
......@@ -14,7 +14,7 @@ class senseSoarMAV : public UAS
Q_INTERFACES(UASInterface)
public:
senseSoarMAV(MAVLinkProtocol* mavlink, int id);
senseSoarMAV(MAVLinkProtocol* mavlink, QThread* thread, int id);
~senseSoarMAV(void);
public slots:
/** @brief Receive a MAVLink message from this MAV */
......
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