|
| 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