diff --git a/include/laser/utils/laser3d_tools.h b/include/laser/utils/laser3d_tools.h index b96b709c2babc74975ad1d1f897843b403a169c0..95275e783e8916eeb72131fca5ffc73bfc08bc82 100644 --- a/include/laser/utils/laser3d_tools.h +++ b/include/laser/utils/laser3d_tools.h @@ -60,17 +60,9 @@ inline void pairAlign(const pcl::PointCloud<pcl::PointXYZ>::Ptr _cloud_ref, auto start = std::chrono::high_resolution_clock::now(); // DURATION -------------------------------------------------------- - // Internal PointCloud pointers (boost::shared_ptr) - pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_ref = pcl::make_shared<pcl::PointCloud<pcl::PointXYZ>>(); - pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_other = pcl::make_shared<pcl::PointCloud<pcl::PointXYZ>>(); - - // Point clouds are considered already downsampled - *cloud_ref = *_cloud_ref; - *cloud_other = *_cloud_other; - // Set input clouds - _registration_solver->setInputSource(cloud_ref); - _registration_solver->setInputTarget(cloud_other); + _registration_solver->setInputSource(_cloud_ref); + _registration_solver->setInputTarget(_cloud_other); // Declare variables Eigen::Matrix4f transform_pcl; @@ -79,7 +71,8 @@ inline void pairAlign(const pcl::PointCloud<pcl::PointXYZ>::Ptr _cloud_ref, Eigen::Matrix4f transform_guess = _transform_guess.matrix().cast<float>(); // Alignment - _registration_solver->align(*cloud_ref, transform_guess); + pcl::PointCloud<pcl::PointXYZ>cloud_out; + _registration_solver->align(cloud_out, transform_guess); transform_pcl = _registration_solver->getFinalTransformation(); // Output the transformation as Isometry of double(s)