sac_segmentation_plane.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) 2012-, Open Perception, 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 the copyright holder(s) 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 <pcl/PCLPointCloud2.h>
00039 #include <pcl/io/pcd_io.h>
00040 #include <pcl/sample_consensus/ransac.h>
00041 #include <pcl/sample_consensus/sac_model_plane.h>
00042 #include <pcl/segmentation/extract_clusters.h>
00043 #include <pcl/console/print.h>
00044 #include <pcl/console/parse.h>
00045 #include <pcl/console/time.h>
00046 
00047 using namespace std;
00048 using namespace pcl;
00049 using namespace pcl::io;
00050 using namespace pcl::console;
00051 
00052 int    default_max_iterations = 1000;
00053 double default_threshold = 0.05;
00054 bool   default_negative = false;
00055 
00056 Eigen::Vector4f    translation;
00057 Eigen::Quaternionf orientation;
00058 
00059 void
00060 printHelp (int, char **argv)
00061 {
00062   print_error ("Syntax is: %s input.pcd output.pcd <options> [optional_arguments]\n", argv[0]);
00063   print_info ("  where options are:\n");
00064   print_info ("                     -thresh X = set the inlier threshold from the plane to (default: "); 
00065   print_value ("%g", default_threshold); print_info (")\n");
00066   print_info ("                     -max_it X = set the maximum number of RANSAC iterations to X (default: "); 
00067   print_value ("%d", default_max_iterations); print_info (")\n");
00068   print_info ("                     -neg 0/1  = if true (1), instead of the plane, it returns the largest cluster on top of the plane (default: "); 
00069   print_value ("%s", default_negative ? "true" : "false"); print_info (")\n");
00070   print_info ("\nOptional arguments are:\n");
00071   print_info ("                     -input_dir X  = batch process all PCD files found in input_dir\n");
00072   print_info ("                     -output_dir X = save the processed files from input_dir in this directory\n");
00073 }
00074 
00075 bool
00076 loadCloud (const string &filename, pcl::PCLPointCloud2 &cloud)
00077 {
00078   TicToc tt;
00079   print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00080 
00081   tt.tic ();
00082   if (loadPCDFile (filename, cloud, translation, orientation) < 0)
00083     return (false);
00084   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00085   print_info ("Available dimensions: "); print_value ("%s\n", getFieldsList (cloud).c_str ());
00086 
00087   return (true);
00088 }
00089 
00090 void
00091 compute (const pcl::PCLPointCloud2::ConstPtr &input, pcl::PCLPointCloud2 &output,
00092          int max_iterations = 1000, double threshold = 0.05, bool negative = false)
00093 {
00094   // Convert data to PointCloud<T>
00095   PointCloud<PointXYZ>::Ptr xyz (new PointCloud<PointXYZ>);
00096   fromPCLPointCloud2 (*input, *xyz);
00097 
00098   // Estimate
00099   TicToc tt;
00100   print_highlight (stderr, "Computing ");
00101   
00102   tt.tic ();
00103 
00104   // Refine the plane indices
00105   typedef SampleConsensusModelPlane<PointXYZ>::Ptr SampleConsensusModelPlanePtr;
00106   SampleConsensusModelPlanePtr model (new SampleConsensusModelPlane<PointXYZ> (xyz));
00107   RandomSampleConsensus<PointXYZ> sac (model, threshold);
00108   sac.setMaxIterations (max_iterations);
00109   bool res = sac.computeModel ();
00110   
00111   vector<int> inliers;
00112   sac.getInliers (inliers);
00113   Eigen::VectorXf coefficients;
00114   sac.getModelCoefficients (coefficients);
00115 
00116   if (!res || inliers.empty ())
00117   {
00118     PCL_ERROR ("No planar model found. Relax thresholds and continue.\n");
00119     return;
00120   }
00121   sac.refineModel (2, 50);
00122   sac.getInliers (inliers);
00123   sac.getModelCoefficients (coefficients);
00124 
00125   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms, plane has : "); print_value ("%zu", inliers.size ()); print_info (" points]\n");
00126 
00127   print_info ("Model coefficients: [");
00128   print_value ("%g %g %g %g", coefficients[0], coefficients[1], coefficients[2], coefficients[3]); print_info ("]\n");
00129 
00130   // Instead of returning the planar model as a set of inliers, return the outliers, but perform a cluster segmentation first
00131   if (negative)
00132   {
00133     // Remove the plane indices from the data
00134     PointIndices::Ptr everything_but_the_plane (new PointIndices);
00135     std::vector<int> indices_fullset (xyz->size ());
00136     for (int p_it = 0; p_it < static_cast<int> (indices_fullset.size ()); ++p_it)
00137       indices_fullset[p_it] = p_it;
00138     
00139     std::sort (inliers.begin (), inliers.end ());
00140     set_difference (indices_fullset.begin (), indices_fullset.end (),
00141                     inliers.begin (), inliers.end (),
00142                     inserter (everything_but_the_plane->indices, everything_but_the_plane->indices.begin ()));
00143 
00144     // Extract largest cluster minus the plane
00145     vector<PointIndices> cluster_indices;
00146     EuclideanClusterExtraction<PointXYZ> ec;
00147     ec.setClusterTolerance (0.02); // 2cm
00148     ec.setMinClusterSize (100);
00149     ec.setInputCloud (xyz);
00150     ec.setIndices (everything_but_the_plane);
00151     ec.extract (cluster_indices);
00152 
00153     // Convert data back
00154     copyPointCloud (*input, cluster_indices[0].indices, output);
00155   }
00156   else
00157   {
00158     // Convert data back
00159     PointCloud<PointXYZ> output_inliers;
00160     copyPointCloud (*input, inliers, output);
00161   }
00162 }
00163 
00164 void
00165 saveCloud (const string &filename, const pcl::PCLPointCloud2 &output)
00166 {
00167   TicToc tt;
00168   tt.tic ();
00169 
00170   print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00171 
00172   PCDWriter w;
00173   w.writeBinaryCompressed (filename, output, translation, orientation);
00174   
00175   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms : "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00176 }
00177 
00178 int
00179 batchProcess (const vector<string> &pcd_files, string &output_dir, int max_it, double thresh, bool negative)
00180 {
00181   vector<string> st;
00182   for (size_t i = 0; i < pcd_files.size (); ++i)
00183   {
00184     // Load the first file
00185     pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
00186     if (!loadCloud (pcd_files[i], *cloud)) 
00187       return (-1);
00188 
00189     // Perform the feature estimation
00190     pcl::PCLPointCloud2 output;
00191     compute (cloud, output, max_it, thresh, negative);
00192 
00193     // Prepare output file name
00194     string filename = pcd_files[i];
00195     boost::trim (filename);
00196     boost::split (st, filename, boost::is_any_of ("/\\"), boost::token_compress_on);
00197     
00198     // Save into the second file
00199     stringstream ss;
00200     ss << output_dir << "/" << st.at (st.size () - 1);
00201     saveCloud (ss.str (), output);
00202   }
00203   return (0);
00204 }
00205 
00206 /* ---[ */
00207 int
00208 main (int argc, char** argv)
00209 {
00210   print_info ("Estimate the largest planar component using SACSegmentation. For more information, use: %s -h\n", argv[0]);
00211 
00212   if (argc < 3)
00213   {
00214     printHelp (argc, argv);
00215     return (-1);
00216   }
00217 
00218   bool debug = false;
00219   console::parse_argument (argc, argv, "-debug", debug);
00220   if (debug)
00221   {
00222     print_highlight ("Enabling debug mode.\n");
00223     console::setVerbosityLevel (console::L_DEBUG);
00224     if (!isVerbosityLevelEnabled (L_DEBUG))
00225       PCL_ERROR ("Error enabling debug mode.\n");
00226   }
00227 
00228   bool batch_mode = false;
00229 
00230   // Command line parsing
00231   int max_it = default_max_iterations;
00232   double thresh = default_threshold;
00233   bool negative = default_negative;
00234   parse_argument (argc, argv, "-max_it", max_it);
00235   parse_argument (argc, argv, "-thresh", thresh);
00236   parse_argument (argc, argv, "-neg", negative);
00237   string input_dir, output_dir;
00238   if (parse_argument (argc, argv, "-input_dir", input_dir) != -1)
00239   {
00240     PCL_INFO ("Input directory given as %s. Batch process mode on.\n", input_dir.c_str ());
00241     if (parse_argument (argc, argv, "-output_dir", output_dir) == -1)
00242     {
00243       PCL_ERROR ("Need an output directory! Please use -output_dir to continue.\n");
00244       return (-1);
00245     }
00246 
00247     // Both input dir and output dir given, switch into batch processing mode
00248     batch_mode = true;
00249   }
00250 
00251   if (!batch_mode)
00252   {
00253     // Parse the command line arguments for .pcd files
00254     vector<int> p_file_indices;
00255     p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00256     if (p_file_indices.size () != 2)
00257     {
00258       print_error ("Need one input PCD file and one output PCD file to continue.\n");
00259       return (-1);
00260     }
00261 
00262     print_info ("Estimating planes with a threshold of: "); 
00263     print_value ("%g\n", thresh); 
00264 
00265     print_info ("Planar model segmentation: ");
00266     print_value ("%s\n", negative ? "false" : "true"); 
00267 
00268     // Load the first file
00269     pcl::PCLPointCloud2::Ptr cloud (new pcl::PCLPointCloud2);
00270     if (!loadCloud (argv[p_file_indices[0]], *cloud)) 
00271       return (-1);
00272 
00273     // Perform the feature estimation
00274     pcl::PCLPointCloud2 output;
00275     compute (cloud, output, max_it, thresh, negative);
00276 
00277     // Save into the second file
00278     saveCloud (argv[p_file_indices[1]], output);
00279   }
00280   else
00281   {
00282     if (input_dir != "" && boost::filesystem::exists (input_dir))
00283     {
00284       vector<string> pcd_files;
00285       boost::filesystem::directory_iterator end_itr;
00286       for (boost::filesystem::directory_iterator itr (input_dir); itr != end_itr; ++itr)
00287       {
00288         // Only add PCD files
00289         if (!is_directory (itr->status ()) && boost::algorithm::to_upper_copy (boost::filesystem::extension (itr->path ())) == ".PCD" )
00290         {
00291           pcd_files.push_back (itr->path ().string ());
00292           PCL_INFO ("[Batch processing mode] Added %s for processing.\n", itr->path ().string ().c_str ());
00293         }
00294       }
00295       batchProcess (pcd_files, output_dir, max_it, thresh, negative);
00296     }
00297     else
00298     {
00299       PCL_ERROR ("Batch processing mode enabled, but invalid input directory (%s) given!\n", input_dir.c_str ());
00300       return (-1);
00301     }
00302   }
00303 }
00304 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:32:37