PID: use new defualt pattern

This commit is contained in:
Iampete1 2023-01-03 17:22:48 +00:00 committed by Andrew Tridgell
parent 18d0dbcd8a
commit dcfc6ae642
2 changed files with 14 additions and 9 deletions

View File

@ -14,22 +14,22 @@ const AP_Param::GroupInfo PID::var_info[] = {
// @Param: P // @Param: P
// @DisplayName: PID Proportional Gain // @DisplayName: PID Proportional Gain
// @Description: P Gain which produces an output value that is proportional to the current error value // @Description: P Gain which produces an output value that is proportional to the current error value
AP_GROUPINFO("P", 0, PID, _kp, 0), AP_GROUPINFO_FLAGS_DEFAULT_POINTER("P", 0, PID, _kp, default_kp),
// @Param: I // @Param: I
// @DisplayName: PID Integral Gain // @DisplayName: PID Integral Gain
// @Description: I Gain which produces an output that is proportional to both the magnitude and the duration of the error // @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), AP_GROUPINFO_FLAGS_DEFAULT_POINTER("I", 1, PID, _ki, default_ki),
// @Param: D // @Param: D
// @DisplayName: PID Derivative Gain // @DisplayName: PID Derivative Gain
// @Description: D Gain which produces an output that is proportional to the rate of change of the error // @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), AP_GROUPINFO_FLAGS_DEFAULT_POINTER("D", 2, PID, _kd, default_kd),
// @Param: IMAX // @Param: IMAX
// @DisplayName: PID Integral Maximum // @DisplayName: PID Integral Maximum
// @Description: The maximum/minimum value that the I term can output // @Description: The maximum/minimum value that the I term can output
AP_GROUPINFO("IMAX", 3, PID, _imax, 0), AP_GROUPINFO_FLAGS_DEFAULT_POINTER("IMAX", 3, PID, _imax, default_kimax),
AP_GROUPEND AP_GROUPEND
}; };

View File

@ -16,13 +16,13 @@ public:
PID(const float & initial_p = 0.0f, PID(const float & initial_p = 0.0f,
const float & initial_i = 0.0f, const float & initial_i = 0.0f,
const float & initial_d = 0.0f, const float & initial_d = 0.0f,
const int16_t & initial_imax = 0) const int16_t & initial_imax = 0):
default_kp(initial_p),
default_ki(initial_i),
default_kd(initial_d),
default_kimax(initial_imax)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);
_kp.set_and_default(initial_p);
_ki.set_and_default(initial_i);
_kd.set_and_default(initial_d);
_imax.set_and_default(initial_imax);
// set _last_derivative as invalid when we startup // set _last_derivative as invalid when we startup
_last_derivative = NAN; _last_derivative = NAN;
@ -121,4 +121,9 @@ private:
/// http://en.wikipedia.org/wiki/Low-pass_filter. /// http://en.wikipedia.org/wiki/Low-pass_filter.
/// ///
static const uint8_t _fCut = 20; static const uint8_t _fCut = 20;
const float default_kp;
const float default_ki;
const float default_kd;
const float default_kimax;
}; };