b.cpp
Go to the documentation of this file.
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 
00057 int
00058   main (int argc, char** argv)
00059 {
00060   // All the objects needed
00061   pcl::PCDReader reader;
00062   pcl::PassThrough<PointT> pass;
00063   pcl::NormalEstimation<PointT, pcl::Normal> ne;
00064   pcl::SACSegmentationFromNormals<PointT, pcl::Normal> seg;
00065   pcl::PCDWriter writer;
00066   pcl::ExtractIndices<PointT> extract;
00067   pcl::ExtractIndices<pcl::Normal> extract_normals;
00068   pcl::KdTreeFLANN<PointT>::Ptr tree (new pcl::KdTreeFLANN<PointT> ());
00069 
00070   // Datasets
00071   pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT> ());
00072   pcl::PointCloud<PointT>::Ptr cloud_filtered (new pcl::PointCloud<PointT> ());
00073   pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal> ());
00074   pcl::ModelCoefficients::Ptr coefficients_plane (new pcl::ModelCoefficients ()), coefficients_cylinder (new pcl::ModelCoefficients ());
00075   pcl::PointIndices::Ptr inliers_plane (new pcl::PointIndices ()), inliers_cylinder (new pcl::PointIndices ());
00076 
00077   // Read in the cloud data
00078   reader.read ("data/table_scene_mug_stereo_textured.pcd", *cloud);
00079   ROS_INFO ("PointCloud has: %zu data points.", cloud->points.size ());
00080 
00081   // Build a passthrough filter to remove spurious NaNs
00082   pass.setInputCloud (cloud);
00083   pass.setFilterFieldName ("z");
00084   pass.setFilterLimits (0, 1.2);
00085   pass.filter (*cloud_filtered);
00086   ROS_INFO ("PointCloud after filtering has: %zu data points.", cloud_filtered->points.size ());
00087 
00088   // Estimate point normals
00089   ne.setSearchMethod (tree);
00090   ne.setInputCloud (cloud_filtered);
00091   ne.setKSearch (50);
00092   ne.compute (*cloud_normals);
00093 
00094   // Create the segmentation object for the planar model and set all the parameters
00095   seg.setOptimizeCoefficients (true);
00096   seg.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00097   seg.setNormalDistanceWeight (0.01);
00098   seg.setMethodType (pcl::SAC_RANSAC);
00099   seg.setMaxIterations (100);
00100   seg.setDistanceThreshold (0.02);
00101   seg.setInputCloud (cloud_filtered);
00102   seg.setInputNormals (cloud_normals);
00103   // Obtain the plane inliers and coefficients
00104   seg.segment (*inliers_plane, *coefficients_plane);
00105   std::cerr << "Plane coefficients: " << *coefficients_plane << std::endl;
00106 
00107   // Extract the planar inliers from the input cloud
00108   extract.setInputCloud (cloud_filtered);
00109   extract.setIndices (inliers_plane);
00110   extract.setNegative (false);
00111 
00112   // Write the planar inliers to disk
00113   pcl::PointCloud<PointT>::Ptr cloud_plane (new pcl::PointCloud<PointT> ());
00114   extract.filter (*cloud_plane);
00115   ROS_INFO ("PointCloud representing the planar component: %zu data points.", cloud_plane->points.size ());
00116   writer.write ("table_scene_mug_stereo_textured_plane.pcd", *cloud_plane, false);
00117 
00118   // Remove the planar inliers, extract the rest
00119   pcl::PointCloud<PointT>::Ptr cloud_cylinder (new pcl::PointCloud<PointT> ());
00120   extract.setNegative (true);
00121   extract.filter (*cloud_cylinder);
00122   extract.filter (*cloud_cylinder);
00123   ROS_INFO ("PointCloud representing the cylindrical component: %zu data points.", cloud_cylinder->points.size ());
00124   writer.write ("table_scene_mug_stereo_textured_cylinder.pcd", *cloud_cylinder, false);
00125 
00126   return (0);
00127 }
00128 /* ]--- */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


as11
Author(s): lucian goron
autogenerated on Thu May 23 2013 18:50:24