From 1ab985fff87d982464921158ef495c4ab89eb389 Mon Sep 17 00:00:00 2001 From: xianglunkai <1322099375@qq.com> Date: Thu, 15 Jun 2023 14:54:19 +0800 Subject: [PATCH] AC_CustomControl_PID: set false to avoid hitting limits --- libraries/AC_CustomControl/AC_CustomControl_PID.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AC_CustomControl/AC_CustomControl_PID.cpp b/libraries/AC_CustomControl/AC_CustomControl_PID.cpp index 7876e8a0b6..29e2163cbb 100644 --- a/libraries/AC_CustomControl/AC_CustomControl_PID.cpp +++ b/libraries/AC_CustomControl/AC_CustomControl_PID.cpp @@ -290,9 +290,9 @@ Vector3f AC_CustomControl_PID::update() // run rate controller Vector3f gyro_latest = _ahrs->get_gyro_latest(); Vector3f motor_out; - motor_out.x = _pid_atti_rate_roll.update_all(target_rate[0], gyro_latest[0], _dt, true); - motor_out.y = _pid_atti_rate_pitch.update_all(target_rate[1], gyro_latest[1], _dt, true); - motor_out.z = _pid_atti_rate_yaw.update_all(target_rate[2], gyro_latest[2], _dt, true); + motor_out.x = _pid_atti_rate_roll.update_all(target_rate[0], gyro_latest[0], _dt, false); + motor_out.y = _pid_atti_rate_pitch.update_all(target_rate[1], gyro_latest[1], _dt, false); + motor_out.z = _pid_atti_rate_yaw.update_all(target_rate[2], gyro_latest[2], _dt, false); return motor_out; }