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

Notch filter df1 #14755

Merged
merged 7 commits into from
May 8, 2020
Merged
Show file tree
Hide file tree
Changes from 6 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
70 changes: 69 additions & 1 deletion src/lib/mathlib/math/filter/NotchFilter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
* @brief Implementation of a Notch filter.
*
* @author Mathieu Bresciani <brescianimathieu@gmail.com>
* @author Samuel Garcin <samuel.garcin@wecorpindustries.com>
*/

#pragma once
Expand Down Expand Up @@ -69,7 +70,7 @@ class NotchFilter
void setParameters(float sample_freq, float notch_freq, float bandwidth);

/**
* Add a new raw value to the filter
* Add a new raw value to the filter using the Direct form II
*
* @return retrieve the filtered result
*/
Expand All @@ -85,6 +86,28 @@ class NotchFilter
return output;
}

/**
* Add a new raw value to the filter using the Direct Form I
*
* @return retrieve the filtered result
*/
inline T applyDF1(const T &sample)
{
// Direct Form I implementation
const T output = _b0 * sample + _b1 * _delay_element_1 + _b2 * _delay_element_2 - _a1 * _delay_element_output_1 - _a2 *
_delay_element_output_2;

// shift inputs
_delay_element_2 = _delay_element_1;
_delay_element_1 = sample;

// shift outputs
_delay_element_output_2 = _delay_element_output_1;
_delay_element_output_1 = output;

return output;
}

float getNotchFreq() const { return _notch_freq; }
float getBandwidth() const { return _bandwidth; }

Expand All @@ -99,8 +122,26 @@ class NotchFilter
b[2] = _b2;
}

/**
* Bypasses the filter update to directly set different filter coefficients.
* Note: the filtered frequency and quality factor saved on the filter lose their
* physical meaning if you use this method to change the filter's coefficients.
* Used for creating clones of a specific filter.
*/
void setCoefficients(float a[2], float b[3])
{
_a1 = a[0];
_a2 = a[1];
_b0 = b[0];
_b1 = b[1];
_b2 = b[2];
}


T reset(const T &sample);

void update(float sample_freq, float notch_freq, float bandwidth);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@francelico I just noticed the actual update() code is missing.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think the update isn't required as we can update the coefficients using setParameters

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hi, yes you are correct @bresch this method is not used anywhere else, it can be deleted. @dagar how should I proceed for the fix, should I make a new PR (and mention this one in the description)?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'll delete it quickly if there's no intention of using it. Thanks for the followup. #16061


protected:
float _notch_freq{};
float _bandwidth{};
Expand All @@ -115,6 +156,8 @@ class NotchFilter

T _delay_element_1;
T _delay_element_2;
T _delay_element_output_1;
T _delay_element_output_2;
};

template<typename T>
Expand All @@ -125,6 +168,8 @@ void NotchFilter<T>::setParameters(float sample_freq, float notch_freq, float ba

_delay_element_1 = {};
_delay_element_2 = {};
_delay_element_output_1 = {};
_delay_element_output_2 = {};

if (notch_freq <= 0.f) {
// no filtering
Expand Down Expand Up @@ -165,4 +210,27 @@ T NotchFilter<T>::reset(const T &sample)
return apply(sample);
}

/**
* Allows to dynamically update the filtered frequency, refresh rate and quality factor.
* Changes the filter's coefficients while conserving the filter's history
* Note: This method will only work if using the applyDF1 function (Direct Form I).
*/
template<typename T>
void NotchFilter<T>::update(float sample_freq, float notch_freq, float bandwidth)
{
// backup state
T delay_element_1_bkup = _delay_element_1;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe we could gain a bit of efficiency if we move the zeroing of the delay elements out of setParameters so we don't need to backup and restore them. Then you can directly use setParameters and we call the new reset() function when needed.

Copy link
Contributor Author

@francelico francelico Apr 28, 2020

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That sounds good, then the update() method is redundant and can be deleted. We would be using the setParameters() method directly to update the filters when needed. In that case, I guess we can just initialise the delay elements directly in the class definition and it should do the job just fine. Is that what you meant?

Concerning the reset() method, I guess I should update it with
_delay_element_output_1 = {};
_delay_element_output_2 = {};
to make sure those are zeroed too, if my understanding of the method is correct.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hi @bresch , I have made changes according to your review, following the approach outlined my comment above. You can refer to a more detailed description within the commit message.

Not all of the CI tests are passing, with the Offboard position control test failing. However I believe it is a problem with the test itself as I haven't modified code relevant to that test.

Let me know if there are any further changes required. Thanks!

T delay_element_2_bkup = _delay_element_2;
T delay_element_output_1_bkup = _delay_element_output_1;
T delay_element_output_2_bkup = _delay_element_output_2;

setParameters(sample_freq, notch_freq, bandwidth);

// restore state
_delay_element_1 = delay_element_1_bkup;
_delay_element_2 = delay_element_2_bkup;
_delay_element_output_1 = delay_element_output_1_bkup;
_delay_element_output_2 = delay_element_output_2_bkup;
}

} // namespace math
33 changes: 32 additions & 1 deletion src/lib/mathlib/math/filter/NotchFilterArray.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@
* @brief Notch filter with array input/output
*
* @author Mathieu Bresciani <brescianimathieu@gmail.com>
* @author Samuel Garcin <samuel.garcin@wecorpindustries.com>
*/

