mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Frsky_Telem: adjust for location flags being moved out of union
This commit is contained in:
parent
1c6b52c8de
commit
38a649033f
@ -726,7 +726,7 @@ uint32_t AP_Frsky_Telem::calc_home(void)
|
|||||||
}
|
}
|
||||||
// altitude between vehicle and home_loc
|
// altitude between vehicle and home_loc
|
||||||
_relative_home_altitude = loc.alt;
|
_relative_home_altitude = loc.alt;
|
||||||
if (!loc.flags.relative_alt) {
|
if (!loc.relative_alt) {
|
||||||
// loc.alt has home altitude added, remove it
|
// loc.alt has home altitude added, remove it
|
||||||
_relative_home_altitude -= _ahrs.get_home().alt;
|
_relative_home_altitude -= _ahrs.get_home().alt;
|
||||||
}
|
}
|
||||||
@ -853,7 +853,7 @@ void AP_Frsky_Telem::calc_nav_alt(void)
|
|||||||
float current_height = 0; // in centimeters above home
|
float current_height = 0; // in centimeters above home
|
||||||
if (_ahrs.get_position(loc)) {
|
if (_ahrs.get_position(loc)) {
|
||||||
current_height = loc.alt*0.01f;
|
current_height = loc.alt*0.01f;
|
||||||
if (!loc.flags.relative_alt) {
|
if (!loc.relative_alt) {
|
||||||
// loc.alt has home altitude added, remove it
|
// loc.alt has home altitude added, remove it
|
||||||
current_height -= _ahrs.get_home().alt*0.01f;
|
current_height -= _ahrs.get_home().alt*0.01f;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user