diff --git a/libraries/Filter/NotchFilter.cpp b/libraries/Filter/NotchFilter.cpp index dbbec6f80a802..3c9a620d6c3f7 100644 --- a/libraries/Filter/NotchFilter.cpp +++ b/libraries/Filter/NotchFilter.cpp @@ -19,6 +19,7 @@ #endif #include "NotchFilter.h" +#include const static float NOTCH_MAX_SLEW = 0.05f; const static float NOTCH_MAX_SLEW_LOWER = 1.0f - NOTCH_MAX_SLEW; @@ -135,6 +136,15 @@ void NotchFilter::reset() need_reset = true; } +#if HAL_LOGGING_ENABLED +// return the frequency to log for the notch +template +float NotchFilter::logging_frequency() const +{ + return initialised ? _center_freq_hz : AP::logger().quiet_nanf(); +} +#endif + /* instantiate template classes */ diff --git a/libraries/Filter/NotchFilter.h b/libraries/Filter/NotchFilter.h index 9f2e49c66acb6..811f7800fccf5 100644 --- a/libraries/Filter/NotchFilter.h +++ b/libraries/Filter/NotchFilter.h @@ -49,9 +49,7 @@ class NotchFilter { } // return the frequency to log for the notch - float logging_frequency(void) const { - return initialised?_center_freq_hz:0; - } + float logging_frequency(void) const; protected: