mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 01:33:56 -04:00
AC_PID: expose filt_hz as a AP_Float
this allows defaults to be overridden
This commit is contained in:
parent
2f100b0804
commit
ccae8979c1
@ -59,8 +59,8 @@ public:
|
||||
AP_Float &kP() { return _kp; }
|
||||
AP_Float &kI() { return _ki; }
|
||||
AP_Float &kD() { return _kd; }
|
||||
AP_Float &filt_hz() { return _filt_hz; }
|
||||
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(); }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user