cluster_extraction.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2011, Willow Garage, Inc.
00006  *  
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  */
00037 
00038 #include <sensor_msgs/PointCloud2.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/io/pcd_io.h>
00041 #include <pcl/segmentation/extract_clusters.h>
00042 #include <pcl/filters/extract_indices.h>
00043 #include <pcl/console/print.h>
00044 #include <pcl/console/parse.h>
00045 #include <pcl/console/time.h>
00046 #include <vector>
00047 #include <boost/lexical_cast.hpp>
00048 #include <boost/make_shared.hpp>
00049 
00050 using namespace pcl;
00051 using namespace pcl::io;
00052 using namespace pcl::console;
00053 
00054 int    default_min = 100;
00055 int    default_max = 25000;
00056 double default_tolerance = 0.02;
00057 
00058 Eigen::Vector4f    translation;
00059 Eigen::Quaternionf orientation;
00060 
00061 void
00062 printHelp (int, char **argv)
00063 {
00064   print_error ("Syntax is: %s input.pcd output.pcd <options>\n", argv[0]);
00065   print_info ("  where options are:\n");
00066   print_info ("                     -min X = use a minimum of X points peer cluster (default: "); 
00067   print_value ("%d", default_min); print_info (")\n");
00068   print_info ("                     -max X      = use a maximum of X points peer cluster (default: "); 
00069   print_value ("%d", default_max); print_info (")\n");
00070   print_info ("                     -tolerance X = the spacial distance between clusters (default: "); 
00071   print_value ("%lf", default_tolerance); print_info (")\n");
00072 }
00073 
00074 bool
00075 loadCloud (const std::string &filename, sensor_msgs::PointCloud2 &cloud)
00076 {
00077   TicToc tt;
00078   print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00079 
00080   tt.tic ();
00081   if (loadPCDFile (filename, cloud, translation, orientation) < 0)
00082     return (false);
00083   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00084   print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00085 
00086   return (true);
00087 }
00088 
00089 void
00090 compute (const sensor_msgs::PointCloud2::ConstPtr &input, std::vector<sensor_msgs::PointCloud2::Ptr> &output,
00091          int min, int max, double tolerance)
00092 {
00093   // Convert data to PointCloud<T>
00094   PointCloud<pcl::PointXYZ>::Ptr xyz (new PointCloud<pcl::PointXYZ>);
00095   fromROSMsg (*input, *xyz);
00096 
00097   // Estimate
00098   TicToc tt;
00099   tt.tic ();
00100   
00101   print_highlight (stderr, "Computing ");
00102 
00103   // Creating the KdTree object for the search method of the extraction
00104   pcl::search::KdTree<pcl::PointXYZ>::Ptr tree (new pcl::search::KdTree<pcl::PointXYZ>);
00105   tree->setInputCloud (xyz);
00106 
00107   std::vector<pcl::PointIndices> cluster_indices;
00108   pcl::EuclideanClusterExtraction<pcl::PointXYZ> ec;
00109   ec.setClusterTolerance (tolerance);
00110   ec.setMinClusterSize (min);
00111   ec.setMaxClusterSize (max);
00112   ec.setSearchMethod (tree);
00113   ec.setInputCloud (xyz);
00114   ec.extract (cluster_indices);
00115 
00116   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cluster_indices.size ()); print_info (" clusters]\n");
00117 
00118   output.reserve (cluster_indices.size ());
00119   for (std::vector<pcl::PointIndices>::const_iterator it = cluster_indices.begin (); it != cluster_indices.end (); ++it)
00120   {
00121     pcl::ExtractIndices<sensor_msgs::PointCloud2> extract;
00122     extract.setInputCloud (input);
00123     extract.setIndices (boost::make_shared<const pcl::PointIndices> (*it));
00124     sensor_msgs::PointCloud2::Ptr out (new sensor_msgs::PointCloud2);
00125     extract.filter (*out);
00126     output.push_back (out);
00127   }
00128 }
00129 
00130 void
00131 saveCloud (const std::string &filename, const std::vector<sensor_msgs::PointCloud2::Ptr> &output)
00132 {
00133   TicToc tt;
00134   tt.tic ();
00135 
00136   std::string basename = filename.substr (0, filename.length () - 4);
00137 
00138   for (size_t i = 0; i < output.size (); i++)
00139   {
00140     std::string clustername = basename + boost::lexical_cast<std::string>(i) + ".pcd";
00141     print_highlight ("Saving "); print_value ("%s ", clustername.c_str ());
00142 
00143     pcl::io::savePCDFile (clustername, *(output[i]), translation, orientation, false);
00144 
00145     print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output[i]->width * output[i]->height); print_info (" points]\n");
00146   }
00147   
00148 }
00149 
00150 /* ---[ */
00151 int
00152 main (int argc, char** argv)
00153 {
00154   print_info ("Extract point clusters using pcl::EuclideanClusterExtraction. For more information, use: %s -h\n", argv[0]);
00155   bool help = false;
00156   parse_argument (argc, argv, "-h", help);
00157   if (argc < 3 || help)
00158   {
00159     printHelp (argc, argv);
00160     return (-1);
00161   }
00162 
00163   // Parse the command line arguments for .pcd files
00164   std::vector<int> p_file_indices;
00165   p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00166   if (p_file_indices.size () != 2)
00167   {
00168     print_error ("Need one input PCD file and one output PCD file to continue.\n");
00169     return (-1);
00170   }
00171 
00172   // Command line parsing
00173   int min = default_min;
00174   int max = default_max;
00175   double tolerance = default_tolerance;
00176   parse_argument (argc, argv, "-min", min);
00177   parse_argument (argc, argv, "-max", max);
00178   parse_argument (argc, argv, "-tolerance", tolerance);
00179 
00180   // Load the first file
00181   sensor_msgs::PointCloud2::Ptr cloud (new sensor_msgs::PointCloud2);
00182   if (!loadCloud (argv[p_file_indices[0]], *cloud)) 
00183     return (-1);
00184 
00185   // Perform the feature estimation
00186   std::vector<sensor_msgs::PointCloud2::Ptr> output;
00187   compute (cloud, output, min, max, tolerance);
00188 
00189   // Save into the second file
00190   saveCloud (argv[p_file_indices[1]], output);
00191 }


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:41