From dcfc6ae642a9355c1ccebbafce2a3a451c8a649a Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 3 Jan 2023 17:22:48 +0000 Subject: [PATCH] PID: use new defualt pattern --- libraries/PID/PID.cpp | 8 ++++---- libraries/PID/PID.h | 15 ++++++++++----- 2 files changed, 14 insertions(+), 9 deletions(-) diff --git a/libraries/PID/PID.cpp b/libraries/PID/PID.cpp index 71079cdbe8..c88ae72eda 100644 --- a/libraries/PID/PID.cpp +++ b/libraries/PID/PID.cpp @@ -14,22 +14,22 @@ 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), + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("P", 0, PID, _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", 1, PID, _ki, 0), + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("I", 1, PID, _ki, default_ki), // @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), + AP_GROUPINFO_FLAGS_DEFAULT_POINTER("D", 2, PID, _kd, default_kd), // @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_GROUPINFO_FLAGS_DEFAULT_POINTER("IMAX", 3, PID, _imax, default_kimax), AP_GROUPEND }; diff --git a/libraries/PID/PID.h b/libraries/PID/PID.h index 0cb13b1257..2d5008d388 100644 --- a/libraries/PID/PID.h +++ b/libraries/PID/PID.h @@ -16,13 +16,13 @@ public: PID(const float & initial_p = 0.0f, const float & initial_i = 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); - _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 _last_derivative = NAN; @@ -121,4 +121,9 @@ private: /// http://en.wikipedia.org/wiki/Low-pass_filter. /// static const uint8_t _fCut = 20; + + const float default_kp; + const float default_ki; + const float default_kd; + const float default_kimax; };