Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Filter: NotchFilter: return NaN for logging_frequency if not initialised #26869

Merged
merged 1 commit into from
Apr 24, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 10 additions & 0 deletions libraries/Filter/NotchFilter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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
*/
Expand Down
4 changes: 1 addition & 3 deletions libraries/Filter/NotchFilter.h
Original file line number Diff line number Diff line change
Expand Up @@ -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:

Expand Down
Loading