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
This commit is contained in:
Peter Barker 2024-07-30 21:51:31 +10:00 committed by Peter Barker
parent 52ba8e8513
commit cac2c63e72
5 changed files with 0 additions and 35 deletions

View File

@ -53,9 +53,6 @@ public:
/// @name parameter accessors /// @name parameter accessors
//@{ //@{
/// Overload the function call operator to permit relatively easy initialisation
void operator() (const float p) { _kp.set(p); }
// accessors // accessors
AP_Float &kP() { return _kp; } AP_Float &kP() { return _kp; }
const AP_Float &kP() const { return _kp; } const AP_Float &kP() const { return _kp; }

View File

@ -390,20 +390,6 @@ void AC_PID::save_gains()
_filt_D_hz.save(); _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 // get_filt_T_alpha - get the target filter alpha
float AC_PID::get_filt_T_alpha(float dt) const float AC_PID::get_filt_T_alpha(float dt) const
{ {

View File

@ -92,9 +92,6 @@ public:
// save gain to eeprom // save gain to eeprom
void save_gains(); 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 // get accessors
const AP_Float &kP() const { return _kp; } const AP_Float &kP() const { return _kp; }
AP_Float &kP() { return _kp; } AP_Float &kP() { return _kp; }

View File

@ -151,18 +151,6 @@ void AC_PI_2D::save_gains()
_filt_hz.save(); _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 // calc_filt_alpha - recalculate the input filter alpha
void AC_PI_2D::calc_filt_alpha() void AC_PI_2D::calc_filt_alpha()
{ {

View File

@ -47,9 +47,6 @@ public:
// save gain to eeprom // save gain to eeprom
void save_gains(); 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 // get accessors
AP_Float &kP() { return _kp; } AP_Float &kP() { return _kp; }
AP_Float &kI() { return _ki; } AP_Float &kI() { return _ki; }