Skip to content

Commit

Permalink
Letting the compiler auto-deduce template parameters
Browse files Browse the repository at this point in the history
  • Loading branch information
kunaltyagi committed Sep 21, 2019
1 parent be85ca2 commit 976c005
Show file tree
Hide file tree
Showing 12 changed files with 24 additions and 24 deletions.
4 changes: 2 additions & 2 deletions apps/src/openni_uniform_sampling.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,8 +91,8 @@ class OpenNIUniformSampling
pcl::PointCloud<pcl::PointXYZRGBA> sampled;
pass_.filter (sampled);
*cloud_ = *cloud;
pcl::copyPointCloud<pcl::PointXYZRGBA, pcl::PointXYZ> (sampled, *keypoints_);

pcl::copyPointCloud (sampled, *keypoints_);
}

void
Expand Down
2 changes: 1 addition & 1 deletion common/include/pcl/common/impl/io.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -264,7 +264,7 @@ pcl::copyPointCloud (const pcl::PointCloud<PointInT> &cloud_in,
// Do we want to copy everything? Remember we assume UNIQUE indices
if (nr_p == cloud_in.points.size ())
{
copyPointCloud<PointInT, PointOutT> (cloud_in, cloud_out);
copyPointCloud (cloud_in, cloud_out);
return;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ main (int argc, char *argv[])

// Create output cloud for DoN results
PointCloud<PointNormal>::Ptr doncloud (new pcl::PointCloud<PointNormal>);
copyPointCloud<PointXYZRGB, PointNormal>(*cloud, *doncloud);
copyPointCloud (*cloud, *doncloud);

std::cout << "Calculating DoN... " << std::endl;
// Create DoN operator
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,7 @@ main(int argc, char** argv)
}

// copies all inliers of the model computed to another PointCloud
pcl::copyPointCloud<pcl::PointXYZ>(*cloud, inliers, *final);
pcl::copyPointCloud (*cloud, inliers, *final);

// creates the visualization object and adds either our original cloud or all of the inliers
// depending on the command line arguments specified.
Expand Down
16 changes: 8 additions & 8 deletions doc/tutorials/content/sources/registration_api/example2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,10 +60,10 @@ estimateNormals (const PointCloud<PointXYZ>::Ptr &src,
// For debugging purposes only: uncomment the lines below and use pcl_viewer to view the results, i.e.:
// pcl_viewer normals_src.pcd
PointCloud<PointNormal> s, t;
copyPointCloud<PointXYZ, PointNormal> (*src, s);
copyPointCloud<Normal, PointNormal> (normals_src, s);
copyPointCloud<PointXYZ, PointNormal> (*tgt, t);
copyPointCloud<Normal, PointNormal> (normals_tgt, t);
copyPointCloud (*src, s);
copyPointCloud (normals_src, s);
copyPointCloud (*tgt, t);
copyPointCloud (normals_tgt, t);
savePCDFileBinary ("normals_src.pcd", s);
savePCDFileBinary ("normals_tgt.pcd", t);
}
Expand Down Expand Up @@ -154,10 +154,10 @@ computeTransformation (const PointCloud<PointXYZ>::Ptr &src,

// Copy the data and save it to disk
/* PointCloud<PointNormal> s, t;
copyPointCloud<PointXYZ, PointNormal> (*keypoints_src, s);
copyPointCloud<Normal, PointNormal> (normals_src, s);
copyPointCloud<PointXYZ, PointNormal> (*keypoints_tgt, t);
copyPointCloud<Normal, PointNormal> (normals_tgt, t);*/
copyPointCloud (*keypoints_src, s);
copyPointCloud (normals_src, s);
copyPointCloud (*keypoints_tgt, t);
copyPointCloud (normals_tgt, t);*/

// Find correspondences between keypoints in FPFH space
CorrespondencesPtr all_correspondences (new Correspondences),
Expand Down
2 changes: 1 addition & 1 deletion examples/features/example_difference_of_normals.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,7 @@ int main (int argc, char *argv[])

// Create output cloud for DoN results
PointCloud<PointOutT>::Ptr doncloud (new pcl::PointCloud<PointOutT>);
copyPointCloud<PointT, PointOutT>(*cloud, *doncloud);
copyPointCloud (*cloud, *doncloud);

std::cout << "Calculating DoN... " << std::endl;
// Create DoN operator
Expand Down
4 changes: 2 additions & 2 deletions filters/include/pcl/filters/impl/morphological_filter.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ pcl::applyMorphologicalOperator (const typename pcl::PointCloud<PointT>::ConstPt
if (cloud_in->empty ())
return;

pcl::copyPointCloud<PointT, PointT> (*cloud_in, cloud_out);
pcl::copyPointCloud (*cloud_in, cloud_out);

pcl::octree::OctreePointCloudSearch<PointT> tree (resolution);

Expand Down Expand Up @@ -116,7 +116,7 @@ pcl::applyMorphologicalOperator (const typename pcl::PointCloud<PointT>::ConstPt
{
pcl::PointCloud<PointT> cloud_temp;

pcl::copyPointCloud<PointT, PointT> (*cloud_in, cloud_temp);
pcl::copyPointCloud (*cloud_in, cloud_temp);

for (size_t p_idx = 0; p_idx < cloud_temp.points.size (); ++p_idx)
{
Expand Down
4 changes: 2 additions & 2 deletions keypoints/include/pcl/keypoints/agast_2d.h
Original file line number Diff line number Diff line change
Expand Up @@ -488,7 +488,7 @@ namespace pcl
{
pcl::PointCloud<pcl::PointUV> output_temp;
detector->applyNonMaxSuppression (image_data, tmp_cloud, output_temp);
pcl::copyPointCloud<pcl::PointUV, Out> (output_temp, output);
pcl::copyPointCloud (output_temp, output);
}
};

Expand Down Expand Up @@ -516,7 +516,7 @@ namespace pcl
{
pcl::PointCloud<pcl::PointUV> output_temp;
detector->detectKeypoints (image_data, output_temp);
pcl::copyPointCloud<pcl::PointUV, Out> (output_temp, output);
pcl::copyPointCloud (output_temp, output);
}
};

Expand Down
2 changes: 1 addition & 1 deletion keypoints/include/pcl/keypoints/impl/brisk_2d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ pcl::BriskKeypoint2D<PointInT, PointOutT, IntensityT>::detectKeypoints (PointClo
brisk_scale_space.constructPyramid (image_data, width, height);
pcl::PointCloud<pcl::PointWithScale> output_temp;
brisk_scale_space.getKeypoints (threshold_, output_temp.points);
pcl::copyPointCloud<pcl::PointWithScale, PointOutT> (output_temp, output);
pcl::copyPointCloud (output_temp, output);

// we do not change the denseness
output.width = int (output.points.size ());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ pcl::GeometricConsistencyGrouping<PointModelT, PointSceneT>::clusterCorresponden

//temp copy of scene cloud with the type cast to ModelT in order to use Ransac
PointCloudPtr temp_scene_cloud_ptr (new PointCloud ());
pcl::copyPointCloud<PointSceneT, PointModelT> (*scene_, *temp_scene_cloud_ptr);
pcl::copyPointCloud (*scene_, *temp_scene_cloud_ptr);

pcl::registration::CorrespondenceRejectorSampleConsensus<PointModelT> corr_rejector;
corr_rejector.setMaximumIterations (10000);
Expand Down
4 changes: 2 additions & 2 deletions recognition/include/pcl/recognition/impl/cg/hough_3d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -274,7 +274,7 @@ pcl::Hough3DGrouping<PointModelT, PointSceneT, PointModelRfT, PointSceneRfT>::cl
// Insert maximas into result vector, after Ransac correspondence rejection
// Temp copy of scene cloud with the type cast to ModelT in order to use Ransac
PointCloudPtr temp_scene_cloud_ptr (new PointCloud);
pcl::copyPointCloud<PointSceneT, PointModelT> (*scene_, *temp_scene_cloud_ptr);
pcl::copyPointCloud (*scene_, *temp_scene_cloud_ptr);

pcl::registration::CorrespondenceRejectorSampleConsensus<PointModelT> corr_rejector;
corr_rejector.setMaximumIterations (10000);
Expand Down Expand Up @@ -355,7 +355,7 @@ pcl::Hough3DGrouping<PointModelT, PointSceneT, PointModelRfT, PointSceneRfT>::re

//// Temp copy of scene cloud with the type cast to ModelT in order to use Ransac
//PointCloudPtr temp_scene_cloud_ptr (new PointCloud);
//pcl::copyPointCloud<PointSceneT, PointModelT> (*scene_, *temp_scene_cloud_ptr);
//pcl::copyPointCloud (*scene_, *temp_scene_cloud_ptr);

//for (size_t i = 0; i < model_instances.size (); ++i)
//{
Expand Down
4 changes: 2 additions & 2 deletions test/io/test_io.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1036,7 +1036,7 @@ TEST (PCL, CopyPointCloud)
cloud_b.points[i].rgba = 255;
}

pcl::copyPointCloud<pcl::PointXYZ, pcl::PointXYZRGBA> (cloud_a, cloud_b);
pcl::copyPointCloud (cloud_a, cloud_b);

for (size_t i = 0; i < cloud_a.points.size (); ++i)
{
Expand All @@ -1047,7 +1047,7 @@ TEST (PCL, CopyPointCloud)
cloud_a.points[i].x = cloud_a.points[i].y = cloud_a.points[i].z = 0;
}

pcl::copyPointCloud<pcl::PointXYZRGBA, pcl::PointXYZ> (cloud_b, cloud_a);
pcl::copyPointCloud (cloud_b, cloud_a);

for (size_t i = 0; i < cloud_a.points.size (); ++i)
{
Expand Down

0 comments on commit 976c005

Please sign in to comment.