From f6c26ad285fb4db73db7aad530b66fbc138768ef Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 4 Feb 2016 11:58:43 +0900 Subject: [PATCH] Copter: remove slow start from acro --- ArduCopter/control_acro.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/ArduCopter/control_acro.cpp b/ArduCopter/control_acro.cpp index d974d624b6..93019ea598 100644 --- a/ArduCopter/control_acro.cpp +++ b/ArduCopter/control_acro.cpp @@ -30,10 +30,6 @@ void Copter::acro_run() if (!motors.armed() || ap.throttle_zero || !motors.get_interlock()) { motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); - // slow start if landed - if (ap.land_complete) { - motors.slow_start(true); - } return; }