00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00043 #include "pcl/ModelCoefficients.h"
00044
00045 #include "pcl/io/pcd_io.h"
00046 #include "pcl/point_types.h"
00047
00048 #include "pcl/sample_consensus/method_types.h"
00049 #include "pcl/sample_consensus/model_types.h"
00050 #include "pcl/filters/passthrough.h"
00051 #include "pcl/filters/project_inliers.h"
00052 #include "pcl/segmentation/sac_segmentation.h"
00053 #include "pcl/surface/convex_hull.h"
00054
00055
00056 int
00057 main (int argc, char** argv)
00058 {
00059 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> ());
00060 pcl::PCDReader reader;
00061 reader.read ("table_scene_mug_stereo_textured.pcd", *cloud);
00062
00063
00064 pcl::PassThrough<pcl::PointXYZ> pass;
00065 pass.setInputCloud (cloud);
00066 pass.setFilterFieldName ("z");
00067 pass.setFilterLimits (0, 1.1);
00068 pass.filter (*cloud_filtered);
00069 ROS_INFO ("PointCloud after filtering has: %zu data points.", cloud_filtered->points.size ());
00070
00071 pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients ());
00072 pcl::PointIndices::Ptr inliers (new pcl::PointIndices ());
00073
00074 pcl::SACSegmentation<pcl::PointXYZ> seg;
00075
00076 seg.setOptimizeCoefficients (true);
00077
00078 seg.setModelType (pcl::SACMODEL_PLANE);
00079 seg.setMethodType (pcl::SAC_RANSAC);
00080 seg.setDistanceThreshold (0.01);
00081
00082 seg.setInputCloud (cloud_filtered);
00083 seg.segment (*inliers, *coefficients);
00084
00085
00086 pcl::ProjectInliers<pcl::PointXYZ> proj;
00087 proj.setModelType (pcl::SACMODEL_PLANE);
00088 proj.setInputCloud (cloud_filtered);
00089 proj.setModelCoefficients (coefficients);
00090 proj.filter (*cloud_projected);
00091
00092
00093 pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_hull (new pcl::PointCloud<pcl::PointXYZ> ());
00094 pcl::ConvexHull<pcl::PointXYZ> chull;
00095 chull.setInputCloud (cloud_projected);
00096 chull.reconstruct (*cloud_hull);
00097
00098 ROS_INFO ("Convex hull has: %zu data points.", cloud_hull->points.size ());
00099
00100 pcl::PCDWriter writer;
00101 writer.write ("table_scene_mug_stereo_textured_hull.pcd", *cloud_hull, false);
00102
00103 return (0);
00104 }
00105