From 285f2dd7910260d9c9847b89d1a96b52ff73fff5 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 10 Mar 2012 12:38:29 -0800 Subject: [PATCH] ACM: removed the experiment for rate error. --- ArduCopter/Attitude.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index dba7ce508d..277e87561b 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -204,8 +204,8 @@ get_nav_throttle(int32_t z_error) rate_error = rate_error - climb_rate; // hack to see if we can smooth out oscillations - if(rate_error < 0) - rate_error = rate_error >> 1; + //if(rate_error < 0) + // rate_error = rate_error >> 1; // limit the rate output = constrain(g.pid_throttle.get_pid(rate_error, .02), -80, 120);