diff --git a/ArduCopter/control_acro.cpp b/ArduCopter/control_acro.cpp index 89c870818e45bd12781d5d682880476ccd660386..db4042d83bd0f17ab831829e4c029b96bc02ed8a 100644 --- a/ArduCopter/control_acro.cpp +++ b/ArduCopter/control_acro.cpp @@ -23,6 +23,10 @@ void Copter::acro_run() // if motors not running reset angle targets if(!motors.armed() || ap.throttle_zero) { attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); + // slow start if landed + if (ap.land_complete) { + motors.slow_start(true); + } return; } diff --git a/ArduCopter/control_stabilize.cpp b/ArduCopter/control_stabilize.cpp index 4a10e061924895e99ca3c6d16d48da5ee6a6d94d..1390260886b0846ff121576a7e439c8431fe06ed 100644 --- a/ArduCopter/control_stabilize.cpp +++ b/ArduCopter/control_stabilize.cpp @@ -28,6 +28,10 @@ void Copter::stabilize_run() // if not armed or throttle at zero, set throttle to zero and exit immediately if(!motors.armed() || ap.throttle_zero) { attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); + // slow start if landed + if (ap.land_complete) { + motors.slow_start(true); + } return; }