Skip to content

Commit

Permalink
fix make_shared errors (koide3#53)
Browse files Browse the repository at this point in the history
Co-authored-by: k.koide <[email protected]>
  • Loading branch information
koide3 and koide3 authored Sep 29, 2021
1 parent 41dc36e commit b7807be
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions src/hdl_graph_slam/registration_methods.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,31 +29,31 @@ pcl::Registration<pcl::PointXYZI, pcl::PointXYZI>::Ptr RegistrationMethods::meth

switch(registration_method) {
case 0: {
auto icp = pcl::make_shared<pcl::IterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>>();
auto icp = pcl::IterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>::Ptr(new pcl::IterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>);
registration = icp;
} break;

default:
std::cerr << "warning: unknown registration method!!" << std::endl;
std::cerr << " : use GICP" << std::endl;
case 1: {
auto gicp = pcl::make_shared<pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>>();
auto gicp = pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>::Ptr(new pcl::GeneralizedIterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>);
registration = gicp;
} break;

case 2: {
auto ndt = pcl::make_shared<pcl::NormalDistributionsTransform<pcl::PointXYZI, pcl::PointXYZI>>();
auto ndt = pcl::NormalDistributionsTransform<pcl::PointXYZI, pcl::PointXYZI>::Ptr(new pcl::NormalDistributionsTransform<pcl::PointXYZI, pcl::PointXYZI>);
ndt->setResolution(registration_resolution);
registration = ndt;
} break;

case 3: {
auto gicp = pcl::make_shared<pclomp::GeneralizedIterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>>();
auto gicp = pclomp::GeneralizedIterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>::Ptr(new pclomp::GeneralizedIterativeClosestPoint<pcl::PointXYZI, pcl::PointXYZI>);
registration = gicp;
} break;

case 4: {
auto ndt = pcl::make_shared<pclomp::NormalDistributionsTransform<pcl::PointXYZI, pcl::PointXYZI>>();
auto ndt = pclomp::NormalDistributionsTransform<pcl::PointXYZI, pcl::PointXYZI>::Ptr(new pclomp::NormalDistributionsTransform<pcl::PointXYZI, pcl::PointXYZI>);
ndt->setResolution(registration_resolution);
registration = ndt;
} break;
Expand Down

0 comments on commit b7807be

Please sign in to comment.