mirror of https://github.com/ArduPilot/ardupilot
APM_Control: move to new constant dt low pass filter class
This commit is contained in:
parent
0c29d4280c
commit
5cc63d7e6f
|
@ -128,9 +128,9 @@ private:
|
||||||
// 5 point mode filter for FF estimate
|
// 5 point mode filter for FF estimate
|
||||||
ModeFilterFloat_Size5 ff_filter;
|
ModeFilterFloat_Size5 ff_filter;
|
||||||
|
|
||||||
LowPassFilterFloat actuator_filter;
|
LowPassFilterConstDtFloat actuator_filter;
|
||||||
LowPassFilterFloat rate_filter;
|
LowPassFilterConstDtFloat rate_filter;
|
||||||
LowPassFilterFloat target_filter;
|
LowPassFilterConstDtFloat target_filter;
|
||||||
|
|
||||||
// separate slew limiters for P and D
|
// separate slew limiters for P and D
|
||||||
float slew_limit_max, slew_limit_tau;
|
float slew_limit_max, slew_limit_tau;
|
||||||
|
|
Loading…
Reference in New Issue