Skip to content

Commit 80007ed

Browse files
authored
fix(obstacle_collision_checker): fix bug with filterPointCloudByTrajectory (#729)
* Add unit test showcasing the issue Signed-off-by: Maxime CLEMENT <[email protected]> * Fix filterPointCloudByTrajectory Signed-off-by: Maxime CLEMENT <[email protected]> * Add NOLINT for direct include of .cpp file Signed-off-by: Maxime CLEMENT <[email protected]>
1 parent 7919b56 commit 80007ed

File tree

4 files changed

+54
-2
lines changed

4 files changed

+54
-2
lines changed

control/obstacle_collision_checker/CMakeLists.txt

+4
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,10 @@ rclcpp_components_register_node(obstacle_collision_checker
4444
if(BUILD_TESTING)
4545
find_package(ament_lint_auto REQUIRED)
4646
ament_lint_auto_find_test_dependencies()
47+
ament_add_ros_isolated_gtest(test_obstacle_collision_checker
48+
test/test_obstacle_collision_checker.cpp
49+
)
50+
target_link_libraries(test_obstacle_collision_checker obstacle_collision_checker)
4751
endif()
4852

4953
ament_auto_package(

control/obstacle_collision_checker/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,7 @@
2626
<depend>tier4_autoware_utils</depend>
2727
<depend>vehicle_info_util</depend>
2828

29+
<test_depend>ament_cmake_ros</test_depend>
2930
<test_depend>ament_lint_auto</test_depend>
3031
<test_depend>autoware_lint_common</test_depend>
3132

control/obstacle_collision_checker/src/obstacle_collision_checker_node/obstacle_collision_checker.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -59,12 +59,13 @@ pcl::PointCloud<pcl::PointXYZ> filterPointCloudByTrajectory(
5959
const autoware_auto_planning_msgs::msg::Trajectory & trajectory, const double radius)
6060
{
6161
pcl::PointCloud<pcl::PointXYZ> filtered_pointcloud;
62-
for (const auto & trajectory_point : trajectory.points) {
63-
for (const auto & point : pointcloud.points) {
62+
for (const auto & point : pointcloud.points) {
63+
for (const auto & trajectory_point : trajectory.points) {
6464
const double dx = trajectory_point.pose.position.x - point.x;
6565
const double dy = trajectory_point.pose.position.y - point.y;
6666
if (std::hypot(dx, dy) < radius) {
6767
filtered_pointcloud.points.push_back(point);
68+
break;
6869
}
6970
}
7071
}
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,46 @@
1+
// Copyright 2022 Tier IV, Inc. All rights reserved.
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 "../src/obstacle_collision_checker_node/obstacle_collision_checker.cpp" // NOLINT
16+
#include "gtest/gtest.h"
17+
18+
TEST(test_obstacle_collision_checker, filterPointCloudByTrajectory)
19+
{
20+
pcl::PointCloud<pcl::PointXYZ> pcl;
21+
autoware_auto_planning_msgs::msg::Trajectory trajectory;
22+
pcl::PointXYZ pcl_point;
23+
autoware_auto_planning_msgs::msg::TrajectoryPoint traj_point;
24+
pcl_point.y = 0.0;
25+
traj_point.pose.position.y = 0.99;
26+
for (double x = 0.0; x < 10.0; x += 1.0) {
27+
pcl_point.x = x;
28+
traj_point.pose.position.x = x;
29+
trajectory.points.push_back(traj_point);
30+
pcl.push_back(pcl_point);
31+
}
32+
// radius < 1: all points are filtered
33+
for (auto radius = 0.0; radius <= 0.99; radius += 0.1) {
34+
const auto filtered_pcl = filterPointCloudByTrajectory(pcl, trajectory, radius);
35+
EXPECT_EQ(filtered_pcl.size(), 0ul);
36+
}
37+
// radius >= 1.0: all points are kept
38+
for (auto radius = 1.0; radius < 10.0; radius += 0.1) {
39+
const auto filtered_pcl = filterPointCloudByTrajectory(pcl, trajectory, radius);
40+
ASSERT_EQ(pcl.size(), filtered_pcl.size());
41+
for (size_t i = 0; i < pcl.size(); ++i) {
42+
EXPECT_EQ(pcl[i].x, filtered_pcl[i].x);
43+
EXPECT_EQ(pcl[i].y, filtered_pcl[i].y);
44+
}
45+
}
46+
}

0 commit comments

Comments
 (0)