Skip to content

Commit

Permalink
Merge pull request #4026 from kunaltyagi/rm_setinputcloud
Browse files Browse the repository at this point in the history
[registration] Removing deprecated method `setInputCloud`  from public API
  • Loading branch information
kunaltyagi authored May 6, 2020
2 parents b696219 + a864e56 commit 17e8333
Show file tree
Hide file tree
Showing 5 changed files with 19 additions and 6 deletions.
4 changes: 2 additions & 2 deletions doc/tutorials/content/sources/iccv2011/include/registration.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ computeInitialAlignment (const PointCloudPtr & source_points, const LocalDescrip
sac_ia.setMaxCorrespondenceDistance (max_correspondence_distance);
sac_ia.setMaximumIterations (nr_iterations);

sac_ia.setInputCloud (source_points);
sac_ia.setInputSource (source_points);
sac_ia.setSourceFeatures (source_descriptors);

sac_ia.setInputTarget (target_points);
Expand Down Expand Up @@ -81,7 +81,7 @@ refineAlignment (const PointCloudPtr & source_points, const PointCloudPtr & targ
PointCloudPtr source_points_transformed (new PointCloud);
pcl::transformPointCloud (*source_points, *source_points_transformed, initial_alignment);

icp.setInputCloud (source_points_transformed);
icp.setInputSource (source_points_transformed);
icp.setInputTarget (target_points);

PointCloud registration_output;
Expand Down
2 changes: 1 addition & 1 deletion doc/tutorials/content/sources/iccv2011/src/tutorial.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -344,7 +344,7 @@ void ICCVTutorial<FeatureType>::determineFinalTransformation ()
{
std::cout << "final registration..." << std::flush;
pcl::Registration<pcl::PointXYZRGB, pcl::PointXYZRGB>::Ptr registration (new pcl::IterativeClosestPoint<pcl::PointXYZRGB, pcl::PointXYZRGB>);
registration->setInputCloud(source_transformed_);
registration->setInputSource(source_transformed_);
//registration->setInputCloud(source_segmented_);
registration->setInputTarget (target_segmented_);
registration->setMaxCorrespondenceDistance(0.05);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ computeInitialAlignment (const PointCloudPtr & source_points, const LocalDescrip
sac_ia.setMaxCorrespondenceDistance (max_correspondence_distance);
sac_ia.setMaximumIterations (nr_iterations);

sac_ia.setInputCloud (source_points);
sac_ia.setInputSource (source_points);
sac_ia.setSourceFeatures (source_descriptors);

sac_ia.setInputTarget (target_points);
Expand Down Expand Up @@ -81,7 +81,7 @@ refineAlignment (const PointCloudPtr & source_points, const PointCloudPtr & targ
PointCloudPtr source_points_transformed (new PointCloud);
pcl::transformPointCloud (*source_points, *source_points_transformed, initial_alignment);

icp.setInputCloud (source_points_transformed);
icp.setInputSource (source_points_transformed);
icp.setInputTarget (target_points);

PointCloud registration_output;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ class TemplateAlignment
void
align (FeatureCloud &template_cloud, TemplateAlignment::Result &result)
{
sac_ia_.setInputCloud (template_cloud.getPointCloud ());
sac_ia_.setInputSource (template_cloud.getPointCloud ());
sac_ia_.setSourceFeatures (template_cloud.getLocalFeatures ());

pcl::PointCloud<pcl::PointXYZ> registration_output;
Expand Down
13 changes: 13 additions & 0 deletions registration/include/pcl/registration/registration.h
Original file line number Diff line number Diff line change
Expand Up @@ -609,6 +609,19 @@ namespace pcl
private:
/** \brief The point representation used (internal). */
PointRepresentationConstPtr point_representation_;

/**
* \brief Remove from public API in favor of \ref setInputSource
*
* Still gives the correct result (with a warning)
*/
void setInputCloud (const PointCloudSourceConstPtr &cloud) override
{
PCL_WARN ("[pcl::registration::Registration] setInputCloud is deprecated."
"Please use setInputSource instead.\n");
setInputSource (cloud);
}

public:
PCL_MAKE_ALIGNED_OPERATOR_NEW
};
Expand Down

0 comments on commit 17e8333

Please sign in to comment.