From cac2c63e7229a1055074084bf491159685e5faf1 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 30 Jul 2024 21:51:31 +1000 Subject: [PATCH] AC_PID: remove method operator remove the metho operator from the class. This means this will no longer work: Quaternion q{0,1,2,3}; q(5,6,7,8); .... that used to set the quaternion componets, but is an odd / atypical syntax to use --- libraries/AC_PID/AC_P.h | 3 --- libraries/AC_PID/AC_PID.cpp | 14 -------------- libraries/AC_PID/AC_PID.h | 3 --- libraries/AC_PID/AC_PI_2D.cpp | 12 ------------ libraries/AC_PID/AC_PI_2D.h | 3 --- 5 files changed, 35 deletions(-) diff --git a/libraries/AC_PID/AC_P.h b/libraries/AC_PID/AC_P.h index e067e445de..f172996677 100644 --- a/libraries/AC_PID/AC_P.h +++ b/libraries/AC_PID/AC_P.h @@ -53,9 +53,6 @@ public: /// @name parameter accessors //@{ - /// Overload the function call operator to permit relatively easy initialisation - void operator() (const float p) { _kp.set(p); } - // accessors AP_Float &kP() { return _kp; } const AP_Float &kP() const { return _kp; } diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index da70334996..ac7c32af34 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -390,20 +390,6 @@ void AC_PID::save_gains() _filt_D_hz.save(); } -/// Overload the function call operator to permit easy initialisation -void AC_PID::operator()(float p_val, float i_val, float d_val, float ff_val, float imax_val, float input_filt_T_hz, float input_filt_E_hz, float input_filt_D_hz, float dff_val) -{ - _kp.set(p_val); - _ki.set(i_val); - _kd.set(d_val); - _kff.set(ff_val); - _kimax.set(fabsf(imax_val)); - _filt_T_hz.set(input_filt_T_hz); - _filt_E_hz.set(input_filt_E_hz); - _filt_D_hz.set(input_filt_D_hz); - _kdff.set(dff_val); -} - // get_filt_T_alpha - get the target filter alpha float AC_PID::get_filt_T_alpha(float dt) const { diff --git a/libraries/AC_PID/AC_PID.h b/libraries/AC_PID/AC_PID.h index fbbebcac7d..2efbec3624 100644 --- a/libraries/AC_PID/AC_PID.h +++ b/libraries/AC_PID/AC_PID.h @@ -92,9 +92,6 @@ public: // save gain to eeprom void save_gains(); - /// operator function call for easy initialisation - void operator()(float p_val, float i_val, float d_val, float ff_val, float imax_val, float input_filt_T_hz, float input_filt_E_hz, float input_filt_D_hz, float dff_val=0); - // get accessors const AP_Float &kP() const { return _kp; } AP_Float &kP() { return _kp; } diff --git a/libraries/AC_PID/AC_PI_2D.cpp b/libraries/AC_PID/AC_PI_2D.cpp index e6c6362464..386982e6a6 100644 --- a/libraries/AC_PID/AC_PI_2D.cpp +++ b/libraries/AC_PID/AC_PI_2D.cpp @@ -151,18 +151,6 @@ void AC_PI_2D::save_gains() _filt_hz.save(); } -/// Overload the function call operator to permit easy initialisation -void AC_PI_2D::operator() (float p, float i, float imaxval, float input_filt_hz, float dt) -{ - _kp.set(p); - _ki.set(i); - _imax.set(fabsf(imaxval)); - _filt_hz.set(input_filt_hz); - _dt = dt; - // calculate the input filter alpha - calc_filt_alpha(); -} - // calc_filt_alpha - recalculate the input filter alpha void AC_PI_2D::calc_filt_alpha() { diff --git a/libraries/AC_PID/AC_PI_2D.h b/libraries/AC_PID/AC_PI_2D.h index c031104531..f70d766fd7 100644 --- a/libraries/AC_PID/AC_PI_2D.h +++ b/libraries/AC_PID/AC_PI_2D.h @@ -47,9 +47,6 @@ public: // save gain to eeprom void save_gains(); - /// operator function call for easy initialisation - void operator() (float p, float i, float imaxval, float input_filt_hz, float dt); - // get accessors AP_Float &kP() { return _kp; } AP_Float &kI() { return _ki; }