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
297d2ac5
Commit
297d2ac5
authored
Jan 10, 2011
by
lm
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Cleaned up Unmanned systems list widget, reduced size requirements of the widget
parent
7d609bc3
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
98 additions
and
40 deletions
+98
-40
UAS.cc
src/uas/UAS.cc
+8
-8
DebugConsole.ui
src/ui/DebugConsole.ui
+39
-4
UASView.ui
src/ui/UASView.ui
+16
-13
UASListWidget.cc
src/ui/uas/UASListWidget.cc
+3
-1
UASView.cc
src/ui/uas/UASView.cc
+31
-14
UASView.h
src/ui/uas/UASView.h
+1
-0
No files found.
src/uas/UAS.cc
View file @
297d2ac5
...
...
@@ -956,27 +956,27 @@ void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDesc
{
case
MAV_STATE_UNINIT
:
uasState
=
tr
(
"UNINIT"
);
stateDescription
=
tr
(
"
Not initialized
"
);
stateDescription
=
tr
(
"
Waiting..
"
);
break
;
case
MAV_STATE_BOOT
:
uasState
=
tr
(
"BOOT"
);
stateDescription
=
tr
(
"Booting
system, please wait
.."
);
stateDescription
=
tr
(
"Booting.."
);
break
;
case
MAV_STATE_CALIBRATING
:
uasState
=
tr
(
"CALIBRATING"
);
stateDescription
=
tr
(
"Calibrating
sensors
.."
);
stateDescription
=
tr
(
"Calibrating.."
);
break
;
case
MAV_STATE_ACTIVE
:
uasState
=
tr
(
"ACTIVE"
);
stateDescription
=
tr
(
"Normal
operation mode
"
);
stateDescription
=
tr
(
"Normal"
);
break
;
case
MAV_STATE_STANDBY
:
uasState
=
tr
(
"STANDBY"
);
stateDescription
=
tr
(
"Standby,
operational
"
);
stateDescription
=
tr
(
"Standby,
OK
"
);
break
;
case
MAV_STATE_CRITICAL
:
uasState
=
tr
(
"CRITICAL"
);
stateDescription
=
tr
(
"F
ailure occured!
"
);
stateDescription
=
tr
(
"F
AILURE: Continue
"
);
break
;
case
MAV_STATE_EMERGENCY
:
uasState
=
tr
(
"EMERGENCY"
);
...
...
@@ -984,11 +984,11 @@ void UAS::getStatusForCode(int statusCode, QString& uasState, QString& stateDesc
break
;
case
MAV_STATE_POWEROFF
:
uasState
=
tr
(
"SHUTDOWN"
);
stateDescription
=
tr
(
"Powering off
system
"
);
stateDescription
=
tr
(
"Powering off"
);
break
;
default:
uasState
=
tr
(
"UNKNOWN"
);
stateDescription
=
tr
(
"
FAILURE: Unknown system
state"
);
stateDescription
=
tr
(
"
Unknown
state"
);
break
;
}
}
...
...
src/ui/DebugConsole.ui
View file @
297d2ac5
...
...
@@ -6,8 +6,8 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
4
47
</width>
<height>
1
81
</height>
<width>
4
69
</width>
<height>
1
90
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
...
...
@@ -24,7 +24,7 @@
<number>
6
</number>
</property>
<item
row=
"0"
column=
"0"
colspan=
"2"
>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_2"
stretch=
"10,0,0,0,0"
>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_2"
stretch=
"10,0,0,0,0
,0
"
>
<item>
<widget
class=
"QComboBox"
name=
"linkComboBox"
>
<property
name=
"maximumSize"
>
...
...
@@ -81,6 +81,19 @@
</property>
</widget>
</item>
<item>
<spacer
name=
"horizontalSpacer_2"
>
<property
name=
"orientation"
>
<enum>
Qt::Horizontal
</enum>
</property>
<property
name=
"sizeHint"
stdset=
"0"
>
<size>
<width>
40
</width>
<height>
20
</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item
row=
"1"
column=
"0"
colspan=
"2"
>
...
...
@@ -107,12 +120,18 @@
</widget>
</item>
<item
row=
"4"
column=
"1"
>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
stretch=
"
0,10,10,10,0
"
>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout"
stretch=
"
100,1,10,1,1,1
"
>
<property
name=
"spacing"
>
<number>
5
</number>
</property>
<item>
<widget
class=
"QComboBox"
name=
"specialComboBox"
>
<property
name=
"maximumSize"
>
<size>
<width>
100
</width>
<height>
16777215
</height>
</size>
</property>
<property
name=
"maxVisibleItems"
>
<number>
10
</number>
</property>
...
...
@@ -188,6 +207,22 @@
</property>
</widget>
</item>
<item>
<spacer
name=
"horizontalSpacer"
>
<property
name=
"orientation"
>
<enum>
Qt::Horizontal
</enum>
</property>
<property
name=
"sizeType"
>
<enum>
QSizePolicy::Expanding
</enum>
</property>
<property
name=
"sizeHint"
stdset=
"0"
>
<size>
<width>
5
</width>
<height>
20
</height>
</size>
</property>
</spacer>
</item>
<item>
<widget
class=
"QPushButton"
name=
"holdButton"
>
<property
name=
"text"
>
...
...
src/ui/UASView.ui
View file @
297d2ac5
...
...
@@ -6,8 +6,8 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
3
35
</width>
<height>
1
2
1
</height>
<width>
3
10
</width>
<height>
1
1
1
</height>
</rect>
</property>
<property
name=
"sizePolicy"
>
...
...
@@ -18,7 +18,7 @@
</property>
<property
name=
"minimumSize"
>
<size>
<width>
335
</width>
<width>
260
</width>
<height>
0
</height>
</size>
</property>
...
...
@@ -73,12 +73,12 @@ QLabel#timeRemainingLabel {
}
QLabel#waypointLabel {
font: 2
4
px;
font: 2
2
px;
}
QGroupBox {
border: 1px solid #4A4A4F;
border-radius:
5
px;
border-radius:
10
px;
padding: 0px 0px 0px 0px;
margin: 0px;
}
...
...
@@ -98,7 +98,7 @@ QGroupBox#heartbeatIcon {
QToolButton#typeButton {
font-weight: bold;
font-size: 12px;
border:
2
px solid #999999;
border:
0
px solid #999999;
border-radius: 5px;
min-width:44px;
max-width: 44px;
...
...
@@ -184,8 +184,11 @@ QProgressBar::chunk#thrustBar {
}
</string>
</property>
<layout
class=
"QHBoxLayout"
name=
"horizontalLayout_2"
>
<property
name=
"spacing"
>
<number>
2
</number>
</property>
<property
name=
"margin"
>
<number>
6
</number>
<number>
2
</number>
</property>
<item>
<widget
class=
"QGroupBox"
name=
"uasViewFrame"
>
...
...
@@ -206,26 +209,26 @@ QProgressBar::chunk#thrustBar {
</property>
<layout
class=
"QGridLayout"
name=
"gridLayout"
>
<property
name=
"horizontalSpacing"
>
<number>
6
</number>
<number>
4
</number>
</property>
<property
name=
"verticalSpacing"
>
<number>
2
</number>
</property>
<property
name=
"margin"
>
<number>
6
</number>
<number>
4
</number>
</property>
<item
row=
"0"
column=
"0"
rowspan=
"5"
colspan=
"2"
>
<widget
class=
"QToolButton"
name=
"typeButton"
>
<property
name=
"minimumSize"
>
<size>
<width>
4
8
</width>
<height>
4
8
</height>
<width>
4
4
</width>
<height>
4
4
</height>
</size>
</property>
<property
name=
"maximumSize"
>
<size>
<width>
4
8
</width>
<height>
4
8
</height>
<width>
4
4
</width>
<height>
4
4
</height>
</size>
</property>
<property
name=
"baseSize"
>
...
...
src/ui/uas/UASListWidget.cc
View file @
297d2ac5
...
...
@@ -50,6 +50,8 @@ UASListWidget::UASListWidget(QWidget *parent) : QWidget(parent), m_ui(new Ui::UA
m_ui
->
setupUi
(
this
);
listLayout
=
new
QVBoxLayout
(
this
);
listLayout
->
setMargin
(
0
);
listLayout
->
setSpacing
(
3
);
listLayout
->
setAlignment
(
Qt
::
AlignTop
);
this
->
setLayout
(
listLayout
);
setObjectName
(
"UNMANNED_SYSTEMS_LIST"
);
...
...
@@ -58,7 +60,7 @@ UASListWidget::UASListWidget(QWidget *parent) : QWidget(parent), m_ui(new Ui::UA
uWidget
=
new
QGCUnconnectedInfoWidget
(
this
);
listLayout
->
addWidget
(
uWidget
);
this
->
setMinimumWidth
(
2
50
);
this
->
setMinimumWidth
(
2
62
);
uasViews
=
QMap
<
UASInterface
*
,
UASView
*>
();
...
...
src/ui/uas/UASView.cc
View file @
297d2ac5
...
...
@@ -59,6 +59,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
lon
(
0
),
alt
(
0
),
groundDistance
(
0
),
localFrame
(
false
),
m_ui
(
new
Ui
::
UASView
)
{
m_ui
->
setupUi
(
this
);
...
...
@@ -109,6 +110,19 @@ UASView::UASView(UASInterface* uas, QWidget *parent) :
// Heartbeat fade
refreshTimer
=
new
QTimer
(
this
);
connect
(
refreshTimer
,
SIGNAL
(
timeout
()),
this
,
SLOT
(
refresh
()));
// Hide kill and shutdown buttons per default
m_ui
->
killButton
->
hide
();
m_ui
->
shutdownButton
->
hide
();
if
(
localFrame
)
{
m_ui
->
gpsLabel
->
hide
();
}
else
{
m_ui
->
positionLabel
->
hide
();
}
}
UASView
::~
UASView
()
...
...
@@ -135,7 +149,7 @@ void UASView::setBackgroundColor()
{
uasColor
=
uasColor
.
darker
(
675
);
}
colorstyle
=
colorstyle
.
sprintf
(
"QGroupBox { border-radius:
5
px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X; border: 2px solid %s; }"
,
colorstyle
=
colorstyle
.
sprintf
(
"QGroupBox { border-radius:
12
px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X; border: 2px solid %s; }"
,
uasColor
.
red
(),
uasColor
.
green
(),
uasColor
.
blue
(),
borderColor
.
toStdString
().
c_str
());
m_ui
->
uasViewFrame
->
setStyleSheet
(
colorstyle
);
}
...
...
@@ -286,11 +300,15 @@ void UASView::setSystemType(UASInterface* uas, unsigned int systemType)
void
UASView
::
updateLocalPosition
(
UASInterface
*
uas
,
double
x
,
double
y
,
double
z
,
quint64
usec
)
{
Q_UNUSED
(
usec
);
if
(
uas
==
this
->
uas
)
Q_UNUSED
(
uas
);
this
->
x
=
x
;
this
->
y
=
y
;
this
->
z
=
z
;
if
(
!
localFrame
)
{
this
->
x
=
x
;
this
->
y
=
y
;
this
->
z
=
z
;
localFrame
=
true
;
m_ui
->
gpsLabel
->
hide
()
;
m_ui
->
positionLabel
->
show
()
;
}
}
...
...
@@ -404,7 +422,7 @@ void UASView::refresh()
// Position
QString
position
;
position
=
position
.
sprintf
(
"%0
2.2f %02.2f %02.2
f m"
,
x
,
y
,
z
);
position
=
position
.
sprintf
(
"%0
5.1f %05.1f %05.1
f m"
,
x
,
y
,
z
);
m_ui
->
positionLabel
->
setText
(
position
);
QString
globalPosition
;
QString
latIndicator
;
...
...
@@ -425,23 +443,22 @@ void UASView::refresh()
{
lonIndicator
=
"W"
;
}
globalPosition
=
globalPosition
.
sprintf
(
"%0
2.2f%s %02.2f%s %02.2
f m"
,
lon
,
lonIndicator
.
toStdString
().
c_str
(),
lat
,
latIndicator
.
toStdString
().
c_str
(),
alt
);
globalPosition
=
globalPosition
.
sprintf
(
"%0
5.1f%s %05.1f%s %05.1
f m"
,
lon
,
lonIndicator
.
toStdString
().
c_str
(),
lat
,
latIndicator
.
toStdString
().
c_str
(),
alt
);
m_ui
->
gpsLabel
->
setText
(
globalPosition
);
// Altitude
if
(
groundDistance
==
0
&&
alt
!=
0
)
{
m_ui
->
groundDistanceLabel
->
setText
(
QString
(
"%1 m"
).
arg
(
alt
));
m_ui
->
groundDistanceLabel
->
setText
(
QString
(
"%1 m"
).
arg
(
alt
,
5
,
'f'
,
1
,
'0'
));
}
else
{
m_ui
->
groundDistanceLabel
->
setText
(
QString
(
"%1 m"
).
arg
(
groundDistance
));
m_ui
->
groundDistanceLabel
->
setText
(
QString
(
"%1 m"
).
arg
(
groundDistance
,
5
,
'f'
,
1
,
'0'
));
}
// Speed
QString
speed
;
speed
=
speed
.
sprintf
(
"%02.2f m/s"
,
totalSpeed
);
m_ui
->
speedLabel
->
setText
(
speed
);
QString
speed
(
"%1 m/s"
);
m_ui
->
speedLabel
->
setText
(
speed
.
arg
(
totalSpeed
,
4
,
'f'
,
1
,
'0'
));
// Thrust
m_ui
->
thrustBar
->
setValue
(
thrust
*
100
);
...
...
@@ -461,7 +478,7 @@ void UASView::refresh()
}
else
{
m_ui
->
timeRemainingLabel
->
setText
(
tr
(
"Calc
ulating
"
));
m_ui
->
timeRemainingLabel
->
setText
(
tr
(
"Calc
..
"
));
}
// Time Elapsed
...
...
@@ -482,7 +499,7 @@ void UASView::refresh()
heartbeatColor
=
heartbeatColor
.
darker
(
150
);
QString
colorstyle
;
colorstyle
=
colorstyle
.
sprintf
(
"QGroupBox { border: 1px solid #EEEEEE; border-radius:
4
px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X;}"
,
colorstyle
=
colorstyle
.
sprintf
(
"QGroupBox { border: 1px solid #EEEEEE; border-radius:
8
px; padding: 0px; margin: 0px; background-color: #%02X%02X%02X;}"
,
heartbeatColor
.
red
(),
heartbeatColor
.
green
(),
heartbeatColor
.
blue
());
m_ui
->
heartbeatIcon
->
setStyleSheet
(
colorstyle
);
m_ui
->
heartbeatIcon
->
setAutoFillBackground
(
true
);
...
...
src/ui/uas/UASView.h
View file @
297d2ac5
...
...
@@ -99,6 +99,7 @@ protected:
float
lon
;
float
alt
;
float
groundDistance
;
bool
localFrame
;
static
const
int
updateInterval
=
300
;
...
...
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