mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
Copter: Autotune: Reduce chance of desync
This commit is contained in:
parent
9669699405
commit
c47b3b8f03
@ -1163,9 +1163,9 @@ void AC_AutoTune_Multi::twitch_test_run(AxisType test_axis, const float dir_sign
|
|||||||
// disable rate limits
|
// disable rate limits
|
||||||
attitude_control->use_sqrt_controller(false);
|
attitude_control->use_sqrt_controller(false);
|
||||||
// hold current attitude
|
// 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)) {
|
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
|
// step angle targets on first iteration
|
||||||
if (twitch_first_iter) {
|
if (twitch_first_iter) {
|
||||||
twitch_first_iter = false;
|
twitch_first_iter = false;
|
||||||
@ -1187,6 +1187,7 @@ void AC_AutoTune_Multi::twitch_test_run(AxisType test_axis, const float dir_sign
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
} else {
|
} 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.
|
// 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
|
// Rate controller will use existing body-frame rates and convert to motor outputs
|
||||||
// for all axes except the one we override here.
|
// for all axes except the one we override here.
|
||||||
|
Loading…
Reference in New Issue
Block a user