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
124997d0
Commit
124997d0
authored
Apr 04, 2010
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Minor UI improvements, pushed implementation of some UI elements
parent
dfae554b
Changes
7
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
40 additions
and
134 deletions
+40
-134
style-mission.css
images/style-mission.css
+8
-31
MAVLinkSimulationLink.cc
src/comm/MAVLinkSimulationLink.cc
+5
-1
UAS.cc
src/uas/UAS.cc
+0
-86
HUD.cc
src/ui/HUD.cc
+1
-1
UASControl.ui
src/ui/UASControl.ui
+8
-2
UASControlWidget.cc
src/ui/uas/UASControlWidget.cc
+15
-13
UASControlWidget.h
src/ui/uas/UASControlWidget.h
+3
-0
No files found.
images/style-mission.css
View file @
124997d0
...
...
@@ -88,7 +88,8 @@ QDockWidget::close-button, QDockWidget::float-button {
QDockWidget
::title
{
text-align
:
left
;
background
:
#222224
;
background
:
#121214
;
color
:
#4A4A4F
;
padding-left
:
5px
;
height
:
10px
;
border-bottom
:
1px
solid
#555555
;
...
...
@@ -194,24 +195,24 @@ QPushButton:checked#controlButton {
}
QProgressBar
{
border
:
1px
solid
#
EEEEEE
;
border
:
1px
solid
#
4A4A4F
;
border-radius
:
4px
;
text-align
:
center
;
padding
:
2px
;
color
:
white
;
color
:
#DDDDDF
;
background-color
:
#111118
;
}
QProgressBar
:horizontal
{
height
12
px;
height
:
9
px
;
}
QProgressBar
:vertical
{
width
12
px;
width
:
9
px
;
}
QProgressBar
::chunk
{
background-color
:
#
656565
;
background-color
:
#
3C7B9E
;
}
QProgressBar
::chunk
#batteryBar
{
...
...
@@ -224,28 +225,4 @@ QProgressBar::chunk#speedBar {
QProgressBar
::chunk
#thrustBar
{
background-color
:
orange
;
}
QProgressBar
::chunk
#bandwidthBar
{
background-color
:
orange
;
}
QProgressBar
::chunk
#loadBar
{
background-color
:
yellow
;
}
QProgressBar
::chunk
#topRotorBar
{
background-color
:
yellow
;
}
QProgressBar
::chunk
#botRotorBar
{
background-color
:
yellow
;
}
QProgressBar
::chunk
#leftServoBar
{
background-color
:
#99BFDD
;
}
QProgressBar
::chunk
#rightServoBar
{
background-color
:
blue
;
}
}
src/comm/MAVLinkSimulationLink.cc
View file @
124997d0
...
...
@@ -484,7 +484,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
status
.
mode
=
MAV_MODE_AUTO
;
break
;
case
MAV_ACTION_RETURN
:
status
.
status
=
MAV_STATE_LANDING
;
break
;
case
MAV_ACTION_MOTORS_START
:
status
.
status
=
MAV_STATE_ACTIVE
;
...
...
@@ -498,6 +498,10 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
status
.
status
=
MAV_STATE_EMERGENCY
;
status
.
mode
=
MAV_MODE_MANUAL
;
break
;
case
MAV_ACTION_SHUTDOWN
:
status
.
status
=
MAV_STATE_POWEROFF
;
status
.
mode
=
MAV_MODE_LOCKED
;
break
;
}
}
break
;
...
...
src/uas/UAS.cc
View file @
124997d0
...
...
@@ -157,92 +157,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
voltageChanged
(
message
.
sysid
,
state
.
vbat
/
1000.0
f
);
}
break
;
/*
case MAVLINK_MSG_ID_SYSTEM:
// std::cerr << std::endl;
// std::cerr << "System Message received" << std::endl;
currentVoltage = message_system_get_voltage(message.payload)/1000.0f;
filterVoltage(currentVoltage);
if (startVoltage == 0) startVoltage = currentVoltage;
timeRemaining = calculateTimeRemaining();
//qDebug() << "Voltage: " << currentVoltage << " Chargelevel: " << getChargeLevel() << " Time remaining " << timeRemaining;
emit batteryChanged(this, filterVoltage(), getChargeLevel(), timeRemaining);
emit voltageChanged(message.acid, message_system_get_voltage(message.payload)/1000.0f);
emit loadChanged(this, message_system_get_cpu_usage(message.payload)/100.0f);
emit valueChanged(uasId, "Battery", message_system_get_voltage(message.payload), MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "CPU Load", message_system_get_cpu_usage(message.payload), MG::TIME::getGroundTimeNow());
break;
case MAVLINK_MSG_ID_ACTUATORS:
emit actuatorChanged(this, 0, message_actuator_get_act1(message.payload));
emit valueChanged(this->getUASID(), "Top Rotor", message_actuator_get_act1(message.payload), MG::TIME::getGroundTimeNow());
emit actuatorChanged(this, 1, message_actuator_get_act2(message.payload));
emit valueChanged(this->getUASID(), "Bottom Rotor", message_actuator_get_act2(message.payload), MG::TIME::getGroundTimeNow());
emit actuatorChanged(this, 2, message_actuator_get_act3(message.payload));
emit valueChanged(this->getUASID(), "Left Servo", message_actuator_get_act3(message.payload), MG::TIME::getGroundTimeNow());
emit actuatorChanged(this, 3, message_actuator_get_act4(message.payload));
emit valueChanged(this->getUASID(), "Right Servo", message_actuator_get_act4(message.payload), MG::TIME::getGroundTimeNow());
// Calculate thrust sum
thrustSum = (message_actuator_get_act1(message.payload) + message_actuator_get_act2(message.payload)) / 2;
emit thrustChanged(this, thrustSum);
break;
case MAVLINK_MSG_ID_STATE:
emit valueChanged(uasId, "State", message_state_get_state(message.payload), MG::TIME::getGroundTimeNow());
getStatusForCode(message_state_get_state(message.payload), uasState, stateDescription);
emit statusChanged(this, uasState, stateDescription);
break;
case MAVLINK_MSG_ID_POSITION:
// Position message is displayed in meters and degrees
{
quint64 time = MG::TIME::getGroundTimeNow();//message_position_get_msec(message.payload);
emit valueChanged(this, "x", message_position_get_posX(message.payload), time);
emit valueChanged(this, "y", message_position_get_posY(message.payload), time);
emit valueChanged(this, "z", message_position_get_posZ(message.payload), time);
emit valueChanged(this, "roll", message_position_get_roll(message.payload), time);
emit valueChanged(this, "pitch", message_position_get_pitch(message.payload), time);
emit valueChanged(this, "yaw", message_position_get_yaw(message.payload), time);
emit valueChanged(this, "x speed", message_position_get_speedX(message.payload), time);
emit valueChanged(this, "y speed", message_position_get_speedY(message.payload), time);
emit valueChanged(this, "z speed", message_position_get_speedZ(message.payload), time);
emit valueChanged(this, "roll speed", message_position_get_speedRoll(message.payload), time);
emit valueChanged(this, "pitch speed", message_position_get_speedPitch(message.payload), time);
emit valueChanged(this, "yaw speed", message_position_get_speedYaw(message.payload), time);
emit localPositionChanged(this, message_position_get_posX(message.payload), message_position_get_posY(message.payload), message_position_get_posZ(message.payload), time);
emit valueChanged(uasId, "x", message_position_get_posX(message.payload), time);
emit valueChanged(uasId, "y", message_position_get_posY(message.payload), time);
emit valueChanged(uasId, "z", message_position_get_posZ(message.payload), time);
emit valueChanged(uasId, "roll", message_position_get_roll(message.payload), time);
emit valueChanged(uasId, "pitch", message_position_get_pitch(message.payload), time);
emit valueChanged(uasId, "yaw", message_position_get_yaw(message.payload), time);
emit valueChanged(uasId, "x speed", message_position_get_speedX(message.payload), time);
emit valueChanged(uasId, "y speed", message_position_get_speedY(message.payload), time);
emit valueChanged(uasId, "z speed", message_position_get_speedZ(message.payload), time);
emit valueChanged(uasId, "roll speed", message_position_get_speedRoll(message.payload), time);
emit valueChanged(uasId, "pitch speed", message_position_get_speedPitch(message.payload), time);
emit valueChanged(uasId, "yaw speed", message_position_get_speedYaw(message.payload), time);
}
break;
case MAVLINK_MSG_ID_MARKER:
emit valueChanged(uasId, "marker confidence", message_marker_get_confidence(message.payload), MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "marker x", message_marker_get_posX(message.payload), MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "marker y", message_marker_get_posY(message.payload), MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "marker z", message_marker_get_posZ(message.payload), MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "marker roll", message_marker_get_roll(message.payload)/M_PI*180.0f, MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "marker pitch", message_marker_get_pitch(message.payload)/M_PI*180.0f, MG::TIME::getGroundTimeNow());
emit valueChanged(uasId, "marker yaw", message_marker_get_yaw(message.payload)/M_PI*180.0f, MG::TIME::getGroundTimeNow());
break;
case MAVLINK_MSG_ID_IMAGE:
//std::cerr << std::endl;
//std::cerr << "IMAGE DATA RECEIVED" << std::endl;
emit imageStarted(message_image_get_rid(message.payload), message_image_get_width(message.payload), message_image_get_height(message.payload), message_image_get_depth(message.payload), message_image_get_channels(message.payload));
break;
case MAVLINK_MSG_ID_BYTES:
//std::cerr << std::endl;
//std::cerr << "BYTES RESSOURCE RECEIVED" << std::endl;
emit imageDataReceived(message_bytestream_get_rid(message.payload), message_bytestream_get_data(message.payload), message_bytestream_get_length(message.payload), message_bytestream_get_index(message.payload));
break;
*/
case
MAVLINK_MSG_ID_RAW_IMU
:
{
raw_imu_t
raw
;
...
...
src/ui/HUD.cc
View file @
124997d0
...
...
@@ -190,7 +190,7 @@ void HUD::updateValue(UASInterface* uas, QString name, double value, quint64 mse
lastUpdate
.
insert
(
name
,
msec
);
//}
qDebug
()
<<
__FILE__
<<
__LINE__
<<
"VALUE:"
<<
value
<<
"MEAN:"
<<
mean
<<
"DOT:"
<<
dot
<<
"COUNT:"
<<
meanCount
;
//
qDebug() << __FILE__ << __LINE__ << "VALUE:" << value << "MEAN:" << mean << "DOT:" << dot << "COUNT:" << meanCount;
}
}
...
...
src/ui/UASControl.ui
View file @
124997d0
...
...
@@ -6,8 +6,8 @@
<rect>
<x>
0
</x>
<y>
0
</y>
<width>
3
95
</width>
<height>
21
5
</height>
<width>
3
87
</width>
<height>
21
2
</height>
</rect>
</property>
<property
name=
"windowTitle"
>
...
...
@@ -17,6 +17,9 @@
<property
name=
"margin"
>
<number>
20
</number>
</property>
<property
name=
"spacing"
>
<number>
6
</number>
</property>
<item
row=
"0"
column=
"0"
colspan=
"4"
>
<widget
class=
"QLabel"
name=
"controlStatusLabel"
>
<property
name=
"text"
>
...
...
@@ -128,6 +131,9 @@
<property
name=
"text"
>
<string>
No actions executed so far
</string>
</property>
<property
name=
"alignment"
>
<set>
Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop
</set>
</property>
</widget>
</item>
</layout>
...
...
src/ui/uas/UASControlWidget.cc
View file @
124997d0
...
...
@@ -64,13 +64,9 @@ void UASControlWidget::setUAS(UASInterface* uas)
disconnect
(
ui
.
controlButton
,
SIGNAL
(
clicked
()),
uas
,
SLOT
(
enable_motors
()));
disconnect
(
ui
.
liftoffButton
,
SIGNAL
(
clicked
()),
uas
,
SLOT
(
launch
()));
disconnect
(
ui
.
landButton
,
SIGNAL
(
clicked
()),
uas
,
SLOT
(
home
()));
//disconnect(ui.haltButton, SIGNAL(clicked()), uas, SLOT(halt()));
//disconnect(ui.continueButton, SIGNAL(clicked()), uas, SLOT(go()));
//disconnect(ui.forceLandButton, SIGNAL(clicked()), uas, SLOT(emergencySTOP()));
disconnect
(
ui
.
shutdownButton
,
SIGNAL
(
clicked
()),
uas
,
SLOT
(
shutdown
()));
//disconnect(uas, SIGNAL(autoModeChanged(bool)), ui.autoButton, SLOT(setChecked(bool)));
//disconnect(ui.autoButton, SIGNAL(clicked(bool)), uas, SLOT(setAutoMode(bool)));
//disconnect(ui.motorsStopButton, SIGNAL(clicked()), uas, SLOT(disable_motors()));
disconnect
(
ui
.
modeComboBox
,
SIGNAL
(
activated
(
int
)),
this
,
SLOT
(
setMode
(
int
)));
disconnect
(
ui
.
setModeButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
transmitMode
()));
}
else
{
...
...
@@ -78,14 +74,9 @@ void UASControlWidget::setUAS(UASInterface* uas)
connect
(
ui
.
controlButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
cycleContextButton
()));
connect
(
ui
.
liftoffButton
,
SIGNAL
(
clicked
()),
uas
,
SLOT
(
launch
()));
connect
(
ui
.
landButton
,
SIGNAL
(
clicked
()),
uas
,
SLOT
(
home
()));
//connect(ui.haltButton, SIGNAL(clicked()), uas, SLOT(halt()));
//connect(ui.continueButton, SIGNAL(clicked()), uas, SLOT(go()));
//connect(ui.forceLandButton, SIGNAL(clicked()), uas, SLOT(emergencySTOP()));
connect
(
ui
.
shutdownButton
,
SIGNAL
(
clicked
()),
uas
,
SLOT
(
shutdown
()));
//connect(ui.autoButton, SIGNAL(clicked(bool)), uas, SLOT(setAutoMode(bool)));
//connect(uas, SIGNAL(autoModeChanged(bool)), ui.autoButton, SLOT(setChecked(bool)));
//connect(ui.motorsStopButton, SIGNAL(clicked()), uas, SLOT(disable_motors()));
connect
(
ui
.
modeComboBox
,
SIGNAL
(
activated
(
int
)),
this
,
SLOT
(
setMode
(
int
)));
connect
(
ui
.
setModeButton
,
SIGNAL
(
clicked
()),
this
,
SLOT
(
transmitMode
()));
ui
.
modeComboBox
->
insertItem
(
0
,
"Select.."
);
ui
.
controlStatusLabel
->
setText
(
tr
(
"Connected to "
)
+
uas
->
getUASName
());
...
...
@@ -100,6 +91,7 @@ UASControlWidget::~UASControlWidget() {
void
UASControlWidget
::
setMode
(
int
mode
)
{
// Adapt context button mode
switch
(
mode
)
{
case
MAV_MODE_LOCKED
:
...
...
@@ -119,7 +111,17 @@ void UASControlWidget::setMode(int mode)
}
// Set mode on system
if
(
mode
>=
MAV_MODE_LOCKED
&&
mode
<=
MAV_MODE_TEST3
)
this
->
uas
->
setMode
(
mode
);
if
(
mode
>=
MAV_MODE_LOCKED
&&
mode
<=
MAV_MODE_TEST3
)
{
uasMode
=
mode
;
ui
.
modeComboBox
->
setCurrentIndex
(
mode
);
}
qDebug
()
<<
"SET MODE REQUESTED"
<<
mode
;
}
void
UASControlWidget
::
transmitMode
()
{
this
->
uas
->
setMode
(
uasMode
);
}
void
UASControlWidget
::
cycleContextButton
()
...
...
src/ui/uas/UASControlWidget.h
View file @
124997d0
...
...
@@ -53,9 +53,12 @@ public slots:
void
cycleContextButton
();
/** @brief Set the operation mode of the MAV */
void
setMode
(
int
mode
);
/** @brief Transmit the operation mode **/
void
transmitMode
();
protected:
UASInterface
*
uas
;
int
uasMode
;
private:
Ui
::
uasControl
ui
;
...
...
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