Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
ba9e5a87
Commit
ba9e5a87
authored
Jan 07, 2011
by
lm
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Improved line plots and gauges
parent
7fa3071d
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
92 additions
and
50 deletions
+92
-50
PxQuadMAV.cc
src/uas/PxQuadMAV.cc
+6
-6
UAS.cc
src/uas/UAS.cc
+18
-1
HDDisplay.cc
src/ui/HDDisplay.cc
+23
-13
HDDisplay.h
src/ui/HDDisplay.h
+4
-2
MainWindow.cc
src/ui/MainWindow.cc
+9
-9
LinechartWidget.cc
src/ui/linechart/LinechartWidget.cc
+32
-19
No files found.
src/uas/PxQuadMAV.cc
View file @
ba9e5a87
...
...
@@ -113,9 +113,9 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
valueChanged
(
uasId
,
"vis. roll"
,
"rad"
,
pos
.
roll
,
time
);
emit
valueChanged
(
uasId
,
"vis. pitch"
,
"rad"
,
pos
.
pitch
,
time
);
emit
valueChanged
(
uasId
,
"vis. yaw"
,
"rad"
,
pos
.
yaw
,
time
);
emit
valueChanged
(
uasId
,
"vis. x"
,
"
rad/s
"
,
pos
.
x
,
time
);
emit
valueChanged
(
uasId
,
"vis. y"
,
"
rad/s
"
,
pos
.
y
,
time
);
emit
valueChanged
(
uasId
,
"vis. z"
,
"
rad/s
"
,
pos
.
z
,
time
);
emit
valueChanged
(
uasId
,
"vis. x"
,
"
m
"
,
pos
.
x
,
time
);
emit
valueChanged
(
uasId
,
"vis. y"
,
"
m
"
,
pos
.
y
,
time
);
emit
valueChanged
(
uasId
,
"vis. z"
,
"
m
"
,
pos
.
z
,
time
);
}
break
;
case
MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE
:
...
...
@@ -127,9 +127,9 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
valueChanged
(
uasId
,
"vicon roll"
,
"rad"
,
pos
.
roll
,
time
);
emit
valueChanged
(
uasId
,
"vicon pitch"
,
"rad"
,
pos
.
pitch
,
time
);
emit
valueChanged
(
uasId
,
"vicon yaw"
,
"rad"
,
pos
.
yaw
,
time
);
emit
valueChanged
(
uasId
,
"vicon x"
,
"
rad/s
"
,
pos
.
x
,
time
);
emit
valueChanged
(
uasId
,
"vicon y"
,
"
rad/s
"
,
pos
.
y
,
time
);
emit
valueChanged
(
uasId
,
"vicon z"
,
"
rad/s
"
,
pos
.
z
,
time
);
emit
valueChanged
(
uasId
,
"vicon x"
,
"
m
"
,
pos
.
x
,
time
);
emit
valueChanged
(
uasId
,
"vicon y"
,
"
m
"
,
pos
.
y
,
time
);
emit
valueChanged
(
uasId
,
"vicon z"
,
"
m
"
,
pos
.
z
,
time
);
emit
localPositionChanged
(
this
,
pos
.
x
,
pos
.
y
,
pos
.
z
,
time
);
}
break
;
...
...
src/uas/UAS.cc
View file @
ba9e5a87
...
...
@@ -313,9 +313,26 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// Emit in angles
emit
valueChanged
(
uasId
,
"roll"
,
"deg"
,
(
attitude
.
roll
/
M_PI
)
*
180.0
,
time
);
emit
valueChanged
(
uasId
,
"pitch"
,
"deg"
,
(
attitude
.
pitch
/
M_PI
)
*
180.0
,
time
);
emit
valueChanged
(
uasId
,
"yaw"
,
"deg"
,
(
attitude
.
yaw
/
M_PI
)
*
180.0
,
time
);
emit
valueChanged
(
uasId
,
"rollspeed"
,
"deg/s"
,
(
attitude
.
rollspeed
/
M_PI
)
*
180.0
,
time
);
emit
valueChanged
(
uasId
,
"pitchspeed"
,
"deg/s"
,
(
attitude
.
pitchspeed
/
M_PI
)
*
180.0
,
time
);
// Force yaw to 180 deg range
double
yaw
=
((
attitude
.
yaw
/
M_PI
)
*
180.0
);
double
sign
=
1.0
;
if
(
yaw
<
0
)
{
sign
=
-
1.0
;
yaw
=
-
yaw
;
}
while
(
yaw
>
180.0
)
{
yaw
-=
180.0
;
}
yaw
*=
sign
;
emit
valueChanged
(
uasId
,
"yaw"
,
"deg"
,
yaw
,
time
);
emit
valueChanged
(
uasId
,
"yawspeed"
,
"deg/s"
,
(
attitude
.
yawspeed
/
M_PI
)
*
180.0
,
time
);
emit
attitudeChanged
(
this
,
attitude
.
roll
,
attitude
.
pitch
,
attitude
.
yaw
,
time
);
...
...
src/ui/HDDisplay.cc
View file @
ba9e5a87
...
...
@@ -58,6 +58,7 @@ HDDisplay::HDDisplay(QStringList* plotList, QString title, QWidget *parent) :
normalStrokeWidth
(
1.0
f
),
fineStrokeWidth
(
0.5
f
),
acceptList
(
new
QStringList
()),
acceptUnitList
(
new
QStringList
()),
lastPaintTime
(
0
),
columns
(
3
),
m_ui
(
new
Ui
::
HDDisplay
)
...
...
@@ -194,7 +195,7 @@ void HDDisplay::saveState()
for
(
int
i
=
0
;
i
<
acceptList
->
count
();
i
++
)
{
QString
key
=
acceptList
->
at
(
i
);
instruments
+=
"|"
+
QString
::
number
(
minValues
.
value
(
key
,
-
1.0
))
+
","
+
key
+
","
+
QString
::
number
(
maxValues
.
value
(
key
,
+
1.0
))
+
","
+
((
symmetric
.
value
(
key
,
false
))
?
"s"
:
""
);
instruments
+=
"|"
+
QString
::
number
(
minValues
.
value
(
key
,
-
1.0
))
+
","
+
key
+
","
+
acceptUnitList
->
at
(
i
)
+
","
+
QString
::
number
(
maxValues
.
value
(
key
,
+
1.0
))
+
","
+
((
symmetric
.
value
(
key
,
false
))
?
"s"
:
""
);
}
// qDebug() << "Saving" << instruments;
...
...
@@ -250,7 +251,7 @@ void HDDisplay::addGauge()
QStringList
items
;
for
(
int
i
=
0
;
i
<
values
.
count
();
++
i
)
{
items
.
append
(
QString
(
"%1,%2,%3
"
).
arg
(
"-180"
).
arg
(
value
s
.
keys
().
at
(
i
)).
arg
(
"+180"
));
items
.
append
(
QString
(
"%1,%2,%3
,%4"
).
arg
(
"-180"
).
arg
(
values
.
keys
().
at
(
i
)).
arg
(
unit
s
.
keys
().
at
(
i
)).
arg
(
"+180"
));
}
bool
ok
;
QString
item
=
QInputDialog
::
getItem
(
this
,
tr
(
"Add Gauge Instrument"
),
...
...
@@ -266,38 +267,47 @@ void HDDisplay::addGauge(const QString& gauge)
if
(
gauge
.
length
()
>
0
)
{
QStringList
parts
=
gauge
.
split
(
','
);
if
(
parts
.
count
()
>
1
)
if
(
parts
.
count
()
>
2
)
{
double
val
;
bool
ok
;
bool
success
=
true
;
QString
key
=
parts
.
at
(
1
);
QString
unit
=
parts
.
at
(
2
);
if
(
!
acceptList
->
contains
(
key
))
{
// Convert min to double number
val
=
parts
.
first
().
toDouble
(
&
ok
);
success
&=
ok
;
if
(
ok
)
minValues
.
insert
(
key
,
val
);
// Convert max to double number
val
=
parts
.
at
(
2
).
toDouble
(
&
ok
);
val
=
parts
.
at
(
3
).
toDouble
(
&
ok
);
success
&=
ok
;
if
(
ok
)
maxValues
.
insert
(
key
,
val
);
// Convert symmetric flag
if
(
parts
.
length
()
>=
4
)
if
(
parts
.
length
()
>=
5
)
{
if
(
parts
.
at
(
3
).
contains
(
"s"
))
if
(
parts
.
at
(
4
).
contains
(
"s"
))
{
symmetric
.
insert
(
key
,
true
);
}
}
// Add value to acceptlist
acceptList
->
append
(
key
);
if
(
success
)
{
// Add value to acceptlist
acceptList
->
append
(
key
);
acceptUnitList
->
append
(
unit
);
}
}
}
else
else
if
(
parts
.
count
()
>
1
)
{
if
(
!
acceptList
->
contains
(
gauge
))
{
acceptList
->
append
(
parts
.
first
());
acceptList
->
append
(
parts
.
at
(
0
));
acceptUnitList
->
append
(
parts
.
at
(
1
));
}
}
}
...
...
@@ -425,14 +435,14 @@ void HDDisplay::setActiveUAS(UASInterface* uas)
if
(
this
->
uas
!=
NULL
)
{
// Disconnect any previously connected active MAV
disconnect
(
this
->
uas
,
SIGNAL
(
valueChanged
(
int
,
QString
,
double
,
quint64
)),
this
,
SLOT
(
updateValue
(
int
,
QString
,
double
,
quint64
)));
disconnect
(
this
->
uas
,
SIGNAL
(
valueChanged
(
int
,
QString
,
QString
,
double
,
quint64
)),
this
,
SLOT
(
updateValue
(
int
,
QString
,
QString
,
double
,
quint64
)));
}
// Now connect the new UAS
//qDebug() << "UAS SET!" << "ID:" << uas->getUASID();
// Setup communication
connect
(
uas
,
SIGNAL
(
valueChanged
(
int
,
QString
,
double
,
quint64
)),
this
,
SLOT
(
updateValue
(
int
,
QString
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
valueChanged
(
int
,
QString
,
QString
,
double
,
quint64
)),
this
,
SLOT
(
updateValue
(
int
,
QString
,
QString
,
double
,
quint64
)));
this
->
uas
=
uas
;
}
...
...
@@ -799,7 +809,7 @@ float HDDisplay::refLineWidthToPen(float line)
return
line
*
2.50
f
;
}
void
HDDisplay
::
updateValue
(
int
uasId
,
QString
name
,
double
value
,
quint64
msec
)
void
HDDisplay
::
updateValue
(
const
int
uasId
,
const
QString
&
name
,
const
QString
&
unit
,
const
double
value
,
const
quint64
msec
)
{
Q_UNUSED
(
uasId
);
// Update mean
...
...
src/ui/HDDisplay.h
View file @
ba9e5a87
...
...
@@ -64,7 +64,7 @@ public:
public
slots
:
/** @brief Update a HDD value */
void
updateValue
(
int
uasId
,
QString
name
,
double
value
,
quint64
msec
);
void
updateValue
(
const
int
uasId
,
const
QString
&
name
,
const
QString
&
unit
,
const
double
value
,
const
quint64
msec
);
void
setActiveUAS
(
UASInterface
*
uas
);
/** @brief Removes a plot item by the action data */
...
...
@@ -137,6 +137,7 @@ protected:
UASInterface
*
uas
;
///< The uas currently monitored
QMap
<
QString
,
float
>
values
;
///< The variables this HUD displays
QMap
<
QString
,
float
>
units
;
///< The units
QMap
<
QString
,
float
>
valuesDot
;
///< First derivative of the variable
QMap
<
QString
,
float
>
valuesMean
;
///< Mean since system startup for this variable
QMap
<
QString
,
int
>
valuesCount
;
///< Number of values received so far
...
...
@@ -177,7 +178,8 @@ protected:
float
normalStrokeWidth
;
///< Normal line stroke width, used throughout the HUD
float
fineStrokeWidth
;
///< Fine line stroke width, used throughout the HUD
QStringList
*
acceptList
;
///< Variable names to plot
QStringList
*
acceptList
;
///< Variable names to plot
QStringList
*
acceptUnitList
;
///< Unit names to plot
quint64
lastPaintTime
;
///< Last time this widget was refreshed
int
columns
;
///< Number of instrument columns
...
...
src/ui/MainWindow.cc
View file @
ba9e5a87
...
...
@@ -290,19 +290,19 @@ void MainWindow::buildPxWidgets()
{
//FIXME: memory of acceptList will never be freed again
QStringList
*
acceptList
=
new
QStringList
();
acceptList
->
append
(
"-1
80,roll (deg),+180
"
);
acceptList
->
append
(
"-1
80,pitch (deg),+180
"
);
acceptList
->
append
(
"-1
80,yaw (deg),+180
"
);
acceptList
->
append
(
"-1
05,roll,deg,+105,s
"
);
acceptList
->
append
(
"-1
05,pitch,deg,+105,s
"
);
acceptList
->
append
(
"-1
05,yaw,deg,+105,s
"
);
acceptList
->
append
(
"-
500,roll V (deg/s),+500
"
);
acceptList
->
append
(
"-
500,pitch V (deg/s),+500
"
);
acceptList
->
append
(
"-
500,yaw V (deg/s),+500
"
);
acceptList
->
append
(
"-
260,rollspeed,deg/s,+260,s
"
);
acceptList
->
append
(
"-
260,pitchspeed,deg/s,+260,s
"
);
acceptList
->
append
(
"-
260,yawspeed,deg/s,+260,s
"
);
//FIXME: memory of acceptList2 will never be freed again
QStringList
*
acceptList2
=
new
QStringList
();
acceptList2
->
append
(
"0,
Abs pressure
,65500"
);
acceptList2
->
append
(
"-2000,
Accel. X, 2000
"
);
acceptList2
->
append
(
"-2000,
Accel. Y, 2000
"
);
acceptList2
->
append
(
"0,
abs pressure,hPa
,65500"
);
acceptList2
->
append
(
"-2000,
accel. X,raw,2000,s
"
);
acceptList2
->
append
(
"-2000,
accel. Y,raw,2000,s
"
);
if
(
!
linechartWidget
)
{
...
...
src/ui/linechart/LinechartWidget.cc
View file @
ba9e5a87
...
...
@@ -344,6 +344,7 @@ void LinechartWidget::appendData(int uasId, const QString& curve, const QString&
// Make sure the curve will be created if it does not yet exist
if
(
!
label
)
{
intData
.
insert
(
curve
+
unit
,
0
);
addCurve
(
curve
,
unit
);
}
...
...
@@ -373,23 +374,30 @@ void LinechartWidget::refresh()
QMap
<
QString
,
QLabel
*>::
iterator
i
;
for
(
i
=
curveLabels
->
begin
();
i
!=
curveLabels
->
end
();
++
i
)
{
double
val
=
activePlot
->
getCurrentValue
(
i
.
key
());
int
intval
=
static_cast
<
int
>
(
val
);
if
(
intval
>=
100000
||
intval
<=
-
100000
)
{
str
.
sprintf
(
"% 11i"
,
intval
);
}
else
if
(
intval
>=
10000
||
intval
<=
-
10000
)
if
(
intData
.
contains
(
i
.
key
()))
{
str
.
sprintf
(
"% 11.2f"
,
val
);
}
else
if
(
intval
>=
1000
||
intval
<=
-
1000
)
{
str
.
sprintf
(
"% 11.4f"
,
val
);
str
.
sprintf
(
"% 11i"
,
intData
.
value
(
i
.
key
()));
}
else
{
str
.
sprintf
(
"% 11.6f"
,
val
);
double
val
=
activePlot
->
getCurrentValue
(
i
.
key
());
int
intval
=
static_cast
<
int
>
(
val
);
if
(
intval
>=
100000
||
intval
<=
-
100000
)
{
str
.
sprintf
(
"% 11i"
,
intval
);
}
else
if
(
intval
>=
10000
||
intval
<=
-
10000
)
{
str
.
sprintf
(
"% 11.2f"
,
val
);
}
else
if
(
intval
>=
1000
||
intval
<=
-
1000
)
{
str
.
sprintf
(
"% 11.4f"
,
val
);
}
else
{
str
.
sprintf
(
"% 11.6f"
,
val
);
}
}
// Value
i
.
value
()
->
setText
(
str
);
...
...
@@ -399,13 +407,18 @@ void LinechartWidget::refresh()
for
(
j
=
curveMeans
->
begin
();
j
!=
curveMeans
->
end
();
++
j
)
{
double
val
=
activePlot
->
getCurrentValue
(
j
.
key
());
if
(
val
>
9999
||
val
<
-
9999
)
int
intval
=
static_cast
<
int
>
(
val
);
if
(
intval
>=
100000
||
intval
<=
-
100000
)
{
str
.
sprintf
(
"% 11i"
,
intval
);
}
else
if
(
intval
>=
10000
||
intval
<=
-
10000
)
{
str
.
sprintf
(
"% 11.2f"
,
val
);
}
else
if
(
val
>
99999
||
val
<
-
99999
)
else
if
(
intval
>=
1000
||
intval
<=
-
1000
)
{
str
.
sprintf
(
"% 11
d"
,
(
int
)
val
);
str
.
sprintf
(
"% 11
.4f"
,
val
);
}
else
{
...
...
@@ -424,7 +437,7 @@ void LinechartWidget::refresh()
for
(
l
=
curveVariances
->
begin
();
l
!=
curveVariances
->
end
();
++
l
)
{
// Variance
str
.
sprintf
(
"%
9.4
e"
,
activePlot
->
getVariance
(
l
.
key
()));
str
.
sprintf
(
"%
8.3
e"
,
activePlot
->
getVariance
(
l
.
key
()));
l
.
value
()
->
setText
(
str
);
}
}
...
...
@@ -539,8 +552,6 @@ void LinechartWidget::createActions()
**/
void
LinechartWidget
::
addCurve
(
const
QString
&
curve
,
const
QString
&
unit
)
{
intData
.
insert
(
curve
+
unit
,
0
);
LinechartPlot
*
plot
=
activePlot
;
// QHBoxLayout *horizontalLayout;
QCheckBox
*
checkBox
;
...
...
@@ -600,6 +611,7 @@ void LinechartWidget::addCurve(const QString& curve, const QString& unit)
// Mean
mean
=
new
QLabel
(
this
);
mean
->
setNum
(
0.00
);
mean
->
setStyleSheet
(
QString
(
"QLabel {font-family:
\"
Courier
\"
; font-weight: bold;}"
));
mean
->
setToolTip
(
tr
(
"Arithmetic mean of "
)
+
curve
);
mean
->
setWhatsThis
(
tr
(
"Arithmetic mean of "
)
+
curve
);
curveMeans
->
insert
(
curve
+
unit
,
mean
);
...
...
@@ -614,6 +626,7 @@ void LinechartWidget::addCurve(const QString& curve, const QString& unit)
// Variance
variance
=
new
QLabel
(
this
);
variance
->
setNum
(
0.00
);
variance
->
setStyleSheet
(
QString
(
"QLabel {font-family:
\"
Courier
\"
; font-weight: bold;}"
));
variance
->
setToolTip
(
tr
(
"Variance of "
)
+
curve
);
variance
->
setWhatsThis
(
tr
(
"Variance of "
)
+
curve
);
curveVariances
->
insert
(
curve
+
unit
,
variance
);
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment