From 61b37ba2eaf6eba83fdf6c40f0f31599c75a87a8 Mon Sep 17 00:00:00 2001
From: vsainz <vsainz@iri.upc.edu>
Date: Wed, 10 Aug 2022 12:03:33 +0200
Subject: [PATCH] pointer cast changed from std::make_shared to
 pcl::make_shared

---
 src/processor/processor_odom_icp_3d.cpp | 6 +++---
 test/gtest_laser3d_tools.cpp            | 4 ++--
 2 files changed, 5 insertions(+), 5 deletions(-)

diff --git a/src/processor/processor_odom_icp_3d.cpp b/src/processor/processor_odom_icp_3d.cpp
index b9275a9a9..979c8e582 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 c8be82381..bbbbb034e 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;
-- 
GitLab