dominant_plane_segmentation.hpp
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  */
00035 
00036 #pragma once
00037 #include <boost/thread/thread.hpp>
00038 #include <boost/date_time/posix_time/posix_time.hpp>
00039 
00040 #include <pcl/apps/dominant_plane_segmentation.h>
00041 #include <pcl/visualization/pcl_visualizer.h>
00042 #include <pcl/features/integral_image_normal.h>
00043 #include <pcl/common/time.h>
00044 
00045 template<typename PointType> void
00046 pcl::apps::DominantPlaneSegmentation<PointType>::compute_table_plane ()
00047 {
00048   // Has the input dataset been set already?
00049   if (!input_)
00050   {
00051     PCL_WARN ("[pcl::apps::DominantPlaneSegmentation] No input dataset given!\n");
00052     return;
00053   }
00054 
00055   CloudConstPtr cloud_;
00056   CloudPtr cloud_filtered_ (new Cloud ());
00057   CloudPtr cloud_downsampled_ (new Cloud ());
00058   pcl::PointCloud<pcl::Normal>::Ptr cloud_normals_ (new pcl::PointCloud<pcl::Normal> ());
00059   pcl::PointIndices::Ptr table_inliers_ (new pcl::PointIndices ());
00060   pcl::ModelCoefficients::Ptr table_coefficients_ (new pcl::ModelCoefficients ());
00061   CloudPtr table_projected_ (new Cloud ());
00062   CloudPtr table_hull_ (new Cloud ());
00063 
00064   typename pcl::search::KdTree<PointType>::Ptr normals_tree_ (new pcl::search::KdTree<PointType>);
00065 
00066   // Normal estimation parameters
00067   n3d_.setKSearch (k_);
00068   n3d_.setSearchMethod (normals_tree_);
00069 
00070   // Table model fitting parameters
00071   seg_.setDistanceThreshold (sac_distance_threshold_);
00072   seg_.setMaxIterations (2000);
00073   seg_.setNormalDistanceWeight (0.1);
00074   seg_.setOptimizeCoefficients (true);
00075   seg_.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00076   seg_.setMethodType (pcl::SAC_RANSAC);
00077   seg_.setProbability (0.99);
00078 
00079   proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00080   bb_cluster_proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00081 
00082   // ---[ PassThroughFilter
00083   pass_.setFilterLimits (float (min_z_bounds_), float (max_z_bounds_));
00084   pass_.setFilterFieldName ("z");
00085   pass_.setInputCloud (input_);
00086   pass_.filter (*cloud_filtered_);
00087 
00088   if (int (cloud_filtered_->points.size ()) < k_)
00089   {
00090     PCL_WARN ("[DominantPlaneSegmentation] Filtering returned %zu points! Aborting.",
00091         cloud_filtered_->points.size ());
00092     return;
00093   }
00094 
00095   // Downsample the point cloud
00096   grid_.setLeafSize (downsample_leaf_, downsample_leaf_, downsample_leaf_);
00097   grid_.setDownsampleAllData (false);
00098   grid_.setInputCloud (cloud_filtered_);
00099   grid_.filter (*cloud_downsampled_);
00100 
00101   // ---[ Estimate the point normals
00102   n3d_.setInputCloud (cloud_downsampled_);
00103   n3d_.compute (*cloud_normals_);
00104 
00105   // ---[ Perform segmentation
00106   seg_.setInputCloud (cloud_downsampled_);
00107   seg_.setInputNormals (cloud_normals_);
00108   seg_.segment (*table_inliers_, *table_coefficients_);
00109 
00110   if (table_inliers_->indices.size () == 0)
00111   {
00112     PCL_WARN ("[DominantPlaneSegmentation] No Plane Inliers points! Aborting.");
00113     return;
00114   }
00115 
00116   // ---[ Extract the plane
00117   proj_.setInputCloud (cloud_downsampled_);
00118   proj_.setIndices (table_inliers_);
00119   proj_.setModelCoefficients (table_coefficients_);
00120   proj_.filter (*table_projected_);
00121 
00122   // ---[ Estimate the convex hull
00123   std::vector<pcl::Vertices> polygons;
00124   CloudPtr table_hull (new Cloud ());
00125   hull_.setInputCloud (table_projected_);
00126   hull_.reconstruct (*table_hull, polygons);
00127 
00128   // Compute the plane coefficients
00129   Eigen::Vector4f model_coefficients;
00130   EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00131 
00132   model_coefficients[0] = table_coefficients_->values[0];
00133   model_coefficients[1] = table_coefficients_->values[1];
00134   model_coefficients[2] = table_coefficients_->values[2];
00135   model_coefficients[3] = table_coefficients_->values[3];
00136 
00137   // Need to flip the plane normal towards the viewpoint
00138   Eigen::Vector4f vp (0, 0, 0, 0);
00139   // See if we need to flip any plane normals
00140   vp -= table_hull->points[0].getVector4fMap ();
00141   vp[3] = 0;
00142   // Dot product between the (viewpoint - point) and the plane normal
00143   float cos_theta = vp.dot (model_coefficients);
00144   // Flip the plane normal
00145   if (cos_theta < 0)
00146   {
00147     model_coefficients *= -1;
00148     model_coefficients[3] = 0;
00149     // Hessian form (D = nc . p_plane (centroid here) + p)
00150     model_coefficients[3] = -1 * (model_coefficients.dot (table_hull->points[0].getVector4fMap ()));
00151   }
00152 
00153   //Set table_coeffs
00154   table_coeffs_ = model_coefficients;
00155 }
00156 
00157 template<typename PointType> void
00158 pcl::apps::DominantPlaneSegmentation<PointType>::compute_fast (std::vector<CloudPtr> & clusters)
00159 {
00160   // Has the input dataset been set already?
00161   if (!input_)
00162   {
00163     PCL_WARN ("[pcl::apps::DominantPlaneSegmentation] No input dataset given!\n");
00164     return;
00165   }
00166 
00167   // Is the input dataset organized?
00168   if (input_->is_dense)
00169   {
00170     PCL_WARN ("[pcl::apps::DominantPlaneSegmentation] compute_fast can only be used with organized point clouds!\n");
00171     return;
00172   }
00173 
00174   CloudConstPtr cloud_;
00175   CloudPtr cloud_filtered_ (new Cloud ());
00176   CloudPtr cloud_downsampled_ (new Cloud ());
00177   pcl::PointCloud<pcl::Normal>::Ptr cloud_normals_ (new pcl::PointCloud<pcl::Normal> ());
00178   pcl::PointIndices::Ptr table_inliers_ (new pcl::PointIndices ());
00179   pcl::ModelCoefficients::Ptr table_coefficients_ (new pcl::ModelCoefficients ());
00180   CloudPtr table_projected_ (new Cloud ());
00181   CloudPtr table_hull_ (new Cloud ());
00182   CloudPtr cloud_objects_ (new Cloud ());
00183   CloudPtr cluster_object_ (new Cloud ());
00184 
00185   typename pcl::search::KdTree<PointType>::Ptr normals_tree_ (new pcl::search::KdTree<PointType>);
00186   typename pcl::search::KdTree<PointType>::Ptr clusters_tree_ (new pcl::search::KdTree<PointType>);
00187   clusters_tree_->setEpsilon (1);
00188 
00189   // Normal estimation parameters
00190   n3d_.setKSearch (k_);
00191   n3d_.setSearchMethod (normals_tree_);
00192 
00193   // Table model fitting parameters
00194   seg_.setDistanceThreshold (sac_distance_threshold_);
00195   seg_.setMaxIterations (2000);
00196   seg_.setNormalDistanceWeight (0.1);
00197   seg_.setOptimizeCoefficients (true);
00198   seg_.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00199   seg_.setMethodType (pcl::SAC_RANSAC);
00200   seg_.setProbability (0.99);
00201 
00202   proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00203   bb_cluster_proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00204 
00205   prism_.setHeightLimits (object_min_height_, object_max_height_);
00206 
00207   // Clustering parameters
00208   cluster_.setClusterTolerance (object_cluster_tolerance_);
00209   cluster_.setMinClusterSize (object_cluster_min_size_);
00210   cluster_.setSearchMethod (clusters_tree_);
00211 
00212   // ---[ PassThroughFilter
00213   pass_.setFilterLimits (float (min_z_bounds_), float (max_z_bounds_));
00214   pass_.setFilterFieldName ("z");
00215   pass_.setInputCloud (input_);
00216   pass_.filter (*cloud_filtered_);
00217 
00218   if (int (cloud_filtered_->points.size ()) < k_)
00219   {
00220     PCL_WARN ("[DominantPlaneSegmentation] Filtering returned %zu points! Aborting.",
00221         cloud_filtered_->points.size ());
00222     return;
00223   }
00224 
00225   // Downsample the point cloud
00226   grid_.setLeafSize (downsample_leaf_, downsample_leaf_, downsample_leaf_);
00227   grid_.setDownsampleAllData (false);
00228   grid_.setInputCloud (cloud_filtered_);
00229   grid_.filter (*cloud_downsampled_);
00230 
00231   // ---[ Estimate the point normals
00232   n3d_.setInputCloud (cloud_downsampled_);
00233   n3d_.compute (*cloud_normals_);
00234 
00235   // ---[ Perform segmentation
00236   seg_.setInputCloud (cloud_downsampled_);
00237   seg_.setInputNormals (cloud_normals_);
00238   seg_.segment (*table_inliers_, *table_coefficients_);
00239 
00240   if (table_inliers_->indices.size () == 0)
00241   {
00242     PCL_WARN ("[DominantPlaneSegmentation] No Plane Inliers points! Aborting.");
00243     return;
00244   }
00245 
00246   // ---[ Extract the plane
00247   proj_.setInputCloud (cloud_downsampled_);
00248   proj_.setIndices (table_inliers_);
00249   proj_.setModelCoefficients (table_coefficients_);
00250   proj_.filter (*table_projected_);
00251 
00252   // ---[ Estimate the convex hull
00253   std::vector<pcl::Vertices> polygons;
00254   CloudPtr table_hull (new Cloud ());
00255   hull_.setInputCloud (table_projected_);
00256   hull_.reconstruct (*table_hull, polygons);
00257 
00258   // Compute the plane coefficients
00259   Eigen::Vector4f model_coefficients;
00260   EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00261 
00262   model_coefficients[0] = table_coefficients_->values[0];
00263   model_coefficients[1] = table_coefficients_->values[1];
00264   model_coefficients[2] = table_coefficients_->values[2];
00265   model_coefficients[3] = table_coefficients_->values[3];
00266 
00267   // Need to flip the plane normal towards the viewpoint
00268   Eigen::Vector4f vp (0, 0, 0, 0);
00269   // See if we need to flip any plane normals
00270   vp -= table_hull->points[0].getVector4fMap ();
00271   vp[3] = 0;
00272   // Dot product between the (viewpoint - point) and the plane normal
00273   float cos_theta = vp.dot (model_coefficients);
00274   // Flip the plane normal
00275   if (cos_theta < 0)
00276   {
00277     model_coefficients *= -1;
00278     model_coefficients[3] = 0;
00279     // Hessian form (D = nc . p_plane (centroid here) + p)
00280     model_coefficients[3] = -1 * (model_coefficients.dot (table_hull->points[0].getVector4fMap ()));
00281   }
00282 
00283   //Set table_coeffs
00284   table_coeffs_ = model_coefficients;
00285 
00286   // ---[ Get the objects on top of the table
00287   pcl::PointIndices cloud_object_indices;
00288   prism_.setInputCloud (input_);
00289   prism_.setInputPlanarHull (table_hull);
00290   prism_.segment (cloud_object_indices);
00291 
00292   pcl::ExtractIndices<PointType> extract_object_indices;
00293   extract_object_indices.setInputCloud (input_);
00294   extract_object_indices.setIndices (boost::make_shared<const pcl::PointIndices> (cloud_object_indices));
00295   extract_object_indices.filter (*cloud_objects_);
00296 
00297   //create new binary pointcloud with intensity values (0 and 1), 0 for non-object pixels and 1 otherwise
00298   pcl::PointCloud<pcl::PointXYZI>::Ptr binary_cloud (new pcl::PointCloud<pcl::PointXYZI>);
00299 
00300   {
00301     binary_cloud->width = input_->width;
00302     binary_cloud->height = input_->height;
00303     binary_cloud->points.resize (input_->points.size ());
00304     binary_cloud->is_dense = input_->is_dense;
00305 
00306     size_t idx;
00307     for (size_t i = 0; i < cloud_object_indices.indices.size (); ++i)
00308     {
00309       idx = cloud_object_indices.indices[i];
00310       binary_cloud->points[idx].getVector4fMap () = input_->points[idx].getVector4fMap ();
00311       binary_cloud->points[idx].intensity = 1.0;
00312     }
00313   }
00314 
00315   //connected components on the binary image
00316 
00317   std::map<float, float> connected_labels;
00318   float c_intensity = 0.1f;
00319   float intensity_incr = 0.1f;
00320 
00321   {
00322 
00323     int wsize = wsize_;
00324     for (int i = 0; i < int (binary_cloud->width); i++)
00325     {
00326       for (int j = 0; j < int (binary_cloud->height); j++)
00327       {
00328         if (binary_cloud->at (i, j).intensity != 0)
00329         {
00330           //check neighboring pixels, first left and then top
00331           //be aware of margins
00332 
00333           if ((i - 1) < 0 && (j - 1) < 0)
00334           {
00335             //top-left pixel
00336             (*binary_cloud) (i, j).intensity = c_intensity;
00337           }
00338           else
00339           {
00340             if ((j - 1) < 0)
00341             {
00342               //top-row, check on the left of pixel to assign a new label or not
00343               int left = check ((*binary_cloud) (i - 1, j), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_);
00344               if (left)
00345               {
00346                 //Nothing found on the left, check bigger window
00347 
00348                 bool found = false;
00349                 for (int kk = 2; kk < wsize && !found; kk++)
00350                 {
00351                   if ((i - kk) < 0)
00352                     continue;
00353 
00354                   int left = check ((*binary_cloud) (i - kk, j), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_);
00355                   if (left == 0)
00356                   {
00357                     found = true;
00358                   }
00359                 }
00360 
00361                 if (!found)
00362                 {
00363                   c_intensity += intensity_incr;
00364                   (*binary_cloud) (i, j).intensity = c_intensity;
00365                 }
00366 
00367               }
00368             }
00369             else
00370             {
00371               if ((i - 1) == 0)
00372               {
00373                 //check only top
00374                 int top = check ((*binary_cloud) (i, j - 1), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_);
00375                 if (top)
00376                 {
00377                   bool found = false;
00378                   for (int kk = 2; kk < wsize && !found; kk++)
00379                   {
00380                     if ((j - kk) < 0)
00381                       continue;
00382 
00383                     int top = check ((*binary_cloud) (i, j - kk), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_);
00384                     if (top == 0)
00385                     {
00386                       found = true;
00387                     }
00388                   }
00389 
00390                   if (!found)
00391                   {
00392                     c_intensity += intensity_incr;
00393                     (*binary_cloud) (i, j).intensity = c_intensity;
00394                   }
00395                 }
00396 
00397               }
00398               else
00399               {
00400                 //check left and top
00401                 int left = check ((*binary_cloud) (i - 1, j), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_);
00402                 int top = check ((*binary_cloud) (i, j - 1), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_);
00403 
00404                 if (left == 0 && top == 0)
00405                 {
00406                   //both top and left had labels, check if they are different
00407                   //if they are, take the smallest one and mark labels to be connected..
00408 
00409                   if ((*binary_cloud) (i - 1, j).intensity != (*binary_cloud) (i, j - 1).intensity)
00410                   {
00411                     float smaller_intensity = (*binary_cloud) (i - 1, j).intensity;
00412                     float bigger_intensity = (*binary_cloud) (i, j - 1).intensity;
00413 
00414                     if ((*binary_cloud) (i - 1, j).intensity > (*binary_cloud) (i, j - 1).intensity)
00415                     {
00416                       smaller_intensity = (*binary_cloud) (i, j - 1).intensity;
00417                       bigger_intensity = (*binary_cloud) (i - 1, j).intensity;
00418                     }
00419 
00420                     connected_labels[bigger_intensity] = smaller_intensity;
00421                     (*binary_cloud) (i, j).intensity = smaller_intensity;
00422                   }
00423                 }
00424 
00425                 if (left == 1 && top == 1)
00426                 {
00427                   //if none had labels, increment c_intensity
00428                   //search first on bigger window
00429                   bool found = false;
00430                   for (int dist = 2; dist < wsize && !found; dist++)
00431                   {
00432                     if (((i - dist) < 0) || ((j - dist) < 0))
00433                       continue;
00434 
00435                     int left = check ((*binary_cloud) (i - dist, j), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_);
00436                     int top = check ((*binary_cloud) (i, j - dist), (*binary_cloud) (i, j), c_intensity, object_cluster_tolerance_);
00437 
00438                     if (left == 0 && top == 0)
00439                     {
00440                       if ((*binary_cloud) (i - dist, j).intensity != (*binary_cloud) (i, j - dist).intensity)
00441                       {
00442                         float smaller_intensity = (*binary_cloud) (i - dist, j).intensity;
00443                         float bigger_intensity = (*binary_cloud) (i, j - dist).intensity;
00444 
00445                         if ((*binary_cloud) (i - dist, j).intensity > (*binary_cloud) (i, j - dist).intensity)
00446                         {
00447                           smaller_intensity = (*binary_cloud) (i, j - dist).intensity;
00448                           bigger_intensity = (*binary_cloud) (i - dist, j).intensity;
00449                         }
00450 
00451                         connected_labels[bigger_intensity] = smaller_intensity;
00452                         (*binary_cloud) (i, j).intensity = smaller_intensity;
00453                         found = true;
00454                       }
00455                     }
00456                     else if (left == 0 || top == 0)
00457                     {
00458                       //one had label
00459                       found = true;
00460                     }
00461                   }
00462 
00463                   if (!found)
00464                   {
00465                     //none had label in the bigger window
00466                     c_intensity += intensity_incr;
00467                     (*binary_cloud) (i, j).intensity = c_intensity;
00468                   }
00469                 }
00470               }
00471             }
00472           }
00473 
00474         }
00475       }
00476     }
00477   }
00478 
00479   std::map<float, pcl::PointIndices> clusters_map;
00480 
00481   {
00482     std::map<float, float>::iterator it;
00483 
00484     for (int i = 0; i < int (binary_cloud->width); i++)
00485     {
00486       for (int j = 0; j < int (binary_cloud->height); j++)
00487       {
00488         if (binary_cloud->at (i, j).intensity != 0)
00489         {
00490           //check if this is a root label...
00491           it = connected_labels.find (binary_cloud->at (i, j).intensity);
00492           while (it != connected_labels.end ())
00493           {
00494             //the label is on the list, change pixel intensity until it has a root label
00495             (*binary_cloud) (i, j).intensity = (*it).second;
00496             it = connected_labels.find (binary_cloud->at (i, j).intensity);
00497           }
00498 
00499           std::map<float, pcl::PointIndices>::iterator it_indices;
00500           it_indices = clusters_map.find (binary_cloud->at (i, j).intensity);
00501           if (it_indices == clusters_map.end ())
00502           {
00503             pcl::PointIndices indices;
00504             clusters_map[binary_cloud->at (i, j).intensity] = indices;
00505           }
00506 
00507           clusters_map[binary_cloud->at (i, j).intensity].indices.push_back (static_cast<int> (j * binary_cloud->width + i));
00508         }
00509       }
00510     }
00511   }
00512 
00513   clusters.resize (clusters_map.size ());
00514 
00515   std::map<float, pcl::PointIndices>::iterator it_indices;
00516   int k = 0;
00517   for (it_indices = clusters_map.begin (); it_indices != clusters_map.end (); it_indices++)
00518   {
00519 
00520     if (int ((*it_indices).second.indices.size ()) >= object_cluster_min_size_)
00521     {
00522 
00523       clusters[k] = CloudPtr (new Cloud ());
00524       pcl::copyPointCloud (*input_, (*it_indices).second.indices, *clusters[k]);
00525       k++;
00526       indices_clusters_.push_back((*it_indices).second);
00527     }
00528   }
00529 
00530   clusters.resize (k);
00531 
00532 }
00533 
00534 template<typename PointType> void
00535 pcl::apps::DominantPlaneSegmentation<PointType>::compute (std::vector<CloudPtr> & clusters)
00536 {
00537 
00538   // Has the input dataset been set already?
00539   if (!input_)
00540   {
00541     PCL_WARN ("[pcl::apps::DominantPlaneSegmentation] No input dataset given!\n");
00542     return;
00543   }
00544 
00545   CloudConstPtr cloud_;
00546   CloudPtr cloud_filtered_ (new Cloud ());
00547   CloudPtr cloud_downsampled_ (new Cloud ());
00548   pcl::PointCloud<pcl::Normal>::Ptr cloud_normals_ (new pcl::PointCloud<pcl::Normal> ());
00549   pcl::PointIndices::Ptr table_inliers_ (new pcl::PointIndices ());
00550   pcl::ModelCoefficients::Ptr table_coefficients_ (new pcl::ModelCoefficients ());
00551   CloudPtr table_projected_ (new Cloud ());
00552   CloudPtr table_hull_ (new Cloud ());
00553   CloudPtr cloud_objects_ (new Cloud ());
00554   CloudPtr cluster_object_ (new Cloud ());
00555 
00556   typename pcl::search::KdTree<PointType>::Ptr normals_tree_ (new pcl::search::KdTree<PointType>);
00557   typename pcl::search::KdTree<PointType>::Ptr clusters_tree_ (new pcl::search::KdTree<PointType>);
00558   clusters_tree_->setEpsilon (1);
00559 
00560   // Normal estimation parameters
00561   n3d_.setKSearch (k_);
00562   n3d_.setSearchMethod (normals_tree_);
00563 
00564   // Table model fitting parameters
00565   seg_.setDistanceThreshold (sac_distance_threshold_);
00566   seg_.setMaxIterations (2000);
00567   seg_.setNormalDistanceWeight (0.1);
00568   seg_.setOptimizeCoefficients (true);
00569   seg_.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00570   seg_.setMethodType (pcl::SAC_RANSAC);
00571   seg_.setProbability (0.99);
00572 
00573   proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00574   bb_cluster_proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00575 
00576   prism_.setHeightLimits (object_min_height_, object_max_height_);
00577 
00578   // Clustering parameters
00579   cluster_.setClusterTolerance (object_cluster_tolerance_);
00580   cluster_.setMinClusterSize (object_cluster_min_size_);
00581   cluster_.setSearchMethod (clusters_tree_);
00582 
00583   // ---[ PassThroughFilter
00584   pass_.setFilterLimits (float (min_z_bounds_), float (max_z_bounds_));
00585   pass_.setFilterFieldName ("z");
00586   pass_.setInputCloud (input_);
00587   pass_.filter (*cloud_filtered_);
00588 
00589   if (int (cloud_filtered_->points.size ()) < k_)
00590   {
00591     PCL_WARN ("[DominantPlaneSegmentation] Filtering returned %zu points! Aborting.",
00592         cloud_filtered_->points.size ());
00593     return;
00594   }
00595 
00596   // Downsample the point cloud
00597   grid_.setLeafSize (downsample_leaf_, downsample_leaf_, downsample_leaf_);
00598   grid_.setDownsampleAllData (false);
00599   grid_.setInputCloud (cloud_filtered_);
00600   grid_.filter (*cloud_downsampled_);
00601 
00602   PCL_INFO ("[DominantPlaneSegmentation] Number of points left after filtering (%f -> %f): %zu out of %zu\n",
00603       min_z_bounds_, max_z_bounds_, cloud_downsampled_->points.size (), input_->points.size ());
00604 
00605   // ---[ Estimate the point normals
00606   n3d_.setInputCloud (cloud_downsampled_);
00607   n3d_.compute (*cloud_normals_);
00608 
00609   PCL_INFO ("[DominantPlaneSegmentation] %zu normals estimated. \n", cloud_normals_->points.size ());
00610 
00611   // ---[ Perform segmentation
00612   seg_.setInputCloud (cloud_downsampled_);
00613   seg_.setInputNormals (cloud_normals_);
00614   seg_.segment (*table_inliers_, *table_coefficients_);
00615 
00616   if (table_inliers_->indices.size () == 0)
00617   {
00618     PCL_WARN ("[DominantPlaneSegmentation] No Plane Inliers points! Aborting.");
00619     return;
00620   }
00621 
00622   // ---[ Extract the plane
00623   proj_.setInputCloud (cloud_downsampled_);
00624   proj_.setIndices (table_inliers_);
00625   proj_.setModelCoefficients (table_coefficients_);
00626   proj_.filter (*table_projected_);
00627 
00628   // ---[ Estimate the convex hull
00629   std::vector<pcl::Vertices> polygons;
00630   CloudPtr table_hull (new Cloud ());
00631   hull_.setInputCloud (table_projected_);
00632   hull_.reconstruct (*table_hull, polygons);
00633 
00634   // Compute the plane coefficients
00635   Eigen::Vector4f model_coefficients;
00636   EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00637 
00638   model_coefficients[0] = table_coefficients_->values[0];
00639   model_coefficients[1] = table_coefficients_->values[1];
00640   model_coefficients[2] = table_coefficients_->values[2];
00641   model_coefficients[3] = table_coefficients_->values[3];
00642 
00643   // Need to flip the plane normal towards the viewpoint
00644   Eigen::Vector4f vp (0, 0, 0, 0);
00645   // See if we need to flip any plane normals
00646   vp -= table_hull->points[0].getVector4fMap ();
00647   vp[3] = 0;
00648   // Dot product between the (viewpoint - point) and the plane normal
00649   float cos_theta = vp.dot (model_coefficients);
00650   // Flip the plane normal
00651   if (cos_theta < 0)
00652   {
00653     model_coefficients *= -1;
00654     model_coefficients[3] = 0;
00655     // Hessian form (D = nc . p_plane (centroid here) + p)
00656     model_coefficients[3] = -1 * (model_coefficients.dot (table_hull->points[0].getVector4fMap ()));
00657   }
00658 
00659   //Set table_coeffs
00660   table_coeffs_ = model_coefficients;
00661 
00662   // ---[ Get the objects on top of the table
00663   pcl::PointIndices cloud_object_indices;
00664   prism_.setInputCloud (cloud_downsampled_);
00665   prism_.setInputPlanarHull (table_hull);
00666   prism_.segment (cloud_object_indices);
00667 
00668   pcl::ExtractIndices<PointType> extract_object_indices;
00669   extract_object_indices.setInputCloud (cloud_downsampled_);
00670   extract_object_indices.setIndices (boost::make_shared<const pcl::PointIndices> (cloud_object_indices));
00671   extract_object_indices.filter (*cloud_objects_);
00672 
00673   if (cloud_objects_->points.size () == 0)
00674     return;
00675 
00676   //down_.reset(new Cloud(*cloud_downsampled_));
00677 
00678   // ---[ Split the objects into Euclidean clusters
00679   std::vector<pcl::PointIndices> clusters2;
00680   cluster_.setInputCloud (cloud_downsampled_);
00681   cluster_.setIndices (boost::make_shared<const pcl::PointIndices> (cloud_object_indices));
00682   cluster_.extract (clusters2);
00683 
00684   PCL_INFO ("[DominantPlaneSegmentation::compute()] Number of clusters found matching the given constraints: %zu.\n",
00685       clusters2.size ());
00686 
00687   clusters.resize (clusters2.size ());
00688 
00689   for (size_t i = 0; i < clusters2.size (); ++i)
00690   {
00691     clusters[i] = CloudPtr (new Cloud ());
00692     pcl::copyPointCloud (*cloud_downsampled_, clusters2[i].indices, *clusters[i]);
00693   }
00694 }
00695 
00696 template<typename PointType>
00697 void
00698 pcl::apps::DominantPlaneSegmentation<PointType>::compute_full (std::vector<CloudPtr> & clusters)
00699 {
00700 
00701   // Has the input dataset been set already?
00702   if (!input_)
00703   {
00704     PCL_WARN ("[pcl::apps::DominantPlaneSegmentation] No input dataset given!\n");
00705     return;
00706   }
00707 
00708   CloudConstPtr cloud_;
00709   CloudPtr cloud_filtered_ (new Cloud ());
00710   CloudPtr cloud_downsampled_ (new Cloud ());
00711   pcl::PointCloud<pcl::Normal>::Ptr cloud_normals_ (new pcl::PointCloud<pcl::Normal> ());
00712   pcl::PointIndices::Ptr table_inliers_ (new pcl::PointIndices ());
00713   pcl::ModelCoefficients::Ptr table_coefficients_ (new pcl::ModelCoefficients ());
00714   CloudPtr table_projected_ (new Cloud ());
00715   CloudPtr table_hull_ (new Cloud ());
00716   CloudPtr cloud_objects_ (new Cloud ());
00717   CloudPtr cluster_object_ (new Cloud ());
00718 
00719   typename pcl::search::KdTree<PointType>::Ptr normals_tree_ (new pcl::search::KdTree<PointType>);
00720   typename pcl::search::KdTree<PointType>::Ptr clusters_tree_ (new pcl::search::KdTree<PointType>);
00721   clusters_tree_->setEpsilon (1);
00722 
00723   // Normal estimation parameters
00724   n3d_.setKSearch (10);
00725   n3d_.setSearchMethod (normals_tree_);
00726 
00727   // Table model fitting parameters
00728   seg_.setDistanceThreshold (sac_distance_threshold_);
00729   seg_.setMaxIterations (2000);
00730   seg_.setNormalDistanceWeight (0.1);
00731   seg_.setOptimizeCoefficients (true);
00732   seg_.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00733   seg_.setMethodType (pcl::SAC_MSAC);
00734   seg_.setProbability (0.98);
00735 
00736   proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00737   bb_cluster_proj_.setModelType (pcl::SACMODEL_NORMAL_PLANE);
00738 
00739   prism_.setHeightLimits (object_min_height_, object_max_height_);
00740 
00741   // Clustering parameters
00742   cluster_.setClusterTolerance (object_cluster_tolerance_);
00743   cluster_.setMinClusterSize (object_cluster_min_size_);
00744   cluster_.setSearchMethod (clusters_tree_);
00745 
00746   // ---[ PassThroughFilter
00747   pass_.setFilterLimits (float (min_z_bounds_), float (max_z_bounds_));
00748   pass_.setFilterFieldName ("z");
00749   pass_.setInputCloud (input_);
00750   pass_.filter (*cloud_filtered_);
00751 
00752   if (int (cloud_filtered_->points.size ()) < k_)
00753   {
00754     PCL_WARN ("[DominantPlaneSegmentation] Filtering returned %zu points! Aborting.",
00755         cloud_filtered_->points.size ());
00756     return;
00757   }
00758 
00759   // Downsample the point cloud
00760   grid_.setLeafSize (downsample_leaf_, downsample_leaf_, downsample_leaf_);
00761   grid_.setDownsampleAllData (false);
00762   grid_.setInputCloud (cloud_filtered_);
00763   grid_.filter (*cloud_downsampled_);
00764 
00765   PCL_INFO ("[DominantPlaneSegmentation] Number of points left after filtering&downsampling (%f -> %f): %zu out of %zu\n",
00766       min_z_bounds_, max_z_bounds_, cloud_downsampled_->points.size (), input_->points.size ());
00767 
00768   // ---[ Estimate the point normals
00769   n3d_.setInputCloud (cloud_downsampled_);
00770   n3d_.compute (*cloud_normals_);
00771 
00772   PCL_INFO ("[DominantPlaneSegmentation] %zu normals estimated. \n", cloud_normals_->points.size ());
00773 
00774   // ---[ Perform segmentation
00775   seg_.setInputCloud (cloud_downsampled_);
00776   seg_.setInputNormals (cloud_normals_);
00777   seg_.segment (*table_inliers_, *table_coefficients_);
00778 
00779   if (table_inliers_->indices.size () == 0)
00780   {
00781     PCL_WARN ("[DominantPlaneSegmentation] No Plane Inliers points! Aborting.");
00782     return;
00783   }
00784 
00785   // ---[ Extract the plane
00786   proj_.setInputCloud (cloud_downsampled_);
00787   proj_.setIndices (table_inliers_);
00788   proj_.setModelCoefficients (table_coefficients_);
00789   proj_.filter (*table_projected_);
00790 
00791   // ---[ Estimate the convex hull
00792   std::vector<pcl::Vertices> polygons;
00793   CloudPtr table_hull (new Cloud ());
00794   hull_.setInputCloud (table_projected_);
00795   hull_.reconstruct (*table_hull, polygons);
00796 
00797   // Compute the plane coefficients
00798   Eigen::Vector4f model_coefficients;
00799   EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00800 
00801   model_coefficients[0] = table_coefficients_->values[0];
00802   model_coefficients[1] = table_coefficients_->values[1];
00803   model_coefficients[2] = table_coefficients_->values[2];
00804   model_coefficients[3] = table_coefficients_->values[3];
00805 
00806   // Need to flip the plane normal towards the viewpoint
00807   Eigen::Vector4f vp (0, 0, 0, 0);
00808   // See if we need to flip any plane normals
00809   vp -= table_hull->points[0].getVector4fMap ();
00810   vp[3] = 0;
00811   // Dot product between the (viewpoint - point) and the plane normal
00812   float cos_theta = vp.dot (model_coefficients);
00813   // Flip the plane normal
00814   if (cos_theta < 0)
00815   {
00816     model_coefficients *= -1;
00817     model_coefficients[3] = 0;
00818     // Hessian form (D = nc . p_plane (centroid here) + p)
00819     model_coefficients[3] = -1 * (model_coefficients.dot (table_hull->points[0].getVector4fMap ()));
00820   }
00821 
00822   //Set table_coeffs
00823   table_coeffs_ = model_coefficients;
00824 
00825   // ---[ Get the objects on top of the table
00826   pcl::PointIndices cloud_object_indices;
00827   prism_.setInputCloud (cloud_filtered_);
00828   prism_.setInputPlanarHull (table_hull);
00829   prism_.segment (cloud_object_indices);
00830 
00831   pcl::ExtractIndices<PointType> extract_object_indices;
00832   extract_object_indices.setInputCloud (cloud_downsampled_);
00833   extract_object_indices.setIndices (boost::make_shared<const pcl::PointIndices> (cloud_object_indices));
00834   extract_object_indices.filter (*cloud_objects_);
00835 
00836   if (cloud_objects_->points.size () == 0)
00837     return;
00838 
00839   // ---[ Split the objects into Euclidean clusters
00840   std::vector<pcl::PointIndices> clusters2;
00841   cluster_.setInputCloud (cloud_filtered_);
00842   cluster_.setIndices (boost::make_shared<const pcl::PointIndices> (cloud_object_indices));
00843   cluster_.extract (clusters2);
00844 
00845   PCL_INFO ("[DominantPlaneSegmentation::compute_full()] Number of clusters found matching the given constraints: %zu.\n",
00846       clusters2.size ());
00847 
00848   clusters.resize (clusters2.size ());
00849 
00850   for (size_t i = 0; i < clusters2.size (); ++i)
00851   {
00852     clusters[i] = CloudPtr (new Cloud ());
00853     pcl::copyPointCloud (*cloud_filtered_, clusters2[i].indices, *clusters[i]);
00854   }
00855 }
00856 
00857 #define PCL_INSTANTIATE_DominantPlaneSegmentation(T) template class PCL_EXPORTS pcl::apps::DominantPlaneSegmentation<T>;


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