From f9192b0c2c04a91841e99ecc9a3a522b780b6897 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Fri, 24 Dec 2021 00:56:33 +1030 Subject: [PATCH] AC_Loiter: use Pos_Control soften_for_landing_xy --- libraries/AC_WPNav/AC_Loiter.cpp | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/libraries/AC_WPNav/AC_Loiter.cpp b/libraries/AC_WPNav/AC_Loiter.cpp index 30f506529a..edfd47ada6 100644 --- a/libraries/AC_WPNav/AC_Loiter.cpp +++ b/libraries/AC_WPNav/AC_Loiter.cpp @@ -132,14 +132,7 @@ void AC_Loiter::init_target() /// reduce response for landing void AC_Loiter::soften_for_landing() { - const Vector3f& curr_pos = _inav.get_position_neu_cm(); - - // set target position to current position - _pos_control.set_pos_target_xy_cm(curr_pos.x, curr_pos.y); - - // also prevent I term build up in xy velocity controller. Note - // that this flag is reset on each loop, in update_xy_controller() - _pos_control.set_externally_limited_xy(); + _pos_control.soften_for_landing_xy(); } /// set pilot desired acceleration in centi-degrees