#pragma once
Expand All @@ -62,7 +63,7 @@ class NotchFilterArray : public NotchFilter<T>
~NotchFilterArray() = default;

/**
* Add new raw values to the filter
* Add new raw values to the filter using the Direct form II.
*
* @return retrieve the filtered result
*/
Expand All @@ -83,6 +84,36 @@ class NotchFilterArray : public NotchFilter<T>
_delay_element_1 = delay_element_0;
}
}

/**
* Add new raw values to the filter using the Direct form I.
*
* @return retrieve the filtered result
*/
inline void applyDF1(T samples[], uint8_t num_samples)
{
for (int n = 0; n < num_samples; n++) {
// Direct Form II implementation
const T output = _b0 * samples[n] + _b1 * _delay_element_1 + _b2 * _delay_element_2 - _a1 * _delay_element_output_1 -
_a2 * _delay_element_output_2;

// don't allow bad values to propagate via the filter
if (!isFinite(output)) {
output = samples[n];
}

// shift inputs
_delay_element_2 = _delay_element_1;
_delay_element_1 = samples[n];

// shift outputs
_delay_element_output_2 = _delay_element_output_1;
_delay_element_output_1 = output;

// writes value to array
samples[n] = output;
}
}
};

} // namespace math
129 changes: 129 additions & 0 deletions src/lib/mathlib/math/filter/NotchFilterTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,30 @@ TEST_F(NotchFilterTest, filteringLowSide)
}
}

TEST_F(NotchFilterTest, filteringLowSideDF1)
{
// Send a 25Hz sinusoidal signal into a 50Hz notch filter
_notch_float.setParameters(_sample_freq, _notch_freq, _bandwidth);
const float signal_freq = 25.f;
const float omega = 2.f * M_PI_F * signal_freq;
float phase_delay = 11.4f * M_PI_F / 180.f; // Given by simulation
float t = 0.f;
float dt = 1.f / _sample_freq;
float out = 0.f;

for (int i = 0; i < 1000; i++) {
float input = sinf(omega * t);
float output_expected = sinf(omega * t - phase_delay);
out = _notch_float.applyDF1(input);
t = i * dt;

// Let some time for the filter to settle
if (i > 30) {
EXPECT_NEAR(out, output_expected, 0.05f);
}
}
}

TEST_F(NotchFilterTest, filteringHighSide)
{
// Send a 98 sinusoidal signal into a 50Hz notch filter
Expand All @@ -125,6 +149,30 @@ TEST_F(NotchFilterTest, filteringHighSide)
}
}

TEST_F(NotchFilterTest, filteringHighSideDF1)
{
// Send a 98 sinusoidal signal into a 50Hz notch filter
_notch_float.setParameters(_sample_freq, _notch_freq, _bandwidth);
const float signal_freq = 98.4f;
const float omega = 2.f * M_PI_F * signal_freq;
float phase_delay = 11.4f * M_PI_F / 180.f; // Given by simulation
float t = 0.f;
float dt = 1.f / _sample_freq;
float out = 0.f;

for (int i = 0; i < 1000; i++) {
float input = sinf(omega * t);
float output_expected = sinf(omega * t + phase_delay);
out = _notch_float.applyDF1(input);
t = i * dt;

// Let some time for the filter to settle
if (i > 30) {
EXPECT_NEAR(out, output_expected, 0.05f);
}
}
}

