QGCMAVLinkUASFactory.cc 4.31 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;

lm's avatar
lm committed
24 25
    switch (heartbeat->autopilot)
    {
26
    case MAV_AUTOPILOT_GENERIC:
lm's avatar
lm committed
27
    {
28 29 30 31 32
        UAS* mav = new UAS(mavlink, sysid);
        // Set the system type
        mav->setSystemType((int)heartbeat->type);
        // Connect this robot to the UAS object
        connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
33 34 35
#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
36
        uas = mav;
37 38
    }
    break;
39
    case MAV_AUTOPILOT_PIXHAWK:
lm's avatar
lm committed
40
    {
41 42 43 44 45 46 47 48
        PxQuadMAV* mav = new PxQuadMAV(mavlink, sysid);
        // Set the system type
        mav->setSystemType((int)heartbeat->type);
        // 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)));
49 50 51
#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
52 53 54
        uas = mav;
    }
    break;
55
    case MAV_AUTOPILOT_SLUGS:
lm's avatar
lm committed
56
    {
57 58 59 60 61 62 63 64 65 66 67
        SlugsMAV* mav = new SlugsMAV(mavlink, sysid);
        // Set the system type
        mav->setSystemType((int)heartbeat->type);
        // 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;
68
    case MAV_AUTOPILOT_ARDUPILOTMEGA:
lm's avatar
lm committed
69
    {
70 71 72 73 74 75 76 77 78 79 80
        ArduPilotMegaMAV* mav = new ArduPilotMegaMAV(mavlink, sysid);
        // Set the system type
        mav->setSystemType((int)heartbeat->type);
        // 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
81
#ifdef QGC_USE_SENSESOAR_MESSAGES
oberion's avatar
oberion committed
82 83 84 85 86 87 88 89
	case MAV_AUTOPILOT_SENSESOAR:
		{
			senseSoarMAV* mav = new senseSoarMAV(mavlink,sysid);
			mav->setSystemType((int)heartbeat->type);
			connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
			uas = mav;
			break;
		}
oberion's avatar
oberion committed
90
#endif
lm's avatar
lm committed
91 92
    default:
    {
93 94 95 96 97 98 99 100 101 102
        UAS* mav = new UAS(mavlink, sysid);
        mav->setSystemType((int)heartbeat->type);
        // 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;
103 104 105 106 107 108 109 110 111 112 113 114 115
    }

    // 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;
}