Copter: remove slow start from acro

This commit is contained in:
Randy Mackay 2016-02-04 11:58:43 +09:00
parent 3c3b74adc8
commit f6c26ad285
1 changed files with 0 additions and 4 deletions

View File

@ -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;
}