convex_hull_2d.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/sample_consensus/method_types.h>
00005 #include <pcl/sample_consensus/model_types.h>
00006 #include <pcl/filters/passthrough.h>
00007 #include <pcl/filters/project_inliers.h>
00008 #include <pcl/segmentation/sac_segmentation.h>
00009 #include <pcl/surface/convex_hull.h>
00010 
00011 int
00012  main (int argc, char** argv)
00013 {
00014   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud (new pcl::PointCloud<pcl::PointXYZ>), cloud_filtered (new pcl::PointCloud<pcl::PointXYZ>), cloud_projected (new pcl::PointCloud<pcl::PointXYZ>);
00015   pcl::PCDReader reader;
00016   reader.read ("table_scene_mug_stereo_textured.pcd", *cloud);
00017 
00018   // Build a filter to remove spurious NaNs
00019   pcl::PassThrough<pcl::PointXYZ> pass;
00020   pass.setInputCloud (cloud);
00021   pass.setFilterFieldName ("z");
00022   pass.setFilterLimits (0, 1.1);
00023   pass.filter (*cloud_filtered);
00024   std::cerr << "PointCloud after filtering has: " << cloud_filtered->points.size () << " data points." << std::endl;
00025 
00026   pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients);
00027   pcl::PointIndices::Ptr inliers (new pcl::PointIndices);
00028   // Create the segmentation object
00029   pcl::SACSegmentation<pcl::PointXYZ> seg;
00030   // Optional
00031   seg.setOptimizeCoefficients (true);
00032   // Mandatory
00033   seg.setModelType (pcl::SACMODEL_PLANE);
00034   seg.setMethodType (pcl::SAC_RANSAC);
00035   seg.setDistanceThreshold (0.01);
00036 
00037   seg.setInputCloud (cloud_filtered);
00038   seg.segment (*inliers, *coefficients);
00039 
00040   // Project the model inliers
00041   pcl::ProjectInliers<pcl::PointXYZ> proj;
00042   proj.setModelType (pcl::SACMODEL_PLANE);
00043   proj.setInputCloud (cloud_filtered);
00044   proj.setIndices (inliers);
00045   proj.setModelCoefficients (coefficients);
00046   proj.filter (*cloud_projected);
00047 
00048   // Create a Convex Hull representation of the projected inliers
00049   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_hull (new pcl::PointCloud<pcl::PointXYZ>);
00050   pcl::ConvexHull<pcl::PointXYZ> chull;
00051   chull.setInputCloud (cloud_projected);
00052   chull.reconstruct (*cloud_hull);
00053 
00054   std::cerr << "Convex hull has: " << cloud_hull->points.size () << " data points." << std::endl;
00055 
00056   pcl::PCDWriter writer;
00057   writer.write ("table_scene_mug_stereo_textured_hull.pcd", *cloud_hull, false);
00058 
00059   return (0);
00060 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:55