From ac7ea2a12c265ff477d9526fb7564c2054a960df Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 27 Oct 2014 14:59:08 +0900 Subject: [PATCH] AC_PosControl: use AttControl's sqrt_controller --- libraries/AC_AttitudeControl/AC_PosControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 9be7b097df..0f5352a76c 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -274,7 +274,7 @@ void AC_PosControl::pos_to_rate_z() } // calculate _vel_target.z using from _pos_error.z using sqrt controller - _vel_target.z = sqrt_controller(_pos_error.z, _p_alt_pos.kP(), _accel_z_cms); + _vel_target.z = AC_AttitudeControl::sqrt_controller(_pos_error.z, _p_alt_pos.kP(), _accel_z_cms); // call rate based throttle controller which will update accel based throttle controller targets rate_to_accel_z();