mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/Filter/LowPassFilter.h
This commit is contained in:
parent
c284fb144f
commit
406abb3fa0
|
@ -21,7 +21,7 @@
|
|||
template <class T>
|
||||
class LowPassFilter : public Filter<T>
|
||||
{
|
||||
public:
|
||||
public:
|
||||
// constructor
|
||||
LowPassFilter(float gain);
|
||||
|
||||
|
@ -29,12 +29,16 @@ class LowPassFilter : public Filter<T>
|
|||
virtual T apply(T sample);
|
||||
|
||||
// reset - clear the filter - next sample added will become the new base value
|
||||
virtual void reset() { _base_value_set = false; };
|
||||
virtual void reset() {
|
||||
_base_value_set = false;
|
||||
};
|
||||
|
||||
// reset - clear the filter and provide the new base value
|
||||
virtual void reset( T new_base_value ) { _base_value = new_base_value; _base_value_set = true;};
|
||||
virtual void reset( T new_base_value ) {
|
||||
_base_value = new_base_value; _base_value_set = true;
|
||||
};
|
||||
|
||||
private:
|
||||
private:
|
||||
float _gain; // gain value (like 0.02) applied to each new value
|
||||
bool _base_value_set; // true if the base value has been set
|
||||
float _base_value; // the number of samples in the filter, maxes out at size of the filter
|
||||
|
@ -71,10 +75,10 @@ LowPassFilter<T>::LowPassFilter(float gain) :
|
|||
// Public Methods //////////////////////////////////////////////////////////////
|
||||
|
||||
template <class T>
|
||||
T LowPassFilter<T>::apply(T sample)
|
||||
T LowPassFilter<T>:: apply(T sample)
|
||||
{
|
||||
// initailise _base_value if required
|
||||
if( ! _base_value_set ) {
|
||||
if( !_base_value_set ) {
|
||||
_base_value = sample;
|
||||
_base_value_set = true;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue