Skip to content

Commit

Permalink
AC_AutoTune: load test gains for correct axis when testing yaw D
Browse files Browse the repository at this point in the history
  • Loading branch information
andyp1per authored and tridge committed May 16, 2023
1 parent 30d71e4 commit 38adb30
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AC_AutoTune/AC_AutoTune_Multi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -346,7 +346,7 @@ void AC_AutoTune_Multi::load_test_gains()
attitude_control->get_rate_yaw_pid().kI(tune_yaw_rp*0.01f);
attitude_control->get_rate_yaw_pid().ff(0.0f);
if (axis == YAW_D) {
attitude_control->get_rate_pitch_pid().kD(tune_yaw_rd);
attitude_control->get_rate_yaw_pid().kD(tune_yaw_rd);
} else {
attitude_control->get_rate_yaw_pid().filt_E_hz(tune_yaw_rLPF);
}
Expand Down

0 comments on commit 38adb30

Please sign in to comment.