Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/FilterTestTool/BiquadFilter.py
9631 views
1
#!/usr/bin/env python3
2
3
""" ArduPilot BiquadFilter
4
5
This program is free software: you can redistribute it and/or modify it under
6
the terms of the GNU General Public License as published by the Free Software
7
Foundation, either version 3 of the License, or (at your option) any later
8
version.
9
This program is distributed in the hope that it will be useful, but WITHOUT
10
ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
11
FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
12
You should have received a copy of the GNU General Public License along with
13
this program. If not, see <http://www.gnu.org/licenses/>.
14
"""
15
16
__author__ = "Guglielmo Cassinelli"
17
__contact__ = "[email protected]"
18
19
import numpy as np
20
21
22
class DigitalLPF:
23
def __init__(self, cutoff_freq, sample_freq):
24
self._cutoff_freq = cutoff_freq
25
self._sample_freq = sample_freq
26
27
self._output = 0
28
29
self.compute_alpha()
30
31
def compute_alpha(self):
32
33
if self._cutoff_freq <= 0 or self._sample_freq <= 0:
34
self.alpha = 1.
35
else:
36
dt = 1. / self._sample_freq
37
rc = 1. / (np.pi * 2 * self._cutoff_freq)
38
a = dt / (dt + rc)
39
self.alpha = np.clip(a, 0, 1)
40
41
def apply(self, sample):
42
self._output += (sample - self._output) * self.alpha
43
return self._output
44
45
46
class BiquadFilterType:
47
LPF = 0
48
PEAK = 1
49
NOTCH = 2
50
51
52
class BiquadFilter:
53
54
def __init__(self, center_freq, sample_freq, type=BiquadFilterType.LPF, attenuation=10, bandwidth=15):
55
self._center_freq = int(center_freq)
56
self._attenuation_db = int(attenuation) # used only by notch, use setter
57
self._bandwidth_hz = int(bandwidth) # used only by notch, use setter
58
59
self._sample_freq = sample_freq
60
self._type = type
61
62
self._delayed_sample1 = 0
63
self._delayed_sample2 = 0
64
self._delayed_output1 = 0
65
self._delayed_output2 = 0
66
67
self.b0 = 0.
68
self.b1 = 0.
69
self.b2 = 0.
70
self.a0 = 1
71
self.a1 = 0.
72
self.a2 = 0.
73
74
self.compute_params()
75
76
def get_sample_freq(self):
77
return self._sample_freq
78
79
def reset(self):
80
self._delayed_sample1 = 0
81
self._delayed_sample2 = 0
82
self._delayed_output1 = 0
83
self._delayed_output2 = 0
84
85
def get_type(self):
86
return self._type
87
88
def set_attenuation(self, attenuation_db):
89
self._attenuation_db = int(attenuation_db)
90
self.compute_params()
91
92
def set_bandwidth(self, bandwidth_hz):
93
self._bandwidth_hz = int(bandwidth_hz)
94
self.compute_params()
95
96
def set_center_freq(self, cutoff_freq):
97
self._center_freq = int(cutoff_freq)
98
self.compute_params()
99
100
def compute_params(self):
101
102
omega = 2 * np.pi * self._center_freq / self._sample_freq
103
sin_om = np.sin(omega)
104
cos_om = np.cos(omega)
105
106
if self._type == BiquadFilterType.LPF:
107
108
if self._center_freq > 0:
109
Q = 1 / np.sqrt(2)
110
alpha = sin_om / (2 * Q)
111
112
self.b0 = (1 - cos_om) / 2
113
self.b1 = 1 - cos_om
114
self.b2 = self.b0
115
self.a0 = 1 + alpha
116
self.a1 = -2 * cos_om
117
self.a2 = 1 - alpha
118
119
elif self._type == BiquadFilterType.PEAK:
120
121
A = 10 ** (-self._attenuation_db / 40)
122
123
# why not the formula below? It prevents a division by 0 when bandwidth = 2*frequency
124
octaves = np.log2(self._center_freq / (self._center_freq - self._bandwidth_hz / 2)) * 2
125
Q = np.sqrt(2 ** octaves) / (2 ** octaves - 1)
126
127
# Q = self._center_freq / self._bandwidth_hz
128
129
alpha = sin_om / (2 * Q / A)
130
131
self.b0 = 1.0 + alpha * A
132
self.b1 = -2.0 * cos_om
133
self.b2 = 1.0 - alpha * A
134
self.a0 = 1.0 + alpha / A
135
self.a1 = -2.0 * cos_om
136
self.a2 = 1.0 - alpha / A
137
138
elif self._type == BiquadFilterType.NOTCH:
139
alpha = sin_om * np.sinh(np.log(2) / 2 * self._bandwidth_hz * omega * sin_om)
140
141
self.b0 = 1
142
self.b1 = -2 * cos_om
143
self.b2 = self.b0
144
self.a0 = 1 + alpha
145
self.a1 = -2 * cos_om
146
self.a2 = 1 - alpha
147
148
self.b0 /= self.a0
149
self.b1 /= self.a0
150
self.b2 /= self.a0
151
self.a1 /= self.a0
152
self.a2 /= self.a0
153
154
def apply(self, sample):
155
156
if self._center_freq <= 0:
157
return sample
158
159
output = (self.b0 * sample + self.b1 * self._delayed_sample1 + self.b2 * self._delayed_sample2 - self.a1
160
* self._delayed_output1 - self.a2 * self._delayed_output2)
161
162
self._delayed_sample2 = self._delayed_sample1
163
self._delayed_sample1 = sample
164
165
self._delayed_output2 = self._delayed_output1
166
self._delayed_output1 = output
167
168
return output
169
170
def get_params(self):
171
172
return {
173
"a1": self.a1,
174
"a2": self.a2,
175
"b0": self.b0,
176
"b1": self.b1,
177
"b2": self.b2,
178
}
179
180
def get_center_freq(self):
181
return self._center_freq
182
183
def get_attenuation(self):
184
return self._attenuation_db
185
186
def get_bandwidth(self):
187
return self._bandwidth_hz
188
189
def freq_response(self, f):
190
if self._center_freq <= 0:
191
return 1
192
193
phi = (np.sin(np.pi * f * 2 / (2 * self._sample_freq))) ** 2
194
r = (((self.b0 + self.b1 + self.b2) ** 2 - 4 * (self.b0 * self.b1 + 4 * self.b0 * self.b2 + self.b1 * self.b2)
195
* phi + 16 * self.b0 * self.b2 * phi * phi)
196
/ ((1 + self.a1 + self.a2) ** 2 - 4 * (self.a1 + 4 * self.a2 + self.a1 * self.a2) * phi + 16
197
* self.a2 * phi * phi))
198
# if r < 0:
199
# r = 0
200
return r ** .5
201
202