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 b2aaf71 commit 272f8f8
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
1 change: 0 additions & 1 deletion libraries/AC_AutoTune/AC_AutoTune.h
Original file line number Diff line number Diff line change
Expand Up @@ -330,7 +330,6 @@ class AC_AutoTune
// variables
uint32_t override_time; // the last time the pilot overrode the controls
uint32_t level_start_time_ms; // start time of waiting for level
uint32_t level_fail_warning_time_ms; // last time level failure warning message was sent to GCS

// time in ms of last pilot override warning
uint32_t last_pilot_override_warning;
Expand Down
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 @@ -1147,9 +1147,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 @@ -1171,6 +1171,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 272f8f8

Please sign in to comment.