Commit 15812f3a authored by Lorenz Meier's avatar Lorenz Meier

Move UAS objects to their own worker threads

parent 65dcf96e
...@@ -21,6 +21,8 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -21,6 +21,8 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
UASInterface* uas; UASInterface* uas;
QThread* worker = new QThread();
switch (heartbeat->autopilot) switch (heartbeat->autopilot)
{ {
case MAV_AUTOPILOT_GENERIC: case MAV_AUTOPILOT_GENERIC:
...@@ -28,6 +30,9 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -28,6 +30,9 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
UAS* mav = new UAS(mavlink, sysid); UAS* mav = new UAS(mavlink, sysid);
// Set the system type // Set the system type
mav->setSystemType((int)heartbeat->type); mav->setSystemType((int)heartbeat->type);
mav->moveToThread(worker);
// Connect this robot to the UAS object // Connect this robot to the UAS object
connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t))); connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
#ifdef QGC_PROTOBUF_ENABLED #ifdef QGC_PROTOBUF_ENABLED
...@@ -41,6 +46,9 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -41,6 +46,9 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
PxQuadMAV* mav = new PxQuadMAV(mavlink, sysid); PxQuadMAV* mav = new PxQuadMAV(mavlink, sysid);
// Set the system type // Set the system type
mav->setSystemType((int)heartbeat->type); mav->setSystemType((int)heartbeat->type);
mav->moveToThread(worker);
// Connect this robot to the UAS object // Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type, // it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special // else the slot of the parent object is called (and thus the special
...@@ -57,6 +65,9 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -57,6 +65,9 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
SlugsMAV* mav = new SlugsMAV(mavlink, sysid); SlugsMAV* mav = new SlugsMAV(mavlink, sysid);
// Set the system type // Set the system type
mav->setSystemType((int)heartbeat->type); mav->setSystemType((int)heartbeat->type);
mav->moveToThread(worker);
// Connect this robot to the UAS object // Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type, // it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special // else the slot of the parent object is called (and thus the special
...@@ -70,6 +81,9 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -70,6 +81,9 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(mavlink, sysid); ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(mavlink, sysid);
// Set the system type // Set the system type
mav->setSystemType((int)heartbeat->type); mav->setSystemType((int)heartbeat->type);
mav->moveToThread(worker);
// Connect this robot to the UAS object // Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type, // it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special // else the slot of the parent object is called (and thus the special
...@@ -83,6 +97,9 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -83,6 +97,9 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
{ {
senseSoarMAV* mav = new senseSoarMAV(mavlink,sysid); senseSoarMAV* mav = new senseSoarMAV(mavlink,sysid);
mav->setSystemType((int)heartbeat->type); mav->setSystemType((int)heartbeat->type);
mav->moveToThread(worker);
connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t))); connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
uas = mav; uas = mav;
break; break;
...@@ -92,6 +109,9 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -92,6 +109,9 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
{ {
UAS* mav = new UAS(mavlink, sysid); UAS* mav = new UAS(mavlink, sysid);
mav->setSystemType((int)heartbeat->type); mav->setSystemType((int)heartbeat->type);
mav->moveToThread(worker);
// Connect this robot to the UAS object // Connect this robot to the UAS object
// it is IMPORTANT here to use the right object type, // it is IMPORTANT here to use the right object type,
// else the slot of the parent object is called (and thus the special // else the slot of the parent object is called (and thus the special
...@@ -111,5 +131,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte ...@@ -111,5 +131,7 @@ UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInte
// Now add UAS to "official" list, which makes the whole application aware of it // Now add UAS to "official" list, which makes the whole application aware of it
UASManager::instance()->addUAS(uas); UASManager::instance()->addUAS(uas);
worker->start(QThread::HighPriority);
return uas; return uas;
} }
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