From daa0cb79147050e8931b8fd941ec80d4713f09fe Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 13 Sep 2013 14:31:55 +0900 Subject: [PATCH] Copter: enable motor slow start in auto mode --- ArduCopter/ArduCopter.pde | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 93c3689fd6..00eb304df2 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -2051,6 +2051,11 @@ void update_throttle_mode(void) case THROTTLE_AUTO: // auto pilot altitude controller with target altitude held in wp_nav.get_desired_alt() if(ap.auto_armed) { + // special handling if we are just taking off + if (ap.land_complete) { + // tell motors to do a slow start. + motors.slow_start(true); + } get_throttle_althold_with_slew(wp_nav.get_desired_alt(), -wp_nav.get_descent_velocity(), wp_nav.get_climb_velocity()); set_target_alt_for_reporting(wp_nav.get_desired_alt()); // To-Do: return get_destination_alt if we are flying to a waypoint }else{