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

fix: update dependencies and deprecated code for ROS 2 jazzy release #6656

Closed
Prev Previous commit
Next Next commit
Fix optional test
Signed-off-by: f0reachARR <f0reach@f0reach.me>
f0reachARR committed May 31, 2024
commit 3fee7c5c01cef3e1fbedbdb935d104010359a9ca
Original file line number Diff line number Diff line change
@@ -76,7 +76,7 @@ TEST(predicted_path_utils, testCalcInterpolatedPose)
for (double t = 0.0; t < 9.0 + 1e-6; t += 1.0) {
const auto p = calcInterpolatedPose(path, t);

EXPECT_NE(p, boost::none);
EXPECT_TRUE(p);
EXPECT_NEAR(p->position.x, t * 1.0, epsilon);
EXPECT_NEAR(p->position.y, 0.0, epsilon);
EXPECT_NEAR(p->position.z, 0.0, epsilon);
@@ -93,7 +93,7 @@ TEST(predicted_path_utils, testCalcInterpolatedPose)
for (double t = 0.0; t < 9.0; t += 0.3) {
const auto p = calcInterpolatedPose(path, t);

EXPECT_NE(p, boost::none);
EXPECT_TRUE(p);
EXPECT_NEAR(p->position.x, t * 1.0, epsilon);
EXPECT_NEAR(p->position.y, 0.0, epsilon);
EXPECT_NEAR(p->position.z, 0.0, epsilon);
@@ -109,20 +109,20 @@ TEST(predicted_path_utils, testCalcInterpolatedPose)
// Negative time
{
const auto p = calcInterpolatedPose(path, -1.0);
EXPECT_EQ(p, boost::none);
EXPECT_FALSE(p);
}

// Over the time horizon
{
const auto p = calcInterpolatedPose(path, 11.0);
EXPECT_EQ(p, boost::none);
EXPECT_FALSE(p);
}

// Empty Path
{
PredictedPath empty_path;
const auto p = calcInterpolatedPose(empty_path, 5.0);
EXPECT_EQ(p, boost::none);
EXPECT_FALSE(p);
}
}
}
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
@@ -24,7 +24,7 @@ TEST(lowpass_filter_1d, filter)
LowpassFilter1d lowpass_filter_1d(0.1);

// initial state
EXPECT_EQ(lowpass_filter_1d.getValue(), boost::none);
EXPECT_FALSE(lowpass_filter_1d.getValue());

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

// reset without value
lowpass_filter_1d.reset();
EXPECT_EQ(lowpass_filter_1d.getValue(), boost::none);
EXPECT_FALSE(lowpass_filter_1d.getValue());

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

{ // initial state
EXPECT_EQ(lowpass_filter_.getValue(), boost::none);
EXPECT_FALSE(lowpass_filter_.getValue());
}

{ // random filter
@@ -58,7 +58,7 @@ TEST(lowpass_filter_twist, filter)

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

{ // reset with value