PID: add parameter descriptions

These actually aren't referred to from anywhere but it makes this class more consistent with other PID classes
This commit is contained in:
Randy Mackay 2016-02-08 20:42:16 +09:00
parent 942da17b7d
commit adfa03ce69
1 changed files with 17 additions and 0 deletions

View File

@ -12,10 +12,27 @@
extern const AP_HAL::HAL& hal;
const AP_Param::GroupInfo PID::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", 0, PID, _kp, 0),
// @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", 1, PID, _ki, 0),
// @Param: D
// @DisplayName: PID Derivative Gain
// @Description: D Gain which produces an output that is proportional to the rate of change of the error
AP_GROUPINFO("D", 2, PID, _kd, 0),
// @Param: IMAX
// @DisplayName: PID Integral Maximum
// @Description: The maximum/minimum value that the I term can output
AP_GROUPINFO("IMAX", 3, PID, _imax, 0),
AP_GROUPEND
};