From 42672de6060ef0f88b70a5ad6ca0eae3facaa223 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Sun, 23 Oct 2016 17:48:55 +1030 Subject: [PATCH] AC_PosControl: set Alt_Hold filter for PID not just D We normally don't use the D term here so setting the filter for PID not just D lets us smooth the throttle response. --- 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 e880c14f63..05fc986744 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -463,7 +463,7 @@ void AC_PosControl::accel_to_throttle(float accel_target_z) } // set input to PID - _pid_accel_z.set_input_filter_d(_accel_error.z); + _pid_accel_z.set_input_filter_all(_accel_error.z); _pid_accel_z.set_desired_rate(accel_target_z); // separately calculate p, i, d values for logging