diff --git a/libraries/Filter/tests/test_notchfilter.cpp b/libraries/Filter/tests/test_notchfilter.cpp index a13c9aeae161a2..6b60611c28af1f 100644 --- a/libraries/Filter/tests/test_notchfilter.cpp +++ b/libraries/Filter/tests/test_notchfilter.cpp @@ -325,4 +325,36 @@ TEST(NotchFilterTest, HarmonicNotchTest4) fclose(f); } +/* + show phase lag versus attenuation + */ +TEST(NotchFilterTest, HarmonicNotchTest5) +{ + const float min_attenuation = 0; + const float max_attenuation = 50; + const uint16_t steps = 200; + + const char *csv_file = "harmonicnotch_test5.csv"; + FILE *f = fopen(csv_file, "w"); + fprintf(f, "Attenuation(dB),Lag(10Hz),Lag(20Hz),Lag(30Hz),Lag(40Hz),Lag(50Hz),Lag(60Hz),Lag(70Hz)\n"); + + for (uint16_t i=0; i