AP_Baro: Check if origin alt is zero before using it as field elevation

This commit is contained in:
rishabsingh3003 2023-09-26 23:20:54 -04:00
parent fa0f089fe1
commit 5fda953316
1 changed files with 3 additions and 1 deletions

View File

@ -1013,7 +1013,9 @@ void AP_Baro::update_field_elevation(void)
is_zero(_field_elevation)) {
// auto-set based on origin
Location origin;
if (!armed && AP::ahrs().get_origin(origin)) {
if (!armed &&
AP::ahrs().get_origin(origin) &&
origin.alt != 0) {
_field_elevation_active = origin.alt * 0.01;
new_field_elev = true;
}