From 1f5727c0b2aacba6d35ca9f5fb01a7a684be623e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 2 Jan 2019 11:08:36 +1100 Subject: [PATCH] AP_Rally: adjust for location flags being moved out of union --- libraries/AP_Rally/AP_Rally.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Rally/AP_Rally.cpp b/libraries/AP_Rally/AP_Rally.cpp index 3344a36a16..05358b25ef 100644 --- a/libraries/AP_Rally/AP_Rally.cpp +++ b/libraries/AP_Rally/AP_Rally.cpp @@ -101,7 +101,7 @@ Location AP_Rally::rally_location_to_location(const RallyLocation &rally_loc) co Location ret = {}; // we return an absolute altitude, as we add homeloc.alt below - ret.flags.relative_alt = false; + ret.relative_alt = false; //Currently can't do true AGL on the APM. Relative altitudes are //relative to HOME point's altitude. Terrain on the board is inbound @@ -152,7 +152,7 @@ Location AP_Rally::calc_best_rally_or_home_location(const Location ¤t_loc, // no valid rally point, return home position return_loc = home_loc; return_loc.alt = rtl_home_alt; - return_loc.flags.relative_alt = false; // read_alt_to_hold returns an absolute altitude + return_loc.relative_alt = false; // read_alt_to_hold returns an absolute altitude if (find_nearest_rally_point(current_loc, ral_loc)) { Location loc = rally_location_to_location(ral_loc);