From e2308e94149088aedcb253cc10c01d357f7e2df4 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Tue, 8 Sep 2020 00:01:06 +0930 Subject: [PATCH] AC_Loiter: use AP_Math control tools common functions --- libraries/AC_WPNav/AC_Loiter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_WPNav/AC_Loiter.cpp b/libraries/AC_WPNav/AC_Loiter.cpp index 38647ac45f..2477f11820 100644 --- a/libraries/AC_WPNav/AC_Loiter.cpp +++ b/libraries/AC_WPNav/AC_Loiter.cpp @@ -279,7 +279,7 @@ void AC_Loiter::calc_desired_velocity(float nav_dt) if (_desired_accel.is_zero()) { if ((AP_HAL::millis()-_brake_timer) > _brake_delay * 1000.0f) { float brake_gain = _pos_control.get_vel_xy_pid().kP() * 0.5f; - loiter_brake_accel = constrain_float(AC_AttitudeControl::sqrt_controller(desired_speed, brake_gain, _brake_jerk_max_cmsss, nav_dt), 0.0f, _brake_accel_cmss); + loiter_brake_accel = constrain_float(sqrt_controller(desired_speed, brake_gain, _brake_jerk_max_cmsss, nav_dt), 0.0f, _brake_accel_cmss); } } else { loiter_brake_accel = 0.0f;