AC_PID: AC_PI: fix param defualting

This commit is contained in:
Iampete1 2023-02-04 13:17:09 +00:00 committed by Randy Mackay
parent eba850d9ef
commit b7907e10c8
1 changed files with 3 additions and 3 deletions

View File

@ -9,17 +9,17 @@ const AP_Param::GroupInfo AC_PI::var_info[] = {
// @Param: P
// @DisplayName: PID Proportional Gain
// @Description: P Gain which produces an output value that is proportional to the current error value
AP_GROUPINFO("P", 1, AC_PI, kP, 0),
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("P", 1, AC_PI, kP, default_kp),
// @Param: I
// @DisplayName: PID Integral Gain
// @Description: I Gain which produces an output that is proportional to both the magnitude and the duration of the error
AP_GROUPINFO("I", 2, AC_PI, kI, 0),
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("I", 2, AC_PI, kI, default_ki),
// @Param: IMAX
// @DisplayName: PID Integral Maximum
// @Description: The maximum/minimum value that the I term can output
AP_GROUPINFO("IMAX", 3, AC_PI, imax, 0),
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("IMAX", 3, AC_PI, imax, default_imax),
AP_GROUPEND
};