QGCMAVLinkUASFactory.cc 4.67 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12
#include "QGCMAVLinkUASFactory.h"
#include "UASManager.h"

QGCMAVLinkUASFactory::QGCMAVLinkUASFactory(QObject *parent) :
    QObject(parent)
{
}

UASInterface* QGCMAVLinkUASFactory::createUAS(MAVLinkProtocol* mavlink, LinkInterface* link, int sysid, mavlink_heartbeat_t* heartbeat, QObject* parent)
{
    QPointer<QObject> p;

lm's avatar
lm committed
13 14
    if (parent != NULL)
    {
15
        p = parent;
lm's avatar
lm committed
16 17 18
    }
    else
    {
19 20 21 22 23
        p = mavlink;
    }

    UASInterface* uas;

24 25
    QThread* worker = new QThread();

lm's avatar
lm committed
26 27
    switch (heartbeat->autopilot)
    {
28
    case MAV_AUTOPILOT_GENERIC:
lm's avatar
lm committed
29
    {
30 31 32
        UAS* mav = new UAS(mavlink, sysid);
        // Set the system type
        mav->setSystemType((int)heartbeat->type);
33 34 35

        mav->moveToThread(worker);

36 37
        // Connect this robot to the UAS object
        connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
38 39 40
#ifdef QGC_PROTOBUF_ENABLED
        connect(mavlink, SIGNAL(extendedMessageReceived(LinkInterface*, std::tr1::shared_ptr<google::protobuf::Message>)), mav, SLOT(receiveExtendedMessage(LinkInterface*, std::tr1::shared_ptr<google::protobuf::Message>)));
#endif
41
        uas = mav;
42 43
    }
    break;
44
    case MAV_AUTOPILOT_PIXHAWK:
lm's avatar
lm committed
45
    {
46 47 48
        PxQuadMAV* mav = new PxQuadMAV(mavlink, sysid);
        // Set the system type
        mav->setSystemType((int)heartbeat->type);
49 50 51

        mav->moveToThread(worker);

52 53 54 55 56
        // 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
        // packets never reach their goal)
        connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
57 58 59
#ifdef QGC_PROTOBUF_ENABLED
        connect(mavlink, SIGNAL(extendedMessageReceived(LinkInterface*, std::tr1::shared_ptr<google::protobuf::Message>)), mav, SLOT(receiveExtendedMessage(LinkInterface*, std::tr1::shared_ptr<google::protobuf::Message>)));
#endif
60 61 62
        uas = mav;
    }
    break;
63
    case MAV_AUTOPILOT_SLUGS:
lm's avatar
lm committed
64
    {
65 66 67
        SlugsMAV* mav = new SlugsMAV(mavlink, sysid);
        // Set the system type
        mav->setSystemType((int)heartbeat->type);
68 69 70

        mav->moveToThread(worker);

71 72 73 74 75 76 77 78
        // 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
        // packets never reach their goal)
        connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
        uas = mav;
    }
    break;
79
    case MAV_AUTOPILOT_ARDUPILOTMEGA:
lm's avatar
lm committed
80
    {
81 82 83
        ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(mavlink, sysid);
        // Set the system type
        mav->setSystemType((int)heartbeat->type);
84 85 86

        mav->moveToThread(worker);

87 88 89 90 91 92 93 94
        // 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
        // packets never reach their goal)
        connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
        uas = mav;
    }
    break;
oberion's avatar
oberion committed
95
#ifdef QGC_USE_SENSESOAR_MESSAGES
oberion's avatar
oberion committed
96 97 98 99
	case MAV_AUTOPILOT_SENSESOAR:
		{
			senseSoarMAV* mav = new senseSoarMAV(mavlink,sysid);
			mav->setSystemType((int)heartbeat->type);
100 101 102

            mav->moveToThread(worker);

oberion's avatar
oberion committed
103 104 105 106
			connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
			uas = mav;
			break;
		}
oberion's avatar
oberion committed
107
#endif
lm's avatar
lm committed
108 109
    default:
    {
110 111
        UAS* mav = new UAS(mavlink, sysid);
        mav->setSystemType((int)heartbeat->type);
112 113 114

        mav->moveToThread(worker);

115 116 117 118 119 120 121 122
        // 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
        // packets never reach their goal)
        connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
        uas = mav;
    }
    break;
123 124 125 126 127 128 129 130 131 132 133
    }

    // Set the autopilot type
    uas->setAutopilotType((int)heartbeat->autopilot);

    // Make UAS aware that this link can be used to communicate with the actual robot
    uas->addLink(link);

    // Now add UAS to "official" list, which makes the whole application aware of it
    UASManager::instance()->addUAS(uas);

134
    worker->start(QThread::HighPriority);
Lorenz Meier's avatar
Lorenz Meier committed
135
    connect(uas, SIGNAL(destroyed()), worker, SLOT(quit()));
136

137 138
    return uas;
}