Skip to content
Snippets Groups Projects
Commit 61b37ba2 authored by Víctor Sainz Ubide's avatar Víctor Sainz Ubide
Browse files

pointer cast changed from std::make_shared to pcl::make_shared

parent 0f68e59b
No related branches found
No related tags found
1 merge request!41Draft: Resolve "New branch laser 3d"
...@@ -48,17 +48,17 @@ ProcessorOdomIcp3d::ProcessorOdomIcp3d(ParamsProcessorOdomIcp3dPtr _params) ...@@ -48,17 +48,17 @@ ProcessorOdomIcp3d::ProcessorOdomIcp3d(ParamsProcessorOdomIcp3dPtr _params)
if (std::strcmp(_params->icp_algorithm.c_str(), "icp_nl") == 0) if (std::strcmp(_params->icp_algorithm.c_str(), "icp_nl") == 0)
{ {
WOLF_INFO("ProcessorOdomIcp3d: Using icp_nl"); 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) else if (std::strcmp(_params->icp_algorithm.c_str(), "icp") == 0)
{ {
WOLF_INFO("ProcessorOdomIcp3d: Using icp"); 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) else if (std::strcmp(_params->icp_algorithm.c_str(), "gicp") == 0)
{ {
WOLF_INFO("ProcessorOdomIcp3d: Using gicp"); 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 else
{ {
......
...@@ -77,7 +77,7 @@ TEST(pairAlign, identity) ...@@ -77,7 +77,7 @@ TEST(pairAlign, identity)
// Solver configuration // Solver configuration
RegistrationPtr registration_solver = 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); registration_solver->setTransformationEpsilon(1e-6);
// Set the maximum distance between two correspondences (src<->tgt) to 10cm // Set the maximum distance between two correspondences (src<->tgt) to 10cm
// Note: adjust this based on the size of your datasets // Note: adjust this based on the size of your datasets
...@@ -123,7 +123,7 @@ TEST(pairAlign, known_transformation) ...@@ -123,7 +123,7 @@ TEST(pairAlign, known_transformation)
// Solver configuration // Solver configuration
RegistrationPtr registration_solver = 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; // pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZ, pcl::PointXYZ> registration_solver;
double max_trans_epsilon_meters = 0.001; double max_trans_epsilon_meters = 0.001;
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment