From 3c3b74adc86abed5515cb3a6bf4793270bc91549 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 4 Feb 2016 11:58:00 +0900 Subject: [PATCH] Copter: remove slow_start from takeoff --- ArduCopter/Attitude.cpp | 3 --- 1 file changed, 3 deletions(-) diff --git a/ArduCopter/Attitude.cpp b/ArduCopter/Attitude.cpp index e4e0c166f2..1513027533 100644 --- a/ArduCopter/Attitude.cpp +++ b/ArduCopter/Attitude.cpp @@ -126,9 +126,6 @@ void Copter::set_throttle_takeoff() { // tell position controller to reset alt target and reset I terms pos_control.init_takeoff(); - - // tell motors to do a slow start - motors.slow_start(true); } // get_pilot_desired_throttle - transform pilot's throttle input to make cruise throttle mid stick