Skip to content

Commit b8a5bb1

Browse files
committed
update year
Signed-off-by: N-Eiki <naganagaeichan@gmail.com>
2 parents db09e06 + c22a15d commit b8a5bb1

File tree

1 file changed

+6
-7
lines changed

1 file changed

+6
-7
lines changed

perception/radar_crossing_objects_noise_filter/test/test_radar_crossing_objects_noise_filter/test_radar_crossing_objects_filter_is_noise.cpp

+6-7
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,7 @@
1818
#include <geometry_msgs/msg/point32.hpp>
1919

2020
#include "radar_crossing_objects_noise_filter/radar_crossing_objects_noise_filter_node.hpp"
21+
2122
#include <gtest/gtest.h>
2223

2324
std::shared_ptr<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFilterNode> get_node(
@@ -26,13 +27,10 @@ std::shared_ptr<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFi
2627
rclcpp::NodeOptions node_options;
2728

2829
node_options.parameter_overrides(
29-
{
30-
{"angle_threshold", angle_threshold},
31-
{"velocity_threshold", velocity_threshold}
32-
}
33-
);
30+
{{"angle_threshold", angle_threshold}, {"velocity_threshold", velocity_threshold}});
3431
auto node =
35-
std::make_shared<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFilterNode>(node_options);
32+
std::make_shared<radar_crossing_objects_noise_filter::RadarCrossingObjectsNoiseFilterNode>(
33+
node_options);
3634
return node;
3735
}
3836

@@ -64,12 +62,14 @@ TEST(RadarCrossingObjectsFilter, IsNoise)
6462
{
6563
double velocity_threshold = 40.0;
6664
double angle_threshold = -1.0472;
65+
6766
auto node = get_node(angle_threshold, velocity_threshold);
6867
EXPECT_TRUE(node->isNoise(object));
6968
}
7069
{
7170
double velocity_threshold = -40.0;
7271
double angle_threshold = 1.0472;
72+
7373
auto node = get_node(angle_threshold, velocity_threshold);
7474
EXPECT_TRUE(node->isNoise(object));
7575
}
@@ -174,4 +174,3 @@ TEST(RadarCrossingObjectsFilter, IsNoise)
174174
}
175175
}
176176
}
177-

0 commit comments

Comments
 (0)