|
| 1 | +// Copyright 2024 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 <autoware_point_types/types.hpp> |
| 16 | +#include <image_projection_based_fusion/utils/utils.hpp> |
| 17 | + |
| 18 | +#include <gtest/gtest.h> |
| 19 | + |
| 20 | +using autoware_point_types::PointXYZI; |
| 21 | + |
| 22 | +void setPointCloud2Fields(sensor_msgs::msg::PointCloud2 & pointcloud) |
| 23 | +{ |
| 24 | + pointcloud.fields.resize(4); |
| 25 | + pointcloud.fields[0].name = "x"; |
| 26 | + pointcloud.fields[1].name = "y"; |
| 27 | + pointcloud.fields[2].name = "z"; |
| 28 | + pointcloud.fields[3].name = "intensity"; |
| 29 | + pointcloud.fields[0].offset = 0; |
| 30 | + pointcloud.fields[1].offset = 4; |
| 31 | + pointcloud.fields[2].offset = 8; |
| 32 | + pointcloud.fields[3].offset = 12; |
| 33 | + pointcloud.fields[0].datatype = sensor_msgs::msg::PointField::FLOAT32; |
| 34 | + pointcloud.fields[1].datatype = sensor_msgs::msg::PointField::FLOAT32; |
| 35 | + pointcloud.fields[2].datatype = sensor_msgs::msg::PointField::FLOAT32; |
| 36 | + pointcloud.fields[3].datatype = sensor_msgs::msg::PointField::FLOAT32; |
| 37 | + pointcloud.fields[0].count = 1; |
| 38 | + pointcloud.fields[1].count = 1; |
| 39 | + pointcloud.fields[2].count = 1; |
| 40 | + pointcloud.fields[3].count = 1; |
| 41 | + pointcloud.height = 1; |
| 42 | + pointcloud.point_step = 16; |
| 43 | + pointcloud.is_bigendian = false; |
| 44 | + pointcloud.is_dense = true; |
| 45 | + pointcloud.header.frame_id = "dummy_frame_id"; |
| 46 | + pointcloud.header.stamp.sec = 0; |
| 47 | + pointcloud.header.stamp.nanosec = 0; |
| 48 | +} |
| 49 | + |
| 50 | +// Test case 1: Test case when the input pointcloud is empty |
| 51 | +TEST(UtilsTest, closest_cluster_empty_cluster_test_case1) |
| 52 | +{ |
| 53 | + sensor_msgs::msg::PointCloud2 pointcloud; |
| 54 | + setPointCloud2Fields(pointcloud); |
| 55 | + pointcloud.data.resize(0); |
| 56 | + pointcloud.width = 0; |
| 57 | + pointcloud.row_step = 0; |
| 58 | + |
| 59 | + pcl::PointXYZ center; |
| 60 | + center.x = 0.0; |
| 61 | + center.y = 0.0; |
| 62 | + center.z = 0.0; |
| 63 | + |
| 64 | + // testing closest_cluster function |
| 65 | + double cluster_2d_tolerance = 0.5; |
| 66 | + int min_cluster_size = 3; |
| 67 | + sensor_msgs::msg::PointCloud2 output_cluster; |
| 68 | + image_projection_based_fusion::closest_cluster( |
| 69 | + pointcloud, cluster_2d_tolerance, min_cluster_size, center, output_cluster); |
| 70 | + EXPECT_EQ(output_cluster.data.size(), std::size_t(0)); |
| 71 | +} |
| 72 | + |
| 73 | +// Test case 2: Test case when the input pointcloud as one cluster |
| 74 | +TEST(UtilsTest, closest_cluster_test_case2) |
| 75 | +{ |
| 76 | + sensor_msgs::msg::PointCloud2 pointcloud; |
| 77 | + setPointCloud2Fields(pointcloud); |
| 78 | + std::vector<float> dummy_x = {0.0, 0.1, 0.2}; |
| 79 | + pointcloud.data.resize(dummy_x.size() * pointcloud.point_step); |
| 80 | + size_t global_offset = 0; |
| 81 | + for (auto x : dummy_x) { |
| 82 | + PointXYZI point; |
| 83 | + point.x = x; |
| 84 | + point.y = 0.0; |
| 85 | + point.z = 0.0; |
| 86 | + point.intensity = 0.0; |
| 87 | + memcpy(&pointcloud.data[global_offset], &point, pointcloud.point_step); |
| 88 | + global_offset += pointcloud.point_step; |
| 89 | + } |
| 90 | + pcl::PointXYZ center; |
| 91 | + center.x = 0.0; |
| 92 | + center.y = 0.0; |
| 93 | + center.z = 0.0; |
| 94 | + |
| 95 | + // testing closest_cluster function |
| 96 | + double cluster_2d_tolerance = 0.5; |
| 97 | + int min_cluster_size = 3; |
| 98 | + sensor_msgs::msg::PointCloud2 output_cluster; |
| 99 | + image_projection_based_fusion::closest_cluster( |
| 100 | + pointcloud, cluster_2d_tolerance, min_cluster_size, center, output_cluster); |
| 101 | + EXPECT_EQ(output_cluster.data.size(), dummy_x.size() * pointcloud.point_step); |
| 102 | +} |
| 103 | + |
| 104 | +// Test case 3: Test case when the input pointcloud as two clusters |
| 105 | +TEST(UtilsTest, closest_cluster_test_case3) |
| 106 | +{ |
| 107 | + sensor_msgs::msg::PointCloud2 pointcloud; |
| 108 | + setPointCloud2Fields(pointcloud); |
| 109 | + std::vector<float> dummy_x = {0.0, 0.1, 0.2, 1.0, 1.1, 1.2, 1.21, 1.22}; |
| 110 | + pointcloud.data.resize(dummy_x.size() * pointcloud.point_step); |
| 111 | + size_t global_offset = 0; |
| 112 | + for (auto x : dummy_x) { |
| 113 | + PointXYZI point; |
| 114 | + point.x = x; |
| 115 | + point.y = 0.0; |
| 116 | + point.z = 0.0; |
| 117 | + point.intensity = 0.0; |
| 118 | + memcpy(&pointcloud.data[global_offset], &point, pointcloud.point_step); |
| 119 | + global_offset += pointcloud.point_step; |
| 120 | + } |
| 121 | + pcl::PointXYZ center; |
| 122 | + center.x = 0.0; |
| 123 | + center.y = 0.0; |
| 124 | + center.z = 0.0; |
| 125 | + |
| 126 | + // testing closest_cluster function |
| 127 | + double cluster_2d_tolerance = 0.5; |
| 128 | + int min_cluster_size = 3; |
| 129 | + sensor_msgs::msg::PointCloud2 output_cluster; |
| 130 | + image_projection_based_fusion::closest_cluster( |
| 131 | + pointcloud, cluster_2d_tolerance, min_cluster_size, center, output_cluster); |
| 132 | + EXPECT_EQ(output_cluster.data.size(), 3 * pointcloud.point_step); |
| 133 | +} |
| 134 | + |
| 135 | +// Test case 4: Test case when the input pointcloud as two clusters |
| 136 | +TEST(UtilsTest, closest_cluster_test_case4) |
| 137 | +{ |
| 138 | + sensor_msgs::msg::PointCloud2 pointcloud; |
| 139 | + setPointCloud2Fields(pointcloud); |
| 140 | + std::vector<float> dummy_x = {0.0, 0.1, 1.0, 1.01, 1.1, 1.2, 1.21, 1.22}; |
| 141 | + pointcloud.data.resize(dummy_x.size() * pointcloud.point_step); |
| 142 | + size_t global_offset = 0; |
| 143 | + for (auto x : dummy_x) { |
| 144 | + PointXYZI point; |
| 145 | + point.x = x; |
| 146 | + point.y = 0.0; |
| 147 | + point.z = 0.0; |
| 148 | + point.intensity = 0.0; |
| 149 | + memcpy(&pointcloud.data[global_offset], &point, pointcloud.point_step); |
| 150 | + global_offset += pointcloud.point_step; |
| 151 | + } |
| 152 | + pcl::PointXYZ center; |
| 153 | + center.x = 0.0; |
| 154 | + center.y = 0.0; |
| 155 | + center.z = 0.0; |
| 156 | + |
| 157 | + // testing closest_cluster function |
| 158 | + double cluster_2d_tolerance = 0.5; |
| 159 | + int min_cluster_size = 3; |
| 160 | + sensor_msgs::msg::PointCloud2 output_cluster; |
| 161 | + image_projection_based_fusion::closest_cluster( |
| 162 | + pointcloud, cluster_2d_tolerance, min_cluster_size, center, output_cluster); |
| 163 | + EXPECT_EQ(output_cluster.data.size(), 6 * pointcloud.point_step); |
| 164 | +} |
| 165 | + |
| 166 | +int main(int argc, char ** argv) |
| 167 | +{ |
| 168 | + testing::InitGoogleTest(&argc, argv); |
| 169 | + return RUN_ALL_TESTS(); |
| 170 | +} |
0 commit comments