From 41a5afdf6434d147b433e77cb161e488f6a76976 Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Sat, 19 Feb 2022 22:18:10 +0530 Subject: [PATCH] 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 --- libraries/AP_Common/Location.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index 92a86ebc23..4ae650312f 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -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