Newer
Older
Michael Carpenter
committed
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
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
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
109
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
#include "UASRawStatusView.h"
#include "MAVLinkDecoder.h"
#include "UASInterface.h"
#include "UAS.h"
#include <QTimer>
#include <QScrollBar>
UASRawStatusView::UASRawStatusView(QWidget *parent) : QWidget(parent)
{
ui.setupUi(this);
ui.tableWidget->setColumnCount(2);
ui.tableWidget->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOn);
ui.tableWidget->setShowGrid(false);
ui.tableWidget->setEditTriggers(QAbstractItemView::NoEditTriggers);
QTimer *timer = new QTimer(this);
connect(timer,SIGNAL(timeout()),this,SLOT(updateTableTimerTick()));
timer->start(2000);
}
void UASRawStatusView::setDecoder(MAVLinkDecoder *decoder)
{
connect(decoder,SIGNAL(valueChanged(int,QString,QString,double,quint64)),this,SLOT(valueChanged(int,QString,QString,double,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint8,quint64)),this,SLOT(valueChanged(int,QString,QString,qint8,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint16,quint64)),this,SLOT(valueChanged(int,QString,QString,qint16,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint32,quint64)),this,SLOT(valueChanged(int,QString,QString,qint32,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint64,quint64)),this,SLOT(valueChanged(int,QString,QString,qint64,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,quint8,quint64)),this,SLOT(valueChanged(int,QString,QString,quint8,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,qint16,quint64)),this,SLOT(valueChanged(int,QString,QString,qint16,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,quint32,quint64)),this,SLOT(valueChanged(int,QString,QString,quint32,quint64)));
connect(decoder,SIGNAL(valueChanged(int,QString,QString,quint64,quint64)),this,SLOT(valueChanged(int,QString,QString,quint64,quint64)));
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec)
{
valueChanged(uasId,name,unit,(double)value,msec);
}
void UASRawStatusView::valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec)
{
valueMap[name] = value;
if (nameToUpdateWidgetMap.contains(name))
{
nameToUpdateWidgetMap[name]->setText(QString::number(value));
}
else
{
m_tableDirty = true;
}
return;
}
void UASRawStatusView::resizeEvent(QResizeEvent *event)
{
m_tableDirty = true;
}
void UASRawStatusView::updateTableTimerTick()
{
if (m_tableDirty)
{
m_tableDirty = false;
int columncount = 2;
bool good = false;
while (!good)
{
ui.tableWidget->clear();
ui.tableWidget->setRowCount(0);
ui.tableWidget->setColumnCount(columncount);
ui.tableWidget->horizontalHeader()->hide();
ui.tableWidget->verticalHeader()->hide();
int currcolumn = 0;
int currrow = 0;
int totalheight = 2 + ui.tableWidget->horizontalScrollBar()->height();
bool broke = false;
for (QMap<QString,double>::const_iterator i=valueMap.constBegin();i!=valueMap.constEnd();i++)
{
if (ui.tableWidget->rowCount() < currrow+1)
{
ui.tableWidget->setRowCount(currrow+1);
}
ui.tableWidget->setItem(currrow,currcolumn,new QTableWidgetItem(i.key().split(".")[1]));
QTableWidgetItem *item = new QTableWidgetItem(QString::number(i.value()));
nameToUpdateWidgetMap[i.key()] = item;
ui.tableWidget->setItem(currrow,currcolumn+1,item);
ui.tableWidget->resizeRowToContents(currrow);
totalheight += ui.tableWidget->rowHeight(currrow);
currrow++;
if ((totalheight + ui.tableWidget->rowHeight(currrow-1)) > ui.tableWidget->height())
{
currcolumn+=2;
totalheight = 2 + ui.tableWidget->horizontalScrollBar()->height();
currrow = 0;
if (currcolumn >= columncount)
{
//We're over what we can do. Add a column and continue.
columncount+=2;
broke = true;
break;
}
}
}
if (!broke)
{
good = true;
}
}
ui.tableWidget->resizeColumnsToContents();
//ui.tableWidget->columnCount()-2
}
}
UASRawStatusView::~UASRawStatusView()
{
}