From d4bbf2fe665f4f9abb5c385ba2ed8b55ca3d82c8 Mon Sep 17 00:00:00 2001 From: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com> Date: Mon, 28 Oct 2024 10:51:16 +0900 Subject: [PATCH] ArduPlane: use frame instead of bools for setting alt frame Signed-off-by: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com> --- ArduPlane/GCS_Mavlink.cpp | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 45a596bc6331a8..849ef79910aa78 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1382,22 +1382,20 @@ void GCS_MAVLINK_Plane::handle_set_position_target_global_int(const mavlink_mess if (pos_target.type_mask & alt_mask) { - cmd.content.location.alt = pos_target.alt * 100; - cmd.content.location.relative_alt = false; - cmd.content.location.terrain_alt = false; + const int32_t alt_cm = pos_target.alt * 100; switch (pos_target.coordinate_frame) { case MAV_FRAME_GLOBAL: case MAV_FRAME_GLOBAL_INT: + cmd.content.location.set_alt_cm(alt_cm, Location::AltFrame::ABSOLUTE); break; //default to MSL altitude case MAV_FRAME_GLOBAL_RELATIVE_ALT: case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT: - cmd.content.location.relative_alt = true; + cmd.content.location.set_alt_cm(alt_cm, Location::AltFrame::ABOVE_HOME); break; case MAV_FRAME_GLOBAL_TERRAIN_ALT: case MAV_FRAME_GLOBAL_TERRAIN_ALT_INT: - cmd.content.location.relative_alt = true; - cmd.content.location.terrain_alt = true; + cmd.content.location.set_alt_cm(alt_cm, Location::AltFrame::ABOVE_TERRAIN); break; default: gcs().send_text(MAV_SEVERITY_WARNING, "Invalid coord frame in SET_POSTION_TARGET_GLOBAL_INT");