TEST_F(NotchFilterTest, filterOnNotch)
{
// Send a 50 sinusoidal signal into a 50Hz notch filter
Expand All @@ -147,6 +195,40 @@ TEST_F(NotchFilterTest, filterOnNotch)
}
}

TEST_F(NotchFilterTest, filterOnNotchDF1)
{
// Send a 50 sinusoidal signal into a 50Hz notch filter
_notch_float.setParameters(_sample_freq, _notch_freq, _bandwidth);
const float signal_freq = 50.0f;
const float omega = 2.f * M_PI_F * signal_freq;
float t = 0.f;
float dt = 1.f / _sample_freq;
float out = 0.f;

for (int i = 0; i < 1000; i++) {
float input = sinf(omega * t);
out = _notch_float.applyDF1(input);
t = i * dt;

// Let some time for the filter to settle
if (i > 50) {
EXPECT_NEAR(out, 0.f, 0.1f);
}
}
}

TEST_F(NotchFilterTest, updateFilter)
{
_notch_float.setParameters(_sample_freq, _notch_freq, _bandwidth);
float new_notch_freq = 100.f;
float new_bandwidth = 10.f;
_notch_float.update(_sample_freq, new_notch_freq, new_bandwidth);

EXPECT_EQ(new_notch_freq, _notch_float.getNotchFreq());
EXPECT_EQ(new_bandwidth, _notch_float.getBandwidth());

}

TEST_F(NotchFilterTest, filterVector3f)
{
// Send three sinusoidal signals (25, 50 and 98.5Hz) into a 50Hz triple notch filter
Expand Down Expand Up @@ -176,6 +258,35 @@ TEST_F(NotchFilterTest, filterVector3f)
}
}

TEST_F(NotchFilterTest, filterVector3fDF1)
{
// Send three sinusoidal signals (25, 50 and 98.5Hz) into a 50Hz triple notch filter
_notch_vector3f.setParameters(_sample_freq, _notch_freq, _bandwidth);

const Vector3f signal_freq(25.f, 50.f, 98.4f);
const Vector3f omega = 2.f * M_PI_F * signal_freq;
const Vector3f phase_delay = Vector3f(-11.4f, 0.f, 11.4f) * M_PI_F / 180.f;

float t = 0.f;
float dt = 1.f / _sample_freq;
Vector3f out{};

for (int i = 0; i < 1000; i++) {
const Vector3f input(sinf(omega(0) * t), sinf(omega(1) * t), sinf(omega(2) * t));
const Vector3f arg = omega * t + phase_delay;
const Vector3f output_expected(sinf(arg(0)), 0.f, sinf(arg(2)));
out = _notch_vector3f.applyDF1(input);
t = i * dt;

// Let some time for the filter to settle
if (i > 50) {
EXPECT_NEAR(out(0), output_expected(0), 0.1f);
EXPECT_NEAR(out(1), output_expected(1), 0.1f);
EXPECT_NEAR(out(2), output_expected(2), 0.1f);
}
}
}

TEST_F(NotchFilterTest, disabled)
{
const float zero_notch_freq = 0.f;
Expand Down Expand Up @@ -211,3 +322,21 @@ TEST_F(NotchFilterTest, disabled)
EXPECT_EQ(out, input);
}
}

TEST_F(NotchFilterTest, setCoefficients)
{

float a_new[2] = {1.f, 2.f};
float b_new[3] = {1.f, 2.f, 3.f};
float a[3];
float b[3];

_notch_float.setCoefficients(a_new, b_new);
_notch_float.getCoefficients(a, b);

for (int i = 0; i < 3; i++) {
if (i >= 1) {EXPECT_EQ(a[i], a_new[i - 1]);} //a0 is not part of set function

EXPECT_EQ(b[i], b_new[i]);
}
}