Skip to content

Commit

Permalink
Copter: Autotune: Reduce chance of desync
Browse files Browse the repository at this point in the history
  • Loading branch information
lthall committed Feb 17, 2024
1 parent 7a9b968 commit 218ebb2
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion libraries/AC_AutoTune/AC_AutoTune_Multi.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1145,9 +1145,9 @@ void AC_AutoTune_Multi::twitch_test_run(AxisType test_axis, const float dir_sign
// disable rate limits
attitude_control->use_sqrt_controller(false);
// hold current attitude
attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, 0.0f);

if ((tune_type == SP_DOWN) || (tune_type == SP_UP)) {
attitude_control->input_rate_bf_roll_pitch_yaw(0.0f, 0.0f, 0.0f);
// step angle targets on first iteration
if (twitch_first_iter) {
twitch_first_iter = false;
Expand All @@ -1169,6 +1169,7 @@ void AC_AutoTune_Multi::twitch_test_run(AxisType test_axis, const float dir_sign
}
}
} else {
attitude_control->input_rate_bf_roll_pitch_yaw_2(0.0f, 0.0f, 0.0f);
// Testing rate P and D gains so will set body-frame rate targets.
// Rate controller will use existing body-frame rates and convert to motor outputs
// for all axes except the one we override here.
Expand Down

0 comments on commit 218ebb2

Please sign in to comment.