From a87e06e6c2b2d911a4a4c08ff5f5c72fea907891 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Thu, 18 Jun 2015 21:40:35 +0900 Subject: [PATCH] Copter: Autotune Final Tweak --- ArduCopter/control_autotune.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/control_autotune.cpp b/ArduCopter/control_autotune.cpp index f7b993f492..37abf986ce 100644 --- a/ArduCopter/control_autotune.cpp +++ b/ArduCopter/control_autotune.cpp @@ -400,8 +400,8 @@ void Copter::autotune_attitude_control() } break; case AUTOTUNE_AXIS_YAW: - autotune_target_rate = constrain_float(attitude_control.max_rate_step_bf_yaw()/1.5f, AUTOTUNE_TARGET_MIN_RATE_YAW_CDS, AUTOTUNE_TARGET_RATE_YAW_CDS); - autotune_target_angle = constrain_float(attitude_control.max_angle_step_bf_yaw(), AUTOTUNE_TARGET_MIN_ANGLE_YAW_CD, AUTOTUNE_TARGET_ANGLE_YAW_CD); + autotune_target_rate = constrain_float(attitude_control.max_rate_step_bf_yaw()*0.75f, AUTOTUNE_TARGET_MIN_RATE_YAW_CDS, AUTOTUNE_TARGET_RATE_YAW_CDS); + autotune_target_angle = constrain_float(attitude_control.max_angle_step_bf_yaw()*0.75f, AUTOTUNE_TARGET_MIN_ANGLE_YAW_CD, AUTOTUNE_TARGET_ANGLE_YAW_CD); autotune_start_rate = ToDeg(ahrs.get_gyro().z) * 100.0f; autotune_start_angle = ahrs.yaw_sensor; rotation_rate_filt.set_cutoff_frequency(AUTOTUNE_Y_FILT_FREQ);