LowPassFilter2p.cpp 3.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110
  1. #include "LowPassFilter2p.h"
  2. ////////////////////////////////////////////////////////////////////////////////////////////
  3. // DigitalBiquadFilter
  4. ////////////////////////////////////////////////////////////////////////////////////////////
  5. template <class T>
  6. DigitalBiquadFilter<T>::DigitalBiquadFilter() {
  7. _delay_element_1 = T();
  8. _delay_element_2 = T();
  9. }
  10. template <class T>
  11. T DigitalBiquadFilter<T>::apply(const T &sample, const struct biquad_params &params) {
  12. if(is_zero(params.cutoff_freq) || is_zero(params.sample_freq)) {
  13. return sample;
  14. }
  15. T delay_element_0 = sample - _delay_element_1 * params.a1 - _delay_element_2 * params.a2;
  16. T output = delay_element_0 * params.b0 + _delay_element_1 * params.b1 + _delay_element_2 * params.b2;
  17. _delay_element_2 = _delay_element_1;
  18. _delay_element_1 = delay_element_0;
  19. return output;
  20. }
  21. template <class T>
  22. void DigitalBiquadFilter<T>::reset() {
  23. _delay_element_1 = _delay_element_2 = T();
  24. }
  25. template <class T>
  26. void DigitalBiquadFilter<T>::compute_params(float sample_freq, float cutoff_freq, biquad_params &ret) {
  27. ret.cutoff_freq = cutoff_freq;
  28. ret.sample_freq = sample_freq;
  29. if (!is_positive(ret.cutoff_freq)) {
  30. // zero cutoff means pass-thru
  31. return;
  32. }
  33. float fr = sample_freq/cutoff_freq;
  34. float ohm = tanf(M_PI/fr);
  35. float c = 1.0f+2.0f*cosf(M_PI/4.0f)*ohm + ohm*ohm;
  36. ret.b0 = ohm*ohm/c;
  37. ret.b1 = 2.0f*ret.b0;
  38. ret.b2 = ret.b0;
  39. ret.a1 = 2.0f*(ohm*ohm-1.0f)/c;
  40. ret.a2 = (1.0f-2.0f*cosf(M_PI/4.0f)*ohm+ohm*ohm)/c;
  41. }
  42. ////////////////////////////////////////////////////////////////////////////////////////////
  43. // LowPassFilter2p
  44. ////////////////////////////////////////////////////////////////////////////////////////////
  45. template <class T>
  46. LowPassFilter2p<T>::LowPassFilter2p() {
  47. memset(&_params, 0, sizeof(_params) );
  48. }
  49. // constructor
  50. template <class T>
  51. LowPassFilter2p<T>::LowPassFilter2p(float sample_freq, float cutoff_freq) {
  52. // set initial parameters
  53. set_cutoff_frequency(sample_freq, cutoff_freq);
  54. }
  55. // change parameters
  56. template <class T>
  57. void LowPassFilter2p<T>::set_cutoff_frequency(float sample_freq, float cutoff_freq) {
  58. DigitalBiquadFilter<T>::compute_params(sample_freq, cutoff_freq, _params);
  59. }
  60. // return the cutoff frequency
  61. template <class T>
  62. float LowPassFilter2p<T>::get_cutoff_freq(void) const {
  63. return _params.cutoff_freq;
  64. }
  65. template <class T>
  66. float LowPassFilter2p<T>::get_sample_freq(void) const {
  67. return _params.sample_freq;
  68. }
  69. template <class T>
  70. T LowPassFilter2p<T>::apply(const T &sample) {
  71. if (!is_positive(_params.cutoff_freq)) {
  72. // zero cutoff means pass-thru
  73. return sample;
  74. }
  75. return _filter.apply(sample, _params);
  76. }
  77. template <class T>
  78. void LowPassFilter2p<T>::reset(void) {
  79. return _filter.reset();
  80. }
  81. /*
  82. * Make an instances
  83. * Otherwise we have to move the constructor implementations to the header file :P
  84. */
  85. template class LowPassFilter2p<int>;
  86. template class LowPassFilter2p<long>;
  87. template class LowPassFilter2p<float>;
  88. template class LowPassFilter2p<Vector2f>;
  89. template class LowPassFilter2p<Vector3f>;