From 716b0fdc88a3ea24e43d2029a04795001cde3bc5 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 15 Mar 2019 12:46:05 +1100 Subject: [PATCH] GCS_MAVLink: use enum class for AltFrame enumeration --- libraries/GCS_MAVLink/GCS.h | 2 +- libraries/GCS_MAVLink/GCS_Common.cpp | 10 +++++----- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index b36c305442..8d612f8758 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -295,7 +295,7 @@ protected: virtual bool in_hil_mode() const { return false; } bool mavlink_coordinate_frame_to_location_alt_frame(uint8_t coordinate_frame, - Location::ALT_FRAME &frame); + Location::AltFrame &frame); // overridable method to check for packet acceptance. Allows for // enforcement of GCS sysid diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index cf6839b73b..003798c262 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -3678,7 +3678,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_int_do_set_home(const mavlink_command_int if (!is_zero(packet.param1)) { return MAV_RESULT_FAILED; } - Location::ALT_FRAME frame; + Location::AltFrame frame; if (!mavlink_coordinate_frame_to_location_alt_frame(packet.frame, frame)) { // unknown coordinate frame return MAV_RESULT_UNSUPPORTED; @@ -4478,20 +4478,20 @@ void GCS::passthru_timer(void) } } -bool GCS_MAVLINK::mavlink_coordinate_frame_to_location_alt_frame(const uint8_t coordinate_frame, Location::ALT_FRAME &frame) +bool GCS_MAVLINK::mavlink_coordinate_frame_to_location_alt_frame(const uint8_t coordinate_frame, Location::AltFrame &frame) { switch (coordinate_frame) { case MAV_FRAME_GLOBAL_RELATIVE_ALT: // solo shot manager incorrectly sends RELATIVE_ALT instead of RELATIVE_ALT_INT case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT: - frame = Location::ALT_FRAME_ABOVE_HOME; + frame = Location::AltFrame::ABOVE_HOME; return true; case MAV_FRAME_GLOBAL_TERRAIN_ALT: case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT: - frame = Location::ALT_FRAME_ABOVE_TERRAIN; + frame = Location::AltFrame::ABOVE_TERRAIN; return true; case MAV_FRAME_GLOBAL: case MAV_FRAME_GLOBAL_INT: - frame = Location::ALT_FRAME_ABSOLUTE; + frame = Location::AltFrame::ABSOLUTE; return true; default: #if CONFIG_HAL_BOARD == HAL_BOARD_SITL