From 09a35cf90f1f112d0c2e19cc4e39ea15b79e0792 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 23 Apr 2014 11:16:41 +0900 Subject: [PATCH] AC_PosControl: bugfix for freezing I-term build-up --- 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 80a5e3fd6d..bb02bfe005 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -618,7 +618,7 @@ void AC_PosControl::rate_to_accel_xy(float dt) lat_i = _pid_rate_lat.get_i(_vel_error.x, dt); } if ((!_limit.accel_xy && !_motors.limit.throttle_upper) || ((lon_i>0&&_vel_error.y<0)||(lon_i<0&&_vel_error.y>0))) { - lon_i = _pid_rate_lat.get_i(_vel_error.y, dt); + lon_i = _pid_rate_lon.get_i(_vel_error.y, dt); } // combine feed forward accel with PID output from velocity error