Commit c23dc4d6 authored by Michael Carpenter's avatar Michael Carpenter

Merge branch 'quickview_textsizing'

parents da79b6ce 8f585b40
......@@ -16,69 +16,8 @@ UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent)
}
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;
}
{
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;
}
{
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;
}*/
//this->setSizePolicy();
loadSettings();
//If we don't have any predefined settings, set some defaults.
if (uasPropertyValueMap.size() == 0)
{
......@@ -98,6 +37,14 @@ UASQuickView::UASQuickView(QWidget *parent) : QWidget(parent)
connect(updateTimer,SIGNAL(timeout()),this,SLOT(updateTimerTick()));
updateTimer->start(1000);
}
UASQuickView::~UASQuickView()
{
if (quickViewSelectDialog)
{
delete quickViewSelectDialog;
}
}
void UASQuickView::actionTriggered()
{
if (quickViewSelectDialog)
......
......@@ -15,6 +15,7 @@ class UASQuickView : public QWidget
Q_OBJECT
public:
UASQuickView(QWidget *parent = 0);
~UASQuickView();
void addSource(MAVLinkDecoder *decoder);
private:
UASInterface *uas;
......
......@@ -6,24 +6,76 @@ UASQuickViewItemSelect::UASQuickViewItemSelect(QWidget *parent) : QWidget(parent
ui.setupUi(this);
currcol = 0;
currrow = 0;
ui.gridLayout->setSpacing(5);
ui.gridLayout->setMargin(0);
}
void UASQuickViewItemSelect::addItem(QString item,bool enabled)
{
QString category = ".";
QString name = item;
if (item.indexOf(":") != -1 && item.indexOf(".") != -1)
{
//Item has a subcateogry
category = item.mid(item.indexOf(":")+1,item.indexOf(".") - item.indexOf(":")-1);
name = item.mid(item.indexOf(".")+1);
}
int col = -1;
if (m_categoryToIndexMap.contains(category))
{
col = m_categoryToIndexMap[category];
}
else
{
m_categoryToIndexMap[category] = currcol++;
col = m_categoryToIndexMap[category];
//New column.
QLabel *titlelabel = new QLabel(this);
titlelabel->setText(category);
titlelabel->show();
ui.gridLayout->addWidget(titlelabel,0,col);
}
QCheckBox *label = new QCheckBox(this);
m_checkboxToValueMap[label] = item;
m_checkBoxList.append(label);
if (enabled)
{
label->setChecked(true);
}
connect(label,SIGNAL(clicked(bool)),this,SLOT(checkBoxClicked(bool)));
label->setText(item);
label->setText(name);
label->show();
ui.gridLayout->addWidget(label,currrow,currcol++);
if (currcol > 10)
//ui.gridLayout->addWidget(label,currrow,currcol++);
bool breakout = false;
int row = -1;
while (!breakout)
{
if (!ui.gridLayout->itemAtPosition(++row,col) || row > 100)
{
breakout = true;
}
}
//Row is the next invalid object, and col is the proper column.
ui.gridLayout->addWidget(label,row,col);
}
void UASQuickViewItemSelect::resizeEvent(QResizeEvent *event)
{
/*for (int i=0;i<m_checkBoxList.size();i++)
{
currcol = 0;
currrow++;
ui.gridLayout->removeWidget(m_checkBoxList[i]);
}
int row = 0;
int col = 0;
for (int i=0;i<m_checkBoxList.size();i++)
{
ui.gridLayout->addWidget(m_checkBoxList[i],row,col);
col++;
ui.gridLayout->widget()->width() > this->width();
//need to reduce column number.
}*/
}
void UASQuickViewItemSelect::checkBoxClicked(bool checked)
{
QCheckBox *check = qobject_cast<QCheckBox*>(sender());
......@@ -31,13 +83,19 @@ void UASQuickViewItemSelect::checkBoxClicked(bool checked)
{
return;
}
QString checkval = check->text();
if (m_checkboxToValueMap.contains(check))
{
checkval = m_checkboxToValueMap[check];
}
if (checked)
{
emit valueEnabled(check->text());
emit valueEnabled(checkval);
}
else
{
emit valueDisabled(check->text());
emit valueDisabled(checkval);
}
}
......
......@@ -2,6 +2,7 @@
#define UASQUICKVIEWITEMSELECT_H
#include <QWidget>
#include <QCheckBox>
#include "ui_UASQuickViewItemSelect.h"
class UASQuickViewItemSelect : public QWidget
......@@ -14,7 +15,12 @@ public:
void addItem(QString item,bool enabled = false);
int currrow;
int currcol;
protected:
void resizeEvent(QResizeEvent *event);
private:
QMap<QString,int> m_categoryToIndexMap;
QMap<QCheckBox*,QString> m_checkboxToValueMap;
QList<QCheckBox*> m_checkBoxList;
Ui::UASQuickViewItemSelect ui;
private slots:
void checkBoxClicked(bool checked);
......
......@@ -6,12 +6,12 @@
<rect>
<x>0</x>
<y>0</y>
<width>571</width>
<height>474</height>
<width>947</width>
<height>248</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
<string>Select Item</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout">
<item>
......@@ -24,14 +24,27 @@
<rect>
<x>0</x>
<y>0</y>
<width>551</width>
<height>454</height>
<width>927</width>
<height>228</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<layout class="QGridLayout" name="gridLayout"/>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</widget>
</widget>
......
......@@ -9,14 +9,15 @@ UASQuickViewTextItem::UASQuickViewTextItem(QWidget *parent) : UASQuickViewItem(p
layout->setMargin(0);
titleLabel = new QLabel(this);
titleLabel->setSizePolicy(QSizePolicy::Ignored,QSizePolicy::Ignored);
titleLabel->setAlignment(Qt::AlignHCenter);
titleLabel->setAlignment(Qt::AlignHCenter | Qt::AlignBottom);
this->layout()->addWidget(titleLabel);
valueLabel = new QLabel(this);
valueLabel->setSizePolicy(QSizePolicy::Ignored,QSizePolicy::Ignored);
valueLabel->setAlignment(Qt::AlignHCenter);
valueLabel->setAlignment(Qt::AlignHCenter | Qt::AlignTop);
valueLabel->setText("0.00");
this->layout()->addWidget(valueLabel);
layout->addSpacerItem(new QSpacerItem(20, 40, QSizePolicy::Minimum, QSizePolicy::Ignored));
//spacerItem = new QSpacerItem(20,40,QSizePolicy::Minimum,QSizePolicy::Ignored);
//layout->addSpacerItem(spacerItem);
QFont valuefont = valueLabel->font();
QFont titlefont = titleLabel->font();
valuefont.setPixelSize(this->height() / 2.0);
......@@ -31,7 +32,14 @@ void UASQuickViewTextItem::setValue(double value)
void UASQuickViewTextItem::setTitle(QString title)
{
titleLabel->setText(title);
if (title.indexOf(".") != -1 && title.indexOf(":") != -1)
{
titleLabel->setText(title.mid(title.indexOf(".")+1));
}
else
{
titleLabel->setText(title);
}
}
void UASQuickViewTextItem::resizeEvent(QResizeEvent *event)
{
......@@ -39,6 +47,7 @@ void UASQuickViewTextItem::resizeEvent(QResizeEvent *event)
QFont titlefont = titleLabel->font();
valuefont.setPixelSize(this->height());
titlefont.setPixelSize(valuefont.pixelSize() / 2.0);
//spacerItem->setGeometry(QRect(0,0,20,this->height()/10.0));
QFontMetrics metrics(valuefont);
//valuefont.setPixelSize(this->height() / 2.0);
......
......@@ -3,6 +3,7 @@
#include "UASQuickViewItem.h"
#include <QLabel>
#include <QSpacerItem>
class UASQuickViewTextItem : public UASQuickViewItem
{
public:
......@@ -14,6 +15,7 @@ protected:
private:
QLabel *titleLabel;
QLabel *valueLabel;
QSpacerItem *spacerItem;
};
#endif // UASQUICKVIEWTEXTITEM_H
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment