UASQuickView.cc 9.68 KB
Newer Older
1 2 3
#include "UASQuickView.h"
#include <QMetaMethod>
#include <QDebug>
4
#include "UASQuickViewItemSelect.h"
5
#include "UASQuickViewTextItem.h"
6
#include <QSettings>
7
#include <QInputDialog>
8
#include "MultiVehicleManager.h"
9 10
UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent),
    uas(NULL)
11
{
12
    quickViewSelectDialog=0;
13 14
    m_columnCount=2;
    m_currentColumn=0;
15
    ui.setupUi(this);
16

17
    ui.horizontalLayout->setMargin(0);
18 19 20
    m_verticalLayoutList.append(new QVBoxLayout());
    ui.horizontalLayout->addItem(m_verticalLayoutList[0]);

21 22
    connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &UASQuickView::_activeVehicleChanged);
    _activeVehicleChanged(MultiVehicleManager::instance()->activeVehicle());
23 24
    this->setContextMenuPolicy(Qt::ActionsContextMenu);

25
    loadSettings();
26

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

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

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

48 49 50
    updateTimer = new QTimer(this);
    connect(updateTimer,SIGNAL(timeout()),this,SLOT(updateTimerTick()));
    updateTimer->start(1000);
51

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

74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91
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();
}
92
void UASQuickView::saveSettings()
93
{
94 95 96 97 98 99 100 101 102 103
    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();
104
    settings.setValue("UAS_QUICK_VIEW_COLUMNS",m_columnCount);
105
}
106 107 108
void UASQuickView::loadSettings()
{
    QSettings settings;
109
    m_columnCount = settings.value("UAS_QUICK_VIEW_COLUMNS",1).toInt();
110
    int size = settings.beginReadArray("UAS_QUICK_VIEW_ITEMS");
111
    for (int i = 0; i < size; i++)
112 113 114 115 116 117 118 119 120
    {
        settings.setArrayIndex(i);
        QString nameval = settings.value("name").toString();
        QString typeval = settings.value("type").toString();
        if (typeval == "text" && !uasPropertyToLabelMap.contains(nameval))
        {
            valueEnabled(nameval);
        }
    }
121 122
    settings.endArray();
    sortItems(m_columnCount);
123 124 125 126
}

void UASQuickView::valueEnabled(QString value)
{
127
    UASQuickViewItem *item = new UASQuickViewTextItem(this);
128
    item->setTitle(value);
129 130 131 132 133 134 135 136 137
    //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;
    }
138 139
    uasPropertyToLabelMap[value] = item;
    uasEnabledPropertyList.append(value);
140

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

}
150 151 152 153 154 155 156 157 158
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());
    }
159 160
    // Item list has all the widgets availble, now re-add them to the layouts.
    for (int i = 0; i < m_verticalLayoutList.size(); i++)
161 162 163 164 165 166
    {
        ui.horizontalLayout->removeItem(m_verticalLayoutList[i]);
        m_verticalLayoutList[i]->deleteLater(); //removeItem de-parents the item.
    }
    m_verticalLayoutList.clear();

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

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

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

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

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

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

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

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

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


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

314 315
    }
}