diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index ccc47768f5..fd2a7951bd 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -991,6 +991,8 @@ set_throttle_takeoff() if (g.pid_throttle_accel.get_integrator() < 0) { g.pid_throttle_accel.reset_I(); } + // tell motors to do a slow start + motors.slow_start(true); } // get_throttle_accel - accelerometer based throttle controller