From 935ea02a711b88f639690031f1766ee13e72ef66 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Fri, 27 Oct 2023 00:17:23 +0100 Subject: [PATCH] Copter: RTL: ensure rally point is in absolute alt frame as RTL_ALT_TYPE takes precedence --- ArduCopter/mode_rtl.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ArduCopter/mode_rtl.cpp b/ArduCopter/mode_rtl.cpp index 795e483e93..7c74838a3f 100644 --- a/ArduCopter/mode_rtl.cpp +++ b/ArduCopter/mode_rtl.cpp @@ -408,9 +408,10 @@ void ModeRTL::build_path() // return target's altitude is updated to a higher altitude that the vehicle can safely return at (frame may also be set) void ModeRTL::compute_return_target() { - // set return target to nearest rally point or home position (Note: alt is absolute) + // set return target to nearest rally point or home position #if HAL_RALLY_ENABLED rtl_path.return_target = copter.rally.calc_best_rally_or_home_location(copter.current_loc, ahrs.get_home().alt); + rtl_path.return_target.change_alt_frame(Location::AltFrame::ABSOLUTE); #else rtl_path.return_target = ahrs.get_home(); #endif