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

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

    UASInterface* uas;

26
    QGCUASWorker* worker = new QGCUASWorker();
27

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

36 37
        // 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
38
        connect(mavlink, SIGNAL(messageReceived(LinkInterface*,mavlink_message_t)), mav->getFileManager(), SLOT(receiveMessage(LinkInterface*, mavlink_message_t)));
39
        uas = mav;
40 41
    }
    break;
42 43 44 45 46 47 48 49 50 51 52 53 54 55
    case MAV_AUTOPILOT_PX4:
    {
        QGXPX4UAS* px4 = new QGXPX4UAS(mavlink, worker, sysid);
        // 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
56 57
    default:
    {
58
        UAS* mav = new UAS(mavlink, worker, sysid);
59
        mav->setSystemType((int)heartbeat->type);
60

61 62 63 64 65 66 67 68
        // 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;
69 70
    }

71 72 73 74
    // Get the UAS ready
    worker->start(QThread::HighPriority);
    connect(uas, SIGNAL(destroyed()), worker, SLOT(quit()));

75 76 77 78 79 80 81 82 83 84 85
    // 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;
}