Path: blob/master/Tools/FilterTestTool/BiquadFilter.py
9631 views
#!/usr/bin/env python312""" ArduPilot BiquadFilter34This program is free software: you can redistribute it and/or modify it under5the terms of the GNU General Public License as published by the Free Software6Foundation, either version 3 of the License, or (at your option) any later7version.8This program is distributed in the hope that it will be useful, but WITHOUT9ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS10FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.11You should have received a copy of the GNU General Public License along with12this program. If not, see <http://www.gnu.org/licenses/>.13"""1415__author__ = "Guglielmo Cassinelli"16__contact__ = "[email protected]"1718import numpy as np192021class DigitalLPF:22def __init__(self, cutoff_freq, sample_freq):23self._cutoff_freq = cutoff_freq24self._sample_freq = sample_freq2526self._output = 02728self.compute_alpha()2930def compute_alpha(self):3132if self._cutoff_freq <= 0 or self._sample_freq <= 0:33self.alpha = 1.34else:35dt = 1. / self._sample_freq36rc = 1. / (np.pi * 2 * self._cutoff_freq)37a = dt / (dt + rc)38self.alpha = np.clip(a, 0, 1)3940def apply(self, sample):41self._output += (sample - self._output) * self.alpha42return self._output434445class BiquadFilterType:46LPF = 047PEAK = 148NOTCH = 2495051class BiquadFilter:5253def __init__(self, center_freq, sample_freq, type=BiquadFilterType.LPF, attenuation=10, bandwidth=15):54self._center_freq = int(center_freq)55self._attenuation_db = int(attenuation) # used only by notch, use setter56self._bandwidth_hz = int(bandwidth) # used only by notch, use setter5758self._sample_freq = sample_freq59self._type = type6061self._delayed_sample1 = 062self._delayed_sample2 = 063self._delayed_output1 = 064self._delayed_output2 = 06566self.b0 = 0.67self.b1 = 0.68self.b2 = 0.69self.a0 = 170self.a1 = 0.71self.a2 = 0.7273self.compute_params()7475def get_sample_freq(self):76return self._sample_freq7778def reset(self):79self._delayed_sample1 = 080self._delayed_sample2 = 081self._delayed_output1 = 082self._delayed_output2 = 08384def get_type(self):85return self._type8687def set_attenuation(self, attenuation_db):88self._attenuation_db = int(attenuation_db)89self.compute_params()9091def set_bandwidth(self, bandwidth_hz):92self._bandwidth_hz = int(bandwidth_hz)93self.compute_params()9495def set_center_freq(self, cutoff_freq):96self._center_freq = int(cutoff_freq)97self.compute_params()9899def compute_params(self):100101omega = 2 * np.pi * self._center_freq / self._sample_freq102sin_om = np.sin(omega)103cos_om = np.cos(omega)104105if self._type == BiquadFilterType.LPF:106107if self._center_freq > 0:108Q = 1 / np.sqrt(2)109alpha = sin_om / (2 * Q)110111self.b0 = (1 - cos_om) / 2112self.b1 = 1 - cos_om113self.b2 = self.b0114self.a0 = 1 + alpha115self.a1 = -2 * cos_om116self.a2 = 1 - alpha117118elif self._type == BiquadFilterType.PEAK:119120A = 10 ** (-self._attenuation_db / 40)121122# why not the formula below? It prevents a division by 0 when bandwidth = 2*frequency123octaves = np.log2(self._center_freq / (self._center_freq - self._bandwidth_hz / 2)) * 2124Q = np.sqrt(2 ** octaves) / (2 ** octaves - 1)125126# Q = self._center_freq / self._bandwidth_hz127128alpha = sin_om / (2 * Q / A)129130self.b0 = 1.0 + alpha * A131self.b1 = -2.0 * cos_om132self.b2 = 1.0 - alpha * A133self.a0 = 1.0 + alpha / A134self.a1 = -2.0 * cos_om135self.a2 = 1.0 - alpha / A136137elif self._type == BiquadFilterType.NOTCH:138alpha = sin_om * np.sinh(np.log(2) / 2 * self._bandwidth_hz * omega * sin_om)139140self.b0 = 1141self.b1 = -2 * cos_om142self.b2 = self.b0143self.a0 = 1 + alpha144self.a1 = -2 * cos_om145self.a2 = 1 - alpha146147self.b0 /= self.a0148self.b1 /= self.a0149self.b2 /= self.a0150self.a1 /= self.a0151self.a2 /= self.a0152153def apply(self, sample):154155if self._center_freq <= 0:156return sample157158output = (self.b0 * sample + self.b1 * self._delayed_sample1 + self.b2 * self._delayed_sample2 - self.a1159* self._delayed_output1 - self.a2 * self._delayed_output2)160161self._delayed_sample2 = self._delayed_sample1162self._delayed_sample1 = sample163164self._delayed_output2 = self._delayed_output1165self._delayed_output1 = output166167return output168169def get_params(self):170171return {172"a1": self.a1,173"a2": self.a2,174"b0": self.b0,175"b1": self.b1,176"b2": self.b2,177}178179def get_center_freq(self):180return self._center_freq181182def get_attenuation(self):183return self._attenuation_db184185def get_bandwidth(self):186return self._bandwidth_hz187188def freq_response(self, f):189if self._center_freq <= 0:190return 1191192phi = (np.sin(np.pi * f * 2 / (2 * self._sample_freq))) ** 2193r = (((self.b0 + self.b1 + self.b2) ** 2 - 4 * (self.b0 * self.b1 + 4 * self.b0 * self.b2 + self.b1 * self.b2)194* phi + 16 * self.b0 * self.b2 * phi * phi)195/ ((1 + self.a1 + self.a2) ** 2 - 4 * (self.a1 + 4 * self.a2 + self.a1 * self.a2) * phi + 16196* self.a2 * phi * phi))197# if r < 0:198# r = 0199return r ** .5200201202