Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Control: change autotune I determination for Roll axis #21027

Merged
merged 1 commit into from
Jul 25, 2022
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 5 additions & 1 deletion libraries/APM_Control/AP_AutoTune.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -415,7 +415,11 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg)
rpid.ff().set(FF);
rpid.kP().set(P);
rpid.kD().set(D);
rpid.kI().set(MAX(P*AUTOTUNE_I_RATIO, (FF / TRIM_TCONST)));
if (type == AUTOTUNE_ROLL) { // for roll set I = smaller of FF or P
rpid.kI().set(MIN(P, (FF / TRIM_TCONST)));
} else { // for pitch/yaw naturally damped axes) set I usually = FF to get 1 sec I closure
rpid.kI().set(MAX(P*AUTOTUNE_I_RATIO, (FF / TRIM_TCONST)));
}

// setup filters to be suitable for time constant and gyro filter
rpid.filt_T_hz().set(10.0/(current.tau * 2 * M_PI));
Expand Down