AP_Control: change I determination for Roll axis

This commit is contained in:
Henry Wurzburg 2022-06-23 14:56:53 -05:00 committed by Andrew Tridgell
parent 28ab8ef316
commit dcde718f20
1 changed files with 5 additions and 1 deletions

View File

@ -415,7 +415,11 @@ void AP_AutoTune::update(AP_PIDInfo &pinfo, float scaler, float angle_err_deg)
rpid.ff().set(FF); rpid.ff().set(FF);
rpid.kP().set(P); rpid.kP().set(P);
rpid.kD().set(D); 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 // setup filters to be suitable for time constant and gyro filter
rpid.filt_T_hz().set(10.0/(current.tau * 2 * M_PI)); rpid.filt_T_hz().set(10.0/(current.tau * 2 * M_PI));