CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

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