diff --git a/ArduPlane/mode_LoiterAltQLand.cpp b/ArduPlane/mode_LoiterAltQLand.cpp index 8fbfd59735..72ac41a555 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);