diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 2fe6869c3c..a43543b79a 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -449,8 +449,6 @@ get_throttle_rate(int16_t z_target_speed) int16_t tmp = ((int32_t)z_target_speed * (int32_t)g.throttle_cruise) / 280; tmp = min(tmp, 500); - if(z_target_speed < 0) tmp = -tmp; - // separately calculate p, i, d values for logging p = g.pid_throttle.get_p(z_rate_error);