AC_PID: expose ff() method in AC_PID

this allows for an abstract AC_PID class to be used in
AC_AttitudeControl for both multicopter and heli
This commit is contained in:
Andrew Tridgell 2017-01-09 18:49:53 +11:00
parent 8e3bf71aa9
commit 2086b591a2
2 changed files with 3 additions and 5 deletions

View File

@ -25,14 +25,9 @@ public:
/// get_leaky_i - replacement for get_i but output is leaded at leak_rate
float get_leaky_i(float leak_rate);
// accessors
float ff() const { return _vff.get(); }
void ff(const float v) { _vff.set(v); }
static const struct AP_Param::GroupInfo var_info[];
private:
AP_Float _vff;
AP_Float _leak_min;
float _last_requested_rate; // Requested rate from last iteration, used to calculate rate change of requested rate

View File

@ -62,6 +62,7 @@ public:
float imax() const { return _imax.get(); }
float filt_hz() const { return _filt_hz.get(); }
float get_filt_alpha() const;
float ff() const { return _vff.get(); }
// set accessors
void kP(const float v) { _kp.set(v); }
@ -69,6 +70,7 @@ public:
void kD(const float v) { _kd.set(v); }
void imax(const float v) { _imax.set(fabsf(v)); }
void filt_hz(const float v);
void ff(const float v) { _vff.set(v); }
float get_integrator() const { return _integrator; }
void set_integrator(float i) { _integrator = i; }
@ -89,6 +91,7 @@ protected:
AP_Float _kd;
AP_Float _imax;
AP_Float _filt_hz; // PID Input filter frequency in Hz
AP_Float _vff; // only used by heli
// flags
struct ac_pid_flags {