UASQuickView.cc 5.8 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51
#include "UASQuickView.h"
#include <QMetaMethod>
#include <QDebug>
UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent)
{
    ui.setupUi(this);
    connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(setActiveUAS(UASInterface*)));
    connect(UASManager::instance(),SIGNAL(UASCreated(UASInterface*)),this,SLOT(addUAS(UASInterface*)));
    if (UASManager::instance()->getActiveUAS())
    {
        addUAS(UASManager::instance()->getActiveUAS());
    }
    this->setContextMenuPolicy(Qt::ActionsContextMenu);


    {
        QAction *action = new QAction("latitude",this);
        action->setCheckable(true);
        action->setChecked(true);
        connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
        this->addAction(action);
        UASQuickViewItem *item = new UASQuickViewItem(this);
        item->setTitle("latitude");
        ui.verticalLayout->addWidget(item);
        uasPropertyToLabelMap["latitude"] = item;
    }

    {
        QAction *action = new QAction("longitude",this);
        action->setCheckable(true);
        action->setChecked(true);
        connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
        this->addAction(action);
        UASQuickViewItem *item = new UASQuickViewItem(this);
        item->setTitle("longitude");
        ui.verticalLayout->addWidget(item);
        uasPropertyToLabelMap["longitude"] = item;
    }

    {
        QAction *action = new QAction("altitude",this);
        action->setCheckable(true);
        action->setChecked(true);
        connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
        this->addAction(action);
        UASQuickViewItem *item = new UASQuickViewItem(this);
        item->setTitle("altitude");
        ui.verticalLayout->addWidget(item);
        uasPropertyToLabelMap["altitude"] = item;
    }

52 53 54 55 56 57 58 59 60 61 62 63
    {
        QAction *action = new QAction("satelliteCount",this);
        action->setCheckable(true);
        action->setChecked(true);
        connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
        this->addAction(action);
        UASQuickViewItem *item = new UASQuickViewItem(this);
        item->setTitle("satelliteCount");
        ui.verticalLayout->addWidget(item);
        uasPropertyToLabelMap["satelliteCount"] = item;
    }

64 65 66 67 68 69 70 71 72 73 74 75
    {
        QAction *action = new QAction("distToWaypoint",this);
        action->setCheckable(true);
        action->setChecked(true);
        connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
        this->addAction(action);
        UASQuickViewItem *item = new UASQuickViewItem(this);
        item->setTitle("distToWaypoint");
        ui.verticalLayout->addWidget(item);
        uasPropertyToLabelMap["distToWaypoint"] = item;
    }

76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108
    updateTimer = new QTimer(this);
    connect(updateTimer,SIGNAL(timeout()),this,SLOT(updateTimerTick()));
    updateTimer->start(1000);
}
void UASQuickView::updateTimerTick()
{
    for (int i=0;i<uasPropertyList.size();i++)
    {
        if (uasPropertyValueMap.contains(uasPropertyList[i]) && uasPropertyToLabelMap.contains(uasPropertyList[i]))
        {
            uasPropertyToLabelMap[uasPropertyList[i]]->setValue(uasPropertyValueMap.value(uasPropertyList[i],0));
        }
    }
}

void UASQuickView::addUAS(UASInterface* uas)
{
    if (uas)
    {
        if (!this->uas)
        {
            setActiveUAS(uas);
        }
    }
}

void UASQuickView::setActiveUAS(UASInterface* uas)
{
    if (!uas)
    {
        return;
    }
    this->uas = uas;
109
    connect(uas,SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)),this,SLOT(valueChanged(int,QString,QString,QVariant,quint64)));
110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155
    uasPropertyList.clear();
    qDebug() << "UASInfoWidget property count:" << uas->metaObject()->propertyCount();
    for (int i=0;i<uas->metaObject()->propertyCount();i++)
    {
        if (uas->metaObject()->property(i).hasNotifySignal())
        {
            qDebug() << "Property:" << i << uas->metaObject()->property(i).name();
            uasPropertyList.append(uas->metaObject()->property(i).name());
            if (!uasPropertyToLabelMap.contains(uas->metaObject()->property(i).name()))
            {
                QAction *action = new QAction(QString(uas->metaObject()->property(i).name()),this);
                action->setCheckable(true);
                connect(action,SIGNAL(toggled(bool)),this,SLOT(actionTriggered(bool)));
                this->addAction(action);
            }
            qDebug() << "Signature:" << uas->metaObject()->property(i).notifySignal().signature();
            int val = this->metaObject()->indexOfMethod("valChanged(double,QString)");
            if (val != -1)
            {

                if (!connect(uas,uas->metaObject()->property(i).notifySignal(),this,this->metaObject()->method(val)))
                {
                    qDebug() << "Error connecting signal";
                }
            }
        }
    }
}
void UASQuickView::actionTriggered(bool checked)
{
    QAction *senderlabel = qobject_cast<QAction*>(sender());
    if (!senderlabel)
    {
        return;
    }
    if (checked)
    {
        UASQuickViewItem *item = new UASQuickViewItem(this);
        item->setTitle(senderlabel->text());
        ui.verticalLayout->addWidget(item);
        uasPropertyToLabelMap[senderlabel->text()] = item;
    }
    else
    {
        ui.verticalLayout->removeWidget(uasPropertyToLabelMap[senderlabel->text()]);
        uasPropertyToLabelMap[senderlabel->text()]->deleteLater();
156 157
        uasPropertyToLabelMap.remove(senderlabel->text());

158 159
    }
}
160 161 162 163
void UASQuickView::valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant value,const quint64 msecs)
{
    uasPropertyValueMap[name] = value.toDouble();
}
164 165 166 167

void UASQuickView::valChanged(double val,QString type)
{
    //qDebug() << "Value changed:" << type << val;
168
   // uasPropertyValueMap[type] = val;
169
}