Skip to content

Commit d7ad651

Browse files
N-Eikiscepter914
authored andcommitted
feat(radar_tracks_noise_filter): add unit test (#6113)
* feat/test_radar_tracks_noise_filter Signed-off-by: N-Eiki <naganagaeichan@gmail.com> * change file name Signed-off-by: N-Eiki <naganagaeichan@gmail.com> --------- Signed-off-by: N-Eiki <naganagaeichan@gmail.com> Co-authored-by: Satoshi Tanaka <16330533+scepter914@users.noreply.github.com>
1 parent a1adbea commit d7ad651

File tree

4 files changed

+129
-0
lines changed

4 files changed

+129
-0
lines changed

sensing/radar_tracks_noise_filter/CMakeLists.txt

+7
Original file line numberDiff line numberDiff line change
@@ -28,9 +28,16 @@ rclcpp_components_register_node(radar_tracks_noise_filter_node_component
2828

2929
# Tests
3030
if(BUILD_TESTING)
31+
find_package(ament_cmake_ros REQUIRED)
3132
list(APPEND AMENT_LINT_AUTO_EXCLUDE ament_cmake_uncrustify)
3233
find_package(ament_lint_auto REQUIRED)
3334
ament_lint_auto_find_test_dependencies()
35+
file(GLOB_RECURSE test_files test/**/*.cpp)
36+
ament_add_ros_isolated_gtest(radar_tracks_noise_filter ${test_files})
37+
38+
target_link_libraries(radar_tracks_noise_filter
39+
radar_tracks_noise_filter_node_component
40+
)
3441
endif()
3542

3643
# Package

sensing/radar_tracks_noise_filter/include/radar_tracks_noise_filter/radar_tracks_noise_filter_node.hpp

+1
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,7 @@ class RadarTrackCrossingNoiseFilterNode : public rclcpp::Node
5757
// Parameter
5858
NodeParam node_param_{};
5959

60+
public:
6061
// Core
6162
bool isNoise(const RadarTrack & radar_track);
6263
};
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,95 @@
1+
// Copyright 2023 Tier IV, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include "radar_tracks_noise_filter/radar_tracks_noise_filter_node.hpp"
16+
17+
#include <radar_msgs/msg/radar_scan.hpp>
18+
19+
#include <gtest/gtest.h>
20+
21+
std::shared_ptr<radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode> get_node(
22+
float velocity_y_threshold)
23+
{
24+
rclcpp::NodeOptions node_options;
25+
node_options.parameter_overrides({
26+
{"node_params.is_amplitude_filter", true},
27+
{"velocity_y_threshold", velocity_y_threshold},
28+
});
29+
30+
auto node =
31+
std::make_shared<radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode>(node_options);
32+
return node;
33+
}
34+
35+
radar_msgs::msg::RadarTrack getRadarTrack(float velocity_x, float velocity_y)
36+
{
37+
radar_msgs::msg::RadarTrack radar_track;
38+
geometry_msgs::msg::Vector3 vector_msg;
39+
vector_msg.x = velocity_x;
40+
vector_msg.y = velocity_y;
41+
vector_msg.z = 0.0;
42+
radar_track.velocity = vector_msg;
43+
return radar_track;
44+
}
45+
46+
TEST(RadarTracksNoiseFilter, isNoise)
47+
{
48+
using radar_msgs::msg::RadarTrack;
49+
using radar_tracks_noise_filter::RadarTrackCrossingNoiseFilterNode;
50+
rclcpp::init(0, nullptr);
51+
{
52+
float velocity_node_threshold = 0.0;
53+
float y_velocity = 0.0;
54+
float x_velocity = 10.0;
55+
std::shared_ptr<RadarTrackCrossingNoiseFilterNode> node = get_node(velocity_node_threshold);
56+
RadarTrack radar_track = getRadarTrack(x_velocity, y_velocity);
57+
EXPECT_TRUE(node->isNoise(radar_track));
58+
}
59+
60+
{
61+
float velocity_node_threshold = -1.0;
62+
float y_velocity = 3.0;
63+
float x_velocity = 10.0;
64+
std::shared_ptr<RadarTrackCrossingNoiseFilterNode> node = get_node(velocity_node_threshold);
65+
RadarTrack radar_track = getRadarTrack(x_velocity, y_velocity);
66+
EXPECT_TRUE(node->isNoise(radar_track));
67+
}
68+
69+
{
70+
float velocity_node_threshold = -1.0;
71+
float y_velocity = 3.0;
72+
float x_velocity = 100.0;
73+
std::shared_ptr<RadarTrackCrossingNoiseFilterNode> node = get_node(velocity_node_threshold);
74+
RadarTrack radar_track = getRadarTrack(x_velocity, y_velocity);
75+
EXPECT_TRUE(node->isNoise(radar_track));
76+
}
77+
78+
{
79+
float velocity_node_threshold = 3.0;
80+
float y_velocity = 1.0;
81+
float x_velocity = 10.0;
82+
std::shared_ptr<RadarTrackCrossingNoiseFilterNode> node = get_node(velocity_node_threshold);
83+
RadarTrack radar_track = getRadarTrack(x_velocity, y_velocity);
84+
EXPECT_FALSE(node->isNoise(radar_track));
85+
}
86+
87+
{
88+
float velocity_node_threshold = 3.0;
89+
float y_velocity = 1.0;
90+
float x_velocity = -10.0;
91+
std::shared_ptr<RadarTrackCrossingNoiseFilterNode> node = get_node(velocity_node_threshold);
92+
RadarTrack radar_track = getRadarTrack(x_velocity, y_velocity);
93+
EXPECT_FALSE(node->isNoise(radar_track));
94+
}
95+
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,26 @@
1+
// Copyright 2023 TierIV
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <rclcpp/rclcpp.hpp>
16+
17+
#include <gtest/gtest.h>
18+
19+
int main(int argc, char * argv[])
20+
{
21+
testing::InitGoogleTest(&argc, argv);
22+
rclcpp::init(argc, argv);
23+
bool result = RUN_ALL_TESTS();
24+
rclcpp::shutdown();
25+
return result;
26+
}

0 commit comments

Comments
 (0)