AverageFilter.h 6.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. //
  14. /// @file AverageFilter.h
  15. /// @brief A class to provide the average of a number of samples
  16. #pragma once
  17. #include "FilterClass.h"
  18. #include "FilterWithBuffer.h"
  19. // 1st parameter <T> is the type of data being filtered.
  20. // 2nd parameter <U> is a larger data type used during summation to prevent overflows
  21. // 3rd parameter <FILTER_SIZE> is the number of elements in the filter
  22. template <class T, class U, uint8_t FILTER_SIZE>
  23. class AverageFilter : public FilterWithBuffer<T,FILTER_SIZE>
  24. {
  25. public:
  26. // constructor
  27. AverageFilter() : FilterWithBuffer<T,FILTER_SIZE>(), _num_samples(0) {
  28. };
  29. // apply - Add a new raw value to the filter, retrieve the filtered result
  30. virtual T apply(T sample) override;
  31. // reset - clear the filter
  32. virtual void reset() override;
  33. protected:
  34. // the number of samples in the filter, maxes out at size of the filter
  35. uint8_t _num_samples;
  36. };
  37. // Typedef for convenience (1st argument is the data type, 2nd is a larger datatype to handle overflows, 3rd is buffer size)
  38. typedef AverageFilter<int8_t,int16_t,2> AverageFilterInt8_Size2;
  39. typedef AverageFilter<int8_t,int16_t,3> AverageFilterInt8_Size3;
  40. typedef AverageFilter<int8_t,int16_t,4> AverageFilterInt8_Size4;
  41. typedef AverageFilter<int8_t,int16_t,5> AverageFilterInt8_Size5;
  42. typedef AverageFilter<uint8_t,uint16_t,2> AverageFilterUInt8_Size2;
  43. typedef AverageFilter<uint8_t,uint16_t,3> AverageFilterUInt8_Size3;
  44. typedef AverageFilter<uint8_t,uint16_t,4> AverageFilterUInt8_Size4;
  45. typedef AverageFilter<uint8_t,uint16_t,5> AverageFilterUInt8_Size5;
  46. typedef AverageFilter<int16_t,int32_t,2> AverageFilterInt16_Size2;
  47. typedef AverageFilter<int16_t,int32_t,3> AverageFilterInt16_Size3;
  48. typedef AverageFilter<int16_t,int32_t,4> AverageFilterInt16_Size4;
  49. typedef AverageFilter<int16_t,int32_t,5> AverageFilterInt16_Size5;
  50. typedef AverageFilter<uint16_t,uint32_t,2> AverageFilterUInt16_Size2;
  51. typedef AverageFilter<uint16_t,uint32_t,3> AverageFilterUInt16_Size3;
  52. typedef AverageFilter<uint16_t,uint32_t,4> AverageFilterUInt16_Size4;
  53. typedef AverageFilter<uint16_t,uint32_t,5> AverageFilterUInt16_Size5;
  54. typedef AverageFilter<int32_t,float,2> AverageFilterInt32_Size2;
  55. typedef AverageFilter<int32_t,float,3> AverageFilterInt32_Size3;
  56. typedef AverageFilter<int32_t,float,4> AverageFilterInt32_Size4;
  57. typedef AverageFilter<int32_t,float,5> AverageFilterInt32_Size5;
  58. typedef AverageFilter<uint32_t,float,2> AverageFilterUInt32_Size2;
  59. typedef AverageFilter<uint32_t,float,3> AverageFilterUInt32_Size3;
  60. typedef AverageFilter<uint32_t,float,4> AverageFilterUInt32_Size4;
  61. typedef AverageFilter<uint32_t,float,5> AverageFilterUInt32_Size5;
  62. typedef AverageFilter<float,float,5> AverageFilterFloat_Size5;
  63. // Public Methods //////////////////////////////////////////////////////////////
  64. template <class T, class U, uint8_t FILTER_SIZE>
  65. T AverageFilter<T,U,FILTER_SIZE>:: apply(T sample)
  66. {
  67. U result = 0;
  68. // call parent's apply function to get the sample into the array
  69. FilterWithBuffer<T,FILTER_SIZE>::apply(sample);
  70. // increment the number of samples so far
  71. _num_samples++;
  72. if( _num_samples > FILTER_SIZE || _num_samples == 0 )
  73. _num_samples = FILTER_SIZE;
  74. // get sum of all values - there is a risk of overflow here that we ignore
  75. for(uint8_t i=0; i<FILTER_SIZE; i++)
  76. result += FilterWithBuffer<T,FILTER_SIZE>::samples[i];
  77. return (T)(result / _num_samples);
  78. }
  79. // reset - clear all samples
  80. template <class T, class U, uint8_t FILTER_SIZE>
  81. void AverageFilter<T,U,FILTER_SIZE>:: reset()
  82. {
  83. // call parent's apply function to get the sample into the array
  84. FilterWithBuffer<T,FILTER_SIZE>::reset();
  85. // clear our variable
  86. _num_samples = 0;
  87. }
  88. /*
  89. * This filter is intended to be used with integral types to be faster and
  90. * avoid loss of precision on floating point arithmetic. The integral type
  91. * chosen must be one that fits FILTER_SIZE values you are filtering.
  92. *
  93. * Differently from other average filters, the result is only returned when
  94. * getf()/getd() is called
  95. */
  96. template <class T, class U, uint8_t FILTER_SIZE>
  97. class AverageIntegralFilter : public AverageFilter<T,U,FILTER_SIZE>
  98. {
  99. public:
  100. /*
  101. * Add a new raw value to the filter: method signature is maintained from
  102. * AverageFilter, but it doesn't retrieve the filtered value: return value
  103. * is always 0. Call getf()/getd() in order to get the filtered value.
  104. */
  105. virtual T apply(T sample) override;
  106. // get the current value as a float
  107. virtual float getf();
  108. // get the current value as a double
  109. virtual double getd();
  110. protected:
  111. // the current sum of samples
  112. U _sum = 0;
  113. };
  114. template <class T, class U, uint8_t FILTER_SIZE>
  115. T AverageIntegralFilter<T,U,FILTER_SIZE>::apply(T sample)
  116. {
  117. T curr = this->samples[this->sample_index];
  118. // call parent's parent apply function to get the sample into the array
  119. FilterWithBuffer<T,FILTER_SIZE>::apply(sample);
  120. // increment the number of samples so far
  121. this->_num_samples++;
  122. if (this->_num_samples > FILTER_SIZE || this->_num_samples == 0) {
  123. this->_num_samples = FILTER_SIZE;
  124. }
  125. _sum -= curr;
  126. _sum += sample;
  127. // don't return the value: caller is forced to call getf() or getd()
  128. return 0;
  129. }
  130. template <class T, class U, uint8_t FILTER_SIZE>
  131. float AverageIntegralFilter<T,U,FILTER_SIZE>::getf()
  132. {
  133. if (this->_num_samples == 0) {
  134. return 0.f;
  135. }
  136. return (float)_sum / this->_num_samples;
  137. }
  138. template <class T, class U, uint8_t FILTER_SIZE>
  139. double AverageIntegralFilter<T,U,FILTER_SIZE>::getd()
  140. {
  141. if (this->_num_samples == 0) {
  142. return 0.f;
  143. }
  144. return (double)_sum / this->_num_samples;
  145. }