DerivativeFilter.cpp 4.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140
  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. /// @file Derivative.cpp
  14. /// @brief A class to implement a derivative (slope) filter
  15. /// See http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/
  16. //
  17. #include <inttypes.h>
  18. #include <AP_Math/AP_Math.h>
  19. #include "Filter.h"
  20. #include "DerivativeFilter.h"
  21. template <class T, uint8_t FILTER_SIZE>
  22. void DerivativeFilter<T,FILTER_SIZE>::update(T sample, uint32_t timestamp)
  23. {
  24. uint8_t i = FilterWithBuffer<T,FILTER_SIZE>::sample_index;
  25. uint8_t i1;
  26. if (i == 0) {
  27. i1 = FILTER_SIZE-1;
  28. } else {
  29. i1 = i-1;
  30. }
  31. if (_timestamps[i1] == timestamp) {
  32. // this is not a new timestamp - ignore
  33. return;
  34. }
  35. // add timestamp before we apply to FilterWithBuffer
  36. _timestamps[i] = timestamp;
  37. // call parent's apply function to get the sample into the array
  38. FilterWithBuffer<T,FILTER_SIZE>::apply(sample);
  39. _new_data = true;
  40. }
  41. template <class T, uint8_t FILTER_SIZE>
  42. float DerivativeFilter<T,FILTER_SIZE>::slope(void)
  43. {
  44. if (!_new_data) {
  45. return _last_slope;
  46. }
  47. float result = 0;
  48. // use f() to make the code match the maths a bit better. Note
  49. // that unlike an average filter, we care about the order of the elements
  50. #define f(i) FilterWithBuffer<T,FILTER_SIZE>::samples[(((FilterWithBuffer<T,FILTER_SIZE>::sample_index-1)+i+1)+3*FILTER_SIZE/2) % FILTER_SIZE]
  51. #define x(i) _timestamps[(((FilterWithBuffer<T,FILTER_SIZE>::sample_index-1)+i+1)+3*FILTER_SIZE/2) % FILTER_SIZE]
  52. if (_timestamps[FILTER_SIZE-1] == _timestamps[FILTER_SIZE-2]) {
  53. // we haven't filled the buffer yet - assume zero derivative
  54. return 0;
  55. }
  56. // N in the paper is FILTER_SIZE
  57. switch (FILTER_SIZE) {
  58. case 5:
  59. result = 2*2*(f(1) - f(-1)) / (x(1) - x(-1))
  60. + 4*1*(f(2) - f(-2)) / (x(2) - x(-2));
  61. result /= 8;
  62. break;
  63. case 7:
  64. result = 2*5*(f(1) - f(-1)) / (x(1) - x(-1))
  65. + 4*4*(f(2) - f(-2)) / (x(2) - x(-2))
  66. + 6*1*(f(3) - f(-3)) / (x(3) - x(-3));
  67. result /= 32;
  68. break;
  69. case 9:
  70. result = 2*14*(f(1) - f(-1)) / (x(1) - x(-1))
  71. + 4*14*(f(2) - f(-2)) / (x(2) - x(-2))
  72. + 6* 6*(f(3) - f(-3)) / (x(3) - x(-3))
  73. + 8* 1*(f(4) - f(-4)) / (x(4) - x(-4));
  74. result /= 128;
  75. break;
  76. case 11:
  77. result = 2*42*(f(1) - f(-1)) / (x(1) - x(-1))
  78. + 4*48*(f(2) - f(-2)) / (x(2) - x(-2))
  79. + 6*27*(f(3) - f(-3)) / (x(3) - x(-3))
  80. + 8* 8*(f(4) - f(-4)) / (x(4) - x(-4))
  81. + 10* 1*(f(5) - f(-5)) / (x(5) - x(-5));
  82. result /= 512;
  83. break;
  84. default:
  85. result = 0;
  86. break;
  87. }
  88. // cope with numerical errors
  89. if (isnan(result) || isinf(result)) {
  90. result = 0;
  91. }
  92. _new_data = false;
  93. _last_slope = result;
  94. return result;
  95. }
  96. // reset - clear all samples
  97. template <class T, uint8_t FILTER_SIZE>
  98. void DerivativeFilter<T,FILTER_SIZE>::reset(void)
  99. {
  100. // call parent's apply function to get the sample into the array
  101. FilterWithBuffer<T,FILTER_SIZE>::reset();
  102. }
  103. // add new instances as needed here
  104. template void DerivativeFilter<float,5>::update(float sample, uint32_t timestamp);
  105. template float DerivativeFilter<float,5>::slope(void);
  106. template void DerivativeFilter<float,5>::reset(void);
  107. template void DerivativeFilter<float,7>::update(float sample, uint32_t timestamp);
  108. template float DerivativeFilter<float,7>::slope(void);
  109. template void DerivativeFilter<float,7>::reset(void);
  110. template void DerivativeFilter<float,9>::update(float sample, uint32_t timestamp);
  111. template float DerivativeFilter<float,9>::slope(void);
  112. template void DerivativeFilter<float,9>::reset(void);
  113. template void DerivativeFilter<float,11>::update(float sample, uint32_t timestamp);
  114. template float DerivativeFilter<float,11>::slope(void);
  115. template void DerivativeFilter<float,11>::reset(void);