AC_WPNav: use enum class for AltFrame enumeration

This commit is contained in:
Peter Barker 2019-03-15 12:45:20 +11:00 committed by Andrew Tridgell
parent 3629273959
commit d9ddb8f34d

View File

@ -997,9 +997,9 @@ bool AC_WPNav::get_vector_NEU(const Location &loc, Vector3f &vec, bool &terrain_
} }
// convert altitude // 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; 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; return false;
} }
vec.z = terr_alt; vec.z = terr_alt;
@ -1007,7 +1007,7 @@ bool AC_WPNav::get_vector_NEU(const Location &loc, Vector3f &vec, bool &terrain_
} else { } else {
terrain_alt = false; terrain_alt = false;
int32_t temp_alt; 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; return false;
} }
vec.z = temp_alt; vec.z = temp_alt;