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
71e4c784
Unverified
Commit
71e4c784
authored
Jul 28, 2020
by
Don Gagne
Committed by
GitHub
Jul 28, 2020
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #8943 from DonLakeFlyer/Altitude
Prefer ALTITUDE message over GPS messages
parents
47baad1a
744c9141
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
14 additions
and
16 deletions
+14
-16
Vehicle.cc
src/Vehicle/Vehicle.cc
+11
-14
Vehicle.h
src/Vehicle/Vehicle.h
+3
-2
No files found.
src/Vehicle/Vehicle.cc
View file @
71e4c784
...
...
@@ -138,8 +138,6 @@ Vehicle::Vehicle(LinkInterface* link,
,
_onboardControlSensorsEnabled
(
0
)
,
_onboardControlSensorsHealth
(
0
)
,
_onboardControlSensorsUnhealthy
(
0
)
,
_gpsRawIntMessageAvailable
(
false
)
,
_globalPositionIntMessageAvailable
(
false
)
,
_defaultCruiseSpeed
(
_settingsManager
->
appSettings
()
->
offlineEditingCruiseSpeed
()
->
rawValue
().
toDouble
())
,
_defaultHoverSpeed
(
_settingsManager
->
appSettings
()
->
offlineEditingHoverSpeed
()
->
rawValue
().
toDouble
())
,
_telemetryRRSSI
(
0
)
...
...
@@ -332,8 +330,6 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
,
_onboardControlSensorsEnabled
(
0
)
,
_onboardControlSensorsHealth
(
0
)
,
_onboardControlSensorsUnhealthy
(
0
)
,
_gpsRawIntMessageAvailable
(
false
)
,
_globalPositionIntMessageAvailable
(
false
)
,
_defaultCruiseSpeed
(
_settingsManager
->
appSettings
()
->
offlineEditingCruiseSpeed
()
->
rawValue
().
toDouble
())
,
_defaultHoverSpeed
(
_settingsManager
->
appSettings
()
->
offlineEditingHoverSpeed
()
->
rawValue
().
toDouble
())
,
_mavlinkProtocolRequestComplete
(
true
)
...
...
@@ -1260,7 +1256,9 @@ void Vehicle::_handleGpsRawInt(mavlink_message_t& message)
_coordinate
=
newPosition
;
emit
coordinateChanged
(
_coordinate
);
}
_altitudeAMSLFact
.
setRawValue
(
gpsRawInt
.
alt
/
1000.0
);
if
(
!
_altitudeMessageAvailable
)
{
_altitudeAMSLFact
.
setRawValue
(
gpsRawInt
.
alt
/
1000.0
);
}
}
}
...
...
@@ -1279,8 +1277,10 @@ void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message)
mavlink_global_position_int_t
globalPositionInt
;
mavlink_msg_global_position_int_decode
(
&
message
,
&
globalPositionInt
);
_altitudeRelativeFact
.
setRawValue
(
globalPositionInt
.
relative_alt
/
1000.0
);
_altitudeAMSLFact
.
setRawValue
(
globalPositionInt
.
alt
/
1000.0
);
if
(
!
_altitudeMessageAvailable
)
{
_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.
...
...
@@ -1438,13 +1438,10 @@ void Vehicle::_handleAltitude(mavlink_message_t& message)
mavlink_altitude_t
altitude
;
mavlink_msg_altitude_decode
(
&
message
,
&
altitude
);
// If data from GPS is available it takes precedence over ALTITUDE message
if
(
!
_globalPositionIntMessageAvailable
)
{
_altitudeRelativeFact
.
setRawValue
(
altitude
.
altitude_relative
);
if
(
!
_gpsRawIntMessageAvailable
)
{
_altitudeAMSLFact
.
setRawValue
(
altitude
.
altitude_amsl
);
}
}
// Data from ALTITUDE message takes precedence over gps messages
_altitudeMessageAvailable
=
true
;
_altitudeRelativeFact
.
setRawValue
(
altitude
.
altitude_relative
);
_altitudeAMSLFact
.
setRawValue
(
altitude
.
altitude_amsl
);
}
void
Vehicle
::
_setCapabilities
(
uint64_t
capabilityBits
)
...
...
src/Vehicle/Vehicle.h
View file @
71e4c784
...
...
@@ -1424,8 +1424,9 @@ private:
uint32_t
_onboardControlSensorsEnabled
;
uint32_t
_onboardControlSensorsHealth
;
uint32_t
_onboardControlSensorsUnhealthy
;
bool
_gpsRawIntMessageAvailable
;
bool
_globalPositionIntMessageAvailable
;
bool
_gpsRawIntMessageAvailable
=
false
;
bool
_globalPositionIntMessageAvailable
=
false
;
bool
_altitudeMessageAvailable
=
false
;
double
_defaultCruiseSpeed
;
double
_defaultHoverSpeed
;
int
_telemetryRRSSI
;
...
...
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