Skip to content

Commit

Permalink
Filter: NotchFilter: return NaN for logging_frequency if not initia…
Browse files Browse the repository at this point in the history
…lised
  • Loading branch information
IamPete1 authored and tridge committed Apr 24, 2024
1 parent 1a39bd1 commit 0a3bdbf
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 3 deletions.
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

0 comments on commit 0a3bdbf

Please sign in to comment.