mirror of https://github.com/ArduPilot/ardupilot
AC_PID: tidy AC_PID construction
This commit is contained in:
parent
70109f968c
commit
06a8dafbf5
|
@ -21,9 +21,36 @@
|
|||
class AC_PID {
|
||||
public:
|
||||
|
||||
struct Defaults {
|
||||
float p;
|
||||
float i;
|
||||
float d;
|
||||
float ff;
|
||||
float imax;
|
||||
float filt_T_hz;
|
||||
float filt_E_hz;
|
||||
float filt_D_hz;
|
||||
float srmax;
|
||||
float srtau;
|
||||
};
|
||||
|
||||
// Constructor for PID
|
||||
AC_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz,
|
||||
float initial_srmax=0, float initial_srtau=1.0);
|
||||
AC_PID(const AC_PID::Defaults &defaults) :
|
||||
AC_PID(
|
||||
defaults.p,
|
||||
defaults.i,
|
||||
defaults.d,
|
||||
defaults.ff,
|
||||
defaults.imax,
|
||||
defaults.filt_T_hz,
|
||||
defaults.filt_E_hz,
|
||||
defaults.filt_D_hz,
|
||||
defaults.srmax,
|
||||
defaults.srtau
|
||||
)
|
||||
{ }
|
||||
|
||||
CLASS_NO_COPY(AC_PID);
|
||||
|
||||
|
|
Loading…
Reference in New Issue