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
7388388b
Commit
7388388b
authored
Sep 02, 2011
by
LM
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fixed a bug in the default options
parent
047dc94e
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
31 additions
and
30 deletions
+31
-30
PxQuadMAV.cc
src/uas/PxQuadMAV.cc
+30
-0
UAS.cc
src/uas/UAS.cc
+1
-30
No files found.
src/uas/PxQuadMAV.cc
View file @
7388388b
...
...
@@ -132,6 +132,36 @@ void PxQuadMAV::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
valueChanged
(
uasId
,
"vis. speed z"
,
"m/s"
,
speed
.
z
,
time
);
}
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_VISUAL_ODOMETRY
:
{
mavlink_visual_odometry_t
pos
;
mavlink_msg_visual_odometry_decode
(
&
message
,
&
pos
);
quint64
time
=
getUnixTime
(
pos
.
frame1_time_us
);
//emit valueChanged(uasId, "vis. time", pos.usec, time);
emit
valueChanged
(
uasId
,
"vis-o. roll"
,
"rad"
,
pos
.
roll
,
time
);
emit
valueChanged
(
uasId
,
"vis-o. pitch"
,
"rad"
,
pos
.
pitch
,
time
);
emit
valueChanged
(
uasId
,
"vis-o. yaw"
,
"rad"
,
pos
.
yaw
,
time
);
emit
valueChanged
(
uasId
,
"vis-o. x"
,
"m"
,
pos
.
x
,
time
);
emit
valueChanged
(
uasId
,
"vis-o. y"
,
"m"
,
pos
.
y
,
time
);
emit
valueChanged
(
uasId
,
"vis-o. z"
,
"m"
,
pos
.
z
,
time
);
}
break
;
case
MAVLINK_MSG_ID_AUX_STATUS
:
{
mavlink_aux_status_t
status
;
mavlink_msg_aux_status_decode
(
&
message
,
&
status
);
...
...
src/uas/UAS.cc
View file @
7388388b
...
...
@@ -75,7 +75,7 @@ paramsOnceRequested(false),
airframe
(
0
),
attitudeKnown
(
false
),
paramManager
(
NULL
),
attitudeStamped
(
tru
e
),
attitudeStamped
(
fals
e
),
lastAttitude
(
0
)
{
color
=
UASInterface
::
getNextColor
();
...
...
@@ -403,35 +403,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
}
}
break
;
#ifdef MAVLINK_ENABLED_PIXHAWK
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_VISION_SPEED_ESTIMATE
:
{
mavlink_vision_speed_estimate_t
speed
;
mavlink_msg_vision_speed_estimate_decode
(
&
message
,
&
speed
);
quint64
time
=
getUnixTime
(
speed
.
usec
);
emit
valueChanged
(
uasId
,
"vis.speed x"
,
"m/s"
,
static_cast
<
double
>
(
speed
.
x
),
time
);
emit
valueChanged
(
uasId
,
"vis.speed y"
,
"m/s"
,
static_cast
<
double
>
(
speed
.
y
),
time
);
emit
valueChanged
(
uasId
,
"vis.speed z"
,
"m/s"
,
static_cast
<
double
>
(
speed
.
z
),
time
);
}
break
;
#endif // PIXHAWK
case
MAVLINK_MSG_ID_RAW_IMU
:
{
mavlink_raw_imu_t
raw
;
...
...
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