|
|
|
@ -43,7 +43,7 @@ const AP_Param::GroupInfo AC_PID::var_info[] = {
@@ -43,7 +43,7 @@ const AP_Param::GroupInfo AC_PID::var_info[] = {
|
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
// Constructor
|
|
|
|
|
AC_PID::AC_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt) : |
|
|
|
|
AC_PID::AC_PID(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float dt, float initial_ff) : |
|
|
|
|
_dt(dt), |
|
|
|
|
_integrator(0.0f), |
|
|
|
|
_input(0.0f), |
|
|
|
@ -57,6 +57,7 @@ AC_PID::AC_PID(float initial_p, float initial_i, float initial_d, float initial_
@@ -57,6 +57,7 @@ AC_PID::AC_PID(float initial_p, float initial_i, float initial_d, float initial_
|
|
|
|
|
_kd = initial_d; |
|
|
|
|
_imax = fabsf(initial_imax); |
|
|
|
|
filt_hz(initial_filt_hz); |
|
|
|
|
_ff = initial_ff; |
|
|
|
|
|
|
|
|
|
// reset input filter to first value received
|
|
|
|
|
_flags._reset_filter = true; |
|
|
|
@ -201,7 +202,7 @@ void AC_PID::save_gains()
@@ -201,7 +202,7 @@ void AC_PID::save_gains()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
/// Overload the function call operator to permit easy initialisation
|
|
|
|
|
void AC_PID::operator() (float p, float i, float d, float imaxval, float input_filt_hz, float dt) |
|
|
|
|
void AC_PID::operator() (float p, float i, float d, float imaxval, float input_filt_hz, float dt, float ffval) |
|
|
|
|
{ |
|
|
|
|
_kp = p; |
|
|
|
|
_ki = i; |
|
|
|
@ -209,6 +210,7 @@ void AC_PID::operator() (float p, float i, float d, float imaxval, float input_f
@@ -209,6 +210,7 @@ void AC_PID::operator() (float p, float i, float d, float imaxval, float input_f
|
|
|
|
|
_imax = fabsf(imaxval); |
|
|
|
|
_filt_hz = input_filt_hz; |
|
|
|
|
_dt = dt; |
|
|
|
|
_ff = ffval; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// calc_filt_alpha - recalculate the input filter alpha
|
|
|
|
|