From b416bc603e4b09ae5a2cc139b810b3beea55e858 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 2 Jan 2019 10:58:24 +1100 Subject: [PATCH] AP_AHRS_DCM: adjust for location flags being moved out of union --- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 6ed1f7a731..77fe1fa0a6 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -982,8 +982,8 @@ bool AP_AHRS_DCM::get_position(struct Location &loc) const loc.lat = _last_lat; loc.lng = _last_lng; loc.alt = AP::baro().get_altitude() * 100 + _home.alt; - loc.flags.relative_alt = 0; - loc.flags.terrain_alt = 0; + loc.relative_alt = 0; + loc.terrain_alt = 0; location_offset(loc, _position_offset_north, _position_offset_east); const AP_GPS &_gps = AP::gps(); if (_flags.fly_forward && _have_position) { @@ -1034,7 +1034,6 @@ bool AP_AHRS_DCM::airspeed_estimate(float *airspeed_ret) const void AP_AHRS_DCM::set_home(const Location &loc) { _home = loc; - _home.options = 0; _home_is_set = true; // log ahrs home and ekf origin dataflash