mirror of https://github.com/ArduPilot/ardupilot
Copter: removed slow_start() from throw mode
This commit is contained in:
parent
3ee88fd8c7
commit
c035ade402
|
@ -124,8 +124,6 @@ void Copter::throw_run()
|
|||
|
||||
// demand zero throttle (motors will be stopped anyway) and continually reset the attitude controller
|
||||
attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt);
|
||||
motors.slow_start(true);
|
||||
|
||||
break;
|
||||
|
||||
case Throw_Detecting:
|
||||
|
|
Loading…
Reference in New Issue