diff --git a/test/registration/test_registration.cpp b/test/registration/test_registration.cpp index bb9b132cb72..4ee6abae134 100644 --- a/test/registration/test_registration.cpp +++ b/test/registration/test_registration.cpp @@ -155,30 +155,26 @@ TEST (PCL, findFeatureCorrespondences) ///////////////////////////////////////////////////////////////////////////////////////////////////////////////// // This test if the ICP algorithm can successfully find the transformation of a cloud that has been -// moved 0.7 in x direction. +// moved 0.7 in z direction. // It indirectly test the KDTree doesn't get an empty input cloud, see #3624 // It is more or less a copy of https://github.com/PointCloudLibrary/pcl/blob/cc7fe363c6463a0abc617b1e17e94ab4bd4169ef/doc/tutorials/content/sources/iterative_closest_point/iterative_closest_point.cpp TEST(PCL, ICP_translated) { - pcl::PointCloud::Ptr cloud_in(new pcl::PointCloud(5,1)); + pcl::PointCloud::Ptr cloud_in(new pcl::PointCloud); pcl::PointCloud::Ptr cloud_out(new pcl::PointCloud); // Fill in the CloudIn data - for (auto& point : *cloud_in) - { - point.x = 1024 * rand() / (RAND_MAX + 1.0f); - point.y = 1024 * rand() / (RAND_MAX + 1.0f); - point.z = 1024 * rand() / (RAND_MAX + 1.0f); - } + *cloud_in = cloud_source; *cloud_out = *cloud_in; for (auto& point : *cloud_out) - point.x += 0.7f; + point.z += 0.7f; pcl::IterativeClosestPoint icp; icp.setInputSource(cloud_in); icp.setInputTarget(cloud_out); + icp.setMaximumIterations (50); pcl::PointCloud Final; icp.align(Final); @@ -190,9 +186,12 @@ TEST(PCL, ICP_translated) EXPECT_LT(icp.getFitnessScore(), 1e-6); // Ensure that the translation found is within acceptable threshold. - EXPECT_NEAR(icp.getFinalTransformation()(0, 3), 0.7, 2e-3); + EXPECT_NEAR(icp.getFinalTransformation()(0, 0), 1.0, 2e-3); + EXPECT_NEAR(icp.getFinalTransformation()(1, 1), 1.0, 2e-3); + EXPECT_NEAR(icp.getFinalTransformation()(2, 2), 1.0, 2e-3); + EXPECT_NEAR(icp.getFinalTransformation()(0, 3), 0.0, 2e-3); EXPECT_NEAR(icp.getFinalTransformation()(1, 3), 0.0, 2e-3); - EXPECT_NEAR(icp.getFinalTransformation()(2, 3), 0.0, 2e-3); + EXPECT_NEAR(icp.getFinalTransformation()(2, 3), 0.7, 2e-3); } //////////////////////////////////////////////////////////////////////////////////////////////////////////////////