APM:Libraries
LowPassFilter.cpp
Go to the documentation of this file.
1 //
6 
7 
8 #include "LowPassFilter.h"
9 
11 // DigitalLPF
13 
14 template <class T>
16  // built in initialization
17  _output = T();
18 }
19 
20 // add a new raw value to the filter, retrieve the filtered result
21 template <class T>
22 T DigitalLPF<T>::apply(const T &sample, float cutoff_freq, float dt) {
23  if (cutoff_freq <= 0.0f || dt <= 0.0f) {
24  _output = sample;
25  return _output;
26  }
27  float rc = 1.0f/(M_2PI*cutoff_freq);
28  alpha = constrain_float(dt/(dt+rc), 0.0f, 1.0f);
29  _output += (sample - _output) * alpha;
30  return _output;
31 }
32 
33 template <class T>
34 T DigitalLPF<T>::apply(const T &sample) {
35  _output += (sample - _output) * alpha;
36  return _output;
37 }
38 
39 template <class T>
40 void DigitalLPF<T>::compute_alpha(float sample_freq, float cutoff_freq) {
41  if (cutoff_freq <= 0.0f || sample_freq <= 0.0f) {
42  alpha = 1.0;
43  } else {
44  float dt = 1.0/sample_freq;
45  float rc = 1.0f/(M_2PI*cutoff_freq);
46  alpha = constrain_float(dt/(dt+rc), 0.0f, 1.0f);
47  }
48 }
49 
50 // get latest filtered value from filter (equal to the value returned by latest call to apply method)
51 template <class T>
52 const T &DigitalLPF<T>::get() const {
53  return _output;
54 }
55 
56 template <class T>
58  _output = value;
59 }
60 
62 // LowPassFilter
64 
65 // constructors
66 template <class T>
68  _cutoff_freq(0.0f) {}
69 
70 template <class T>
71 LowPassFilter<T>::LowPassFilter(float cutoff_freq) :
72  _cutoff_freq(cutoff_freq) {}
73 
74 template <class T>
75 LowPassFilter<T>::LowPassFilter(float sample_freq, float cutoff_freq)
76 {
77  set_cutoff_frequency(sample_freq, cutoff_freq);
78 }
79 
80 // change parameters
81 template <class T>
82 void LowPassFilter<T>::set_cutoff_frequency(float cutoff_freq) {
83  _cutoff_freq = cutoff_freq;
84 }
85 
86 template <class T>
87 void LowPassFilter<T>::set_cutoff_frequency(float sample_freq, float cutoff_freq) {
88  _cutoff_freq = cutoff_freq;
89  _filter.compute_alpha(sample_freq, cutoff_freq);
90 }
91 
92 // return the cutoff frequency
93 template <class T>
95  return _cutoff_freq;
96 }
97 
98 template <class T>
99 T LowPassFilter<T>::apply(T sample, float dt) {
100  return _filter.apply(sample, _cutoff_freq, dt);
101 }
102 
103 template <class T>
105  return _filter.apply(sample);
106 }
107 
108 template <class T>
109 const T &LowPassFilter<T>::get() const {
110  return _filter.get();
111 }
112 
113 template <class T>
115  _filter.reset(value);
116 }
117 
118 /*
119  * Make an instances
120  * Otherwise we have to move the constructor implementations to the header file :P
121  */
122 template class LowPassFilter<int>;
123 template class LowPassFilter<long>;
124 template class LowPassFilter<float>;
125 template class LowPassFilter<Vector2f>;
126 template class LowPassFilter<Vector3f>;
127 
float get_cutoff_freq(void) const
float _cutoff_freq
Definition: LowPassFilter.h:91
T apply(const T &sample, float cutoff_freq, float dt)
static RC_Channel * rc
Definition: RC_Channel.cpp:17
void reset(T value)
void set_cutoff_frequency(float cutoff_freq)
DigitalLPF< T > _filter
Definition: LowPassFilter.h:94
void compute_alpha(float sample_freq, float cutoff_freq)
#define f(i)
#define M_2PI
Definition: definitions.h:19
const T & get() const
A class to implement a low pass filter without losing precision even for int types the downside being...
void reset(void)
Definition: LowPassFilter.h:88
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
float value
const T & get() const
T apply(T sample, float dt)