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
81ccc01d
Commit
81ccc01d
authored
Feb 04, 2011
by
pixhawk
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Minor improvements throughout the application to improve usability
parent
ca9e82a3
Changes
7
Expand all
Hide whitespace changes
Inline
Side-by-side
Showing
7 changed files
with
180 additions
and
137 deletions
+180
-137
MAVLinkSimulationMAV.cc
src/comm/MAVLinkSimulationMAV.cc
+11
-8
PxQuadMAV.cc
src/uas/PxQuadMAV.cc
+3
-19
UAS.cc
src/uas/UAS.cc
+22
-10
HSIDisplay.cc
src/ui/HSIDisplay.cc
+125
-95
HSIDisplay.h
src/ui/HSIDisplay.h
+2
-0
MainWindow.cc
src/ui/MainWindow.cc
+11
-5
MapWidget.cc
src/ui/MapWidget.cc
+6
-0
No files found.
src/comm/MAVLinkSimulationMAV.cc
View file @
81ccc01d
...
...
@@ -121,8 +121,8 @@ void MAVLinkSimulationMAV::mainloop()
pos
.
alt
=
z
*
1000.0
;
pos
.
lat
=
y
*
1E7
;
pos
.
lon
=
x
*
1E7
;
pos
.
vx
=
0
;
pos
.
vy
=
0
;
pos
.
vx
=
sin
(
yaw
)
*
10.0
f
;
pos
.
vy
=
cos
(
yaw
)
*
10.0
f
;
pos
.
vz
=
0
;
mavlink_msg_global_position_int_encode
(
systemid
,
MAV_COMP_ID_IMU
,
&
msg
,
&
pos
);
link
->
sendMAVLinkMessage
(
&
msg
);
...
...
@@ -164,18 +164,21 @@ void MAVLinkSimulationMAV::mainloop()
control_status
.
control_pos_xy
=
1
;
control_status
.
control_pos_yaw
=
1
;
control_status
.
control_pos_z
=
1
;
control_status
.
gps_fix
=
2
;
// 2D GPS fix
control_status
.
position_fix
=
3
;
// 3D fix from GPS + barometric pressure
control_status
.
vision_fix
=
0
;
// no fix from vision system
mavlink_msg_control_status_encode
(
systemid
,
MAV_COMP_ID_IMU
,
&
ret
,
&
control_status
);
link
->
sendMAVLinkMessage
(
&
ret
);
// Send actual controller outputs
// This message just shows the direction
// and magnitude of the control output
mavlink_position_controller_output_t
pos
;
pos
.
x
=
sin
(
yaw
)
*
127.0
f
;
pos
.
y
=
cos
(
yaw
)
*
127.0
f
;
pos
.
z
=
0
;
mavlink_msg_position_controller_output_encode
(
systemid
,
MAV_COMP_ID_IMU
,
&
ret
,
&
pos
);
link
->
sendMAVLinkMessage
(
&
ret
);
//
mavlink_position_controller_output_t pos;
//
pos.x = sin(yaw)*127.0f;
//
pos.y = cos(yaw)*127.0f;
//
pos.z = 0;
//
mavlink_msg_position_controller_output_encode(systemid, MAV_COMP_ID_IMU, &ret, &pos);
//
link->sendMAVLinkMessage(&ret);
// Send a named value with name "FLOAT" and 0.5f as value
...
...
src/uas/PxQuadMAV.cc
View file @
81ccc01d
...
...
@@ -50,9 +50,9 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
if
(
message
.
sysid
==
uasId
)
{
QString
uasState
;
QString
stateDescription
;
QString
patternPath
;
//
QString uasState;
//
QString stateDescription;
//
QString patternPath;
switch
(
message
.
msgid
)
{
case
MAVLINK_MSG_ID_RAW_AUX
:
...
...
@@ -155,22 +155,6 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
valueChanged
(
uasId
,
"Load"
,
"%"
,
((
float
)
status
.
load
)
/
1000.0
f
,
MG
::
TIME
::
getGroundTimeNow
());
}
break
;
case
MAVLINK_MSG_ID_CONTROL_STATUS
:
{
mavlink_control_status_t
status
;
mavlink_msg_control_status_decode
(
&
message
,
&
status
);
// Emit control status vector
emit
attitudeControlEnabled
(
static_cast
<
bool
>
(
status
.
control_att
));
emit
positionXYControlEnabled
(
static_cast
<
bool
>
(
status
.
control_pos_xy
));
emit
positionZControlEnabled
(
static_cast
<
bool
>
(
status
.
control_pos_z
));
emit
positionYawControlEnabled
(
static_cast
<
bool
>
(
status
.
control_pos_yaw
));
// Emit localization status vector
emit
localizationChanged
(
this
,
status
.
position_fix
);
emit
visionLocalizationChanged
(
this
,
status
.
vision_fix
);
emit
gpsLocalizationChanged
(
this
,
status
.
gps_fix
);
}
break
;
default:
// Do nothing
break
;
...
...
src/uas/UAS.cc
View file @
81ccc01d
...
...
@@ -349,6 +349,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
}
break
;
case
MAVLINK_MSG_ID_CONTROL_STATUS
:
{
mavlink_control_status_t
status
;
mavlink_msg_control_status_decode
(
&
message
,
&
status
);
// Emit control status vector
emit
attitudeControlEnabled
(
static_cast
<
bool
>
(
status
.
control_att
));
emit
positionXYControlEnabled
(
static_cast
<
bool
>
(
status
.
control_pos_xy
));
emit
positionZControlEnabled
(
static_cast
<
bool
>
(
status
.
control_pos_z
));
emit
positionYawControlEnabled
(
static_cast
<
bool
>
(
status
.
control_pos_yaw
));
// Emit localization status vector
emit
localizationChanged
(
this
,
status
.
position_fix
);
emit
visionLocalizationChanged
(
this
,
status
.
vision_fix
);
emit
gpsLocalizationChanged
(
this
,
status
.
gps_fix
);
}
break
;
case
MAVLINK_MSG_ID_RAW_IMU
:
{
mavlink_raw_imu_t
raw
;
...
...
@@ -480,6 +496,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
valueChanged
(
uasId
,
"gps z speed"
,
"m/s"
,
speedZ
,
time
);
emit
globalPositionChanged
(
this
,
longitude
,
latitude
,
altitude
,
time
);
emit
speedChanged
(
this
,
speedX
,
speedY
,
speedZ
,
time
);
emit
valueChanged
(
uasId
,
"gpsspeed"
,
"m/s"
,
sqrt
(
speedX
*
speedX
+
speedY
*
speedY
+
speedZ
*
speedZ
),
time
);
// Set internal state
if
(
!
positionLock
)
{
...
...
@@ -506,15 +523,10 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
valueChanged
(
uasId
,
"latitude"
,
"deg"
,
pos
.
lat
,
time
);
emit
valueChanged
(
uasId
,
"longitude"
,
"deg"
,
pos
.
lon
,
time
);
// FIXME REMOVE
longitude
=
pos
.
lon
;
latitude
=
pos
.
lat
;
altitude
=
pos
.
alt
;
emit
globalPositionChanged
(
this
,
longitude
,
latitude
,
altitude
,
time
);
if
(
pos
.
fix_type
>
0
)
{
emit
globalPositionChanged
(
this
,
pos
.
lon
,
pos
.
lat
,
pos
.
alt
,
time
);
emit
valueChanged
(
uasId
,
"gpsspeed"
,
"m/s"
,
pos
.
v
,
time
);
// Check for NaN
int
alt
=
pos
.
alt
;
...
...
@@ -560,9 +572,9 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
mavlink_raw_pressure_t
pressure
;
mavlink_msg_raw_pressure_decode
(
&
message
,
&
pressure
);
quint64
time
=
this
->
getUnixTime
(
0
);
emit
valueChanged
(
uasId
,
"abs pressure"
,
"hP"
,
pressure
.
press_abs
,
time
);
emit
valueChanged
(
uasId
,
"diff pressure 1"
,
"hP"
,
pressure
.
press_diff1
,
time
);
emit
valueChanged
(
uasId
,
"diff pressure 2"
,
"hP"
,
pressure
.
press_diff2
,
time
);
emit
valueChanged
(
uasId
,
"abs pressure"
,
"hP
a
"
,
pressure
.
press_abs
,
time
);
emit
valueChanged
(
uasId
,
"diff pressure 1"
,
"hP
a
"
,
pressure
.
press_diff1
,
time
);
emit
valueChanged
(
uasId
,
"diff pressure 2"
,
"hP
a
"
,
pressure
.
press_diff2
,
time
);
}
break
;
case
MAVLINK_MSG_ID_RC_CHANNELS_RAW
:
...
...
@@ -1017,7 +1029,7 @@ void UAS::forwardMessage(mavlink_message_t message)
{
if
(
serial
!=
links
->
at
(
i
))
{
qDebug
()
<<
"Forwarding Over link: "
<<
serial
->
getName
()
<<
" "
<<
serial
;
qDebug
()
<<
"
Antenna tracking:
Forwarding Over link: "
<<
serial
->
getName
()
<<
" "
<<
serial
;
sendMessage
(
serial
,
message
);
}
}
...
...
src/ui/HSIDisplay.cc
View file @
81ccc01d
This diff is collapsed.
Click to expand it.
src/ui/HSIDisplay.h
View file @
81ccc01d
...
...
@@ -248,6 +248,8 @@ protected:
// Data indicators
bool
setPointKnown
;
///< Controller setpoint known status flag
bool
positionSetPointKnown
;
///< Position setpoint known status flag
bool
userSetPointSet
;
private:
};
...
...
src/ui/MainWindow.cc
View file @
81ccc01d
...
...
@@ -210,6 +210,8 @@ void MainWindow::setDefaultSettingsForAp()
settings
.
setValue
(
buildMenuKey
(
SUB_SECTION_CHECKED
,
MainWindow
::
MENU_UAS_LIST
,
VIEW_OPERATOR
),
true
);
// ENABLE HUD TOOL WIDGET
settings
.
setValue
(
buildMenuKey
(
SUB_SECTION_CHECKED
,
MainWindow
::
MENU_HUD
,
VIEW_OPERATOR
),
true
);
// ENABLE WAYPOINTS
settings
.
setValue
(
buildMenuKey
(
SUB_SECTION_CHECKED
,
MainWindow
::
MENU_WAYPOINTS
,
VIEW_OPERATOR
),
true
);
}
// ENGINEER VIEW DEFAULT
...
...
@@ -399,15 +401,19 @@ void MainWindow::buildPxWidgets()
acceptList
->
append
(
"-105,pitch,deg,+105,s"
);
acceptList
->
append
(
"-105,yaw,deg,+105,s"
);
acceptList
->
append
(
"-260,rollspeed,deg/s,+260,s"
);
acceptList
->
append
(
"-260,pitchspeed,deg/s,+260,s"
);
acceptList
->
append
(
"-260,yawspeed,deg/s,+260,s"
);
acceptList
->
append
(
"-60,rollspeed,deg/s,+60,s"
);
acceptList
->
append
(
"-60,pitchspeed,deg/s,+60,s"
);
acceptList
->
append
(
"-60,yawspeed,deg/s,+60,s"
);
acceptList
->
append
(
"0,airspeed,m/s,30"
);
acceptList
->
append
(
"0,gpsspeed,m/s,30"
);
acceptList
->
append
(
"0,truespeed,m/s,30"
);
//FIXME: memory of acceptList2 will never be freed again
QStringList
*
acceptList2
=
new
QStringList
();
acceptList2
->
append
(
"0,abs pressure,hPa,65500"
);
acceptList2
->
append
(
"-999,accel. X,raw,999,s"
);
acceptList2
->
append
(
"-999,accel. Y,raw,999,s"
);
acceptList2
->
append
(
"-2048,accel. x,raw,2048,s"
);
acceptList2
->
append
(
"-2048,accel. y,raw,2048,s"
);
acceptList2
->
append
(
"-2048,accel. z,raw,2048,s"
);
if
(
!
linechartWidget
)
{
...
...
src/ui/MapWidget.cc
View file @
81ccc01d
...
...
@@ -157,12 +157,18 @@ MapWidget::MapWidget(QWidget *parent) :
zoomout
->
setStyleSheet
(
buttonStyle
);
createPath
=
new
QPushButton
(
QIcon
(
":/images/actions/go-bottom.svg"
),
""
,
this
);
createPath
->
setStyleSheet
(
buttonStyle
);
createPath
->
setToolTip
(
tr
(
"Start / end waypoint add mode"
));
createPath
->
setStatusTip
(
tr
(
"Start / end waypoint add mode"
));
// clearTracking = new QPushButton(QIcon(""), "", this);
// clearTracking->setStyleSheet(buttonStyle);
followgps
=
new
QPushButton
(
QIcon
(
":/images/actions/system-lock-screen.svg"
),
""
,
this
);
followgps
->
setStyleSheet
(
buttonStyle
);
followgps
->
setToolTip
(
tr
(
"Follow the position of the current MAV with the map center"
));
followgps
->
setStatusTip
(
tr
(
"Follow the position of the current MAV with the map center"
));
QPushButton
*
goToButton
=
new
QPushButton
(
QIcon
(
""
),
"T"
,
this
);
goToButton
->
setStyleSheet
(
buttonStyle
);
goToButton
->
setToolTip
(
tr
(
"Enter a latitude/longitude position to move the map to"
));
goToButton
->
setStatusTip
(
tr
(
"Enter a latitude/longitude position to move the map to"
));
zoomin
->
setMaximumWidth
(
30
);
zoomout
->
setMaximumWidth
(
30
);
...
...
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