mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Math: adjust for location flags being moved out of union
This commit is contained in:
parent
e8da58201a
commit
ce37c9f69b
@ -174,8 +174,8 @@ bool location_sanitize(const struct Location &defaultLoc, struct Location &loc)
|
||||
}
|
||||
|
||||
// convert relative alt=0 to mean current alt
|
||||
if (loc.alt == 0 && loc.flags.relative_alt) {
|
||||
loc.flags.relative_alt = false;
|
||||
if (loc.alt == 0 && loc.relative_alt) {
|
||||
loc.relative_alt = false;
|
||||
loc.alt = defaultLoc.alt;
|
||||
has_changed = true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user