UASQuickView.cc 9.7 KB
Newer Older
1
#include "UASQuickView.h"
2
#include "UASQuickViewItemSelect.h"
3
#include "UASQuickViewTextItem.h"
4 5 6 7 8
#include "MultiVehicleManager.h"
#include "UAS.h"

#include <QMetaMethod>
#include <QDebug>
9
#include <QSettings>
10
#include <QInputDialog>
11

12 13
UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent),
    uas(NULL)
14
{
15
    quickViewSelectDialog=0;
16 17
    m_columnCount=2;
    m_currentColumn=0;
18
    ui.setupUi(this);
19

20
    ui.horizontalLayout->setMargin(0);
21 22 23
    m_verticalLayoutList.append(new QVBoxLayout());
    ui.horizontalLayout->addItem(m_verticalLayoutList[0]);

24 25
    connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &UASQuickView::_activeVehicleChanged);
    _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle());
26 27
    this->setContextMenuPolicy(Qt::ActionsContextMenu);

28
    loadSettings();
29

30 31 32
    //If we don't have any predefined settings, set some defaults.
    if (uasPropertyValueMap.size() == 0)
    {
33
        valueEnabled("altitudeAMSL");
34 35
        valueEnabled("altitudeAMSLFT");
        valueEnabled("altitudeWGS84");
36
        valueEnabled("altitudeRelative");
37
        valueEnabled("groundSpeed");
38
        valueEnabled("distToWaypoint");
39
    }
40

41
    QAction *action = new QAction("Add/Remove Items",this);
42 43 44
    action->setCheckable(false);
    connect(action,SIGNAL(triggered()),this,SLOT(actionTriggered()));
    this->addAction(action);
45

46 47 48 49 50
    QAction *columnaction = new QAction("Set Column Count",this);
    columnaction->setCheckable(false);
    connect(columnaction,SIGNAL(triggered()),this,SLOT(columnActionTriggered()));
    this->addAction(columnaction);

51 52 53
    updateTimer = new QTimer(this);
    connect(updateTimer,SIGNAL(timeout()),this,SLOT(updateTimerTick()));
    updateTimer->start(1000);
54

55
}
56 57 58 59 60 61 62
UASQuickView::~UASQuickView()
{
    if (quickViewSelectDialog)
    {
        delete quickViewSelectDialog;
    }
}
63 64 65
void UASQuickView::columnActionTriggered()
{
    bool ok = false;
66 67
    int newcolumns = QInputDialog::getInt(
        this,"Columns","Enter number of columns", m_columnCount, 1, 10, 1, &ok);
68 69 70 71 72 73 74 75
    if (!ok)
    {
        return;
    }
    m_columnCount = newcolumns;
    sortItems(newcolumns);
    saveSettings();
}
76

77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94
void UASQuickView::actionTriggered()
{
    if (quickViewSelectDialog)
    {
        quickViewSelectDialog->show();
        return;
    }
    quickViewSelectDialog = new UASQuickViewItemSelect();
    connect(quickViewSelectDialog,SIGNAL(destroyed()),this,SLOT(selectDialogClosed()));
    connect(quickViewSelectDialog,SIGNAL(valueDisabled(QString)),this,SLOT(valueDisabled(QString)));
    connect(quickViewSelectDialog,SIGNAL(valueEnabled(QString)),this,SLOT(valueEnabled(QString)));
    quickViewSelectDialog->setAttribute(Qt::WA_DeleteOnClose,true);
    for (QMap<QString,double>::const_iterator i = uasPropertyValueMap.constBegin();i!=uasPropertyValueMap.constEnd();i++)
    {
        quickViewSelectDialog->addItem(i.key(),uasEnabledPropertyList.contains(i.key()));
    }
    quickViewSelectDialog->show();
}
95
void UASQuickView::saveSettings()
96
{
97 98 99 100 101 102 103 104 105 106
    QSettings settings;
    settings.beginWriteArray("UAS_QUICK_VIEW_ITEMS");
    int count = 0;
    for (QMap<QString,UASQuickViewItem*>::const_iterator i = uasPropertyToLabelMap.constBegin();i!=uasPropertyToLabelMap.constEnd();i++)
    {
        settings.setArrayIndex(count++);
        settings.setValue("name",i.key());
        settings.setValue("type","text");
    }
    settings.endArray();
107
    settings.setValue("UAS_QUICK_VIEW_COLUMNS",m_columnCount);
108
}
109 110 111
void UASQuickView::loadSettings()
{
    QSettings settings;
112
    m_columnCount = settings.value("UAS_QUICK_VIEW_COLUMNS",1).toInt();
113
    int size = settings.beginReadArray("UAS_QUICK_VIEW_ITEMS");
114
    for (int i = 0; i < size; i++)
115 116 117 118 119 120 121 122 123
    {
        settings.setArrayIndex(i);
        QString nameval = settings.value("name").toString();
        QString typeval = settings.value("type").toString();
        if (typeval == "text" && !uasPropertyToLabelMap.contains(nameval))
        {
            valueEnabled(nameval);
        }
    }
124 125
    settings.endArray();
    sortItems(m_columnCount);
126 127 128 129
}

