Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/FilterTestTool/BiquadFilter.py
Views: 1798
#!/usr/bin/env python1# -*- coding: utf-8 -*-23""" ArduPilot BiquadFilter45This program is free software: you can redistribute it and/or modify it under6the terms of the GNU General Public License as published by the Free Software7Foundation, either version 3 of the License, or (at your option) any later8version.9This program is distributed in the hope that it will be useful, but WITHOUT10ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS11FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.12You should have received a copy of the GNU General Public License along with13this program. If not, see <http://www.gnu.org/licenses/>.14"""1516__author__ = "Guglielmo Cassinelli"17__contact__ = "[email protected]"1819import numpy as np202122class DigitalLPF:23def __init__(self, cutoff_freq, sample_freq):24self._cutoff_freq = cutoff_freq25self._sample_freq = sample_freq2627self._output = 02829self.compute_alpha()3031def compute_alpha(self):3233if self._cutoff_freq <= 0 or self._sample_freq <= 0:34self.alpha = 1.35else:36dt = 1. / self._sample_freq37rc = 1. / (np.pi * 2 * self._cutoff_freq)38a = dt / (dt + rc)39self.alpha = np.clip(a, 0, 1)4041def apply(self, sample):42self._output += (sample - self._output) * self.alpha43return self._output444546class BiquadFilterType:47LPF = 048PEAK = 149NOTCH = 2505152class BiquadFilter:5354def __init__(self, center_freq, sample_freq, type=BiquadFilterType.LPF, attenuation=10, bandwidth=15):55self._center_freq = int(center_freq)56self._attenuation_db = int(attenuation) # used only by notch, use setter57self._bandwidth_hz = int(bandwidth) # used only by notch, use setter5859self._sample_freq = sample_freq60self._type = type6162self._delayed_sample1 = 063self._delayed_sample2 = 064self._delayed_output1 = 065self._delayed_output2 = 06667self.b0 = 0.68self.b1 = 0.69self.b2 = 0.70self.a0 = 171self.a1 = 0.72self.a2 = 0.7374self.compute_params()7576def get_sample_freq(self):77return self._sample_freq7879def reset(self):80self._delayed_sample1 = 081self._delayed_sample2 = 082self._delayed_output1 = 083self._delayed_output2 = 08485def get_type(self):86return self._type8788def set_attenuation(self, attenuation_db):89self._attenuation_db = int(attenuation_db)90self.compute_params()9192def set_bandwidth(self, bandwidth_hz):93self._bandwidth_hz = int(bandwidth_hz)94self.compute_params()9596def set_center_freq(self, cutoff_freq):97self._center_freq = int(cutoff_freq)98self.compute_params()99100def compute_params(self):101102omega = 2 * np.pi * self._center_freq / self._sample_freq103sin_om = np.sin(omega)104cos_om = np.cos(omega)105106if self._type == BiquadFilterType.LPF:107108if self._center_freq > 0:109Q = 1 / np.sqrt(2)110alpha = sin_om / (2 * Q)111112self.b0 = (1 - cos_om) / 2113self.b1 = 1 - cos_om114self.b2 = self.b0115self.a0 = 1 + alpha116self.a1 = -2 * cos_om117self.a2 = 1 - alpha118119elif self._type == BiquadFilterType.PEAK:120121A = 10 ** (-self._attenuation_db / 40)122123# why not the formula below? It prevents a division by 0 when bandwidth = 2*frequency124octaves = np.log2(self._center_freq / (self._center_freq - self._bandwidth_hz / 2)) * 2125Q = np.sqrt(2 ** octaves) / (2 ** octaves - 1)126127# Q = self._center_freq / self._bandwidth_hz128129alpha = sin_om / (2 * Q / A)130131self.b0 = 1.0 + alpha * A132self.b1 = -2.0 * cos_om133self.b2 = 1.0 - alpha * A134self.a0 = 1.0 + alpha / A135self.a1 = -2.0 * cos_om136self.a2 = 1.0 - alpha / A137138elif self._type == BiquadFilterType.NOTCH:139alpha = sin_om * np.sinh(np.log(2) / 2 * self._bandwidth_hz * omega * sin_om)140141self.b0 = 1142self.b1 = -2 * cos_om143self.b2 = self.b0144self.a0 = 1 + alpha145self.a1 = -2 * cos_om146self.a2 = 1 - alpha147148self.b0 /= self.a0149self.b1 /= self.a0150self.b2 /= self.a0151self.a1 /= self.a0152self.a2 /= self.a0153154def apply(self, sample):155156if self._center_freq <= 0:157return sample158159output = (self.b0 * sample + self.b1 * self._delayed_sample1 + self.b2 * self._delayed_sample2 - self.a1160* self._delayed_output1 - self.a2 * self._delayed_output2)161162self._delayed_sample2 = self._delayed_sample1163self._delayed_sample1 = sample164165self._delayed_output2 = self._delayed_output1166self._delayed_output1 = output167168return output169170def get_params(self):171172return {173"a1": self.a1,174"a2": self.a2,175"b0": self.b0,176"b1": self.b1,177"b2": self.b2,178}179180def get_center_freq(self):181return self._center_freq182183def get_attenuation(self):184return self._attenuation_db185186def get_bandwidth(self):187return self._bandwidth_hz188189def freq_response(self, f):190if self._center_freq <= 0:191return 1192193phi = (np.sin(np.pi * f * 2 / (2 * self._sample_freq))) ** 2194r = (((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 + 16197* self.a2 * phi * phi))198# if r < 0:199# r = 0200return r ** .5201202203