Filter: NotchFilter: return NaN for `logging_frequency` if not initialised

This commit is contained in:
Iampete1 2024-04-23 01:36:25 +01:00 committed by Andrew Tridgell
parent 1a39bd1a6e
commit 0a3bdbfdc9
2 changed files with 11 additions and 3 deletions

View File

@ -19,6 +19,7 @@
#endif
#include "NotchFilter.h"
#include <AP_Logger/AP_Logger.h>
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<T>::reset()
need_reset = true;
}
#if HAL_LOGGING_ENABLED
// return the frequency to log for the notch
template <class T>
float NotchFilter<T>::logging_frequency() const
{
return initialised ? _center_freq_hz : AP::logger().quiet_nanf();
}
#endif
/*
instantiate template classes
*/

View File

@ -49,9 +49,7 @@ public:
}
// 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: