AC_AutoTune: correct incorrect min raw rate valuee

This commit is contained in:
Andy Piper 2023-06-24 21:56:38 +01:00 committed by Andrew Tridgell
parent 86b6785fca
commit f7e657f6c5
1 changed files with 1 additions and 1 deletions

View File

@ -1110,7 +1110,7 @@ void AC_AutoTune_Multi::twitch_test_init()
}
case YAW:
case YAW_D: {
target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_RLLPIT_CDS, step_scaler*AUTOTUNE_TARGET_RATE_YAW_CDS);
target_max_rate = MAX(AUTOTUNE_TARGET_MIN_RATE_YAW_CDS, step_scaler*AUTOTUNE_TARGET_RATE_YAW_CDS);
target_rate = constrain_float(ToDeg(attitude_control->max_rate_step_bf_yaw()*0.75f)*100.0f, AUTOTUNE_TARGET_MIN_RATE_YAW_CDS, target_max_rate);
target_angle = constrain_float(ToDeg(attitude_control->max_angle_step_bf_yaw()*0.75f)*100.0f, AUTOTUNE_TARGET_MIN_ANGLE_YAW_CD, AUTOTUNE_TARGET_ANGLE_YAW_CD);
if (axis == YAW_D) {