mirror of https://github.com/ArduPilot/ardupilot
AC_AutoTune: zero out D_FF during twitching
This commit is contained in:
parent
64e7964011
commit
2352990d90
|
@ -286,9 +286,9 @@ protected:
|
|||
LowPassFilterFloat rotation_rate_filt; // filtered rotation rate in radians/second
|
||||
|
||||
// backup of currently being tuned parameter values
|
||||
float orig_roll_rp, orig_roll_ri, orig_roll_rd, orig_roll_rff, orig_roll_fltt, orig_roll_smax, orig_roll_sp, orig_roll_accel;
|
||||
float orig_pitch_rp, orig_pitch_ri, orig_pitch_rd, orig_pitch_rff, orig_pitch_fltt, orig_pitch_smax, orig_pitch_sp, orig_pitch_accel;
|
||||
float orig_yaw_rp, orig_yaw_ri, orig_yaw_rd, orig_yaw_rff, orig_yaw_fltt, orig_yaw_smax, orig_yaw_rLPF, orig_yaw_sp, orig_yaw_accel;
|
||||
float orig_roll_rp, orig_roll_ri, orig_roll_rd, orig_roll_rff, orig_roll_dff, orig_roll_fltt, orig_roll_smax, orig_roll_sp, orig_roll_accel;
|
||||
float orig_pitch_rp, orig_pitch_ri, orig_pitch_rd, orig_pitch_rff, orig_pitch_dff, orig_pitch_fltt, orig_pitch_smax, orig_pitch_sp, orig_pitch_accel;
|
||||
float orig_yaw_rp, orig_yaw_ri, orig_yaw_rd, orig_yaw_rff, orig_yaw_dff, orig_yaw_fltt, orig_yaw_smax, orig_yaw_rLPF, orig_yaw_sp, orig_yaw_accel;
|
||||
bool orig_bf_feedforward;
|
||||
|
||||
// currently being tuned parameter values
|
||||
|
|
|
@ -149,6 +149,7 @@ void AC_AutoTune_Multi::backup_gains_and_initialise()
|
|||
orig_roll_ri = attitude_control->get_rate_roll_pid().kI();
|
||||
orig_roll_rd = attitude_control->get_rate_roll_pid().kD();
|
||||
orig_roll_rff = attitude_control->get_rate_roll_pid().ff();
|
||||
orig_roll_dff = attitude_control->get_rate_roll_pid().kDff();
|
||||
orig_roll_fltt = attitude_control->get_rate_roll_pid().filt_T_hz();
|
||||
orig_roll_smax = attitude_control->get_rate_roll_pid().slew_limit();
|
||||
orig_roll_sp = attitude_control->get_angle_roll_p().kP();
|
||||
|
@ -162,6 +163,7 @@ void AC_AutoTune_Multi::backup_gains_and_initialise()
|
|||
orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();
|
||||
orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
|
||||
orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff();
|
||||
orig_pitch_dff = attitude_control->get_rate_pitch_pid().kDff();
|
||||
orig_pitch_fltt = attitude_control->get_rate_pitch_pid().filt_T_hz();
|
||||
orig_pitch_smax = attitude_control->get_rate_pitch_pid().slew_limit();
|
||||
orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();
|
||||
|
@ -175,6 +177,7 @@ void AC_AutoTune_Multi::backup_gains_and_initialise()
|
|||
orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();
|
||||
orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
|
||||
orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff();
|
||||
orig_yaw_dff = attitude_control->get_rate_yaw_pid().kDff();
|
||||
orig_yaw_fltt = attitude_control->get_rate_yaw_pid().filt_T_hz();
|
||||
orig_yaw_smax = attitude_control->get_rate_yaw_pid().slew_limit();
|
||||
orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
|
||||
|
@ -206,6 +209,7 @@ void AC_AutoTune_Multi::load_orig_gains()
|
|||
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);
|
||||
|
@ -218,6 +222,7 @@ void AC_AutoTune_Multi::load_orig_gains()
|
|||
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);
|
||||
|
@ -230,6 +235,7 @@ void AC_AutoTune_Multi::load_orig_gains()
|
|||
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);
|
||||
|
@ -253,6 +259,7 @@ void AC_AutoTune_Multi::load_tuned_gains()
|
|||
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->set_accel_roll_max_cdss(tune_roll_accel);
|
||||
}
|
||||
|
@ -263,6 +270,7 @@ void AC_AutoTune_Multi::load_tuned_gains()
|
|||
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->set_accel_pitch_max_cdss(tune_pitch_accel);
|
||||
}
|
||||
|
@ -278,6 +286,7 @@ void AC_AutoTune_Multi::load_tuned_gains()
|
|||
attitude_control->get_rate_yaw_pid().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->set_accel_yaw_max_cdss(tune_yaw_accel);
|
||||
}
|
||||
|
@ -296,6 +305,7 @@ void AC_AutoTune_Multi::load_intra_test_gains()
|
|||
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);
|
||||
|
@ -305,6 +315,7 @@ void AC_AutoTune_Multi::load_intra_test_gains()
|
|||
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);
|
||||
|
@ -314,6 +325,7 @@ void AC_AutoTune_Multi::load_intra_test_gains()
|
|||
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);
|
||||
|
@ -331,6 +343,7 @@ void AC_AutoTune_Multi::load_test_gains()
|
|||
attitude_control->get_rate_roll_pid().kI(tune_roll_rp*0.01f);
|
||||
attitude_control->get_rate_roll_pid().kD(tune_roll_rd);
|
||||
attitude_control->get_rate_roll_pid().ff(0.0f);
|
||||
attitude_control->get_rate_roll_pid().kDff(0.0f);
|
||||
attitude_control->get_rate_roll_pid().filt_T_hz(0.0f);
|
||||
attitude_control->get_rate_roll_pid().slew_limit(0.0f);
|
||||
attitude_control->get_angle_roll_p().kP(tune_roll_sp);
|
||||
|
@ -340,6 +353,7 @@ void AC_AutoTune_Multi::load_test_gains()
|
|||
attitude_control->get_rate_pitch_pid().kI(tune_pitch_rp*0.01f);
|
||||
attitude_control->get_rate_pitch_pid().kD(tune_pitch_rd);
|
||||
attitude_control->get_rate_pitch_pid().ff(0.0f);
|
||||
attitude_control->get_rate_pitch_pid().kDff(0.0f);
|
||||
attitude_control->get_rate_pitch_pid().filt_T_hz(0.0f);
|
||||
attitude_control->get_rate_pitch_pid().slew_limit(0.0f);
|
||||
attitude_control->get_angle_pitch_p().kP(tune_pitch_sp);
|
||||
|
@ -349,6 +363,7 @@ void AC_AutoTune_Multi::load_test_gains()
|
|||
attitude_control->get_rate_yaw_pid().kP(tune_yaw_rp);
|
||||
attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*0.01f);
|
||||
attitude_control->get_rate_yaw_pid().ff(0.0f);
|
||||
attitude_control->get_rate_yaw_pid().kDff(0.0f);
|
||||
if (axis == YAW_D) {
|
||||
attitude_control->get_rate_yaw_pid().kD(tune_yaw_rd);
|
||||
} else {
|
||||
|
@ -383,6 +398,7 @@ void AC_AutoTune_Multi::save_tuning_gains()
|
|||
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().save_gains();
|
||||
|
@ -399,6 +415,7 @@ void AC_AutoTune_Multi::save_tuning_gains()
|
|||
orig_roll_ri = attitude_control->get_rate_roll_pid().kI();
|
||||
orig_roll_rd = attitude_control->get_rate_roll_pid().kD();
|
||||
orig_roll_rff = attitude_control->get_rate_roll_pid().ff();
|
||||
orig_roll_dff = attitude_control->get_rate_roll_pid().kDff();
|
||||
orig_roll_sp = attitude_control->get_angle_roll_p().kP();
|
||||
orig_roll_accel = attitude_control->get_accel_roll_max_cdss();
|
||||
}
|
||||
|
@ -409,6 +426,7 @@ void AC_AutoTune_Multi::save_tuning_gains()
|
|||
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().save_gains();
|
||||
|
@ -425,6 +443,7 @@ void AC_AutoTune_Multi::save_tuning_gains()
|
|||
orig_pitch_ri = attitude_control->get_rate_pitch_pid().kI();
|
||||
orig_pitch_rd = attitude_control->get_rate_pitch_pid().kD();
|
||||
orig_pitch_rff = attitude_control->get_rate_pitch_pid().ff();
|
||||
orig_pitch_dff = attitude_control->get_rate_pitch_pid().kDff();
|
||||
orig_pitch_sp = attitude_control->get_angle_pitch_p().kP();
|
||||
orig_pitch_accel = attitude_control->get_accel_pitch_max_cdss();
|
||||
}
|
||||
|
@ -435,6 +454,7 @@ void AC_AutoTune_Multi::save_tuning_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);
|
||||
if (yaw_d_enabled()) {
|
||||
|
@ -457,6 +477,7 @@ void AC_AutoTune_Multi::save_tuning_gains()
|
|||
orig_yaw_ri = attitude_control->get_rate_yaw_pid().kI();
|
||||
orig_yaw_rd = attitude_control->get_rate_yaw_pid().kD();
|
||||
orig_yaw_rff = attitude_control->get_rate_yaw_pid().ff();
|
||||
orig_yaw_dff = attitude_control->get_rate_yaw_pid().kDff();
|
||||
orig_yaw_rLPF = attitude_control->get_rate_yaw_pid().filt_E_hz();
|
||||
orig_yaw_sp = attitude_control->get_angle_yaw_p().kP();
|
||||
orig_yaw_accel = attitude_control->get_accel_yaw_max_cdss();
|
||||
|
|
Loading…
Reference in New Issue