Path: blob/master/Tools/FilterTestTool/FilterTest.py
9486 views
# -*- coding: utf-8 -*-12# flake8: noqa34""" ArduPilot IMU Filter Test Class56This program is free software: you can redistribute it and/or modify it under7the terms of the GNU General Public License as published by the Free Software8Foundation, either version 3 of the License, or (at your option) any later9version.10This program is distributed in the hope that it will be useful, but WITHOUT11ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS12FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.13You should have received a copy of the GNU General Public License along with14this program. If not, see <http://www.gnu.org/licenses/>.15"""1617__author__ = "Guglielmo Cassinelli"18__contact__ = "[email protected]"1920import numpy as np21import matplotlib.pyplot as plt22from matplotlib.widgets import Slider23from matplotlib.animation import FuncAnimation24from scipy import signal25from BiquadFilter import BiquadFilterType, BiquadFilter2627sliders = [] # matplotlib sliders must be global28anim = None # matplotlib animations must be global293031class FilterTest:32FILTER_DEBOUNCE = 10 # ms3334FILT_SHAPE_DT_FACTOR = 1 # increase to reduce filter shape size3536FFT_N = 5123738filters = {}3940def __init__(self, acc_t, acc_x, acc_y, acc_z, gyr_t, gyr_x, gyr_y, gyr_z, acc_freq, gyr_freq,41acc_lpf_cutoff, gyr_lpf_cutoff,42acc_notch_freq, acc_notch_att, acc_notch_band,43gyr_notch_freq, gyr_notch_att, gyr_notch_band,44log_name, accel_notch=False, second_notch=False):4546self.filter_color_map = plt.get_cmap('summer')4748self.filters["acc"] = [49BiquadFilter(acc_lpf_cutoff, acc_freq)50]5152if accel_notch:53self.filters["acc"].append(54BiquadFilter(acc_notch_freq, acc_freq, BiquadFilterType.PEAK, acc_notch_att, acc_notch_band),55)5657self.filters["gyr"] = [58BiquadFilter(gyr_lpf_cutoff, gyr_freq),59BiquadFilter(gyr_notch_freq, gyr_freq, BiquadFilterType.PEAK, gyr_notch_att, gyr_notch_band)60]6162if second_notch:63self.filters["acc"].append(64BiquadFilter(acc_notch_freq * 2, acc_freq, BiquadFilterType.PEAK, acc_notch_att, acc_notch_band)65)66self.filters["gyr"].append(67BiquadFilter(gyr_notch_freq * 2, gyr_freq, BiquadFilterType.PEAK, gyr_notch_att, gyr_notch_band)68)6970self.ACC_t = acc_t71self.ACC_x = acc_x72self.ACC_y = acc_y73self.ACC_z = acc_z7475self.GYR_t = gyr_t76self.GYR_x = gyr_x77self.GYR_y = gyr_y78self.GYR_z = gyr_z7980self.GYR_freq = gyr_freq81self.ACC_freq = acc_freq8283self.gyr_dt = 1. / gyr_freq84self.acc_dt = 1. / acc_freq8586self.timer = None8788self.updated_artists = []8990# INIT91self.init_plot(log_name)9293def test_acc_filters(self):94filt_xs = self.test_filters(self.filters["acc"], self.ACC_t, self.ACC_x)95filt_ys = self.test_filters(self.filters["acc"], self.ACC_t, self.ACC_y)96filt_zs = self.test_filters(self.filters["acc"], self.ACC_t, self.ACC_z)97return filt_xs, filt_ys, filt_zs9899def test_gyr_filters(self):100filt_xs = self.test_filters(self.filters["gyr"], self.GYR_t, self.GYR_x)101filt_ys = self.test_filters(self.filters["gyr"], self.GYR_t, self.GYR_y)102filt_zs = self.test_filters(self.filters["gyr"], self.GYR_t, self.GYR_z)103return filt_xs, filt_ys, filt_zs104105def test_filters(self, filters, Ts, Xs):106for f in filters:107f.reset()108109x_filtered = []110111for i, t in enumerate(Ts):112x = Xs[i]113114x_f = x115for filt in filters:116x_f = filt.apply(x_f)117118x_filtered.append(x_f)119120return x_filtered121122def get_filter_shape(self, filter):123samples = int(filter.get_sample_freq()) # resolution of filter shape based on sample rate124x_space = np.linspace(0.0, samples // 2, samples // int(2 * self.FILT_SHAPE_DT_FACTOR))125return x_space, filter.freq_response(x_space)126127def init_signal_plot(self, ax, Ts, Xs, Ys, Zs, Xs_filtered, Ys_filtered, Zs_filtered, label):128ax.plot(Ts, Xs, linewidth=1, label="{}X".format(label), alpha=0.5)129ax.plot(Ts, Ys, linewidth=1, label="{}Y".format(label), alpha=0.5)130ax.plot(Ts, Zs, linewidth=1, label="{}Z".format(label), alpha=0.5)131filtered_x_ax, = ax.plot(Ts, Xs_filtered, linewidth=1, label="{}X filtered".format(label), alpha=1)132filtered_y_ax, = ax.plot(Ts, Ys_filtered, linewidth=1, label="{}Y filtered".format(label), alpha=1)133filtered_z_ax, = ax.plot(Ts, Zs_filtered, linewidth=1, label="{}Z filtered".format(label), alpha=1)134ax.legend(prop={'size': 8})135return filtered_x_ax, filtered_y_ax, filtered_z_ax136137def fft_to_xdata(self, fft):138n = len(fft)139norm_factor = 2. / n140return norm_factor * np.abs(fft[:n // 2])141142def plot_fft(self, ax, x, fft, label):143fft_ax, = ax.plot(x, self.fft_to_xdata(fft), label=label)144return fft_ax145146def init_fft(self, ax, Ts, Xs, Ys, Zs, sample_rate, dt, Xs_filtered, Ys_filtered, Zs_filtered, label):147148_freqs_raw_x, _times_raw_x, _stft_raw_x = signal.stft(Xs, sample_rate, window='hann', nperseg=self.FFT_N)149raw_fft_x = np.average(np.abs(_stft_raw_x), axis=1)150151_freqs_raw_y, _times_raw_y, _stft_raw_y = signal.stft(Ys, sample_rate, window='hann', nperseg=self.FFT_N)152raw_fft_y = np.average(np.abs(_stft_raw_y), axis=1)153154_freqs_raw_z, _times_raw_z, _stft_raw_z = signal.stft(Zs, sample_rate, window='hann', nperseg=self.FFT_N)155raw_fft_z = np.average(np.abs(_stft_raw_z), axis=1)156157_freqs_x, _times_x, _stft_x = signal.stft(Xs_filtered, sample_rate, window='hann', nperseg=self.FFT_N)158filtered_fft_x = np.average(np.abs(_stft_x), axis=1)159160_freqs_y, _times_y, _stft_y = signal.stft(Ys_filtered, sample_rate, window='hann', nperseg=self.FFT_N)161filtered_fft_y = np.average(np.abs(_stft_y), axis=1)162163_freqs_z, _times_z, _stft_z = signal.stft(Zs_filtered, sample_rate, window='hann', nperseg=self.FFT_N)164filtered_fft_z = np.average(np.abs(_stft_z), axis=1)165166ax.plot(_freqs_raw_x, raw_fft_x, alpha=0.5, linewidth=1, label="{}x FFT".format(label))167ax.plot(_freqs_raw_y, raw_fft_y, alpha=0.5, linewidth=1, label="{}y FFT".format(label))168ax.plot(_freqs_raw_z, raw_fft_z, alpha=0.5, linewidth=1, label="{}z FFT".format(label))169170filtered_fft_ax_x, = ax.plot(_freqs_x, filtered_fft_x, label="filt. {}x FFT".format(label))171filtered_fft_ax_y, = ax.plot(_freqs_y, filtered_fft_y, label="filt. {}y FFT".format(label))172filtered_fft_ax_z, = ax.plot(_freqs_z, filtered_fft_z, label="filt. {}z FFT".format(label))173174# FFT175# samples = len(Ts)176# x_space = np.linspace(0.0, 1.0 / (2.0 * dt), samples // 2)177# filtered_data = np.hanning(len(Xs_filtered)) * Xs_filtered178# raw_fft = np.fft.fft(np.hanning(len(Xs)) * Xs)179# filtered_fft = np.fft.fft(filtered_data, n=self.FFT_N)180# self.plot_fft(ax, x_space, raw_fft, "{} FFT".format(label))181# fft_freq = np.fft.fftfreq(self.FFT_N, d=dt)182# x_space183# filtered_fft_ax = self.plot_fft(ax, fft_freq[:self.FFT_N // 2], filtered_fft, "filtered {} FFT".format(label))184185ax.set_xlabel("frequency")186# ax.set_xscale("log")187# ax.xaxis.set_major_formatter(ScalarFormatter())188ax.legend(prop={'size': 8})189190return filtered_fft_ax_x, filtered_fft_ax_y, filtered_fft_ax_z191192def init_filter_shape(self, ax, filter, color):193center = filter.get_center_freq()194x_space, lpf_shape = self.get_filter_shape(filter)195196plot_slpf_shape, = ax.plot(x_space, lpf_shape, c=color, label="LPF shape")197xvline_lpf_cutoff = ax.axvline(x=center, linestyle="--", c=color) # LPF cutoff freq198199return plot_slpf_shape, xvline_lpf_cutoff200201def create_slider(self, name, rect, max, value, color, callback):202global sliders203ax_slider = self.fig.add_axes(rect, facecolor='lightgoldenrodyellow')204slider = Slider(ax_slider, name, 0, max, valinit=np.sqrt(max * value), valstep=1, color=color)205slider.valtext.set_text(value)206207# slider.drawon = False208209def changed(val, cbk, max, slider):210# non linear slider to better control small values211val = int(val ** 2 / max)212slider.valtext.set_text(val)213cbk(val)214215slider.on_changed(lambda val, cbk=callback, max=max, s=slider: changed(val, cbk, max, s))216sliders.append(slider)217218def delay_update(self, update_cbk):219def _delayed_update(self, cbk):220self.timer.stop()221cbk()222223# delay actual filtering224if self.fig:225if self.timer:226self.timer.stop()227self.timer = self.fig.canvas.new_timer(interval=self.FILTER_DEBOUNCE)228self.timer.add_callback(lambda self=self: _delayed_update(self, update_cbk))229self.timer.start()230231def update_filter_shape(self, filter, shape, center_line):232x_data, new_shape = self.get_filter_shape(filter)233234shape.set_ydata(new_shape)235center_line.set_xdata(filter.get_center_freq())236237self.updated_artists.extend([238shape,239center_line,240])241242def update_signal_and_fft_plot(self, filters_key, time_list, sample_lists, signal_shapes, fft_shapes, shape,243center_line, sample_rate):244# print("update_signal_and_fft_plot", self.filters[filters_key][0].get_center_freq())245Xs, Ys, Zs = sample_lists246signal_shape_x, signal_shape_y, signal_shape_z = signal_shapes247fft_shape_x, fft_shape_y, fft_shape_z = fft_shapes248249Xs_filtered = self.test_filters(self.filters[filters_key], time_list, Xs)250Ys_filtered = self.test_filters(self.filters[filters_key], time_list, Ys)251Zs_filtered = self.test_filters(self.filters[filters_key], time_list, Zs)252253signal_shape_x.set_ydata(Xs_filtered)254signal_shape_y.set_ydata(Ys_filtered)255signal_shape_z.set_ydata(Zs_filtered)256257self.updated_artists.extend([signal_shape_x, signal_shape_y, signal_shape_z])258259_freqs_x, _times_x, _stft_x = signal.stft(Xs_filtered, sample_rate, window='hann', nperseg=self.FFT_N)260filtered_fft_x = np.average(np.abs(_stft_x), axis=1)261262_freqs_y, _times_y, _stft_y = signal.stft(Ys_filtered, sample_rate, window='hann', nperseg=self.FFT_N)263filtered_fft_y = np.average(np.abs(_stft_y), axis=1)264265_freqs_z, _times_z, _stft_z = signal.stft(Zs_filtered, sample_rate, window='hann', nperseg=self.FFT_N)266filtered_fft_z = np.average(np.abs(_stft_z), axis=1)267268fft_shape_x.set_ydata(filtered_fft_x)269fft_shape_y.set_ydata(filtered_fft_y)270fft_shape_z.set_ydata(filtered_fft_z)271272self.updated_artists.extend([273fft_shape_x, fft_shape_y, fft_shape_z,274shape, center_line,275])276277# self.fig.canvas.draw()278279def animation_update(self):280updated_artists = self.updated_artists.copy()281282# if updated_artists:283# print("animation update")284285# reset updated artists286self.updated_artists = []287288return updated_artists289290def update_filter(self, val, cbk, filter, shape, center_line, filters_key, time_list, sample_lists, signal_shapes,291fft_shapes):292# this callback sets the parameter controlled by the slider293cbk(val)294# print("filter update",val)295# update filter shape and delay fft update296self.update_filter_shape(filter, shape, center_line)297sample_freq = filter.get_sample_freq()298self.delay_update(299lambda self=self: self.update_signal_and_fft_plot(filters_key, time_list, sample_lists, signal_shapes,300fft_shapes, shape, center_line, sample_freq))301302def create_filter_control(self, name, filter, rect, max, default, shape, center_line, cbk, filters_key, time_list,303sample_lists, signal_shapes, fft_shapes, filt_color):304self.create_slider(name, rect, max, default, filt_color, lambda val, cbk=cbk, self=self, filter=filter, shape=shape,305center_line=center_line, filters_key=filters_key,306time_list=time_list, sample_list=sample_lists,307signal_shape=signal_shapes, fft_shape=fft_shapes:308self.update_filter(val, cbk, filter, shape, center_line, filters_key,309time_list, sample_list, signal_shape, fft_shape))310311def create_controls(self, filters_key, base_rect, padding, ax_fft, time_list, sample_lists, signal_shapes,312fft_shapes):313ax_filter = ax_fft.twinx()314ax_filter.set_navigate(False)315ax_filter.set_yticks([])316317num_filters = len(self.filters[filters_key])318319for i, filter in enumerate(self.filters[filters_key]):320filt_type = filter.get_type()321filt_color = self.filter_color_map(i / num_filters)322filt_shape, filt_cutoff = self.init_filter_shape(ax_filter, filter, filt_color)323324if filt_type == BiquadFilterType.PEAK:325name = "Notch"326else:327name = "LPF"328329# control for center freq is common to all filters330self.create_filter_control("{} freq".format(name), filter, base_rect, 500, filter.get_center_freq(),331filt_shape, filt_cutoff,332lambda val, filter=filter: filter.set_center_freq(val),333filters_key, time_list, sample_lists, signal_shapes, fft_shapes, filt_color)334# move down of control height + padding335base_rect[1] -= (base_rect[3] + padding)336337if filt_type == BiquadFilterType.PEAK:338self.create_filter_control("{} att (db)".format(name), filter, base_rect, 100, filter.get_attenuation(),339filt_shape, filt_cutoff,340lambda val, filter=filter: filter.set_attenuation(val),341filters_key, time_list, sample_lists, signal_shapes, fft_shapes, filt_color)342base_rect[1] -= (base_rect[3] + padding)343self.create_filter_control("{} band".format(name), filter, base_rect, 300, filter.get_bandwidth(),344filt_shape, filt_cutoff,345lambda val, filter=filter: filter.set_bandwidth(val),346filters_key, time_list, sample_lists, signal_shapes, fft_shapes, filt_color)347base_rect[1] -= (base_rect[3] + padding)348349def create_spectrogram(self, data, name, sample_rate):350freqs, times, Sx = signal.spectrogram(np.array(data), fs=sample_rate, window='hanning',351nperseg=self.FFT_N, noverlap=self.FFT_N - self.FFT_N // 10,352detrend=False, scaling='spectrum')353354f, ax = plt.subplots(figsize=(4.8, 2.4))355ax.pcolormesh(times, freqs, 10 * np.log10(Sx), cmap='viridis')356ax.set_title(name)357ax.set_ylabel('Frequency (Hz)')358ax.set_xlabel('Time (s)')359360def init_plot(self, log_name):361362self.fig = plt.figure(figsize=(14, 9))363self.fig.canvas.set_window_title("ArduPilot Filter Test Tool - {}".format(log_name))364self.fig.canvas.draw()365366rows = 2367cols = 3368raw_acc_index = 1369fft_acc_index = raw_acc_index + 1370raw_gyr_index = cols + 1371fft_gyr_index = raw_gyr_index + 1372373# signal374self.ax_acc = self.fig.add_subplot(rows, cols, raw_acc_index)375self.ax_gyr = self.fig.add_subplot(rows, cols, raw_gyr_index, sharex=self.ax_acc)376377accx_filtered, accy_filtered, accz_filtered = self.test_acc_filters()378self.ax_filtered_accx, self.ax_filtered_accy, self.ax_filtered_accz = self.init_signal_plot(self.ax_acc,379self.ACC_t,380self.ACC_x,381self.ACC_y,382self.ACC_z,383accx_filtered,384accy_filtered,385accz_filtered,386"AccX")387388gyrx_filtered, gyry_filtered, gyrz_filtered = self.test_gyr_filters()389self.ax_filtered_gyrx, self.ax_filtered_gyry, self.ax_filtered_gyrz = self.init_signal_plot(self.ax_gyr,390self.GYR_t,391self.GYR_x,392self.GYR_y,393self.GYR_z,394gyrx_filtered,395gyry_filtered,396gyrz_filtered,397"GyrX")398399# FFT400self.ax_acc_fft = self.fig.add_subplot(rows, cols, fft_acc_index)401self.ax_gyr_fft = self.fig.add_subplot(rows, cols, fft_gyr_index)402403self.acc_filtered_fft_ax_x, self.acc_filtered_fft_ax_y, self.acc_filtered_fft_ax_z = self.init_fft(404self.ax_acc_fft, self.ACC_t, self.ACC_x, self.ACC_y, self.ACC_z, self.ACC_freq, self.acc_dt, accx_filtered,405accy_filtered, accz_filtered, "AccX")406self.gyr_filtered_fft_ax_x, self.gyr_filtered_fft_ax_y, self.gyr_filtered_fft_ax_z = self.init_fft(407self.ax_gyr_fft, self.GYR_t, self.GYR_x, self.GYR_y, self.GYR_z, self.GYR_freq, self.gyr_dt, gyrx_filtered,408gyry_filtered, gyrz_filtered, "GyrX")409410self.fig.tight_layout()411412# TODO add y z413self.create_controls("acc", [0.75, 0.95, 0.2, 0.02], 0.01, self.ax_acc_fft, self.ACC_t,414(self.ACC_x, self.ACC_y, self.ACC_z),415(self.ax_filtered_accx, self.ax_filtered_accy, self.ax_filtered_accz),416(self.acc_filtered_fft_ax_x, self.acc_filtered_fft_ax_y, self.acc_filtered_fft_ax_z))417self.create_controls("gyr", [0.75, 0.45, 0.2, 0.02], 0.01, self.ax_gyr_fft, self.GYR_t,418(self.GYR_x, self.GYR_y, self.GYR_z),419(self.ax_filtered_gyrx, self.ax_filtered_gyry, self.ax_filtered_gyrz),420(self.gyr_filtered_fft_ax_x, self.gyr_filtered_fft_ax_y, self.gyr_filtered_fft_ax_z))421422# setup animation for continuous update423global anim424anim = FuncAnimation(self.fig, lambda frame, self=self: self.animation_update(), interval=1, blit=False)425426# Work in progress here...427# self.create_spectrogram(self.GYR_x, "GyrX", self.GYR_freq)428# self.create_spectrogram(gyrx_filtered, "GyrX filtered", self.GYR_freq)429# self.create_spectrogram(self.ACC_x, "AccX", self.ACC_freq)430# self.create_spectrogram(accx_filtered, "AccX filtered", self.ACC_freq)431432plt.show()433434self.print_filter_param_info()435436def print_filter_param_info(self):437if len(self.filters["acc"]) > 2 or len(self.filters["gyr"]) > 2:438print("Testing too many filters unsupported from firmware, cannot calculate parameters to set them")439return440441print("To have the last filter settings in the graphs set the following parameters:\n")442443for f in self.filters["acc"]:444filt_type = f.get_type()445446if filt_type == BiquadFilterType.PEAK: # NOTCH447print("INS_NOTCA_ENABLE,", 1)448print("INS_NOTCA_FREQ,", f.get_center_freq())449print("INS_NOTCA_BW,", f.get_bandwidth())450print("INS_NOTCA_ATT,", f.get_attenuation())451else: # LPF452print("INS_ACCEL_FILTER,", f.get_center_freq())453454for f in self.filters["gyr"]:455filt_type = f.get_type()456457if filt_type == BiquadFilterType.PEAK: # NOTCH458print("INS_HNTC2_ENABLE,", 1)459print("INS_HNTC2_FREQ,", f.get_center_freq())460print("INS_HNTC2_BW,", f.get_bandwidth())461print("INS_HNTC2_ATT,", f.get_attenuation())462else: # LPF463print("INS_GYRO_FILTER,", f.get_center_freq())464465print("\n+---------+")466print("| WARNING |")467print("+---------+")468print("Always check the onboard FFT to setup filters, this tool only simulate effects of filtering.")469470471