Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
9a11483b
Commit
9a11483b
authored
Jan 06, 2011
by
pixhawk
Browse files
Fixed many, many small visual issues
parent
887469bb
Changes
15
Hide whitespace changes
Inline
Side-by-side
images/style-outdoor.css
0 → 100644
View file @
9a11483b
*
{
font-family
:
"Bitstream Vera Sans"
;
font
:
"Roman"
;
font-size
:
12px
;
}
QWidget
#colorIcon
{}
QWidget
{
background-color
:
#F6F6F6
;
color
:
#000000
;
background-clip
:
border
;
font-size
:
11px
;
}
QGroupBox
{
border
:
1px
solid
#222216
;
border-radius
:
3px
;
padding
:
10px
0px
0px
0px
;
margin-top
:
1ex
;
/* leave space at the top for the title */
}
QCheckBox
{
/*background-color: #252528;*/
color
:
#222221
;
}
QCheckBox
::indicator
{
border
:
1px
solid
#111111
;
border-radius
:
2px
;
color
:
#222221
;
width
:
10px
;
height
:
10px
;
}
QLineEdit
{
border
:
1px
solid
#111111
;
border-radius
:
2px
;
}
QTextEdit
{
border
:
1px
solid
#111111
;
border-radius
:
2px
;
}
QPlainTextEdit
{
border
:
1px
solid
#111111
;
border-radius
:
2px
;
}
QComboBox
{
border
:
1px
solid
#111111
;
border-radius
:
2px
;
}
QCheckBox
::indicator:checked
{
background-color
:
#222222
;
}
QCheckBox
::indicator:checked:hover
{
background-color
:
#222222
;
}
QCheckBox
::indicator:checked:pressed
{
background-color
:
#222222
;
}
QCheckBox
::indicator:indeterminate:hover
{
image
:
url(:/images/checkbox_indeterminate_hover.png)
;
}
QCheckBox
::indicator:indeterminate:pressed
{
image
:
url(:/images/checkbox_indeterminate_pressed.png)
;
}
QGroupBox
::title
{
subcontrol-origin
:
margin
;
subcontrol-position
:
top
center
;
/* position at the top center */
margin
:
0
3px
0px
3px
;
padding
:
0
3px
0px
0px
;
font
:
bold
8px
;
color
:
#DDDDDF
;
}
QMainWindow
::separator
{
background
:
#090909
;
width
:
2px
;
/* when vertical */
height
:
2px
;
/* when horizontal */
}
QMainWindow
::separator:hover
{
background
:
white
;
}
QDockWidget
{
border
:
1px
solid
#32345E
;
/* titlebar-close-icon: url(close.png);
titlebar-normal-icon: url(undock.png);*/
}
QDockWidget
::title
{
text-align
:
left
;
/* align the text to the left */
background
:
lightgray
;
padding-left
:
5px
;
}
QDockWidget
::close-button
,
QDockWidget
::float-button
{
border
:
1px
solid
transparent
;
background
:
darkgray
;
padding
:
0px
;
}
QDockWidget
::close-button:hover
,
QDockWidget
::float-button:hover
{
background
:
gray
;
}
QDockWidget
::close-button:pressed
,
QDockWidget
::float-button:pressed
{
padding
:
1px
-1px
-1px
1px
;
}
QDockWidget
::close-button
,
QDockWidget
::float-button
{
background-color
:
#181820
;
color
:
#EEEEEE
;
}
QDockWidget
::title
{
text-align
:
left
;
background
:
#121214
;
color
:
#4A4A4F
;
padding-left
:
5px
;
height
:
10px
;
border-bottom
:
1px
solid
#222222
;
}
QSeparator
{
color
:
#EEEEEE
;
}
QSpinBox
{
min-height
:
14px
;
max-height
:
18px
;
border
:
1px
solid
#4A4A4F
;
border-radius
:
5px
;
}
QSpinBox
::up-button
{
subcontrol-origin
:
border
;
subcontrol-position
:
top
right
;
/* position at the top right corner */
border-image
:
url(:/images/actions/go-up.svg)
1
;
border-width
:
1px
;
}
QSpinBox
::down-button
{
subcontrol-origin
:
border
;
subcontrol-position
:
bottom
right
;
/* position at the top right corner */
border-image
:
url(:/images/actions/go-down.svg)
1
;
border-width
:
1px
;
}
QDoubleSpinBox
{
min-height
:
14px
;
max-height
:
18px
;
border
:
1px
solid
#4A4A4F
;
border-radius
:
5px
;
}
QDoubleSpinBox
::up-button
{
subcontrol-origin
:
border
;
subcontrol-position
:
top
right
;
/* position at the top right corner */
border-image
:
url(:/images/actions/go-up.svg)
1
;
border-width
:
1px
;
max-width
:
5px
;
}
QDoubleSpinBox
::down-button
{
subcontrol-origin
:
border
;
subcontrol-position
:
bottom
right
;
/* position at the top right corner */
border-image
:
url(:/images/actions/go-down.svg)
1
;
border-width
:
1px
;
max-width
:
5px
;
}
QPushButton
{
font-weight
:
bold
;
min-height
:
18px
;
max-height
:
18px
;
border
:
2px
solid
#4A4A4F
;
border-radius
:
5px
;
padding-left
:
10px
;
padding-right
:
10px
;
background-color
:
qlineargradient
(
x1
:
0
,
y1
:
0
,
x2
:
0
,
y2
:
1
,
stop
:
0
#232228
,
stop
:
1
#020208
);
}
QPushButton
:checked
{
background-color
:
qlineargradient
(
x1
:
0
,
y1
:
0
,
x2
:
0
,
y2
:
1
,
stop
:
0
#404040
,
stop
:
1
#808080
);
}
QPushButton
:pressed
{
background-color
:
qlineargradient
(
x1
:
0
,
y1
:
0
,
x2
:
0
,
y2
:
1
,
stop
:
0
#bbbbbb
,
stop
:
1
#b0b0b0
);
}
QToolButton
{
font-weight
:
bold
;
min-height
:
16px
;
min-width
:
24px
;
max-height
:
18px
;
border
:
2px
solid
#4A4A4F
;
border-radius
:
5px
;
background-color
:
qlineargradient
(
x1
:
0
,
y1
:
0
,
x2
:
0
,
y2
:
1
,
stop
:
0
#232228
,
stop
:
1
#020208
);
}
QToolButton
:checked
{
background-color
:
qlineargradient
(
x1
:
0
,
y1
:
0
,
x2
:
0
,
y2
:
1
,
stop
:
0
#090909
,
stop
:
1
#353535
);
}
QToolButton
:pressed
{
background-color
:
qlineargradient
(
x1
:
0
,
y1
:
0
,
x2
:
0
,
y2
:
1
,
stop
:
0
#bbbbbb
,
stop
:
1
#b0b0b0
);
}
QToolTip
{
background-color
:
#404040
;
border-radius
:
3px
;
}
QPushButton
#forceLandButton
{
font-weight
:
bold
;
min-height
:
30px
;
color
:
#000000
;
background
:
qlineargradient
(
x1
:
0
,
y1
:
0
,
x2
:
0
,
y2
:
1
,
stop
:
0
#ffee01
,
stop
:
1
#ae8f00
)
url("ICONDIR/control/emergency-button.png")
;
background-clip
:
border
;
border-width
:
1px
;
border-color
:
#222222
;
border-radius
:
5px
;
}
QPushButton
:pressed
#forceLandButton
{
font-weight
:
bold
;
min-height
:
30px
;
color
:
#000000
;
background
:
qlineargradient
(
x1
:
0
,
y1
:
0
,
x2
:
0
,
y2
:
1
,
stop
:
0
#bbaa00
,
stop
:
1
#a05b00
)
url("ICONDIR/control/emergency-button.png")
;
background-clip
:
border
;
border-width
:
1px
;
border-color
:
#222222
;
border-radius
:
5px
;
}
QPushButton
#killButton
{
font-weight
:
bold
;
min-height
:
30px
;
color
:
#000000
;
background
:
qlineargradient
(
x1
:
0
,
y1
:
0
,
x2
:
0
,
y2
:
1
,
stop
:
0
#ffb917
,
stop
:
1
#b37300
)
url("ICONDIR/control/emergency-button.png")
;
background-clip
:
border
;
border-width
:
1px
;
border-color
:
#222222
;
border-radius
:
5px
;
}
QPushButton
:pressed
#killButton
{
font-weight
:
bold
;
min-height
:
30px
;
color
:
#000000
;
background
:
qlineargradient
(
x1
:
0
,
y1
:
0
,
x2
:
0
,
y2
:
1
,
stop
:
0
#bb8500
,
stop
:
1
#903000
)
url("ICONDIR/control/emergency-button.png")
;
background-clip
:
border
;
border-width
:
1px
;
border-color
:
#222222
;
border-radius
:
5px
;
}
QPushButton
#controlButton
{
min-height
:
25px
;
background-color
:
qlineargradient
(
x1
:
0
,
y1
:
0
,
x2
:
0
,
y2
:
1
,
stop
:
0
#A0AE00
,
stop
:
1
#909E00
);
}
QPushButton
:checked
#controlButton
{
background-color
:
qlineargradient
(
x1
:
0
,
y1
:
0
,
x2
:
0
,
y2
:
1
,
stop
:
0
#b76f11
,
stop
:
1
#e1a718
);
}
QProgressBar
{
border
:
1px
solid
#4A4A4F
;
border-radius
:
4px
;
text-align
:
center
;
padding
:
2px
;
color
:
#DDDDDF
;
background-color
:
#111118
;
}
QProgressBar
:horizontal
{
height
:
9px
;
}
QProgressBar
:vertical
{
width
:
9px
;
}
QProgressBar
::chunk
{
background-color
:
#3C7B9E
;
}
QProgressBar
::chunk
#batteryBar
{
background-color
:
green
;
}
QProgressBar
::chunk
#speedBar
{
background-color
:
yellow
;
}
QProgressBar
::chunk
#thrustBar
{
background-color
:
orange
;
}
qgroundcontrol.pri
View file @
9a11483b
...
...
@@ -83,6 +83,9 @@ macx {
QMAKE_POST_LINK += && cp -rf $$BASEDIR/audio $$TARGETDIR/qgroundcontrol.app/Contents/MacOs
# Copy google earth starter file
QMAKE_POST_LINK += && cp -f $$BASEDIR/images/earth.html $$TARGETDIR/qgroundcontrol.app/Contents/MacOs
# Copy CSS stylesheets
QMAKE_POST_LINK += && cp -f $$BASEDIR/images/style-mission.css $$TARGETDIR/qgroundcontrol.app/Contents/MacOs/style-indoor.css
QMAKE_POST_LINK += && cp -f $$BASEDIR/images/style-outdoor.css $$TARGETDIR/qgroundcontrol.app/Contents/MacOs
# Copy model files
#QMAKE_POST_LINK += && cp -f $$BASEDIR/models/*.dae $$TARGETDIR/qgroundcontrol.app/Contents/MacOs
...
...
src/QGC.cc
View file @
9a11483b
...
...
@@ -34,4 +34,9 @@ quint64 groundTimeUsecs()
return
static_cast
<
quint64
>
(
microseconds
+
(
time
.
time
().
msec
()
*
1000
));
}
int
applicationVersion
()
{
return
APPLICATIONVERSION
;
}
}
src/QGC.h
View file @
9a11483b
...
...
@@ -15,9 +15,11 @@ namespace QGC
/** @brief Get the current ground time in microseconds */
quint64
groundTimeUsecs
();
int
applicationVersion
();
const
QString
APPNAME
=
"QGROUNDCONTROL"
;
const
QString
COMPANYNAME
=
"OPENMAV"
;
const
int
APPLICATIONVERSION
=
80
;
// 0.8.0
}
#define QGC_EVENTLOOP_DEBUG 0
...
...
src/comm/MAVLinkSimulationLink.cc
View file @
9a11483b
...
...
@@ -447,7 +447,7 @@ void MAVLinkSimulationLink::mainloop()
chan
.
chan5_raw
=
(
chan
.
chan3_raw
+
chan
.
chan4_raw
)
/
2.0
f
;
chan
.
chan6_raw
=
(
chan
.
chan3_raw
+
chan
.
chan2_raw
)
/
2.0
f
;
chan
.
chan7_raw
=
(
chan
.
chan4_raw
+
chan
.
chan2_raw
)
/
2.0
f
;
chan
.
chan8_raw
=
(
chan
.
chan6_raw
+
chan
.
chan2_raw
)
/
2.0
f
;
chan
.
chan8_raw
=
0
;
chan
.
rssi
=
100
;
messageSize
=
mavlink_msg_rc_channels_raw_encode
(
systemId
,
componentId
,
&
msg
,
&
chan
);
// Allocate buffer with packet data
...
...
src/uas/UAS.cc
View file @
9a11483b
...
...
@@ -279,15 +279,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_msg_raw_imu_decode
(
&
message
,
&
raw
);
quint64
time
=
getUnixTime
(
raw
.
usec
);
emit
valueChanged
(
uasId
,
"
A
ccel
. X
"
,
raw
.
xacc
,
time
);
emit
valueChanged
(
uasId
,
"
A
ccel
. Y
"
,
raw
.
yacc
,
time
);
emit
valueChanged
(
uasId
,
"
A
ccel
. Z
"
,
raw
.
zacc
,
time
);
emit
valueChanged
(
uasId
,
"
G
yro
Phi
"
,
static_cast
<
double
>
(
raw
.
xgyro
),
time
);
emit
valueChanged
(
uasId
,
"
G
yro
Theta
"
,
static_cast
<
double
>
(
raw
.
ygyro
),
time
);
emit
valueChanged
(
uasId
,
"
G
yro
Psi
"
,
static_cast
<
double
>
(
raw
.
zgyro
),
time
);
emit
valueChanged
(
uasId
,
"
M
ag
. X
"
,
raw
.
xmag
,
time
);
emit
valueChanged
(
uasId
,
"
M
ag
. Y
"
,
raw
.
ymag
,
time
);
emit
valueChanged
(
uasId
,
"
M
ag
. Z
"
,
raw
.
zmag
,
time
);
emit
valueChanged
(
uasId
,
"
a
ccel
x
"
,
raw
.
xacc
,
time
);
emit
valueChanged
(
uasId
,
"
a
ccel
y
"
,
raw
.
yacc
,
time
);
emit
valueChanged
(
uasId
,
"
a
ccel
z
"
,
raw
.
zacc
,
time
);
emit
valueChanged
(
uasId
,
"
g
yro
roll
"
,
static_cast
<
double
>
(
raw
.
xgyro
),
time
);
emit
valueChanged
(
uasId
,
"
g
yro
pitch
"
,
static_cast
<
double
>
(
raw
.
ygyro
),
time
);
emit
valueChanged
(
uasId
,
"
g
yro
yaw
"
,
static_cast
<
double
>
(
raw
.
zgyro
),
time
);
emit
valueChanged
(
uasId
,
"
m
ag
x
"
,
raw
.
xmag
,
time
);
emit
valueChanged
(
uasId
,
"
m
ag
y
"
,
raw
.
ymag
,
time
);
emit
valueChanged
(
uasId
,
"
m
ag
z
"
,
raw
.
zmag
,
time
);
}
break
;
case
MAVLINK_MSG_ID_ATTITUDE
:
...
...
@@ -303,20 +303,20 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// emit valueChanged(uasId, "roll IMU", mavlink_msg_attitude_get_roll(&message), time);
// emit valueChanged(uasId, "pitch IMU", mavlink_msg_attitude_get_pitch(&message), time);
// emit valueChanged(uasId, "yaw IMU", mavlink_msg_attitude_get_yaw(&message), time);
emit
valueChanged
(
uasId
,
"roll
IMU
"
,
mavlink_msg_attitude_get_roll
(
&
message
),
time
);
emit
valueChanged
(
uasId
,
"pitch
IMU
"
,
mavlink_msg_attitude_get_pitch
(
&
message
),
time
);
emit
valueChanged
(
uasId
,
"yaw
IMU
"
,
mavlink_msg_attitude_get_yaw
(
&
message
),
time
);
emit
valueChanged
(
uasId
,
"rollspeed
IMU
"
,
attitude
.
rollspeed
,
time
);
emit
valueChanged
(
uasId
,
"pitchspeed
IMU
"
,
attitude
.
pitchspeed
,
time
);
emit
valueChanged
(
uasId
,
"yawspeed
IMU
"
,
attitude
.
yawspeed
,
time
);
emit
valueChanged
(
uasId
,
"roll
(rad)
"
,
mavlink_msg_attitude_get_roll
(
&
message
),
time
);
emit
valueChanged
(
uasId
,
"pitch
(rad)
"
,
mavlink_msg_attitude_get_pitch
(
&
message
),
time
);
emit
valueChanged
(
uasId
,
"yaw
(rad)
"
,
mavlink_msg_attitude_get_yaw
(
&
message
),
time
);
emit
valueChanged
(
uasId
,
"rollspeed
(rad)
"
,
attitude
.
rollspeed
,
time
);
emit
valueChanged
(
uasId
,
"pitchspeed
(rad)
"
,
attitude
.
pitchspeed
,
time
);
emit
valueChanged
(
uasId
,
"yawspeed
(rad)
"
,
attitude
.
yawspeed
,
time
);
// 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
,
"roll
V (deg/s)
"
,
(
attitude
.
rollspeed
/
M_PI
)
*
180.0
,
time
);
emit
valueChanged
(
uasId
,
"pitch
V (deg/s)
"
,
(
attitude
.
pitchspeed
/
M_PI
)
*
180.0
,
time
);
emit
valueChanged
(
uasId
,
"yaw
V (deg/s)
"
,
(
attitude
.
yawspeed
/
M_PI
)
*
180.0
,
time
);
emit
valueChanged
(
uasId
,
"roll"
,
(
attitude
.
roll
/
M_PI
)
*
180.0
,
time
);
emit
valueChanged
(
uasId
,
"pitch"
,
(
attitude
.
pitch
/
M_PI
)
*
180.0
,
time
);
emit
valueChanged
(
uasId
,
"yaw"
,
(
attitude
.
yaw
/
M_PI
)
*
180.0
,
time
);
emit
valueChanged
(
uasId
,
"roll
speed
"
,
(
attitude
.
rollspeed
/
M_PI
)
*
180.0
,
time
);
emit
valueChanged
(
uasId
,
"pitch
speed
"
,
(
attitude
.
pitchspeed
/
M_PI
)
*
180.0
,
time
);
emit
valueChanged
(
uasId
,
"yaw
speed
"
,
(
attitude
.
yawspeed
/
M_PI
)
*
180.0
,
time
);
emit
attitudeChanged
(
this
,
attitude
.
roll
,
attitude
.
pitch
,
attitude
.
yaw
,
time
);
}
...
...
@@ -334,9 +334,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
valueChanged
(
uasId
,
"x"
,
pos
.
x
,
time
);
emit
valueChanged
(
uasId
,
"y"
,
pos
.
y
,
time
);
emit
valueChanged
(
uasId
,
"z"
,
pos
.
z
,
time
);
emit
valueChanged
(
uasId
,
"
V
x"
,
pos
.
vx
,
time
);
emit
valueChanged
(
uasId
,
"
V
y"
,
pos
.
vy
,
time
);
emit
valueChanged
(
uasId
,
"
V
z"
,
pos
.
vz
,
time
);
emit
valueChanged
(
uasId
,
"x
speed
"
,
pos
.
vx
,
time
);
emit
valueChanged
(
uasId
,
"y
speed
"
,
pos
.
vy
,
time
);
emit
valueChanged
(
uasId
,
"z
speed
"
,
pos
.
vz
,
time
);
emit
localPositionChanged
(
this
,
pos
.
x
,
pos
.
y
,
pos
.
z
,
time
);
emit
speedChanged
(
this
,
pos
.
vx
,
pos
.
vy
,
pos
.
vz
,
time
);
...
...
@@ -366,12 +366,12 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
speedX
=
pos
.
vx
/
100.0
;
speedY
=
pos
.
vy
/
100.0
;
speedZ
=
pos
.
vz
/
100.0
;
emit
valueChanged
(
uasId
,
"lat"
,
pos
.
lat
,
time
);
emit
valueChanged
(
uasId
,
"lon"
,
pos
.
lon
,
time
);
emit
valueChanged
(
uasId
,
"alt"
,
pos
.
alt
,
time
);
emit
valueChanged
(
uasId
,
"g
-vx
"
,
speedX
,
time
);
emit
valueChanged
(
uasId
,
"g
-vy
"
,
speedY
,
time
);
emit
valueChanged
(
uasId
,
"g
-vz
"
,
speedZ
,
time
);
emit
valueChanged
(
uasId
,
"lat
itude
"
,
pos
.
lat
,
time
);
emit
valueChanged
(
uasId
,
"lon
gitude
"
,
pos
.
lon
,
time
);
emit
valueChanged
(
uasId
,
"alt
itutde
"
,
pos
.
alt
,
time
);
emit
valueChanged
(
uasId
,
"g
ps x speed
"
,
speedX
,
time
);
emit
valueChanged
(
uasId
,
"g
ps y speed
"
,
speedY
,
time
);
emit
valueChanged
(
uasId
,
"g
ps z speed
"
,
speedZ
,
time
);
emit
globalPositionChanged
(
this
,
longitude
,
latitude
,
altitude
,
time
);
emit
speedChanged
(
this
,
speedX
,
speedY
,
speedZ
,
time
);
// Set internal state
...
...
@@ -397,8 +397,8 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// quint64 time = getUnixTime(pos.usec);
quint64
time
=
MG
::
TIME
::
getGroundTimeNow
();
emit
valueChanged
(
uasId
,
"lat"
,
pos
.
lat
,
time
);
emit
valueChanged
(
uasId
,
"lon"
,
pos
.
lon
,
time
);
emit
valueChanged
(
uasId
,
"lat
itude
"
,
pos
.
lat
,
time
);
emit
valueChanged
(
uasId
,
"lon
gitude
"
,
pos
.
lon
,
time
);
if
(
pos
.
fix_type
>
0
)
{
...
...
@@ -411,7 +411,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
alt
=
0
;
emit
textMessageReceived
(
uasId
,
message
.
compid
,
255
,
"GCS ERROR: RECEIVED NaN FOR ALTITUDE"
);
}
emit
valueChanged
(
uasId
,
"alt"
,
pos
.
alt
,
time
);
emit
valueChanged
(
uasId
,
"alt
itude
"
,
pos
.
alt
,
time
);
// Smaller than threshold and not NaN
if
(
pos
.
v
<
1000000
&&
pos
.
v
==
pos
.
v
)
{
...
...
@@ -447,9 +447,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
mavlink_raw_pressure_t
pressure
;
mavlink_msg_raw_pressure_decode
(
&
message
,
&
pressure
);
emit
valueChanged
(
uasId
,
"
A
bs pressure"
,
pressure
.
press_abs
,
this
->
getUnixTime
(
0
));
emit
valueChanged
(
uasId
,
"
D
iff pressure 1"
,
pressure
.
press_diff1
,
this
->
getUnixTime
(
0
));
emit
valueChanged
(
uasId
,
"
D
iff pressure 2"
,
pressure
.
press_diff2
,
this
->
getUnixTime
(
0
));
emit
valueChanged
(
uasId
,
"
a
bs pressure"
,
pressure
.
press_abs
,
this
->
getUnixTime
(
0
));
emit
valueChanged
(
uasId
,
"
d
iff pressure 1"
,
pressure
.
press_diff1
,
this
->
getUnixTime
(
0
));
emit
valueChanged
(
uasId
,
"
d
iff pressure 2"
,
pressure
.
press_diff2
,
this
->
getUnixTime
(
0
));
}
break
;
case
MAVLINK_MSG_ID_RC_CHANNELS_RAW
:
...
...
src/ui/HDDisplay.cc
View file @
9a11483b
...
...
@@ -194,10 +194,10 @@ 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
));
instruments
+=
"|"
+
QString
::
number
(
minValues
.
value
(
key
,
-
1.0
))
+
","
+
key
+
","
+
QString
::
number
(
maxValues
.
value
(
key
,
+
1.0
))
+
","
+
((
symmetric
.
value
(
key
,
false
))
?
"s"
:
""
)
;
}
qDebug
()
<<
"Saving"
<<
instruments
;
//
qDebug() << "Saving" << instruments;
settings
.
setValue
(
windowTitle
()
+
"_gauges"
,
instruments
);
settings
.
sync
();
...
...
@@ -240,6 +240,8 @@ void HDDisplay::removeItemByAction()
acceptList
->
removeAt
(
index
);
minValues
.
remove
(
item
);
maxValues
.
remove
(
item
);
symmetric
.
remove
(
item
);
adjustGaugeAspectRatio
();
}
}
...
...
@@ -277,8 +279,16 @@ void HDDisplay::addGauge(const QString& gauge)
val
=
parts
.
first
().
toDouble
(
&
ok
);
if
(
ok
)
minValues
.
insert
(
key
,
val
);
// Convert max to double number
val
=
parts
.
las
t
().
toDouble
(
&
ok
);
val
=
parts
.
a
t
(
2
).
toDouble
(
&
ok
);
if
(
ok
)
maxValues
.
insert
(
key
,
val
);
// Convert symmetric flag
if
(
parts
.
length
()
>=
4
)
{
if
(
parts
.
at
(
3
).
contains
(
"s"
))
{
symmetric
.
insert
(
key
,
true
);
}
}
// Add value to acceptlist
acceptList
->
append
(
key
);
}
...
...
@@ -394,7 +404,7 @@ void HDDisplay::renderOverlay()
for
(
int
i
=
0
;
i
<
acceptList
->
size
();
++
i
)
{
QString
value
=
acceptList
->
at
(
i
);
drawGauge
(
xCoord
,
yCoord
,
gaugeWidth
/
2.0
f
,
minValues
.
value
(
value
,
-
1.0
f
),
maxValues
.
value
(
value
,
1.0
f
),
value
,
values
.
value
(
value
,
minValues
.
value
(
value
,
0.0
f
)),
gaugeColor
,
&
painter
,
goodRanges
.
value
(
value
,
qMakePair
(
0.0
f
,
0.5
f
)),
critRanges
.
value
(
value
,
qMakePair
(
0.7
f
,
1.0
f
)),
true
);
drawGauge
(
xCoord
,
yCoord
,
gaugeWidth
/
2.0
f
,
minValues
.
value
(
value
,
-
1.0
f
),
maxValues
.
value
(
value
,
1.0
f
),
value
,
values
.
value
(
value
,
minValues
.
value
(
value
,
0.0
f
)),
gaugeColor
,
&
painter
,
symmetric
.
value
(
value
,
false
),
goodRanges
.
value
(
value
,
qMakePair
(
0.0
f
,
0.5
f
)),
critRanges
.
value
(
value
,
qMakePair
(
0.7
f
,
1.0
f
)),
true
);
xCoord
+=
gaugeWidth
+
leftSpacing
;
// Move one row down if necessary
if
(
xCoord
+
gaugeWidth
*
0.9
f
>
vwidth
)
...
...
@@ -513,17 +523,33 @@ void HDDisplay::drawChangeRateStrip(float xRef, float yRef, float height, float
paintText
(
label
,
defaultColor
,
3.0
f
,
xRef
+
width
/
2.0
f
,
yRef
+
height
-
((
scaledValue
-
minRate
)
/
(
maxRate
-
minRate
))
*
height
-
1.6
f
,
painter
);
}
void
HDDisplay
::
drawGauge
(
float
xRef
,
float
yRef
,
float
radius
,
float
min
,
float
max
,
QString
name
,
float
value
,
const
QColor
&
color
,
QPainter
*
painter
,
QPair
<
float
,
float
>
goodRange
,
QPair
<
float
,
float
>
criticalRange
,
bool
solid
)
void
HDDisplay
::
drawGauge
(
float
xRef
,
float
yRef
,
float
radius
,
float
min
,
float
max
,
QString
name
,
float
value
,
const
QColor
&
color
,
QPainter
*
painter
,
bool
symmetric
,
QPair
<
float
,
float
>
goodRange
,
QPair
<
float
,
float
>
criticalRange
,
bool
solid
)
{
// Draw the circle
QPen
circlePen
(
Qt
::
SolidLine
);
// Rotate the whole gauge with this angle (in radians) for the zero position
const
float
zeroRotation
=
0.49
f
;
float
zeroRotation
;
if
(
symmetric
)
{
zeroRotation
=
1.35
f
;
}
else
{
zeroRotation
=
0.49
f
;
}
// Scale the rotation so that the gauge does one revolution
// per max. change
const
float
rangeScale
=
((
2.0
f
*
M_PI
)
/
(
max
-
min
))
*
0.72
f
;
float
rangeScale
;
if
(
symmetric
)
{
rangeScale
=
((
2.0
f
*
M_PI
)
/
(
max
-
min
))
*
0.57
f
;
}
else
{
rangeScale
=
((
2.0
f
*
M_PI
)
/
(
max
-
min
))
*
0.72
f
;
}
const
float
scaledValue
=
(
value
-
min
)
*
rangeScale
;
...
...
@@ -558,7 +584,15 @@ void HDDisplay::drawGauge(float xRef, float yRef, float radius, float min, float
QBrush
brush
(
QGC
::
colorBackground
,
Qt
::
SolidPattern
);
painter
->
setBrush
(
brush
);
painter
->
setPen
(
Qt
::
NoPen
);
painter
->
drawRect
(
refToScreenX
(
xRef
-
radius
/
2.5
f
),
refToScreenY
(
yRef
+
nameHeight
+
radius
/
4.0
f
),
refToScreenX
(
radius
+
radius
/
2.0
f
),
refToScreenY
((
radius
-
radius
/
4.0
f
)
*
1.2
f
));
if
(
symmetric
)
{
painter
->
drawRect
(
refToScreenX
(
xRef
-
radius
),
refToScreenY
(
yRef
+
nameHeight
+
radius
/
4.0
f
),
refToScreenX
(
radius
+
radius
),
refToScreenY
((
radius
-
radius
/
4.0
f
)
*
1.2
f
));
}
else
{
painter
->
drawRect
(
refToScreenX
(
xRef
-
radius
/
2.5
f
),
refToScreenY
(
yRef
+
nameHeight
+
radius
/
4.0
f
),
refToScreenX
(
radius
+
radius
/
2.0
f
),
refToScreenY
((
radius
-
radius
/
4.0
f
)
*
1.2
f
));
}
// Draw good value and crit. value markers
if
(
goodRange
.
first
!=
goodRange
.
second
)
...
...
src/ui/HDDisplay.h
View file @
9a11483b
...
...
@@ -114,7 +114,7 @@ protected:
void
drawChangeRateStrip
(
float
xRef
,
float
yRef
,
float
height
,
float
minRate
,
float
maxRate
,
float
value
,
QPainter
*
painter
);
void
drawChangeIndicatorGauge
(
float
xRef
,
float
yRef
,
float
radius
,
float
expectedMaxChange
,
float
value
,
const
QColor
&
color
,
QPainter
*
painter
,
bool
solid
=
true
);
void
drawGauge
(
float
xRef
,
float
yRef
,
float
radius
,
float
min
,
float
max
,
const
QString
name
,
float
value
,
const
QColor
&
color
,
QPainter
*
painter
,
QPair
<
float
,
float
>
goodRange
,
QPair
<
float
,
float
>
criticalRange
,
bool
solid
=
true
);
void
drawGauge
(
float
xRef
,
float
yRef
,
float
radius
,
float
min
,
float
max
,
const
QString
name
,
float
value
,
const
QColor
&
color
,
QPainter
*
painter
,
bool
symmetric
,
QPair
<
float
,
float
>
goodRange
,
QPair
<
float
,
float
>
criticalRange
,
bool
solid
=
true
);
void
drawSystemIndicator
(
float
xRef
,
float
yRef
,
int
maxNum
,
float
maxWidth
,
float
maxHeight
,
QPainter
*
painter
);
void
paintText
(
QString
text
,
QColor
color
,
float
fontSize
,
float
refX
,
float
refY
,
QPainter
*
painter
);
...
...
@@ -143,6 +143,7 @@ protected:
QMap
<
QString
,
quint64
>
lastUpdate
;
///< The last update time for this variable
QMap
<
QString
,
float
>
minValues
;
///< The minimum value this variable is assumed to have
QMap
<
QString
,
float
>
maxValues
;
///< The maximum value this variable is assumed to have
QMap
<
QString
,
bool
>
symmetric
;
///< Draw the gauge / dial symmetric bool = yes
QMap
<
QString
,
QPair
<
float
,
float
>
>
goodRanges
;
///< The range of good values
QMap
<
QString
,
QPair
<
float
,
float
>
>
critRanges
;
///< The range of critical values
double
scalingFactor
;
///< Factor used to scale all absolute values to screen coordinates
...
...
src/ui/HUD.cc
View file @
9a11483b
...
...
@@ -242,8 +242,7 @@ void HUD::updateValue(UASInterface* uas, QString name, double value, quint64 mse
*/
void
HUD
::
setActiveUAS
(
UASInterface
*
uas
)
{
qDebug
()
<<
"ATTEMPTING TO SET UAS"
;
if
(
this
->
uas
!=
NULL
&&
this
->
uas
!=
uas
)
if
(
this
->
uas
!=
NULL
)
{
// Disconnect any previously connected active MAV
disconnect
(
uas
,
SIGNAL
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitude
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
...
...
@@ -254,25 +253,15 @@ void HUD::setActiveUAS(UASInterface* uas)
}
// Now connect the new UAS
//if (this->uas != uas)
// {
qDebug
()
<<
"UAS SET!"
<<
"ID:"
<<
uas
->
getUASID
();
// Setup communication
connect
(
uas
,
SIGNAL
(
attitudeChanged
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)),
this
,
SLOT
(
updateAttitude
(
UASInterface
*
,
double
,
double
,
double
,
quint64
)));
connect
(
uas
,
SIGNAL
(
batteryChanged
(
UASInterface
*
,
double
,
double
,
int
)),
this
,
SLOT
(
updateBattery
(
UASInterface
*
,
double
,
double
,
int
)));
connect
(
uas
,
SIGNAL
(
statusChanged
(
UASInterface
*
,
QString
,
QString
)),
this
,
SLOT
(
updateState
(
UASInterface
*
,
QString
)));
connect
(
uas
,
SIGNAL
(
modeChanged
(
int
,
QString
,
QString
)),
this
,
SLOT
(
updateMode
(
int
,
QString
,
QString
)));
connect
(
uas
,
SIGNAL
(
heartbeat
(
UASInterface
*
)),
this
,
SLOT
(
receiveHeartbeat
(
UASInterface
*
)));
//connect(uas, SIGNAL(thrustChanged(UASInterface*, double)), this, SLOT(updateThrust(UASInterface*, double)));
//connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateLocalPosition(UASInterface*,double,double,double,quint64)));
//connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64)));
//connect(uas, SIGNAL(speedChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateSpeed(UASInterface*,double,double,double,quint64)));
//connect(uas, SIGNAL(statusChanged(UASInterface*,QString,QString)), this, SLOT(updateState(UASInterface*,QString,QString)));
//connect(uas, SIGNAL(loadChanged(UASInterface*, double)), this, SLOT(updateLoad(UASInterface*, double)));
//connect(uas, SIGNAL(attitudeThrustSetPointChanged(UASInterface*,double,double,double,double,quint64)), this, SLOT(updateAttitudeThrustSetPoint(UASInterface*,double,double,double,double,quint64)));
//connect(uas, SIGNAL(valueChanged(UASInterface*,QString,double,quint64)), this, SLOT(updateValue(UASInterface*,QString,double,quint64)));
//}
// Set new UAS
this
->
uas
=
uas
;
}
void
HUD
::
updateAttitudeThrustSetPoint
(
UASInterface
*
,
double
rollDesired
,
double
pitchDesired
,
double
yawDesired
,
double
thrustDesired
,
quint64
msec
)
...
...
@@ -329,7 +318,7 @@ void HUD::updateLocalPosition(UASInterface* uas,double x,double y,double z,quint
updateValue
(
uas
,
"z"
,
z
,
timestamp
);
}
void
HUD
::
updateGlobalPosition
(
UASInterface
*
,
double
lat
,
double
lon
,
double
altitude
,
quint64
timestamp
)
void
HUD
::
updateGlobalPosition
(
UASInterface
*
uas
,
double
lat
,
double
lon
,
double
altitude
,
quint64
timestamp
)
{
updateValue
(
uas
,
"lat"
,
lat
,
timestamp
);
updateValue
(
uas
,
"lon"
,
lon
,
timestamp
);
...
...
@@ -581,7 +570,7 @@ void HUD::paintHUD()
// Translate for yaw
const
float
maxYawTrans
=
60.0
f
;
static
float
yawDiff
=
0.0
f
;
float
newYawDiff
=
valuesDot
.
value
(
"yaw"
,
0.0
f
);
if
(
isinf
(
newYawDiff
))
newYawDiff
=
yawDiff
;
if
(
newYawDiff
>
M_PI
)
newYawDiff
=
newYawDiff
-
M_PI
;
...
...
src/ui/HUD.h
View file @
9a11483b
...
...
@@ -188,6 +188,7 @@ protected:
float
roll
;
float
pitch
;
float
yaw
;
float
yawDiff
;
void
paintEvent
(
QPaintEvent
*
event
);
};
...
...
src/ui/MainWindow.cc
View file @
9a11483b
...
...
@@ -63,15 +63,55 @@ MainWindow* MainWindow::instance()
MainWindow
::
MainWindow
(
QWidget
*
parent
)
:
QMainWindow
(
parent
),
toolsMenuActions
(),
currentView
(
VIEW_
OPERATO
R
),
currentView
(
VIEW_
ENGINEE
R
),
aboutToCloseFlag
(
false
),
settings
()
{
// Get current settings
settings
.
sync
();
if
(
!
settings
.
contains
(
"CURRENT_VIEW"
))
{
// Set this view as default view
settings
.
setValue
(
"CURRENT_VIEW"
,
currentView
);
// Enable default tools
// ENABLE UAS LIST
settings
.
setValue
(
buildMenuKey
(
SUB_SECTION_CHECKED
,
MainWindow
::
MENU_UAS_LIST
,
currentView
),
true
);
// ENABLE COMMUNICATION CONSOLE
settings
.
setValue
(
buildMenuKey
(
SUB_SECTION_CHECKED
,
MainWindow
::
MENU_DEBUG_CONSOLE
,
currentView
),
true
);
}
else
{
currentView
=
(
VIEW_SECTIONS
)
settings
.
value
(
"CURRENT_VIEW"
,
currentView
).
toInt
();
}
// Check if the settings exist, instantiate defaults if necessary
QString
centralKey
=
buildMenuKey
(
SUB_SECTION_CHECKED
,
CENTRAL_MAP
,
currentView
);
// OPERATOR VIEW DEFAULT
QString
centralKey
=
buildMenuKey
(
SUB_SECTION_CHECKED
,
CENTRAL_MAP
,
VIEW_OPERATOR
);
if
(
!
settings
.
contains
(
centralKey
))
{
settings
.
setValue
(
centralKey
,
true
);
}
// ENGINEER VIEW DEFAULT
centralKey
=
buildMenuKey
(
SUB_SECTION_CHECKED
,
CENTRAL_LINECHART
,
VIEW_ENGINEER
);
if
(
!
settings
.
contains
(
centralKey
))
{
settings
.
setValue
(
centralKey
,
true
);
}
// MAVLINK VIEW DEFAULT
centralKey
=
buildMenuKey
(
SUB_SECTION_CHECKED
,
CENTRAL_PROTOCOL
,
VIEW_MAVLINK
);
if
(
!
settings
.
contains
(
centralKey
))
{
settings
.
setValue
(
centralKey
,
true
);
}
// PILOT VIEW DEFAULT
centralKey
=
buildMenuKey
(
SUB_SECTION_CHECKED
,
CENTRAL_HUD
,
VIEW_PILOT
);
if
(
!
settings
.
contains
(
centralKey
))
{
settings
.
setValue
(
centralKey
,
true
);
...
...
@@ -88,6 +128,24 @@ MainWindow::MainWindow(QWidget *parent):
// Setup user interface
ui
.
setupUi
(
this
);
// Bind together the perspective actions
QActionGroup
*
perspectives
=
new
QActionGroup
(
ui
.
menuPerspectives
);
perspectives
->
addAction
(
ui
.
actionEngineersView
);
perspectives
->
addAction
(
ui
.
actionMavlinkView
);
perspectives
->
addAction
(
ui
.
actionPilotsView
);
perspectives
->
addAction
(
ui
.
actionOperatorsView
);
perspectives
->
setExclusive
(
true
);
// Mark the right one as selected
if
(
currentView
==
VIEW_ENGINEER
)
ui
.
actionEngineersView
->
setChecked
(
true
);
if
(
currentView
==
VIEW_MAVLINK
)
ui
.
actionMavlinkView
->
setChecked
(
true
);
if
(
currentView
==
VIEW_PILOT
)
ui
.
actionPilotsView
->
setChecked
(
true
);
if
(
currentView
==
VIEW_OPERATOR
)
ui
.
actionOperatorsView
->
setChecked
(
true
);
// The pilot view is not available on startup
ui
.
actionPilotsView
->
setEnabled
(
false
);
buildCommonWidgets
();
connectCommonWidgets
();
...
...
@@ -104,7 +162,13 @@ MainWindow::MainWindow(QWidget *parent):
qApp
->
setStyle
(
"plastique"
);
// Set style sheet as last step
reloadStylesheet
();
QFile
*
styleSheet
=
new
QFile
(
":/images/style-mission.css"
);
if
(
styleSheet
->
open
(
QIODevice
::
ReadOnly
|
QIODevice
::
Text
))
{
QString
style
=
QString
(
styleSheet
->
readAll
());
style
.
replace
(
"ICONDIR"
,
QCoreApplication
::
applicationDirPath
()
+
"/images/"
);
qApp
->
setStyleSheet
(
style
);
}
// Create actions
connectCommonActions
();
...
...
@@ -122,10 +186,11 @@ MainWindow::MainWindow(QWidget *parent):
statusBar
()
->
setSizeGripEnabled
(
true
);
if
(
settings
.
contains
(
"geometry"
))
// Restore the window position and size
if
(
settings
.
contains
(
getWindowGeometryKey
()))
{
// Restore the window geometry
restoreGeometry
(
settings
.
value
(
"
geometry
"
).
toByteArray
());
restoreGeometry
(
settings
.
value
(
ge
tWindowGe
ometry
Key
()
).
toByteArray
());
}
else
{
...
...
@@ -149,6 +214,16 @@ MainWindow::~MainWindow()
}
QString
MainWindow
::
getWindowStateKey
()
{
return
QString
::
number
(
currentView
)
+
"/windowstate"
;
}
QString
MainWindow
::
getWindowGeometryKey
()
{
return
QString
::
number
(
currentView
)
+
"/geometry"
;
}
void
MainWindow
::
buildCommonWidgets
()
{
//TODO: move protocol outside UI
...
...
@@ -580,15 +655,6 @@ void MainWindow::showTheWidget (TOOLS_WIDGET_NAMES widget, VIEW_SECTIONS view)
tempVisible
=
settings
.
value
(
buildMenuKey
(
SUB_SECTION_CHECKED
,
widget
,
view
),
false
).
toBool
();
// Some widgets are per default visible. Overwrite the settings value if not present.
if
(
widget
==
MainWindow
::
MENU_UAS_LIST
)
{
if
(
!
settings
.
contains
(
buildMenuKey
(
SUB_SECTION_CHECKED
,
widget
,
view
)))
{
tempVisible
=
true
;
}
}
if
(
tempWidget
)
{
toolsMenuActions
[
widget
]
->
setChecked
(
tempVisible
);
...
...
@@ -633,10 +699,15 @@ QString MainWindow::buildMenuKey(SETTINGS_SECTIONS section, TOOLS_WIDGET_NAMES t
void
MainWindow
::
closeEvent
(
QCloseEvent
*
event
)
{
settings
.
setValue
(
"
geometry
"
,
saveGeometry
());
settings
.
setValue
(
ge
tWindowGe
ometry
Key
()
,
saveGeometry
());
//settings.setValue("windowState", saveState());
aboutToCloseFlag
=
true
;
settings
.
setValue
(
"VIEW_ON_APPLICATION_CLOSE"
,
currentView
);
// Save the last current view in any case
settings
.
setValue
(
"CURRENT_VIEW"
,
currentView
);
// Save the current window state, but only if a system is connected (else no real number of widgets would be present)
if
(
UASManager
::
instance
()
->
getActiveUAS
())
settings
.
setValue
(
getWindowStateKey
(),
saveState
(
QGC
::
applicationVersion
()));
// Save the current view only if a UAS is connected
if
(
UASManager
::
instance
()
->
getUASList
().
length
()
>
0
)
settings
.
setValue
(
"CURRENT_VIEW_WITH_UAS_CONNECTED"
,
currentView
);
settings
.
sync
();
QMainWindow
::
closeEvent
(
event
);
}
...
...
@@ -864,8 +935,25 @@ void MainWindow::saveScreen()
*/
void
MainWindow
::
reloadStylesheet
()
{
QString
fileName
=
QCoreApplication
::
applicationDirPath
()
+
"/style-indoor.css"
;
// Let user select style sheet
fileName
=
QFileDialog
::
getOpenFileName
(
this
,
tr
(
"Specify stylesheet"
),
fileName
,
tr
(
"CSS Stylesheet (*.css);;"
));
if
(
!
fileName
.
endsWith
(
".css"
))
{
QMessageBox
msgBox
;
msgBox
.
setIcon
(
QMessageBox
::
Information
);
msgBox
.
setText
(
tr
(
"QGroundControl did lot load a new style"
));
msgBox
.
setInformativeText
(
tr
(
"No suitable .css file selected. Please select a valid .css file."
));
msgBox
.
setStandardButtons
(
QMessageBox
::
Ok
);
msgBox
.
setDefaultButton
(
QMessageBox
::
Ok
);
msgBox
.
exec
();
return
;
}
// Load style sheet
QFile
*
styleSheet
=
new
QFile
(
QCoreApplication
::
applicationDirPath
()
+
"/qgroundcontrol.css"
);
QFile
*
styleSheet
=
new
QFile
(
fileName
);
if
(
!
styleSheet
->
exists
())
{
styleSheet
=
new
QFile
(
":/images/style-mission.css"
);
...
...
@@ -878,7 +966,13 @@ void MainWindow::reloadStylesheet()
}
else
{
qDebug
()
<<
"Style not set:"
<<
styleSheet
->
fileName
()
<<
"opened: "
<<
styleSheet
->
isOpen
();
QMessageBox
msgBox
;
msgBox
.
setIcon
(
QMessageBox
::
Information
);
msgBox
.
setText
(
tr
(
"QGroundControl did lot load a new style"
));
msgBox
.
setInformativeText
(
tr
(
"Stylesheet file %1 was not readable"
).
arg
(
fileName
));
msgBox
.
setStandardButtons
(
QMessageBox
::
Ok
);
msgBox
.
setDefaultButton
(
QMessageBox
::
Ok
);
msgBox
.
exec
();
}
delete
styleSheet
;
}
...
...
@@ -956,9 +1050,9 @@ void MainWindow::connectCommonActions()
connect
(
ui
.
actionReloadStyle
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
reloadStylesheet
()));
// Help Actions
connect
(
ui
.
actionOnline_
d
ocumentation
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
showHelp
()));
connect
(
ui
.
actionOnline_
D
ocumentation
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
showHelp
()));
connect
(
ui
.
actionDeveloper_Credits
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
showCredits
()));
connect
(
ui
.
actionProject_Roadmap
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
showRoadMap
()));
connect
(
ui
.
actionProject_Roadmap
_2
,
SIGNAL
(
triggered
()),
this
,
SLOT
(
showRoadMap
()));
}
void
MainWindow
::
connectPxActions
()
...
...
@@ -977,7 +1071,7 @@ void MainWindow::connectSlugsActions()
void
MainWindow
::
showHelp
()
{
if
(
!
QDesktopServices
::
openUrl
(
QUrl
(
"http://qgroundcontrol.org/user
_guide
"
)))
if
(
!
QDesktopServices
::
openUrl
(
QUrl
(
"http://qgroundcontrol.org/user
s/
"
)))
{
QMessageBox
msgBox
;
msgBox
.
setIcon
(
QMessageBox
::
Critical
);
...
...
@@ -991,7 +1085,7 @@ void MainWindow::showHelp()
void
MainWindow
::
showCredits
()
{
if
(
!
QDesktopServices
::
openUrl
(
QUrl
(
"http://qgroundcontrol.org/credits"
)))
if
(
!
QDesktopServices
::
openUrl
(
QUrl
(
"http://qgroundcontrol.org/credits
/
"
)))
{
QMessageBox
msgBox
;
msgBox
.
setIcon
(
QMessageBox
::
Critical
);
...
...
@@ -1005,7 +1099,7 @@ void MainWindow::showCredits()
void
MainWindow
::
showRoadMap
()
{
if
(
!
QDesktopServices
::
openUrl
(
QUrl
(
"http://qgroundcontrol.org/roadmap"
)))
if
(
!
QDesktopServices
::
openUrl
(
QUrl
(
"http://qgroundcontrol.org/roadmap
/
"
)))
{
QMessageBox
msgBox
;
msgBox
.
setIcon
(
QMessageBox
::
Critical
);
...
...
@@ -1053,10 +1147,14 @@ void MainWindow::addLink(LinkInterface *link)
void
MainWindow
::
UASCreated
(
UASInterface
*
uas
)
{
// Connect the UAS to the full user interface
if
(
uas
!=
NULL
)
{
// The pilot view was not available on startup, enable it now
ui
.
actionPilotsView
->
setEnabled
(
true
);
QIcon
icon
;
// Set matching icon
switch
(
uas
->
getSystemType
())
...
...
@@ -1117,13 +1215,6 @@ void MainWindow::UASCreated(UASInterface* uas)
}
}
// Camera view
//camera->addUAS(uas);
// Revalidate UI
// TODO Stylesheet reloading should in theory not be necessary
reloadStylesheet
();
switch
(
uas
->
getAutopilotType
())
{
case
(
MAV_AUTOPILOT_SLUGS
):
...
...
@@ -1185,11 +1276,18 @@ void MainWindow::UASCreated(UASInterface* uas)
qDebug
()
<<
"UPDATING THE VIEW SINCE THIS IS THE FIRST CONNECTED SYSTEM"
;
// Load last view if setting is present
if
(
settings
.
contains
(
"
VIEW_ON_APPLICATION_CLOSE
"
))
if
(
settings
.
contains
(
"
CURRENT_VIEW_WITH_UAS_CONNECTED
"
))
{
int
view
=
settings
.
value
(
"
VIEW_ON_APPLICATION_CLOSE
"
).
toInt
();
int
view
=
settings
.
value
(
"
CURRENT_VIEW_WITH_UAS_CONNECTED
"
).
toInt
();
currentView
=
(
VIEW_SECTIONS
)
view
;
presentView
();
// Restore the widget positions and size
if
(
settings
.
contains
(
getWindowStateKey
()))
{
restoreState
(
settings
.
value
(
getWindowStateKey
()).
toByteArray
(),
QGC
::
applicationVersion
());
}
}
else
{
...
...
@@ -1205,6 +1303,11 @@ void MainWindow::UASCreated(UASInterface* uas)
*/
void
MainWindow
::
clearView
()
{
// Save current state
if
(
UASManager
::
instance
()
->
getActiveUAS
())
settings
.
setValue
(
getWindowStateKey
(),
saveState
(
QGC
::
applicationVersion
()));
settings
.
setValue
(
getWindowGeometryKey
(),
saveGeometry
());
settings
.
sync
();
// Remove all dock widgets from main window
QObjectList
childList
(
this
->
children
()
);
...
...
@@ -1227,51 +1330,61 @@ void MainWindow::clearView()
void
MainWindow
::
loadEngineerView
()
{
clearView
();
if
(
currentView
!=
VIEW_ENGINEER
)
{
clearView
();
currentView
=
VIEW_ENGINEER
;
currentView
=
VIEW_ENGINEER
;
presentView
();
presentView
();
}
}
void
MainWindow
::
loadOperatorView
()
{
clearView
();
if
(
currentView
!=
VIEW_OPERATOR
)
{
clearView
();
currentView
=
VIEW_OPERATOR
;
currentView
=
VIEW_OPERATOR
;
presentView
();
presentView
();
}
}
void
MainWindow
::
loadPilotView
()
{
clearView
();
if
(
currentView
!=
VIEW_PILOT
)
{
clearView
();
currentView
=
VIEW_PILOT
;
currentView
=
VIEW_PILOT
;
presentView
();
presentView
();
}
}
void
MainWindow
::
loadMAVLinkView
()
{
clearView
();
if
(
currentView
!=
VIEW_MAVLINK
)
{
clearView
();
currentView
=
VIEW_MAVLINK
;
currentView
=
VIEW_MAVLINK
;
presentView
();
presentView
();
}
}
void
MainWindow
::
presentView
()
{
qDebug
()
<<
"LC"
;
// LINE CHART
showTheCentralWidget
(
CENTRAL_LINECHART
,
currentView
);
// MAP
qDebug
()
<<
"MAP"
;
showTheCentralWidget
(
CENTRAL_MAP
,
currentView
);
// PROTOCOL
qDebug
()
<<
"CP"
;
showTheCentralWidget
(
CENTRAL_PROTOCOL
,
currentView
);
// HEAD UP DISPLAY
...
...
@@ -1286,6 +1399,9 @@ void MainWindow::presentView()
// GLOBAL 3D VIEW
showTheCentralWidget
(
CENTRAL_3D_MAP
,
currentView
);
// DATA PLOT
showTheCentralWidget
(
CENTRAL_DATA_PLOT
,
currentView
);
// Show docked widgets based on current view and autopilot type
...
...
@@ -1319,12 +1435,16 @@ void MainWindow::presentView()
if
(
headUpDockWidget
)
{
HUD
*
tmpHud
=
dynamic_cast
<
HUD
*>
(
headUpDockWidget
->
widget
()
);
if
(
tmpHud
){
if
(
settings
.
value
(
buildMenuKey
(
SUB_SECTION_CHECKED
,
MENU_HUD
,
currentView
)).
toBool
()){
if
(
tmpHud
)
{
if
(
settings
.
value
(
buildMenuKey
(
SUB_SECTION_CHECKED
,
MENU_HUD
,
currentView
)).
toBool
())
{
addDockWidget
(
static_cast
<
Qt
::
DockWidgetArea
>
(
settings
.
value
(
buildMenuKey
(
SUB_SECTION_LOCATION
,
MENU_HUD
,
currentView
)).
toInt
()),
hsiDockWidget
);
headUpDockWidget
->
show
();
}
else
{
}
else
{
headUpDockWidget
->
hide
();
}
}
...
...
@@ -1348,52 +1468,12 @@ void MainWindow::presentView()
// HORIZONTAL SITUATION INDICATOR
showTheWidget
(
MENU_HSI
,
currentView
);
// if (hsiDockWidget)
// {
// HSIDisplay* hsi = dynamic_cast<HSIDisplay*>( hsiDockWidget->widget() );
// if (hsi){
// if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HSI,currentView)).toBool()){
// addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HSI, currentView)).toInt()),
// hsiDockWidget);
// }
// }
// }
// HEAD DOWN 1
showTheWidget
(
MENU_HDD_1
,
currentView
);
// if (headDown1DockWidget)
// {
// HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown1DockWidget->widget());
// if (hdd) {
// if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_1,currentView)).toBool()) {
// addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_1, currentView)).toInt()),
// headDown1DockWidget);
// headDown1DockWidget->show();
// hdd->start();
// } else {
// headDown1DockWidget->hide();;
// hdd->stop();
// }
// }
// }
// HEAD DOWN 2
showTheWidget
(
MENU_HDD_2
,
currentView
);
// if (headDown2DockWidget)
// {
// HDDisplay *hdd = dynamic_cast<HDDisplay*>(headDown2DockWidget->widget());
// if (hdd){
// if (settings.value(buildMenuKey (SUB_SECTION_CHECKED,MENU_HDD_2,currentView)).toBool()){
// addDockWidget(static_cast <Qt::DockWidgetArea>(settings.value(buildMenuKey (SUB_SECTION_LOCATION,MENU_HDD_2, currentView)).toInt()),
// headDown2DockWidget);
// headDown2DockWidget->show();
// hdd->start();
// } else {
// headDown2DockWidget->hide();
// hdd->stop();
// }
// }
// }
this
->
show
();
...
...
@@ -1404,7 +1484,7 @@ void MainWindow::showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SE
bool
tempVisible
;
QWidget
*
tempWidget
=
dockWidgets
[
centralWidget
];
tempVisible
=
settings
.
value
(
buildMenuKey
(
SUB_SECTION_CHECKED
,
centralWidget
,
view
)).
toBool
();
tempVisible
=
settings
.
value
(
buildMenuKey
(
SUB_SECTION_CHECKED
,
centralWidget
,
view
)
,
false
).
toBool
();
qDebug
()
<<
buildMenuKey
(
SUB_SECTION_CHECKED
,
centralWidget
,
view
)
<<
tempVisible
;
if
(
toolsMenuActions
[
centralWidget
])
{
...
...
@@ -1417,78 +1497,27 @@ void MainWindow::showTheCentralWidget (TOOLS_WIDGET_NAMES centralWidget, VIEW_SE
}
}
void
MainWindow
::
loadWidgets
()
{
loadOperatorView
();
//loadMAVLinkView();
//loadPilotView();
}
void
MainWindow
::
loadDataView
(
QString
fileName
)
{
// DATAPLOT
if
(
dataplotWidget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
{
centerStack
->
setCurrentWidget
(
dataplotWidget
);
dataplotWidget
->
loadFile
(
fileName
);
}
}
}
void
MainWindow
::
load3DMapView
()
{
#ifdef QGC_OSGEARTH_ENABLED
clearView
();
// Set data plot in settings as current widget and then run usual update procedure
QString
chKey
=
buildMenuKey
(
SUB_SECTION_CHECKED
,
static_cast
<
TOOLS_WIDGET_NAMES
>
(
CENTRAL_DATA_PLOT
),
currentView
);
settings
.
setValue
(
chKey
,
true
);
// 3D map
if
(
_3DMapWidget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
{
//map3DWidget->setActive(true);
centerStack
->
setCurrentWidget
(
_3DMapWidget
);
}
}
#endif
}
void
MainWindow
::
loadGoogleEarthView
()
{
#if (defined _MSC_VER) | (defined Q_OS_MAC)
clearView
();
presentView
();
//
3D map
if
(
gEarth
Widget
)
//
Plot is now selected, now load data from file
if
(
dataplot
Widget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
{
centerStack
->
setCurrentWidget
(
gEarthWidget
);
}
dataplotWidget
->
loadFile
(
fileName
);
}
#endif
// QStackedWidget *centerStack = dynamic_cast<QStackedWidget*>(centralWidget());
// if (centerStack)
// {
// centerStack->setCurrentWidget(dataplotWidget);
// dataplotWidget->loadFile(fileName);
// }
// }
}
void
MainWindow
::
load3DView
()
{
#ifdef QGC_OSG_ENABLED
clearView
();
// 3D map
if
(
_3DWidget
)
{
QStackedWidget
*
centerStack
=
dynamic_cast
<
QStackedWidget
*>
(
centralWidget
());
if
(
centerStack
)
{
//map3DWidget->setActive(true);
centerStack
->
setCurrentWidget
(
_3DWidget
);
}
}
#endif
}
src/ui/MainWindow.h
View file @
9a11483b
...
...
@@ -142,19 +142,19 @@ public slots:
==========================================================
*/
void
loadWidgets
();
//
void loadWidgets();
/** @brief Load data view, allowing to plot flight data */
void
loadDataView
(
QString
fileName
);
/** @brief Load 3D map view */
void
load3DMapView
();
//
/** @brief Load 3D map view */
//
void load3DMapView();
/** @brief Load 3D Google Earth view */
void
loadGoogleEarthView
();
//
/** @brief Load 3D Google Earth view */
//
void loadGoogleEarthView();
/** @brief Load 3D view */
void
load3DView
();
//
/** @brief Load 3D view */
//
void load3DView();
/**
* @brief Shows a Docked Widget based on the action sender
...
...
@@ -393,6 +393,8 @@ private:
Ui
::
MainWindow
ui
;
QString
buildMenuKey
(
SETTINGS_SECTIONS
section
,
TOOLS_WIDGET_NAMES
tool
,
VIEW_SECTIONS
view
);
QString
getWindowStateKey
();
QString
getWindowGeometryKey
();
};
...
...
src/ui/MainWindow.ui
View file @
9a11483b
...
...
@@ -38,7 +38,7 @@
<x>
0
</x>
<y>
0
</y>
<width>
1000
</width>
<height>
2
5
</height>
<height>
2
2
</height>
</rect>
</property>
<widget
class=
"QMenu"
name=
"menuMGround"
>
...
...
@@ -50,6 +50,7 @@
<addaction
name=
"actionMuteAudioOutput"
/>
<addaction
name=
"actionSimulate"
/>
<addaction
name=
"separator"
/>
<addaction
name=
"actionReloadStyle"
/>
<addaction
name=
"actionExit"
/>
</widget>
<widget
class=
"QMenu"
name=
"menuNetwork"
>
...
...
@@ -100,7 +101,6 @@
<addaction
name=
"actionPilotsView"
/>
<addaction
name=
"separator"
/>
<addaction
name=
"actionMavlinkView"
/>
<addaction
name=
"actionReloadStyle"
/>
</widget>
<addaction
name=
"menuMGround"
/>
<addaction
name=
"menuNetwork"
/>
...
...
@@ -179,33 +179,6 @@
<string>
Open UAS Preferences
</string>
</property>
</action>
<action
name=
"actionEngineerView"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/apps/utilities-system-monitor.svg
</normaloff>
:/images/apps/utilities-system-monitor.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Show engineer view
</string>
</property>
</action>
<action
name=
"actionPilotView"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/status/weather-overcast.svg
</normaloff>
:/images/status/weather-overcast.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Show pilot view
</string>
</property>
</action>
<action
name=
"actionStyleConfig"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/categories/applications-internet.svg
</normaloff>
:/images/categories/applications-internet.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Reload visual style
</string>
</property>
</action>
<action
name=
"actionJoystickSettings"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
...
...
@@ -218,30 +191,6 @@
<bool>
true
</bool>
</property>
</action>
<action
name=
"actionOperatorView"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/status/network-wireless-encrypted.svg
</normaloff>
:/images/status/network-wireless-encrypted.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Show operator view
</string>
</property>
<property
name=
"toolTip"
>
<string>
Shop the 2D map and system status
</string>
</property>
</action>
<action
name=
"action3DView"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/categories/preferences-system.svg
</normaloff>
:/images/categories/preferences-system.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Show 3D Local View
</string>
</property>
<property
name=
"toolTip"
>
<string>
Show 3D view
</string>
</property>
</action>
<action
name=
"actionSimulate"
>
<property
name=
"checkable"
>
<bool>
true
</bool>
...
...
@@ -257,87 +206,6 @@
<string>
Simulate one vehicle to test and evaluate this application
</string>
</property>
</action>
<action
name=
"actionShow_full_view"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/status/network-transmit-receive.svg
</normaloff>
:/images/status/network-transmit-receive.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Show full view
</string>
</property>
</action>
<action
name=
"actionShow_MAVLink_view"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/devices/network-wired.svg
</normaloff>
:/images/devices/network-wired.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Show MAVLink view
</string>
</property>
</action>
<action
name=
"actionOnline_documentation"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/categories/applications-internet.svg
</normaloff>
:/images/categories/applications-internet.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Online documentation
</string>
</property>
</action>
<action
name=
"actionShow_data_analysis_view"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/apps/utilities-system-monitor.svg
</normaloff>
:/images/apps/utilities-system-monitor.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Show data analysis view
</string>
</property>
</action>
<action
name=
"actionProject_Roadmap"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/status/software-update-available.svg
</normaloff>
:/images/status/software-update-available.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Project Roadmap
</string>
</property>
</action>
<action
name=
"actionCredits_Developers"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/categories/preferences-system.svg
</normaloff>
:/images/categories/preferences-system.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Credits / Developers
</string>
</property>
</action>
<action
name=
"actionGlobalOperatorView"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/categories/applications-internet.svg
</normaloff>
:/images/categories/applications-internet.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Show 2D Map View
</string>
</property>
</action>
<action
name=
"action3DMapView"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/categories/applications-internet.svg
</normaloff>
:/images/categories/applications-internet.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Show 3D Global View
</string>
</property>
</action>
<action
name=
"actionGoogleEarthView"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/mapproviders/googleearth.svg
</normaloff>
:/images/mapproviders/googleearth.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Google Earth View
</string>
</property>
</action>
<action
name=
"actionShow_Slugs_View"
>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
...
...
@@ -387,6 +255,9 @@
</property>
</action>
<action
name=
"actionOperatorsView"
>
<property
name=
"checkable"
>
<bool>
true
</bool>
</property>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/status/weather-overcast.svg
</normaloff>
:/images/status/weather-overcast.svg
</iconset>
...
...
@@ -396,6 +267,9 @@
</property>
</action>
<action
name=
"actionEngineersView"
>
<property
name=
"checkable"
>
<bool>
true
</bool>
</property>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/apps/utilities-system-monitor.svg
</normaloff>
:/images/apps/utilities-system-monitor.svg
</iconset>
...
...
@@ -405,6 +279,9 @@
</property>
</action>
<action
name=
"actionMavlinkView"
>
<property
name=
"checkable"
>
<bool>
true
</bool>
</property>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/devices/network-wired.svg
</normaloff>
:/images/devices/network-wired.svg
</iconset>
...
...
@@ -419,10 +296,13 @@
<normaloff>
:/images/categories/applications-internet.svg
</normaloff>
:/images/categories/applications-internet.svg
</iconset>
</property>
<property
name=
"text"
>
<string>
Reload Style
</string>
<string>
Reload Style
sheet
</string>
</property>
</action>
<action
name=
"actionPilotsView"
>
<property
name=
"checkable"
>
<bool>
true
</bool>
</property>
<property
name=
"icon"
>
<iconset
resource=
"../../mavground.qrc"
>
<normaloff>
:/images/status/network-wireless-encrypted.svg
</normaloff>
:/images/status/network-wireless-encrypted.svg
</iconset>
...
...
src/ui/QGCRemoteControlView.cc
View file @
9a11483b
...
...
@@ -197,7 +197,7 @@ void QGCRemoteControlView::redraw()
// Update raw values
for
(
int
i
=
0
;
i
<
rawLabels
.
count
();
i
++
)
{
rawLabels
.
at
(
i
)
->
setText
(
QString
(
"%1 us"
).
arg
(
raw
.
at
(
i
),
4
));
rawLabels
.
at
(
i
)
->
setText
(
QString
(
"%1 us"
).
arg
(
raw
.
at
(
i
),
4
,
10
,
QChar
(
'0'
)
));
}
// Update percent bars
...
...
src/ui/linechart/LinechartWidget.cc
View file @
9a11483b
...
...
@@ -266,14 +266,17 @@ void LinechartWidget::createLayout()
void
LinechartWidget
::
appendData
(
int
uasId
,
QString
curve
,
double
value
,
quint64
usec
)
{
// Order matters here, first append to plot, then update curve list
activePlot
->
appendData
(
curve
,
usec
,
value
);
// Store data
QLabel
*
label
=
curveLabels
->
value
(
curve
,
NULL
);
// Make sure the curve will be created if it does not yet exist
if
(
!
label
)
if
(
isVisible
())
{
addCurve
(
curve
);
// Order matters here, first append to plot, then update curve list
activePlot
->
appendData
(
curve
,
usec
,
value
);
// Store data
QLabel
*
label
=
curveLabels
->
value
(
curve
,
NULL
);
// Make sure the curve will be created if it does not yet exist
if
(
!
label
)
{
addCurve
(
curve
);
}
}
// Log data
...
...
@@ -305,7 +308,15 @@ void LinechartWidget::refresh()
QMap
<
QString
,
QLabel
*>::
iterator
i
;
for
(
i
=
curveLabels
->
begin
();
i
!=
curveLabels
->
end
();
++
i
)
{
str
.
sprintf
(
"%+.2f"
,
activePlot
->
getCurrentValue
(
i
.
key
()));
double
val
=
activePlot
->
getCurrentValue
(
i
.
key
());
if
(
val
>
9999
||
val
<
0.002
)
{
str
.
sprintf
(
"% 10e"
,
val
);
}
else
{
str
.
sprintf
(
"% 10f"
,
val
);
}
// Value
i
.
value
()
->
setText
(
str
);
}
...
...
@@ -313,7 +324,7 @@ void LinechartWidget::refresh()
QMap
<
QString
,
QLabel
*>::
iterator
j
;
for
(
j
=
curveMeans
->
begin
();
j
!=
curveMeans
->
end
();
++
j
)
{
str
.
sprintf
(
"%
+
.2
f
"
,
activePlot
->
getMean
(
j
.
key
()));
str
.
sprintf
(
"%
8
.2
e
"
,
activePlot
->
getMean
(
j
.
key
()));
j
.
value
()
->
setText
(
str
);
}
// QMap<QString, QLabel*>::iterator k;
...
...
@@ -327,7 +338,7 @@ void LinechartWidget::refresh()
for
(
l
=
curveVariances
->
begin
();
l
!=
curveVariances
->
end
();
++
l
)
{
// Variance
str
.
sprintf
(
"%
.2
e"
,
activePlot
->
getVariance
(
l
.
key
()));
str
.
sprintf
(
"%
8
e"
,
activePlot
->
getVariance
(
l
.
key
()));
l
.
value
()
->
setText
(
str
);
}
}
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new 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