From d9ddb8f34da2828cf3d310155d12114ed1f37912 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 15 Mar 2019 12:45:20 +1100 Subject: [PATCH] AC_WPNav: use enum class for AltFrame enumeration --- libraries/AC_WPNav/AC_WPNav.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index 3e981e36bc..f877aae2f8 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -997,9 +997,9 @@ bool AC_WPNav::get_vector_NEU(const Location &loc, Vector3f &vec, bool &terrain_ } // convert altitude - if (loc.get_alt_frame() == Location::ALT_FRAME_ABOVE_TERRAIN) { + if (loc.get_alt_frame() == Location::AltFrame::ABOVE_TERRAIN) { int32_t terr_alt; - if (!loc.get_alt_cm(Location::ALT_FRAME_ABOVE_TERRAIN, terr_alt)) { + if (!loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, terr_alt)) { return false; } vec.z = terr_alt; @@ -1007,7 +1007,7 @@ bool AC_WPNav::get_vector_NEU(const Location &loc, Vector3f &vec, bool &terrain_ } else { terrain_alt = false; int32_t temp_alt; - if (!loc.get_alt_cm(Location::ALT_FRAME_ABOVE_ORIGIN, temp_alt)) { + if (!loc.get_alt_cm(Location::AltFrame::ABOVE_ORIGIN, temp_alt)) { return false; } vec.z = temp_alt;