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
69a50719
Commit
69a50719
authored
Aug 03, 2017
by
Jacob Walser
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Fix for missing altitude updates on APM
parent
59428e13
Changes
1
Hide whitespace changes
Inline
Side-by-side
Showing
1 changed file
with
5 additions
and
3 deletions
+5
-3
Vehicle.cc
src/Vehicle/Vehicle.cc
+5
-3
No files found.
src/Vehicle/Vehicle.cc
View file @
69a50719
...
...
@@ -716,7 +716,11 @@ void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message)
mavlink_global_position_int_t
globalPositionInt
;
mavlink_msg_global_position_int_decode
(
&
message
,
&
globalPositionInt
);
// ArduPilot sends bogus GLOBAL_POSITION_INT messages with lat/lat 0/0 even when it has not gps signal
_altitudeRelativeFact
.
setRawValue
(
globalPositionInt
.
relative_alt
/
1000.0
);
_altitudeAMSLFact
.
setRawValue
(
globalPositionInt
.
alt
/
1000.0
);
// ArduPilot sends bogus GLOBAL_POSITION_INT messages with lat/lat 0/0 even when it has no gps signal
// Apparently, this is in order to transport relative altitude information.
if
(
globalPositionInt
.
lat
==
0
&&
globalPositionInt
.
lon
==
0
)
{
return
;
}
...
...
@@ -727,8 +731,6 @@ void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message)
_coordinate
.
setLongitude
(
globalPositionInt
.
lon
/
(
double
)
1E7
);
_coordinate
.
setAltitude
(
globalPositionInt
.
alt
/
1000.0
);
emit
coordinateChanged
(
_coordinate
);
_altitudeRelativeFact
.
setRawValue
(
globalPositionInt
.
relative_alt
/
1000.0
);
_altitudeAMSLFact
.
setRawValue
(
globalPositionInt
.
alt
/
1000.0
);
}
void
Vehicle
::
_handleAltitude
(
mavlink_message_t
&
message
)
...
...
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