APM:Libraries
DerivativeFilter.cpp
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
19 //
20 #include <inttypes.h>
21 #include <AP_Math/AP_Math.h>
22 #include "Filter.h"
23 #include "DerivativeFilter.h"
24 
25 
26 template <class T, uint8_t FILTER_SIZE>
27 void DerivativeFilter<T,FILTER_SIZE>::update(T sample, uint32_t timestamp)
28 {
30  uint8_t i1;
31  if (i == 0) {
32  i1 = FILTER_SIZE-1;
33  } else {
34  i1 = i-1;
35  }
36  if (_timestamps[i1] == timestamp) {
37  // this is not a new timestamp - ignore
38  return;
39  }
40 
41  // add timestamp before we apply to FilterWithBuffer
42  _timestamps[i] = timestamp;
43 
44  // call parent's apply function to get the sample into the array
46 
47  _new_data = true;
48 }
49 
50 
51 template <class T, uint8_t FILTER_SIZE>
53 {
54  if (!_new_data) {
55  return _last_slope;
56  }
57 
58  float result = 0;
59 
60  // use f() to make the code match the maths a bit better. Note
61  // that unlike an average filter, we care about the order of the elements
62 #define f(i) FilterWithBuffer<T,FILTER_SIZE>::samples[(((FilterWithBuffer<T,FILTER_SIZE>::sample_index-1)+i+1)+3*FILTER_SIZE/2) % FILTER_SIZE]
63 #define x(i) _timestamps[(((FilterWithBuffer<T,FILTER_SIZE>::sample_index-1)+i+1)+3*FILTER_SIZE/2) % FILTER_SIZE]
64 
65  if (_timestamps[FILTER_SIZE-1] == _timestamps[FILTER_SIZE-2]) {
66  // we haven't filled the buffer yet - assume zero derivative
67  return 0;
68  }
69 
70  // N in the paper is FILTER_SIZE
71  switch (FILTER_SIZE) {
72  case 5:
73  result = 2*2*(f(1) - f(-1)) / (x(1) - x(-1))
74  + 4*1*(f(2) - f(-2)) / (x(2) - x(-2));
75  result /= 8;
76  break;
77  case 7:
78  result = 2*5*(f(1) - f(-1)) / (x(1) - x(-1))
79  + 4*4*(f(2) - f(-2)) / (x(2) - x(-2))
80  + 6*1*(f(3) - f(-3)) / (x(3) - x(-3));
81  result /= 32;
82  break;
83  case 9:
84  result = 2*14*(f(1) - f(-1)) / (x(1) - x(-1))
85  + 4*14*(f(2) - f(-2)) / (x(2) - x(-2))
86  + 6* 6*(f(3) - f(-3)) / (x(3) - x(-3))
87  + 8* 1*(f(4) - f(-4)) / (x(4) - x(-4));
88  result /= 128;
89  break;
90  case 11:
91  result = 2*42*(f(1) - f(-1)) / (x(1) - x(-1))
92  + 4*48*(f(2) - f(-2)) / (x(2) - x(-2))
93  + 6*27*(f(3) - f(-3)) / (x(3) - x(-3))
94  + 8* 8*(f(4) - f(-4)) / (x(4) - x(-4))
95  + 10* 1*(f(5) - f(-5)) / (x(5) - x(-5));
96  result /= 512;
97  break;
98  default:
99  result = 0;
100  break;
101  }
102 
103  // cope with numerical errors
104  if (isnan(result) || isinf(result)) {
105  result = 0;
106  }
107 
108  _new_data = false;
109  _last_slope = result;
110 
111  return result;
112 }
113 
114 // reset - clear all samples
115 template <class T, uint8_t FILTER_SIZE>
117 {
118  // call parent's apply function to get the sample into the array
120 }
121 
122 // add new instances as needed here
123 template void DerivativeFilter<float,5>::update(float sample, uint32_t timestamp);
124 template float DerivativeFilter<float,5>::slope(void);
125 template void DerivativeFilter<float,5>::reset(void);
126 
127 template void DerivativeFilter<float,7>::update(float sample, uint32_t timestamp);
128 template float DerivativeFilter<float,7>::slope(void);
129 template void DerivativeFilter<float,7>::reset(void);
130 
131 template void DerivativeFilter<float,9>::update(float sample, uint32_t timestamp);
132 template float DerivativeFilter<float,9>::slope(void);
133 template void DerivativeFilter<float,9>::reset(void);
134 
135 template void DerivativeFilter<float,11>::update(float sample, uint32_t timestamp);
136 template float DerivativeFilter<float,11>::slope(void);
137 template void DerivativeFilter<float,11>::reset(void);
138 
139 
140 
void update(T sample, uint32_t timestamp)
virtual void reset()
virtual T apply(T sample)
const char * result
Definition: Printf.cpp:16
#define x(i)
#define f(i)
virtual void reset()