mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_PID: params always use set method
This commit is contained in:
parent
aa6a908f8e
commit
8d216fbce3
@ -54,7 +54,7 @@ public:
|
|||||||
//@{
|
//@{
|
||||||
|
|
||||||
/// Overload the function call operator to permit relatively easy initialisation
|
/// Overload the function call operator to permit relatively easy initialisation
|
||||||
void operator() (const float p) { _kp = p; }
|
void operator() (const float p) { _kp.set(p); }
|
||||||
|
|
||||||
// accessors
|
// accessors
|
||||||
AP_Float &kP() { return _kp; }
|
AP_Float &kP() { return _kp; }
|
||||||
|
@ -282,7 +282,7 @@ void AC_PID::load_gains()
|
|||||||
_kd.load();
|
_kd.load();
|
||||||
_kff.load();
|
_kff.load();
|
||||||
_kimax.load();
|
_kimax.load();
|
||||||
_kimax = fabsf(_kimax);
|
_kimax.set(fabsf(_kimax));
|
||||||
_filt_T_hz.load();
|
_filt_T_hz.load();
|
||||||
_filt_E_hz.load();
|
_filt_E_hz.load();
|
||||||
_filt_D_hz.load();
|
_filt_D_hz.load();
|
||||||
@ -304,14 +304,14 @@ void AC_PID::save_gains()
|
|||||||
/// Overload the function call operator to permit easy initialisation
|
/// 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 dt)
|
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 dt)
|
||||||
{
|
{
|
||||||
_kp = p_val;
|
_kp.set(p_val);
|
||||||
_ki = i_val;
|
_ki.set(i_val);
|
||||||
_kd = d_val;
|
_kd.set(d_val);
|
||||||
_kff = ff_val;
|
_kff.set(ff_val);
|
||||||
_kimax = fabsf(imax_val);
|
_kimax.set(fabsf(imax_val));
|
||||||
_filt_T_hz = input_filt_T_hz;
|
_filt_T_hz.set(input_filt_T_hz);
|
||||||
_filt_E_hz = input_filt_E_hz;
|
_filt_E_hz.set(input_filt_E_hz);
|
||||||
_filt_D_hz = input_filt_D_hz;
|
_filt_D_hz.set(input_filt_D_hz);
|
||||||
_dt = dt;
|
_dt = dt;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -60,7 +60,7 @@ void AC_PI_2D::filt_hz(float hz)
|
|||||||
_filt_hz.set(fabsf(hz));
|
_filt_hz.set(fabsf(hz));
|
||||||
|
|
||||||
// sanity check _filt_hz
|
// sanity check _filt_hz
|
||||||
_filt_hz = MAX(_filt_hz, AC_PI_2D_FILT_HZ_MIN);
|
_filt_hz.set(MAX(_filt_hz, AC_PI_2D_FILT_HZ_MIN));
|
||||||
|
|
||||||
// calculate the input filter alpha
|
// calculate the input filter alpha
|
||||||
calc_filt_alpha();
|
calc_filt_alpha();
|
||||||
@ -135,7 +135,7 @@ void AC_PI_2D::load_gains()
|
|||||||
_kp.load();
|
_kp.load();
|
||||||
_ki.load();
|
_ki.load();
|
||||||
_imax.load();
|
_imax.load();
|
||||||
_imax = fabsf(_imax);
|
_imax.set(fabsf(_imax));
|
||||||
_filt_hz.load();
|
_filt_hz.load();
|
||||||
|
|
||||||
// calculate the input filter alpha
|
// calculate the input filter alpha
|
||||||
@ -154,10 +154,10 @@ void AC_PI_2D::save_gains()
|
|||||||
/// Overload the function call operator to permit easy initialisation
|
/// 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)
|
void AC_PI_2D::operator() (float p, float i, float imaxval, float input_filt_hz, float dt)
|
||||||
{
|
{
|
||||||
_kp = p;
|
_kp.set(p);
|
||||||
_ki = i;
|
_ki.set(i);
|
||||||
_imax = fabsf(imaxval);
|
_imax.set(fabsf(imaxval));
|
||||||
_filt_hz = input_filt_hz;
|
_filt_hz.set(input_filt_hz);
|
||||||
_dt = dt;
|
_dt = dt;
|
||||||
// calculate the input filter alpha
|
// calculate the input filter alpha
|
||||||
calc_filt_alpha();
|
calc_filt_alpha();
|
||||||
|
Loading…
Reference in New Issue
Block a user