mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Baro: Check if origin alt is zero before using it as field elevation
This commit is contained in:
parent
fa0f089fe1
commit
5fda953316
@ -1013,7 +1013,9 @@ void AP_Baro::update_field_elevation(void)
|
|||||||
is_zero(_field_elevation)) {
|
is_zero(_field_elevation)) {
|
||||||
// auto-set based on origin
|
// auto-set based on origin
|
||||||
Location 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;
|
_field_elevation_active = origin.alt * 0.01;
|
||||||
new_field_elev = true;
|
new_field_elev = true;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user