diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index e32ea0cd9d..16c6cd59fe 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -165,7 +165,8 @@ get_nav_throttle(int32_t z_error) //output -= constrain(rate_d, -25, 25); // light filter of output - output = (old_output * 3 + output) / 4; + //output = (old_output * 3 + output) / 4; + output = (old_output + output) / 2; // save our output old_output = output;