From 31c7e696ddf2249605e6e94207ff2e7263f78032 Mon Sep 17 00:00:00 2001 From: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com> Date: Wed, 6 Nov 2024 01:20:23 -0700 Subject: [PATCH] ArduPlane: use set_alt_m when possible Signed-off-by: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com> --- ArduPlane/mode_LoiterAltQLand.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduPlane/mode_LoiterAltQLand.cpp b/ArduPlane/mode_LoiterAltQLand.cpp index 8fbfd59735cd2..72ac41a5557aa 100644 --- a/ArduPlane/mode_LoiterAltQLand.cpp +++ b/ArduPlane/mode_LoiterAltQLand.cpp @@ -43,12 +43,12 @@ bool ModeLoiterAltQLand::handle_guided_request(Location target_loc) // setup altitude #if AP_TERRAIN_AVAILABLE if (plane.terrain_enabled_in_mode(Mode::Number::QLAND)) { - target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_TERRAIN); + target_loc.set_alt_m(quadplane.qrtl_alt, Location::AltFrame::ABOVE_TERRAIN); } else { - target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME); + target_loc.set_alt_m(quadplane.qrtl_alt, Location::AltFrame::ABOVE_HOME); } #else - target_loc.set_alt_cm(quadplane.qrtl_alt*100UL, Location::AltFrame::ABOVE_HOME); + target_loc.set_alt_m(quadplane.qrtl_alt, Location::AltFrame::ABOVE_HOME); #endif plane.set_guided_WP(target_loc);