From 58505d8242071fe7ceb45f9769de34686c5ed8ac Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 10 Jun 2015 20:04:40 +0900 Subject: [PATCH] Copter: autotune relaxes alt controller when landed --- ArduCopter/control_autotune.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/control_autotune.cpp b/ArduCopter/control_autotune.cpp index 940537ae03..70e618a23f 100644 --- a/ArduCopter/control_autotune.cpp +++ b/ArduCopter/control_autotune.cpp @@ -293,7 +293,7 @@ void Copter::autotune_run() if (ap.land_complete) { // move throttle to between minimum and non-takeoff-throttle to keep us on the ground attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(channel_throttle->control_in),true,g.throttle_filt); - pos_control.set_alt_target_to_current_alt(); + pos_control.relax_alt_hold_controllers(get_throttle_pre_takeoff(channel_throttle->control_in)-throttle_average); }else{ // check if pilot is overriding the controls if (!is_zero(target_roll) || !is_zero(target_pitch) || !is_zero(target_yaw_rate) || !is_zero(target_climb_rate)) {