segmentation_cylinder.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 #include <pcl/ModelCoefficients.h>
00038 
00039 #include <pcl/io/pcd_io.h>
00040 #include <pcl/point_types.h>
00041 
00042 #include <pcl/features/normal_3d.h>
00043 
00044 #include <pcl/filters/extract_indices.h>
00045 #include <pcl/filters/passthrough.h>
00046 
00047 #include <pcl/sample_consensus/method_types.h>
00048 #include <pcl/sample_consensus/model_types.h>
00049 #include <pcl/segmentation/sac_segmentation.h>
00050 
00051 typedef pcl::PointXYZ PointT;
00052 
00053 /* ---[ */
00054 int
00055   main (int argc, char** argv)
00056 {
00057   // All the objects needed
00058   /*****************************************************
00059    * TODO 1: What do these classes do - document next lines
00060    * Documentation http://www.ros.org/doc/api/pcl/html/annotated.html
00061    */
00062   pcl::PCDReader reader;
00063   pcl::PassThrough<PointT> pass;
00064   pcl::NormalEstimation<PointT, pcl::Normal> ne;
00065   pcl::SACSegmentationFromNormals<PointT, pcl::Normal> seg;
00066   pcl::PCDWriter writer;
00067   pcl::ExtractIndices<PointT> extract;
00068   pcl::ExtractIndices<pcl::Normal> extract_normals;
00069   pcl::KdTreeFLANN<PointT>::Ptr tree (new pcl::KdTreeFLANN<PointT> ());
00070 
00071   // Datasets
00072   pcl::PointCloud<PointT>::Ptr cloud (new pcl::PointCloud<PointT> ());
00073   pcl::PointCloud<PointT>::Ptr cloud_filtered (new pcl::PointCloud<PointT> ());
00074   pcl::PointCloud<pcl::Normal>::Ptr cloud_normals (new pcl::PointCloud<pcl::Normal> ());
00075   pcl::ModelCoefficients::Ptr coefficients_plane (new pcl::ModelCoefficients ()), coefficients_cylinder (new pcl::ModelCoefficients ());
00076   pcl::PointIndices::Ptr inliers_plane (new pcl::PointIndices ()), inliers_cylinder (new pcl::PointIndices ());
00077 
00078   /*****************************************************
00079    * TODO 2: Read in the input pointcloud: data/table_scene_mug_stereo_textured.pcd
00080    * Use "reader" object
00081    */
00082 
00083 
00084   // Build a passthrough filter to remove spurious NaNs
00085   pass.setInputCloud (cloud);
00086   pass.setFilterFieldName ("z");
00087   pass.setFilterLimits (0, 1.5);
00088   pass.filter (*cloud_filtered);
00089   ROS_INFO ("PointCloud after filtering has: %zu data points.", cloud_filtered->points.size ());
00090 
00091 
00092   /*****************************************************
00093    * TODO 3: Estimate the normals
00094    * Use "ne" object, methods to be called in order: setSearchMethod, setInputCloud, setKSearch, compute
00095    */
00096 
00097 
00098     /*****************************************************
00099    * TODO 4: Create the segmentation object for the planar model and set all the parameters
00100    * Use "seg" object, methods to be called in order: setOptimizeCoefficients, setNormalDistanceWeight, 
00101    * setMethodType (use SAC_RANSAC), setMaxIterations, setDistanceThreshold, setInputCloud, segment 
00102    */
00103 
00104 
00105   /*****************************************************
00106    * TODO 5: print out plane coefficients
00107    */
00108   std::cerr << "Plane coefficients: " << /*todo*/ << std::endl;
00109 
00110 
00111   // Extract the planar inliers from the input cloud
00112   extract.setInputCloud (cloud_filtered);
00113   extract.setIndices (inliers_plane);
00114   extract.setNegative (false);
00115 
00116 
00117   pcl::PointCloud<PointT>::Ptr cloud_plane (new pcl::PointCloud<PointT> ());
00118   extract.filter (*cloud_plane);
00119   ROS_INFO ("PointCloud representing the planar component: %zu data points.", cloud_plane->points.size ());
00120   /*****************************************************
00121    * TODO 6:  Write the planar inliers to disk
00122    * Use "writer" object
00123    */
00124 
00125 
00126     /*****************************************************
00127    * TODO 7:  Remove the planar inliers, extract the cluster lying on a table
00128    * Use "extract" object and use the following functions in order setNegative, filter
00129    */
00130 
00131 
00132   /*****************************************************
00133    * TODO 8:  Write the cluster to disk
00134    */
00135 
00136   return (0);
00137 }
00138 /* ]--- */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


as11
Author(s): lucian goron
autogenerated on Sun Oct 6 2013 12:08:02