mirror of https://github.com/ArduPilot/ardupilot
LowPassFilter: make methods non-virtual
No classes inherit from this class so no need for set_cutoff_frequency, set_time_constant and reset(T) to be declared virtual. Saves 6 bytes of RAM.
This commit is contained in:
parent
38222d65e9
commit
a0369b85d1
|
@ -34,8 +34,8 @@ public:
|
||||||
// constructor
|
// constructor
|
||||||
LowPassFilter();
|
LowPassFilter();
|
||||||
|
|
||||||
virtual void set_cutoff_frequency(float time_step, float cutoff_freq);
|
void set_cutoff_frequency(float time_step, float cutoff_freq);
|
||||||
virtual void set_time_constant(float time_step, float time_constant);
|
void set_time_constant(float time_step, float time_constant);
|
||||||
|
|
||||||
// apply - Add a new raw value to the filter, retrieve the filtered result
|
// apply - Add a new raw value to the filter, retrieve the filtered result
|
||||||
virtual T apply(T sample);
|
virtual T apply(T sample);
|
||||||
|
@ -46,7 +46,7 @@ public:
|
||||||
};
|
};
|
||||||
|
|
||||||
// reset - clear the filter and provide the new base value
|
// reset - clear the filter and provide the new base value
|
||||||
virtual void reset( T new_base_value ) {
|
void reset( T new_base_value ) {
|
||||||
_base_value = new_base_value; _base_value_set = true;
|
_base_value = new_base_value; _base_value_set = true;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue