mirror of https://github.com/ArduPilot/ardupilot
AC_PID: AC_PI_2D format changes
This commit is contained in:
parent
7eb4e9b370
commit
f0f87be06d
|
@ -19,7 +19,7 @@ public:
|
|||
// Constructor for PID
|
||||
AC_PI_2D(float initial_p, float initial_i, float initial_imax, float initial_filt_hz, float dt);
|
||||
|
||||
// set_dt - set time step in seconds
|
||||
// set time step in seconds
|
||||
void set_dt(float dt);
|
||||
|
||||
// set_input - set input to PID controller
|
||||
|
@ -57,10 +57,10 @@ public:
|
|||
float get_filt_alpha() const { return _filt_alpha; }
|
||||
|
||||
// set accessors
|
||||
void kP(const float v) { _kp.set(v); }
|
||||
void kI(const float v) { _ki.set(v); }
|
||||
void imax(const float v) { _imax.set(fabsf(v)); }
|
||||
void filt_hz(const float v);
|
||||
void kP(float v) { _kp.set(v); }
|
||||
void kI(float v) { _ki.set(v); }
|
||||
void imax(float v) { _imax.set(fabsf(v)); }
|
||||
void filt_hz(float hz);
|
||||
|
||||
Vector2f get_integrator() const { return _integrator; }
|
||||
void set_integrator(const Vector2f &i) { _integrator = i; }
|
||||
|
@ -69,7 +69,7 @@ public:
|
|||
// parameter var table
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
protected:
|
||||
private:
|
||||
|
||||
// calc_filt_alpha - recalculate the input filter alpha
|
||||
void calc_filt_alpha();
|
||||
|
|
Loading…
Reference in New Issue