void UASQuickView::valueEnabled(QString value)
{
130
    UASQuickViewItem *item = new UASQuickViewTextItem(this);
131
    item->setTitle(value);
132 133 134 135 136 137 138 139 140
    //ui.verticalLayout->addWidget(item);
    //m_currentColumn
    m_verticalLayoutList[m_currentColumn]->addWidget(item);
    m_PropertyToLayoutIndexMap[value] = m_currentColumn;
    m_currentColumn++;
    if (m_currentColumn >= m_columnCount-1)
    {
        m_currentColumn = 0;
    }
141 142
    uasPropertyToLabelMap[value] = item;
    uasEnabledPropertyList.append(value);
143

144 145 146 147 148
    if (!uasPropertyValueMap.contains(value))
    {
        uasPropertyValueMap[value] = 0;
    }
    saveSettings();
149 150
    item->show();
    sortItems(m_columnCount);
151 152

}
153 154 155 156 157 158 159 160 161
void UASQuickView::sortItems(int columncount)
{
    QList<QWidget*> itemlist;
    for (QMap<QString,UASQuickViewItem*>::const_iterator i = uasPropertyToLabelMap.constBegin();i!=uasPropertyToLabelMap.constEnd();i++)
    {
        m_verticalLayoutList[m_PropertyToLayoutIndexMap[i.key()]]->removeWidget(i.value());
        m_PropertyToLayoutIndexMap.remove(i.key());
        itemlist.append(i.value());
    }
162 163
    // Item list has all the widgets availble, now re-add them to the layouts.
    for (int i = 0; i < m_verticalLayoutList.size(); i++)
164 165 166 167 168 169
    {
        ui.horizontalLayout->removeItem(m_verticalLayoutList[i]);
        m_verticalLayoutList[i]->deleteLater(); //removeItem de-parents the item.
    }
    m_verticalLayoutList.clear();

170 171
    // Create a vertical layout for every intended column
    for (int i = 0; i < columncount; i++)
172
    {
173
        QVBoxLayout *layout = new QVBoxLayout();
174 175
        ui.horizontalLayout->addItem(layout);
        m_verticalLayoutList.append(layout);
176
        layout->setMargin(0);
177 178 179 180
    }

    //Cycle through all items and add them to the layout
    int currcol = 0;
181
    for (int i = 0; i < itemlist.size(); i++)
182 183 184 185 186 187 188 189 190
    {
        m_verticalLayoutList[currcol]->addWidget(itemlist[i]);
        currcol++;
        if (currcol >= columncount)
        {
            currcol = 0;
        }
    }
    m_currentColumn = currcol;
191 192 193 194 195
    QApplication::processEvents();
    recalculateItemTextSizing();
}
void UASQuickView::resizeEvent(QResizeEvent *evt)
{
196
    Q_UNUSED(evt);
197 198 199 200 201 202 203 204 205 206 207 208 209
    recalculateItemTextSizing();
}
void UASQuickView::recalculateItemTextSizing()
{
    int minpixelsize = 65535;
    for (QMap<QString,UASQuickViewItem*>::const_iterator i = uasPropertyToLabelMap.constBegin();i!=uasPropertyToLabelMap.constEnd();i++)
    {
        int tempmin = i.value()->minValuePixelSize();
        if (tempmin < minpixelsize)
        {
            minpixelsize = tempmin;
        }
    }
210 211
    if(minpixelsize < 6)
        minpixelsize = 6;
212 213 214 215
    for (QMap<QString,UASQuickViewItem*>::const_iterator i = uasPropertyToLabelMap.constBegin();i!=uasPropertyToLabelMap.constEnd();i++)
    {
        i.value()->setValuePixelSize(minpixelsize);
    }
216
}
217 218 219 220 221 222 223 224

