$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: segmentation_cylinder.cpp 35522 2011-01-26 08:17:01Z rusu $ 00035 * 00036 */ 00037 00052 #include <pcl/ModelCoefficients.h> 00053 00054 #include <pcl/io/pcd_io.h> 00055 #include <pcl/point_types.h> 00056 00057 #include <pcl/features/normal_3d.h> 00058 00059 #include <pcl/filters/extract_indices.h> 00060 #include <pcl/filters/passthrough.h> 00061 00062 #include <pcl/sample_consensus/method_types.h> 00063 #include <pcl/sample_consensus/model_types.h> 00064 #include <pcl/segmentation/sac_segmentation.h> 00065 00066 typedef pcl::PointXYZ PointT; 00067 00068 /* ---[ */ 00069 int 00070 main (int argc, char** argv) 00071 { 00072 // All the objects needed 00073 pcl::PCDReader reader; 00074 pcl::PassThrough<PointT> pass; 00075 pcl::NormalEstimation<PointT, pcl::Normal> ne; 00076 pcl::SACSegmentationFromNormals<PointT, pcl::Normal> seg; 00077 pcl::PCDWriter writer; 00078 pcl::ExtractIndices<PointT> extract; 00079 pcl::ExtractIndices<pcl::Normal> extract_normals; 00080 pcl::KdTreeFLANN<PointT>::Ptr tree (new pcl::KdTreeFLANN<PointT> ()); 00081 00082 // Datasets 00083 pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT> ()); 00084 pcl::PointCloud<PointT>::Ptr cloud_filtered (new pcl::PointCloud<PointT> ()); 00085 pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal> ()); 00086 pcl::ModelCoefficients::Ptr coefficients_plane (new pcl::ModelCoefficients ()), coefficients_cylinder (new pcl::ModelCoefficients ()); 00087 pcl::PointIndices::Ptr inliers_plane (new pcl::PointIndices ()), inliers_cylinder (new pcl::PointIndices ()); 00088 00089 // Read in the cloud data 00090 reader.read ("data/table_scene_mug_stereo_textured.pcd", *cloud); 00091 ROS_INFO ("PointCloud has: %zu data points.", cloud->points.size ()); 00092 00093 // Build a passthrough filter to remove spurious NaNs 00094 pass.setInputCloud (cloud); 00095 pass.setFilterFieldName ("z"); 00096 pass.setFilterLimits (0, 1.5); 00097 pass.filter (*cloud_filtered); 00098 ROS_INFO ("PointCloud after filtering has: %zu data points.", cloud_filtered->points.size ()); 00099 00100 // Estimate point normals 00101 ne.setSearchMethod (tree); 00102 ne.setInputCloud (cloud_filtered); 00103 ne.setKSearch (50); 00104 ne.compute (*cloud_normals); 00105 00106 // Create the segmentation object for the planar model and set all the parameters 00107 seg.setOptimizeCoefficients (true); 00108 seg.setModelType (pcl::SACMODEL_NORMAL_PLANE); 00109 seg.setNormalDistanceWeight (0.1); 00110 seg.setMethodType (pcl::SAC_RANSAC); 00111 seg.setMaxIterations (100); 00112 seg.setDistanceThreshold (0.03); 00113 seg.setInputCloud (cloud_filtered); 00114 seg.setInputNormals (cloud_normals); 00115 // Obtain the plane inliers and coefficients 00116 seg.segment (*inliers_plane, *coefficients_plane); 00117 std::cerr << "Plane coefficients: " << *coefficients_plane << std::endl; 00118 00119 // Extract the planar inliers from the input cloud 00120 extract.setInputCloud (cloud_filtered); 00121 extract.setIndices (inliers_plane); 00122 extract.setNegative (false); 00123 00124 // Write the planar inliers to disk 00125 pcl::PointCloud<PointT>::Ptr cloud_plane (new pcl::PointCloud<PointT> ()); 00126 extract.filter (*cloud_plane); 00127 ROS_INFO ("PointCloud representing the planar component: %zu data points.", cloud_plane->points.size ()); 00128 writer.write ("table_scene_mug_stereo_textured_plane.pcd", *cloud_plane, false); 00129 00130 // Remove the planar inliers, extract the rest 00131 extract.setNegative (true); 00132 extract.filter (*cloud_filtered); 00133 extract_normals.setNegative (true); 00134 extract_normals.setInputCloud (cloud_normals); 00135 extract_normals.setIndices (inliers_plane); 00136 extract_normals.filter (*cloud_normals); 00137 00138 // Create the segmentation object for cylinder segmentation and set all the parameters 00139 seg.setOptimizeCoefficients (true); 00140 seg.setModelType (pcl::SACMODEL_CYLINDER); 00141 seg.setMethodType (pcl::SAC_RANSAC); 00142 seg.setNormalDistanceWeight (0.1); 00143 seg.setMaxIterations (10000); 00144 seg.setDistanceThreshold (0.05); 00145 seg.setRadiusLimits (0, 0.1); 00146 seg.setInputCloud (cloud_filtered); 00147 seg.setInputNormals (cloud_normals); 00148 00149 // Obtain the cylinder inliers and coefficients 00150 seg.segment (*inliers_cylinder, *coefficients_cylinder); 00151 std::cerr << "Cylinder coefficients: " << *coefficients_cylinder << std::endl; 00152 00153 // Write the cylinder inliers to disk 00154 extract.setInputCloud (cloud_filtered); 00155 extract.setIndices (inliers_cylinder); 00156 extract.setNegative (false); 00157 pcl::PointCloud<PointT>::Ptr cloud_cylinder (new pcl::PointCloud<PointT> ()); 00158 extract.filter (*cloud_cylinder); 00159 ROS_INFO ("PointCloud representing the cylindrical component: %zu data points.", cloud_cylinder->points.size ()); 00160 writer.write ("table_scene_mug_stereo_textured_cylinder.pcd", *cloud_cylinder, false); 00161 00162 return (0); 00163 } 00164 /* ]--- */