diff --git a/libraries/Filter/tests/plot_harmonictest2.gnu b/libraries/Filter/tests/plot_harmonictest2.gnu new file mode 100644 index 00000000000000..2df39eb16c5b1a --- /dev/null +++ b/libraries/Filter/tests/plot_harmonictest2.gnu @@ -0,0 +1,11 @@ +#!/usr/bin/gnuplot -persist +set y2tics 0,10 +set ytics nomirror +set style data linespoints +set key autotitle +set datafile separator "," +set key autotitle columnhead +set xlabel "Freq(Hz)" +set ylabel "Attenuation(dB)" +#set ylabel2 "PhaseLag(deg)" +plot "harmonicnotch_test2.csv" using 1:2 axis x1y1, "harmonicnotch_test2.csv" using 1:3 axis x1y2 diff --git a/libraries/Filter/tests/plot_harmonictest3.gnu b/libraries/Filter/tests/plot_harmonictest3.gnu new file mode 100644 index 00000000000000..d2f7cc337a8652 --- /dev/null +++ b/libraries/Filter/tests/plot_harmonictest3.gnu @@ -0,0 +1,12 @@ +#!/usr/bin/gnuplot -persist +set y2tics 0,10 +set ytics nomirror +set style data linespoints +set key autotitle +set datafile separator "," +set key autotitle columnhead +set xlabel "Freq(Hz)" +set ylabel "Attenuation(dB)" +#set ylabel2 "PhaseLag(deg)" +plot "harmonicnotch_test3.csv" using 1:2 axis x1y1, "harmonicnotch_test3.csv" using 1:3 axis x1y2, "harmonicnotch_test3.csv" using 1:4 axis x1y1, "harmonicnotch_test3.csv" using 1:5 axis x1y2 + diff --git a/libraries/Filter/tests/plot_harmonictest4.gnu b/libraries/Filter/tests/plot_harmonictest4.gnu new file mode 100644 index 00000000000000..cfc8b5117e8e30 --- /dev/null +++ b/libraries/Filter/tests/plot_harmonictest4.gnu @@ -0,0 +1,12 @@ +#!/usr/bin/gnuplot -persist +set y2tics 0,10 +set ytics nomirror +set style data linespoints +set key autotitle +set datafile separator "," +set key autotitle columnhead +set xlabel "Freq(Hz)" +set ylabel "Attenuation(dB)" +set key left bottom +plot "harmonicnotch_test4.csv" using 1:2, "harmonicnotch_test4.csv" using 1:3, "harmonicnotch_test4.csv" using 1:4, "harmonicnotch_test4.csv" using 1:5, "harmonicnotch_test4.csv" using 1:6, "harmonicnotch_test4.csv" using 1:7, "harmonicnotch_test4.csv" using 1:8 + diff --git a/libraries/Filter/tests/test_notchfilter.cpp b/libraries/Filter/tests/test_notchfilter.cpp index 716678b6f8cba7..88145bb697b4c1 100644 --- a/libraries/Filter/tests/test_notchfilter.cpp +++ b/libraries/Filter/tests/test_notchfilter.cpp @@ -6,6 +6,12 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); +static double ratio_to_dB(double ratio) +{ + return 10*log(ratio); +} + +#if 0 /* test if a reset of a notch filter results in no glitch in the following samples with constant input @@ -162,5 +168,164 @@ TEST(NotchFilterTest, HarmonicNotchTest) EXPECT_NEAR(integrals[4].get_lag_degrees(5), 55.23, 0.5); EXPECT_NEAR(integrals[9].get_lag_degrees(10), 112.23, 0.5); } +#endif + + +/* + calculate attenuation and phase lag for a single harmonic notch filter + */ +static void test_one_filter(float base_freq, float attenuation_dB, + float bandwidth, float test_freq, float source_freq, + uint16_t harmonics, uint16_t options, + float &phase_lag, float &out_attenuation_dB) +{ + const uint16_t rate_hz = 2000; + const uint32_t samples = 50000; + const float test_amplitude = 1.0; + const double dt = 1.0 / rate_hz; + + HarmonicNotchFilter filter {}; + struct { + double last_in; + double last_out; + double v_max; + uint32_t last_crossing; + uint32_t total_lag_samples; + uint32_t lag_count; + float get_lag_degrees(const float freq) const { + const float lag_avg = total_lag_samples/float(lag_count); + return (360.0 * lag_avg * freq) / rate_hz; + } + } integral {}; + + auto &f = filter; + const uint8_t num_harmonics = __builtin_popcount(harmonics); + + HarmonicNotchFilterParams notch_params {}; + notch_params.set_options(options); + f.allocate_filters(num_harmonics, harmonics, notch_params.num_composite_notches()); + notch_params.set_attenuation(attenuation_dB); + notch_params.set_bandwidth_hz(bandwidth); + notch_params.set_center_freq_hz(base_freq); + notch_params.set_freq_min_ratio(1.0); + f.init(rate_hz, notch_params); + f.update(source_freq); + + for (uint32_t s=0; s= samples/10) { + integral.v_max = MAX(integral.v_max, v); + } + if (sample >= 0 && integral.last_in < 0) { + integral.last_crossing = s; + } + if (v >= 0 && integral.last_out < 0 && integral.last_crossing != 0) { + integral.total_lag_samples += s - integral.last_crossing; + integral.lag_count++; + } + integral.last_in = sample; + integral.last_out = v; + f.update(source_freq); + } + phase_lag = integral.get_lag_degrees(test_freq); + out_attenuation_dB = ratio_to_dB(integral.v_max/test_amplitude); +} + +/* + test the test_one_filter function + */ +TEST(NotchFilterTest, HarmonicNotchTest2) +{ + const float min_freq = 1.0; + const float max_freq = 200; + const uint16_t steps = 1000; + + const char *csv_file = "harmonicnotch_test2.csv"; + FILE *f = fopen(csv_file, "w"); + fprintf(f, "Freq(Hz),Attenuation(dB),Lag(deg)\n"); + + for (uint16_t i=0; i