diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 55cd5624a4..d335956dc8 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -1995,8 +1995,13 @@ void update_throttle_mode(void) 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{ +#if FRAME_CONFIG == HELI_FRAME + // collective pitch should not be full negative to avoid harshing the mechanics. Use Stab Coll Min. + set_throttle_out(motors.stab_col_min*10, false); +#else // pilot's throttle must be at zero so keep motors off set_throttle_out(0, false); +#endif // HELI_FRAME // deactivate accel based throttle controller throttle_accel_deactivate(); set_target_alt_for_reporting(0);