AC_AutoTune: rename pid setters to include set_ in the names

This commit is contained in:
Peter Barker 2024-07-30 21:37:50 +10:00 committed by Andrew Tridgell
parent fae3b39b15
commit 7f4074a22c
2 changed files with 142 additions and 142 deletions

View File

@ -599,37 +599,37 @@ void AC_AutoTune_Heli::load_gain_set(AxisType s_axis, float rate_p, float rate_i
{
switch (s_axis) {
case AxisType::ROLL:
attitude_control->get_rate_roll_pid().kP(rate_p);
attitude_control->get_rate_roll_pid().kI(rate_i);
attitude_control->get_rate_roll_pid().kD(rate_d);
attitude_control->get_rate_roll_pid().ff(rate_ff);
attitude_control->get_rate_roll_pid().filt_T_hz(rate_fltt);
attitude_control->get_rate_roll_pid().slew_limit(smax);
attitude_control->get_angle_roll_p().kP(angle_p);
attitude_control->get_rate_roll_pid().set_kP(rate_p);
attitude_control->get_rate_roll_pid().set_kI(rate_i);
attitude_control->get_rate_roll_pid().set_kD(rate_d);
attitude_control->get_rate_roll_pid().set_ff(rate_ff);
attitude_control->get_rate_roll_pid().set_filt_T_hz(rate_fltt);
attitude_control->get_rate_roll_pid().set_slew_limit(smax);
attitude_control->get_angle_roll_p().set_kP(angle_p);
attitude_control->set_accel_roll_max_cdss(max_accel);
attitude_control->set_ang_vel_roll_max_degs(max_rate);
break;
case AxisType::PITCH:
attitude_control->get_rate_pitch_pid().kP(rate_p);
attitude_control->get_rate_pitch_pid().kI(rate_i);
attitude_control->get_rate_pitch_pid().kD(rate_d);
attitude_control->get_rate_pitch_pid().ff(rate_ff);
attitude_control->get_rate_pitch_pid().filt_T_hz(rate_fltt);
attitude_control->get_rate_pitch_pid().slew_limit(smax);
attitude_control->get_angle_pitch_p().kP(angle_p);
attitude_control->get_rate_pitch_pid().set_kP(rate_p);
attitude_control->get_rate_pitch_pid().set_kI(rate_i);
attitude_control->get_rate_pitch_pid().set_kD(rate_d);
attitude_control->get_rate_pitch_pid().set_ff(rate_ff);
attitude_control->get_rate_pitch_pid().set_filt_T_hz(rate_fltt);
attitude_control->get_rate_pitch_pid().set_slew_limit(smax);
attitude_control->get_angle_pitch_p().set_kP(angle_p);
attitude_control->set_accel_pitch_max_cdss(max_accel);
attitude_control->set_ang_vel_pitch_max_degs(max_rate);
break;
case AxisType::YAW:
case AxisType::YAW_D:
attitude_control->get_rate_yaw_pid().kP(rate_p);
attitude_control->get_rate_yaw_pid().kI(rate_i);
attitude_control->get_rate_yaw_pid().kD(rate_d);
attitude_control->get_rate_yaw_pid().ff(rate_ff);
attitude_control->get_rate_yaw_pid().filt_T_hz(rate_fltt);
attitude_control->get_rate_yaw_pid().slew_limit(smax);
attitude_control->get_rate_yaw_pid().filt_E_hz(rate_flte);
attitude_control->get_angle_yaw_p().kP(angle_p);
attitude_control->get_rate_yaw_pid().set_kP(rate_p);
attitude_control->get_rate_yaw_pid().set_kI(rate_i);
attitude_control->get_rate_yaw_pid().set_kD(rate_d);
attitude_control->get_rate_yaw_pid().set_ff(rate_ff);
attitude_control->get_rate_yaw_pid().set_filt_T_hz(rate_fltt);
attitude_control->get_rate_yaw_pid().set_slew_limit(smax);
attitude_control->get_rate_yaw_pid().set_filt_E_hz(rate_flte);
attitude_control->get_angle_yaw_p().set_kP(angle_p);
attitude_control->set_accel_yaw_max_cdss(max_accel);
attitude_control->set_ang_vel_yaw_max_degs(max_rate);
break;

View File

@ -212,41 +212,41 @@ void AC_AutoTune_Multi::load_orig_gains()
attitude_control->bf_feedforward(orig_bf_feedforward);
if (roll_enabled()) {
if (!is_zero(orig_roll_rp)) {
attitude_control->get_rate_roll_pid().kP(orig_roll_rp);
attitude_control->get_rate_roll_pid().kI(orig_roll_ri);
attitude_control->get_rate_roll_pid().kD(orig_roll_rd);
attitude_control->get_rate_roll_pid().ff(orig_roll_rff);
attitude_control->get_rate_roll_pid().kDff(orig_roll_dff);
attitude_control->get_rate_roll_pid().filt_T_hz(orig_roll_fltt);
attitude_control->get_rate_roll_pid().slew_limit(orig_roll_smax);
attitude_control->get_angle_roll_p().kP(orig_roll_sp);
attitude_control->get_rate_roll_pid().set_kP(orig_roll_rp);
attitude_control->get_rate_roll_pid().set_kI(orig_roll_ri);
attitude_control->get_rate_roll_pid().set_kD(orig_roll_rd);
attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff);
attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff);
attitude_control->get_rate_roll_pid().set_filt_T_hz(orig_roll_fltt);
attitude_control->get_rate_roll_pid().set_slew_limit(orig_roll_smax);
attitude_control->get_angle_roll_p().set_kP(orig_roll_sp);
attitude_control->set_accel_roll_max_cdss(orig_roll_accel);
}
}
if (pitch_enabled()) {
if (!is_zero(orig_pitch_rp)) {
attitude_control->get_rate_pitch_pid().kP(orig_pitch_rp);
attitude_control->get_rate_pitch_pid().kI(orig_pitch_ri);
attitude_control->get_rate_pitch_pid().kD(orig_pitch_rd);
attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff);
attitude_control->get_rate_pitch_pid().kDff(orig_pitch_dff);
attitude_control->get_rate_pitch_pid().filt_T_hz(orig_pitch_fltt);
attitude_control->get_rate_pitch_pid().slew_limit(orig_pitch_smax);
attitude_control->get_angle_pitch_p().kP(orig_pitch_sp);
attitude_control->get_rate_pitch_pid().set_kP(orig_pitch_rp);
attitude_control->get_rate_pitch_pid().set_kI(orig_pitch_ri);
attitude_control->get_rate_pitch_pid().set_kD(orig_pitch_rd);
attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff);
attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff);
attitude_control->get_rate_pitch_pid().set_filt_T_hz(orig_pitch_fltt);
attitude_control->get_rate_pitch_pid().set_slew_limit(orig_pitch_smax);
attitude_control->get_angle_pitch_p().set_kP(orig_pitch_sp);
attitude_control->set_accel_pitch_max_cdss(orig_pitch_accel);
}
}
if (yaw_enabled() || yaw_d_enabled()) {
if (!is_zero(orig_yaw_rp)) {
attitude_control->get_rate_yaw_pid().kP(orig_yaw_rp);
attitude_control->get_rate_yaw_pid().kI(orig_yaw_ri);
attitude_control->get_rate_yaw_pid().kD(orig_yaw_rd);
attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff);
attitude_control->get_rate_yaw_pid().kDff(orig_yaw_dff);
attitude_control->get_rate_yaw_pid().filt_E_hz(orig_yaw_rLPF);
attitude_control->get_rate_yaw_pid().filt_T_hz(orig_yaw_fltt);
attitude_control->get_rate_yaw_pid().slew_limit(orig_yaw_smax);
attitude_control->get_angle_yaw_p().kP(orig_yaw_sp);
attitude_control->get_rate_yaw_pid().set_kP(orig_yaw_rp);
attitude_control->get_rate_yaw_pid().set_kI(orig_yaw_ri);
attitude_control->get_rate_yaw_pid().set_kD(orig_yaw_rd);
attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff);
attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff);
attitude_control->get_rate_yaw_pid().set_filt_E_hz(orig_yaw_rLPF);
attitude_control->get_rate_yaw_pid().set_filt_T_hz(orig_yaw_fltt);
attitude_control->get_rate_yaw_pid().set_slew_limit(orig_yaw_smax);
attitude_control->get_angle_yaw_p().set_kP(orig_yaw_sp);
attitude_control->set_accel_yaw_max_cdss(orig_yaw_accel);
}
}
@ -262,39 +262,39 @@ void AC_AutoTune_Multi::load_tuned_gains()
}
if (roll_enabled()) {
if (!is_zero(tune_roll_rp)) {
attitude_control->get_rate_roll_pid().kP(tune_roll_rp);
attitude_control->get_rate_roll_pid().kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);
attitude_control->get_rate_roll_pid().kD(tune_roll_rd);
attitude_control->get_rate_roll_pid().ff(orig_roll_rff);
attitude_control->get_rate_roll_pid().kDff(orig_roll_dff);
attitude_control->get_angle_roll_p().kP(tune_roll_sp);
attitude_control->get_rate_roll_pid().set_kP(tune_roll_rp);
attitude_control->get_rate_roll_pid().set_kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);
attitude_control->get_rate_roll_pid().set_kD(tune_roll_rd);
attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff);
attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff);
attitude_control->get_angle_roll_p().set_kP(tune_roll_sp);
attitude_control->set_accel_roll_max_cdss(tune_roll_accel);
}
}
if (pitch_enabled()) {
if (!is_zero(tune_pitch_rp)) {
attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp);
attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);
attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd);
attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff);
attitude_control->get_rate_pitch_pid().kDff(orig_pitch_dff);
attitude_control->get_angle_pitch_p().kP(tune_pitch_sp);
attitude_control->get_rate_pitch_pid().set_kP(tune_pitch_rp);
attitude_control->get_rate_pitch_pid().set_kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);
attitude_control->get_rate_pitch_pid().set_kD(tune_pitch_rd);
attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff);
attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff);
attitude_control->get_angle_pitch_p().set_kP(tune_pitch_sp);
attitude_control->set_accel_pitch_max_cdss(tune_pitch_accel);
}
}
if (yaw_enabled() || yaw_d_enabled()) {
if (!is_zero(tune_yaw_rp)) {
attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp);
attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL);
attitude_control->get_rate_yaw_pid().set_kP(tune_yaw_rp);
attitude_control->get_rate_yaw_pid().set_kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL);
if (yaw_d_enabled()) {
attitude_control->get_rate_yaw_pid().kD(tune_yaw_rd);
attitude_control->get_rate_yaw_pid().set_kD(tune_yaw_rd);
}
if (yaw_enabled()) {
attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF);
attitude_control->get_rate_yaw_pid().set_filt_E_hz(tune_yaw_rLPF);
}
attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff);
attitude_control->get_rate_yaw_pid().kDff(orig_yaw_dff);
attitude_control->get_angle_yaw_p().kP(tune_yaw_sp);
attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff);
attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff);
attitude_control->get_angle_yaw_p().set_kP(tune_yaw_sp);
attitude_control->set_accel_yaw_max_cdss(tune_yaw_accel);
}
}
@ -308,35 +308,35 @@ void AC_AutoTune_Multi::load_intra_test_gains()
// sanity check the gains
attitude_control->bf_feedforward(true);
if (roll_enabled()) {
attitude_control->get_rate_roll_pid().kP(orig_roll_rp);
attitude_control->get_rate_roll_pid().kI(orig_roll_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
attitude_control->get_rate_roll_pid().kD(orig_roll_rd);
attitude_control->get_rate_roll_pid().ff(orig_roll_rff);
attitude_control->get_rate_roll_pid().kDff(orig_roll_dff);
attitude_control->get_rate_roll_pid().filt_T_hz(orig_roll_fltt);
attitude_control->get_rate_roll_pid().slew_limit(orig_roll_smax);
attitude_control->get_angle_roll_p().kP(orig_roll_sp);
attitude_control->get_rate_roll_pid().set_kP(orig_roll_rp);
attitude_control->get_rate_roll_pid().set_kI(orig_roll_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
attitude_control->get_rate_roll_pid().set_kD(orig_roll_rd);
attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff);
attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff);
attitude_control->get_rate_roll_pid().set_filt_T_hz(orig_roll_fltt);
attitude_control->get_rate_roll_pid().set_slew_limit(orig_roll_smax);
attitude_control->get_angle_roll_p().set_kP(orig_roll_sp);
}
if (pitch_enabled()) {
attitude_control->get_rate_pitch_pid().kP(orig_pitch_rp);
attitude_control->get_rate_pitch_pid().kI(orig_pitch_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
attitude_control->get_rate_pitch_pid().kD(orig_pitch_rd);
attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff);
attitude_control->get_rate_pitch_pid().kDff(orig_pitch_dff);
attitude_control->get_rate_pitch_pid().filt_T_hz(orig_pitch_fltt);
attitude_control->get_rate_pitch_pid().slew_limit(orig_pitch_smax);
attitude_control->get_angle_pitch_p().kP(orig_pitch_sp);
attitude_control->get_rate_pitch_pid().set_kP(orig_pitch_rp);
attitude_control->get_rate_pitch_pid().set_kI(orig_pitch_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
attitude_control->get_rate_pitch_pid().set_kD(orig_pitch_rd);
attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff);
attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff);
attitude_control->get_rate_pitch_pid().set_filt_T_hz(orig_pitch_fltt);
attitude_control->get_rate_pitch_pid().set_slew_limit(orig_pitch_smax);
attitude_control->get_angle_pitch_p().set_kP(orig_pitch_sp);
}
if (yaw_enabled() || yaw_d_enabled()) {
attitude_control->get_rate_yaw_pid().kP(orig_yaw_rp);
attitude_control->get_rate_yaw_pid().kI(orig_yaw_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
attitude_control->get_rate_yaw_pid().kD(orig_yaw_rd);
attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff);
attitude_control->get_rate_yaw_pid().kDff(orig_yaw_dff);
attitude_control->get_rate_yaw_pid().filt_T_hz(orig_yaw_fltt);
attitude_control->get_rate_yaw_pid().slew_limit(orig_yaw_smax);
attitude_control->get_rate_yaw_pid().filt_E_hz(orig_yaw_rLPF);
attitude_control->get_angle_yaw_p().kP(orig_yaw_sp);
attitude_control->get_rate_yaw_pid().set_kP(orig_yaw_rp);
attitude_control->get_rate_yaw_pid().set_kI(orig_yaw_rp*AUTOTUNE_PI_RATIO_FOR_TESTING);
attitude_control->get_rate_yaw_pid().set_kD(orig_yaw_rd);
attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff);
attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff);
attitude_control->get_rate_yaw_pid().set_filt_T_hz(orig_yaw_fltt);
attitude_control->get_rate_yaw_pid().set_slew_limit(orig_yaw_smax);
attitude_control->get_rate_yaw_pid().set_filt_E_hz(orig_yaw_rLPF);
attitude_control->get_angle_yaw_p().set_kP(orig_yaw_sp);
}
}
@ -346,40 +346,40 @@ void AC_AutoTune_Multi::load_test_gains()
{
switch (axis) {
case AxisType::ROLL:
attitude_control->get_rate_roll_pid().kP(tune_roll_rp);
attitude_control->get_rate_roll_pid().kI(tune_roll_rp * 0.01);
attitude_control->get_rate_roll_pid().kD(tune_roll_rd);
attitude_control->get_rate_roll_pid().ff(0.0);
attitude_control->get_rate_roll_pid().kDff(0.0);
attitude_control->get_rate_roll_pid().filt_T_hz(0.0);
attitude_control->get_rate_roll_pid().slew_limit(0.0);
attitude_control->get_angle_roll_p().kP(tune_roll_sp);
attitude_control->get_rate_roll_pid().set_kP(tune_roll_rp);
attitude_control->get_rate_roll_pid().set_kI(tune_roll_rp * 0.01);
attitude_control->get_rate_roll_pid().set_kD(tune_roll_rd);
attitude_control->get_rate_roll_pid().set_ff(0.0);
attitude_control->get_rate_roll_pid().set_kDff(0.0);
attitude_control->get_rate_roll_pid().set_filt_T_hz(0.0);
attitude_control->get_rate_roll_pid().set_slew_limit(0.0);
attitude_control->get_angle_roll_p().set_kP(tune_roll_sp);
break;
case AxisType::PITCH:
attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp);
attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp * 0.01);
attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd);
attitude_control->get_rate_pitch_pid().ff(0.0);
attitude_control->get_rate_pitch_pid().kDff(0.0);
attitude_control->get_rate_pitch_pid().filt_T_hz(0.0);
attitude_control->get_rate_pitch_pid().slew_limit(0.0);
attitude_control->get_angle_pitch_p().kP(tune_pitch_sp);
attitude_control->get_rate_pitch_pid().set_kP(tune_pitch_rp);
attitude_control->get_rate_pitch_pid().set_kI(tune_pitch_rp * 0.01);
attitude_control->get_rate_pitch_pid().set_kD(tune_pitch_rd);
attitude_control->get_rate_pitch_pid().set_ff(0.0);
attitude_control->get_rate_pitch_pid().set_kDff(0.0);
attitude_control->get_rate_pitch_pid().set_filt_T_hz(0.0);
attitude_control->get_rate_pitch_pid().set_slew_limit(0.0);
attitude_control->get_angle_pitch_p().set_kP(tune_pitch_sp);
break;
case AxisType::YAW:
case AxisType::YAW_D:
attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp);
attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp * 0.01);
attitude_control->get_rate_yaw_pid().ff(0.0);
attitude_control->get_rate_yaw_pid().kDff(0.0);
attitude_control->get_rate_yaw_pid().set_kP(tune_yaw_rp);
attitude_control->get_rate_yaw_pid().set_kI(tune_yaw_rp * 0.01);
attitude_control->get_rate_yaw_pid().set_ff(0.0);
attitude_control->get_rate_yaw_pid().set_kDff(0.0);
if (axis == AxisType::YAW_D) {
attitude_control->get_rate_yaw_pid().kD(tune_yaw_rd);
attitude_control->get_rate_yaw_pid().set_kD(tune_yaw_rd);
} else {
attitude_control->get_rate_yaw_pid().kD(0.0);
attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF);
attitude_control->get_rate_yaw_pid().set_kD(0.0);
attitude_control->get_rate_yaw_pid().set_filt_E_hz(tune_yaw_rLPF);
}
attitude_control->get_rate_yaw_pid().filt_T_hz(0.0);
attitude_control->get_rate_yaw_pid().slew_limit(0.0);
attitude_control->get_angle_yaw_p().kP(tune_yaw_sp);
attitude_control->get_rate_yaw_pid().set_filt_T_hz(0.0);
attitude_control->get_rate_yaw_pid().set_slew_limit(0.0);
attitude_control->get_angle_yaw_p().set_kP(tune_yaw_sp);
break;
}
}
@ -402,17 +402,17 @@ void AC_AutoTune_Multi::save_tuning_gains()
// sanity check the rate P values
if ((axes_completed & AUTOTUNE_AXIS_BITMASK_ROLL) && roll_enabled() && !is_zero(tune_roll_rp)) {
// rate roll gains
attitude_control->get_rate_roll_pid().kP(tune_roll_rp);
attitude_control->get_rate_roll_pid().kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);
attitude_control->get_rate_roll_pid().kD(tune_roll_rd);
attitude_control->get_rate_roll_pid().ff(orig_roll_rff);
attitude_control->get_rate_roll_pid().kDff(orig_roll_dff);
attitude_control->get_rate_roll_pid().filt_T_hz(orig_roll_fltt);
attitude_control->get_rate_roll_pid().slew_limit(orig_roll_smax);
attitude_control->get_rate_roll_pid().set_kP(tune_roll_rp);
attitude_control->get_rate_roll_pid().set_kI(tune_roll_rp*AUTOTUNE_PI_RATIO_FINAL);
attitude_control->get_rate_roll_pid().set_kD(tune_roll_rd);
attitude_control->get_rate_roll_pid().set_ff(orig_roll_rff);
attitude_control->get_rate_roll_pid().set_kDff(orig_roll_dff);
attitude_control->get_rate_roll_pid().set_filt_T_hz(orig_roll_fltt);
attitude_control->get_rate_roll_pid().set_slew_limit(orig_roll_smax);
attitude_control->get_rate_roll_pid().save_gains();
// stabilize roll
attitude_control->get_angle_roll_p().kP(tune_roll_sp);
attitude_control->get_angle_roll_p().set_kP(tune_roll_sp);
attitude_control->get_angle_roll_p().save_gains();
// acceleration roll
@ -430,17 +430,17 @@ void AC_AutoTune_Multi::save_tuning_gains()
if ((axes_completed & AUTOTUNE_AXIS_BITMASK_PITCH) && pitch_enabled() && !is_zero(tune_pitch_rp)) {
// rate pitch gains
attitude_control->get_rate_pitch_pid().kP(tune_pitch_rp);
attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);
attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd);
attitude_control->get_rate_pitch_pid().ff(orig_pitch_rff);
attitude_control->get_rate_pitch_pid().kDff(orig_pitch_dff);
attitude_control->get_rate_pitch_pid().filt_T_hz(orig_pitch_fltt);
attitude_control->get_rate_pitch_pid().slew_limit(orig_pitch_smax);
attitude_control->get_rate_pitch_pid().set_kP(tune_pitch_rp);
attitude_control->get_rate_pitch_pid().set_kI(tune_pitch_rp*AUTOTUNE_PI_RATIO_FINAL);
attitude_control->get_rate_pitch_pid().set_kD(tune_pitch_rd);
attitude_control->get_rate_pitch_pid().set_ff(orig_pitch_rff);
attitude_control->get_rate_pitch_pid().set_kDff(orig_pitch_dff);
attitude_control->get_rate_pitch_pid().set_filt_T_hz(orig_pitch_fltt);
attitude_control->get_rate_pitch_pid().set_slew_limit(orig_pitch_smax);
attitude_control->get_rate_pitch_pid().save_gains();
// stabilize pitch
attitude_control->get_angle_pitch_p().kP(tune_pitch_sp);
attitude_control->get_angle_pitch_p().set_kP(tune_pitch_sp);
attitude_control->get_angle_pitch_p().save_gains();
// acceleration pitch
@ -459,22 +459,22 @@ void AC_AutoTune_Multi::save_tuning_gains()
if ((((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW) && yaw_enabled())
|| ((axes_completed & AUTOTUNE_AXIS_BITMASK_YAW_D) && yaw_d_enabled())) && !is_zero(tune_yaw_rp)) {
// rate yaw gains
attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp);
attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL);
attitude_control->get_rate_yaw_pid().ff(orig_yaw_rff);
attitude_control->get_rate_yaw_pid().kDff(orig_yaw_dff);
attitude_control->get_rate_yaw_pid().filt_T_hz(orig_yaw_fltt);
attitude_control->get_rate_yaw_pid().slew_limit(orig_yaw_smax);
attitude_control->get_rate_yaw_pid().set_kP(tune_yaw_rp);
attitude_control->get_rate_yaw_pid().set_kI(tune_yaw_rp*AUTOTUNE_YAW_PI_RATIO_FINAL);
attitude_control->get_rate_yaw_pid().set_ff(orig_yaw_rff);
attitude_control->get_rate_yaw_pid().set_kDff(orig_yaw_dff);
attitude_control->get_rate_yaw_pid().set_filt_T_hz(orig_yaw_fltt);
attitude_control->get_rate_yaw_pid().set_slew_limit(orig_yaw_smax);
if (yaw_d_enabled()) {
attitude_control->get_rate_yaw_pid().kD(tune_yaw_rd);
attitude_control->get_rate_yaw_pid().set_kD(tune_yaw_rd);
}
if (yaw_enabled()) {
attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF);
attitude_control->get_rate_yaw_pid().set_filt_E_hz(tune_yaw_rLPF);
}
attitude_control->get_rate_yaw_pid().save_gains();
// stabilize yaw
attitude_control->get_angle_yaw_p().kP(tune_yaw_sp);
attitude_control->get_angle_yaw_p().set_kP(tune_yaw_sp);
attitude_control->get_angle_yaw_p().save_gains();
// acceleration yaw