QGCWaypointListMulti.cc 1.76 KB
Newer Older
1 2 3 4 5 6
#include "QGCWaypointListMulti.h"
#include "ui_QGCWaypointListMulti.h"
#include "UASManager.h"

QGCWaypointListMulti::QGCWaypointListMulti(QWidget *parent) :
    QWidget(parent),
7 8
    ui(new Ui::QGCWaypointListMulti),
    offline_uas_id(0)
9 10
{
    ui->setupUi(this);
11
    setMinimumSize(600, 80);
12 13
    connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(systemCreated(UASInterface*)));
    connect(UASManager::instance(), SIGNAL(activeUASSet(int)), this, SLOT(systemSetActive(int)));
14

15 16
    WaypointList* list = new WaypointList(ui->stackedWidget, NULL);
    lists.insert(offline_uas_id, list);
17
    ui->stackedWidget->addWidget(list);
18 19 20 21 22
}

void QGCWaypointListMulti::systemDeleted(QObject* uas)
{
    UASInterface* mav = dynamic_cast<UASInterface*>(uas);
lm's avatar
lm committed
23 24
    if (mav)
    {
25 26
        int id = mav->getUASID();
        WaypointList* list = lists.value(id, NULL);
lm's avatar
lm committed
27 28
        if (list)
        {
29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46
            delete list;
            lists.remove(id);
        }
    }
}

void QGCWaypointListMulti::systemCreated(UASInterface* uas)
{
    WaypointList* list = new WaypointList(ui->stackedWidget, uas);
    lists.insert(uas->getUASID(), list);
    ui->stackedWidget->addWidget(list);
    // Ensure widget is deleted when system is deleted
    connect(uas, SIGNAL(destroyed(QObject*)), this, SLOT(systemDeleted(QObject*)));
}

void QGCWaypointListMulti::systemSetActive(int uas)
{
    WaypointList* list = lists.value(uas, NULL);
47
    if (list) {
48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67
        ui->stackedWidget->setCurrentWidget(list);
    }
}

QGCWaypointListMulti::~QGCWaypointListMulti()
{
    delete ui;
}

void QGCWaypointListMulti::changeEvent(QEvent *e)
{
    QWidget::changeEvent(e);
    switch (e->type()) {
    case QEvent::LanguageChange:
        ui->retranslateUi(this);
        break;
    default:
        break;
    }
}