Skip to content

Commit

Permalink
fix(signal_processing): unit test bug
Browse files Browse the repository at this point in the history
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 committed Sep 27, 2022
1 parent 93cc9bd commit 4c739d6
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ class LowpassFilterInterface
public:
explicit LowpassFilterInterface(const double gain) : gain_(gain) {}

void reset() { x_ = T{}; }
void reset() { x_ = {}; }
void reset(const T & x) { x_ = x; }

boost::optional<T> getValue() const { return x_; }
Expand Down
4 changes: 2 additions & 2 deletions common/signal_processing/test/src/lowpass_filter_1d_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ TEST(lowpass_filter_1d, filter)
LowpassFilter1d lowpass_filter_1d(0.1);

// initial state
EXPECT_EQ(*lowpass_filter_1d.getValue(), {});
EXPECT_EQ(lowpass_filter_1d.getValue(), boost::none);

// random filter
EXPECT_NEAR(lowpass_filter_1d.filter(0.0), 0.0, epsilon);
Expand All @@ -33,7 +33,7 @@ TEST(lowpass_filter_1d, filter)

// reset without value
lowpass_filter_1d.reset();
EXPECT_EQ(*lowpass_filter_1d.getValue(), {});
EXPECT_EQ(lowpass_filter_1d.getValue(), boost::none);

// reset with value
lowpass_filter_1d.reset(-1.1);
Expand Down
17 changes: 2 additions & 15 deletions common/signal_processing/test/src/lowpass_filter_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,13 +39,7 @@ TEST(lowpass_filter_twist, filter)
LowpassFilterTwist lowpass_filter_(0.1);

{ // initial state
const auto filtered_twist = lowpass_filter_.getValue();
EXPECT_NEAR(filtered_twist->linear.x, 0.0, epsilon);
EXPECT_NEAR(filtered_twist->linear.y, 0.0, epsilon);
EXPECT_NEAR(filtered_twist->linear.z, 0.0, epsilon);
EXPECT_NEAR(filtered_twist->angular.x, 0.0, epsilon);
EXPECT_NEAR(filtered_twist->angular.y, 0.0, epsilon);
EXPECT_NEAR(filtered_twist->angular.z, 0.0, epsilon);
EXPECT_EQ(lowpass_filter_.getValue(), boost::none);
}

{ // random filter
Expand All @@ -62,14 +56,7 @@ TEST(lowpass_filter_twist, filter)

{ // reset without value
lowpass_filter_.reset();

const auto filtered_twist = lowpass_filter_.getValue();
EXPECT_NEAR(filtered_twist->linear.x, 0.0, epsilon);
EXPECT_NEAR(filtered_twist->linear.y, 0.0, epsilon);
EXPECT_NEAR(filtered_twist->linear.z, 0.0, epsilon);
EXPECT_NEAR(filtered_twist->angular.x, 0.0, epsilon);
EXPECT_NEAR(filtered_twist->angular.y, 0.0, epsilon);
EXPECT_NEAR(filtered_twist->angular.z, 0.0, epsilon);
EXPECT_EQ(lowpass_filter_.getValue(), boost::none);
}

{ // reset with value
Expand Down

0 comments on commit 4c739d6

Please sign in to comment.