diff --git a/src/processor/processor_odom_icp_3d.cpp b/src/processor/processor_odom_icp_3d.cpp index b9275a9a946f7063a0366cc69ca94871f1f781a5..979c8e5823bad6527087e69a8364dc141fc7e11b 100644 --- a/src/processor/processor_odom_icp_3d.cpp +++ b/src/processor/processor_odom_icp_3d.cpp @@ -48,17 +48,17 @@ ProcessorOdomIcp3d::ProcessorOdomIcp3d(ParamsProcessorOdomIcp3dPtr _params) if (std::strcmp(_params->icp_algorithm.c_str(), "icp_nl") == 0) { WOLF_INFO("ProcessorOdomIcp3d: Using icp_nl"); - registration_solver_ = std::make_shared<pcl::IterativeClosestPointNonLinear<pcl::PointXYZ, pcl::PointXYZ>>(); + registration_solver_ = pcl::make_shared<pcl::IterativeClosestPointNonLinear<pcl::PointXYZ, pcl::PointXYZ>>(); } else if (std::strcmp(_params->icp_algorithm.c_str(), "icp") == 0) { WOLF_INFO("ProcessorOdomIcp3d: Using icp"); - registration_solver_ = std::make_shared<pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ>>(); + registration_solver_ = pcl::make_shared<pcl::IterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ>>(); } else if (std::strcmp(_params->icp_algorithm.c_str(), "gicp") == 0) { WOLF_INFO("ProcessorOdomIcp3d: Using gicp"); - registration_solver_ = std::make_shared<pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ>>(); + registration_solver_ = pcl::make_shared<pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ>>(); } else { diff --git a/test/gtest_laser3d_tools.cpp b/test/gtest_laser3d_tools.cpp index c8be82381b387e40be45446b503da317d9f6c77b..bbbbb034e2cd1b6f73c8f47596a25ddca05c509b 100644 --- a/test/gtest_laser3d_tools.cpp +++ b/test/gtest_laser3d_tools.cpp @@ -77,7 +77,7 @@ TEST(pairAlign, identity) // Solver configuration RegistrationPtr registration_solver = - std::make_shared<pcl::IterativeClosestPointNonLinear<pcl::PointXYZ, pcl::PointXYZ>>(); + pcl::make_shared<pcl::IterativeClosestPointNonLinear<pcl::PointXYZ, pcl::PointXYZ>>(); registration_solver->setTransformationEpsilon(1e-6); // Set the maximum distance between two correspondences (src<->tgt) to 10cm // Note: adjust this based on the size of your datasets @@ -123,7 +123,7 @@ TEST(pairAlign, known_transformation) // Solver configuration RegistrationPtr registration_solver = - std::make_shared<pcl::IterativeClosestPointNonLinear<pcl::PointXYZ, pcl::PointXYZ>>(); + pcl::make_shared<pcl::IterativeClosestPointNonLinear<pcl::PointXYZ, pcl::PointXYZ>>(); // pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> registration_solver; double max_trans_epsilon_meters = 0.001;