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

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
14 15
    if (parent != NULL)
    {
16
        p = parent;
lm's avatar
lm committed
17 18 19
    }
    else
    {
20 21 22 23 24
        p = mavlink;
    }

    UASInterface* uas;

25
    QGCUASWorker* worker = new QGCUASWorker();
26

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

35 36
        // Connect this robot to the UAS object
        connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
37 38 39
#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
40
        uas = mav;
41 42
    }
    break;
43
    case MAV_AUTOPILOT_PIXHAWK:
lm's avatar
lm committed
44
    {
45
        PxQuadMAV* mav = new PxQuadMAV(mavlink, worker, sysid);
46 47
        // Set the system type
        mav->setSystemType((int)heartbeat->type);
48

49 50 51 52 53
        // 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)));
54 55 56
#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
57 58 59
        uas = mav;
    }
    break;
60
    case MAV_AUTOPILOT_SLUGS:
lm's avatar
lm committed
61
    {
62
        SlugsMAV* mav = new SlugsMAV(mavlink, worker, sysid);
63 64
        // Set the system type
        mav->setSystemType((int)heartbeat->type);
65

66 67 68 69 70 71 72 73
        // 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;
74
    case MAV_AUTOPILOT_ARDUPILOTMEGA:
lm's avatar
lm committed
75
    {
76
        ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(mavlink, worker, sysid);
77 78
        // Set the system type
        mav->setSystemType((int)heartbeat->type);
79

80 81 82 83 84 85 86 87
        // 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
88
#ifdef QGC_USE_SENSESOAR_MESSAGES
oberion's avatar
oberion committed
89 90
	case MAV_AUTOPILOT_SENSESOAR:
		{
91
            senseSoarMAV* mav = new senseSoarMAV(mavlink,worker, sysid);
oberion's avatar
oberion committed
92
			mav->setSystemType((int)heartbeat->type);
93 94 95

            mav->moveToThread(worker);

oberion's avatar
oberion committed
96 97 98 99
			connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
			uas = mav;
			break;
		}
oberion's avatar
oberion committed
100
#endif
lm's avatar
lm committed
101 102
    default:
    {
103
        UAS* mav = new UAS(mavlink, worker, sysid);
104
        mav->setSystemType((int)heartbeat->type);
105

106 107 108 109 110 111 112 113
        // 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;
114 115
    }

116 117 118 119
    // Get the UAS ready
    worker->start(QThread::HighPriority);
    connect(uas, SIGNAL(destroyed()), worker, SLOT(quit()));

120 121 122 123 124 125 126 127 128 129 130
    // 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);

    return uas;
}