From ef6b1733264c90a6620f9f6ce4efc40e07c8ea96 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 27 Jul 2015 16:37:37 +0900 Subject: [PATCH] Copter: slow start motors after landing in Stabilize, Acro --- ArduCopter/control_acro.cpp | 4 ++++ ArduCopter/control_stabilize.cpp | 4 ++++ 2 files changed, 8 insertions(+) diff --git a/ArduCopter/control_acro.cpp b/ArduCopter/control_acro.cpp index 89c870818e..db4042d83b 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 4a10e06192..1390260886 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; }