QGCMAVLinkUASFactory.cc 2.6 KB
Newer Older
1 2
#include "QGCMAVLinkUASFactory.h"
#include "UASManager.h"
3
#include "QGXPX4UAS.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;

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

33 34
        // Connect this robot to the UAS object
        connect(mavlink, SIGNAL(messageReceived(LinkInterface*, mavlink_message_t)), mav, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
Lorenz Meier's avatar
Lorenz Meier committed
35
        connect(mavlink, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), mav->getFileManager(), SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
36
        uas = mav;
37 38
    }
    break;
39 40
    case MAV_AUTOPILOT_PX4:
    {
41
        QGXPX4UAS* px4 = new QGXPX4UAS(mavlink, sysid);
42 43 44 45 46 47 48 49 50 51 52
        // Set the system type
        px4->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)), px4, SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
        uas = px4;
    }
    break;
lm's avatar
lm committed
53 54
    default:
    {
55
        UAS* mav = new UAS(mavlink, sysid);
56
        mav->setSystemType((int)heartbeat->type);
57

58 59 60 61 62 63 64 65
        // 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;
66 67 68 69 70 71 72 73
    }

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

74
    // First thing we do with a new UAS is get the parameters
75
    uas->getParamManager()->requestParameterList();
76
    
77 78
    // Now add UAS to "official" list, which makes the whole application aware of it
    UASManager::instance()->addUAS(uas);
79
    
80 81
    return uas;
}