$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * $Id: surface_convex_hull.cpp 36118 2011-02-22 00:10:08Z rusu $ 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 // Build a filter to remove spurious NaNs 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 // Create the segmentation object 00074 pcl::SACSegmentation<pcl::PointXYZ> seg; 00075 // Optional 00076 seg.setOptimizeCoefficients (true); 00077 // Mandatory 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 // Project the model inliers 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 // Create a Convex Hull representation of the projected inliers 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 /* ]--- */