mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_Common: use default location alt frame while sanitizing location alt
We should also set alt frame along with copying altitude value while sanitizing it
This commit is contained in:
parent
a47445bde9
commit
41a5afdf64
@ -355,9 +355,11 @@ bool Location::sanitize(const Location &defaultLoc)
|
||||
|
||||
// convert relative alt=0 to mean current alt
|
||||
if (alt == 0 && relative_alt) {
|
||||
relative_alt = false;
|
||||
alt = defaultLoc.alt;
|
||||
has_changed = true;
|
||||
int32_t defaultLoc_alt;
|
||||
if (defaultLoc.get_alt_cm(get_alt_frame(), defaultLoc_alt)) {
|
||||
alt = defaultLoc_alt;
|
||||
has_changed = true;
|
||||
}
|
||||
}
|
||||
|
||||
// limit lat/lng to appropriate ranges
|
||||
|
Loading…
Reference in New Issue
Block a user