cylinder_segmentation.cpp
Go to the documentation of this file.
00001 #include <pcl/ModelCoefficients.h>
00002 #include <pcl/io/pcd_io.h>
00003 #include <pcl/point_types.h>
00004 #include <pcl/filters/extract_indices.h>
00005 #include <pcl/filters/passthrough.h>
00006 #include <pcl/features/normal_3d.h>
00007 #include <pcl/sample_consensus/method_types.h>
00008 #include <pcl/sample_consensus/model_types.h>
00009 #include <pcl/segmentation/sac_segmentation.h>
00010 
00011 typedef pcl::PointXYZ PointT;
00012 
00013 int
00014 main (int argc, char** argv)
00015 {
00016   // All the objects needed
00017   pcl::PCDReader reader;
00018   pcl::PassThrough<PointT> pass;
00019   pcl::NormalEstimation<PointT, pcl::Normal> ne;
00020   pcl::SACSegmentationFromNormals<PointT, pcl::Normal> seg; 
00021   pcl::PCDWriter writer;
00022   pcl::ExtractIndices<PointT> extract;
00023   pcl::ExtractIndices<pcl::Normal> extract_normals;
00024   pcl::search::KdTree<PointT>::Ptr tree (new pcl::search::KdTree<PointT> ());
00025 
00026   // Datasets
00027   pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT>);
00028   pcl::PointCloud<PointT>::Ptr cloud_filtered (new pcl::PointCloud<PointT>);
00029   pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal>);
00030   pcl::PointCloud<PointT>::Ptr cloud_filtered2 (new pcl::PointCloud<PointT>);
00031   pcl::PointCloud<pcl::Normal>::Ptr cloud_normals2 (new pcl::PointCloud<pcl::Normal>);
00032   pcl::ModelCoefficients::Ptr coefficients_plane (new pcl::ModelCoefficients), coefficients_cylinder (new pcl::ModelCoefficients);
00033   pcl::PointIndices::Ptr inliers_plane (new pcl::PointIndices), inliers_cylinder (new pcl::PointIndices);
00034 
00035   // Read in the cloud data
00036   reader.read ("table_scene_mug_stereo_textured.pcd", *cloud);
00037   std::cerr << "PointCloud has: " << cloud->points.size () << " data points." << std::endl;
00038 
00039   // Build a passthrough filter to remove spurious NaNs
00040   pass.setInputCloud (cloud);
00041   pass.setFilterFieldName ("z");
00042   pass.setFilterLimits (0, 1.5);
00043   pass.filter (*cloud_filtered);
00044   std::cerr << "PointCloud after filtering has: " << cloud_filtered->points.size () << " data points." << std::endl;
00045 
00046   // Estimate point normals
00047   ne.setSearchMethod (tree);
00048   ne.setInputCloud (cloud_filtered);
00049   ne.setKSearch (50);
00050   ne.compute (*cloud_normals);
00051 
00052   // Create the segmentation object for the planar model and set all the parameters
00053   seg.setOptimizeCoefficients (true);
00054   seg.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00055   seg.setNormalDistanceWeight (0.1);
00056   seg.setMethodType (pcl::SAC_RANSAC);
00057   seg.setMaxIterations (100);
00058   seg.setDistanceThreshold (0.03);
00059   seg.setInputCloud (cloud_filtered);
00060   seg.setInputNormals (cloud_normals);
00061   // Obtain the plane inliers and coefficients
00062   seg.segment (*inliers_plane, *coefficients_plane);
00063   std::cerr << "Plane coefficients: " << *coefficients_plane << std::endl;
00064 
00065   // Extract the planar inliers from the input cloud
00066   extract.setInputCloud (cloud_filtered);
00067   extract.setIndices (inliers_plane);
00068   extract.setNegative (false);
00069 
00070   // Write the planar inliers to disk
00071   pcl::PointCloud<PointT>::Ptr cloud_plane (new pcl::PointCloud<PointT> ());
00072   extract.filter (*cloud_plane);
00073   std::cerr << "PointCloud representing the planar component: " << cloud_plane->points.size () << " data points." << std::endl;
00074   writer.write ("table_scene_mug_stereo_textured_plane.pcd", *cloud_plane, false);
00075 
00076   // Remove the planar inliers, extract the rest
00077   extract.setNegative (true);
00078   extract.filter (*cloud_filtered2);
00079   extract_normals.setNegative (true);
00080   extract_normals.setInputCloud (cloud_normals);
00081   extract_normals.setIndices (inliers_plane);
00082   extract_normals.filter (*cloud_normals2);
00083 
00084   // Create the segmentation object for cylinder segmentation and set all the parameters
00085   seg.setOptimizeCoefficients (true);
00086   seg.setModelType (pcl::SACMODEL_CYLINDER);
00087   seg.setMethodType (pcl::SAC_RANSAC);
00088   seg.setNormalDistanceWeight (0.1);
00089   seg.setMaxIterations (10000);
00090   seg.setDistanceThreshold (0.05);
00091   seg.setRadiusLimits (0, 0.1);
00092   seg.setInputCloud (cloud_filtered2);
00093   seg.setInputNormals (cloud_normals2);
00094 
00095   // Obtain the cylinder inliers and coefficients
00096   seg.segment (*inliers_cylinder, *coefficients_cylinder);
00097   std::cerr << "Cylinder coefficients: " << *coefficients_cylinder << std::endl;
00098 
00099   // Write the cylinder inliers to disk
00100   extract.setInputCloud (cloud_filtered2);
00101   extract.setIndices (inliers_cylinder);
00102   extract.setNegative (false);
00103   pcl::PointCloud<PointT>::Ptr cloud_cylinder (new pcl::PointCloud<PointT> ());
00104   extract.filter (*cloud_cylinder);
00105   if (cloud_cylinder->points.empty ()) 
00106     std::cerr << "Can't find the cylindrical component." << std::endl;
00107   else
00108   {
00109           std::cerr << "PointCloud representing the cylindrical component: " << cloud_cylinder->points.size () << " data points." << std::endl;
00110           writer.write ("table_scene_mug_stereo_textured_cylinder.pcd", *cloud_cylinder, false);
00111   }
00112   return (0);
00113 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:23:21