From 9be604e3ce928e4397cadca3eff0e95d18631be3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 2 Jan 2019 11:07:57 +1100 Subject: [PATCH] AP_NavEKF2: adjust for location flags being moved out of union --- libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp index e49a3cd216..8e7b793c8b 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp @@ -322,8 +322,8 @@ bool NavEKF2_core::getLLH(struct Location &loc) const if(getPosD(posD) && getOriginLLH(origin)) { // Altitude returned is an absolute altitude relative to the WGS-84 spherioid loc.alt = origin.alt - posD*100; - loc.flags.relative_alt = 0; - loc.flags.terrain_alt = 0; + loc.relative_alt = 0; + loc.terrain_alt = 0; // there are three modes of operation, absolute position (GPS fusion), relative position (optical flow fusion) and constant position (no aiding) if (filterStatus.flags.horiz_pos_abs || filterStatus.flags.horiz_pos_rel) { @@ -354,8 +354,8 @@ bool NavEKF2_core::getLLH(struct Location &loc) const if ((gps.status() >= AP_GPS::GPS_OK_FIX_3D)) { const struct Location &gpsloc = gps.location(); loc = gpsloc; - loc.flags.relative_alt = 0; - loc.flags.terrain_alt = 0; + loc.relative_alt = 0; + loc.terrain_alt = 0; } return false; }