void UASQuickView::valueDisabled(QString value)
{
    if (uasPropertyToLabelMap.contains(value))
    {
        UASQuickViewItem *item = uasPropertyToLabelMap[value];
        uasPropertyToLabelMap.remove(value);
        item->hide();
225 226 227 228
        //ui.verticalLayout->removeWidget(item);
        //layout->removeWidget(item);
        m_verticalLayoutList[m_PropertyToLayoutIndexMap[value]]->removeWidget(item);
        sortItems(m_columnCount);
229 230
        item->deleteLater();
        uasEnabledPropertyList.removeOne(value);
231
        saveSettings();
232 233 234 235 236 237 238 239
    }
}

void UASQuickView::selectDialogClosed()
{
    quickViewSelectDialog = 0;
}

240 241
void UASQuickView::updateTimerTick()
{
242 243
    //uasPropertyValueMap
    for (QMap<QString,UASQuickViewItem*>::const_iterator i = uasPropertyToLabelMap.constBegin(); i != uasPropertyToLabelMap.constEnd();i++)
244
    {
245
        if (uasPropertyValueMap.contains(i.key()))
246
        {
247
            i.value()->setValue(uasPropertyValueMap[i.key()]);
248 249 250 251
        }
    }
}

252
void UASQuickView::_activeVehicleChanged(Vehicle* vehicle)
253
{
Don Gagne's avatar
Don Gagne committed
254
    if (uas || !vehicle) {
255 256
        return;
    }
257
    this->uas = vehicle->uas();
Don Gagne's avatar
Don Gagne committed
258
    connect(uas, SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)),this,SLOT(valueChanged(int,QString,QString,QVariant,quint64)));
259 260 261
}
void UASQuickView::addSource(MAVLinkDecoder *decoder)
{
262
    connect(decoder,SIGNAL(valueChanged(int,QString,QString,QVariant,quint64)),this,SLOT(valueChanged(int,QString,QString,QVariant,quint64)));
263
}
264

265
void UASQuickView::valueChanged(const int uasId, const QString& name, const QString& unit, const QVariant &variant, const quint64 msec)
266
{
267 268
    Q_UNUSED(uasId);
    Q_UNUSED(unit);
269 270
    Q_UNUSED(msec);
    
271 272
    bool ok;
    double value = variant.toDouble(&ok);
Don Gagne's avatar
Don Gagne committed
273
    QMetaType::Type metaType = static_cast<QMetaType::Type>(variant.type());
Don Gagne's avatar
Don Gagne committed
274
    if(!ok || metaType == QMetaType::QString || metaType == QMetaType::QByteArray)
275 276
        return;

277 278 279 280 281 282 283 284 285 286
    if (!uasPropertyValueMap.contains(name))
    {
        if (quickViewSelectDialog)
        {
            quickViewSelectDialog->addItem(name);
        }
    }
    uasPropertyValueMap[name] = value;
}

287 288 289 290 291 292 293 294 295
void UASQuickView::actionTriggered(bool checked)
{
    QAction *senderlabel = qobject_cast<QAction*>(sender());
    if (!senderlabel)
    {
        return;
    }
    if (checked)
    {
296 297
        valueEnabled(senderlabel->text());
        /*UASQuickViewItem *item = new UASQuickViewTextItem(this);
298
        item->setTitle(senderlabel->text());
299 300 301 302 303 304 305 306 307 308
        layout->addWidget(item);
        //ui.verticalLayout->addWidget(item);
        m_currentColumn++;
        if (m_currentColumn >= m_verticalLayoutList.size())
        {
            m_currentColumn = 0;
        }
        uasPropertyToLabelMap[senderlabel->text()] = item;*/


309 310 311
    }
    else
    {
312 313
        valueDisabled(senderlabel->text());
        /*layout->removeWidget(uasPropertyToLabelMap[senderlabel->text()]);
314
        uasPropertyToLabelMap[senderlabel->text()]->deleteLater();
315
        uasPropertyToLabelMap.remove(senderlabel->text());*/
316

317 318
    }
}