convex_hull.hpp
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) 2010-2012, 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  * $Id: convex_hull.hpp 6214 2012-07-06 19:31:29Z rusu $
00037  *
00038  */
00039 
00040 #include <pcl/pcl_config.h>
00041 #ifdef HAVE_QHULL
00042 
00043 #ifndef PCL_SURFACE_IMPL_CONVEX_HULL_H_
00044 #define PCL_SURFACE_IMPL_CONVEX_HULL_H_
00045 
00046 #include <pcl/surface/convex_hull.h>
00047 #include <pcl/common/common.h>
00048 #include <pcl/common/eigen.h>
00049 #include <pcl/common/transforms.h>
00050 #include <pcl/common/io.h>
00051 #include <stdio.h>
00052 #include <stdlib.h>
00053 #include <pcl/surface/qhull.h>
00054 
00056 template <typename PointInT> void
00057 pcl::ConvexHull<PointInT>::calculateInputDimension ()
00058 {
00059   PCL_WARN ("[pcl::%s::calculateInputDimension] WARNING: Input dimension not specified.  Automatically determining input dimension.\n", getClassName ().c_str ());
00060   EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00061   Eigen::Vector4f xyz_centroid;
00062   computeMeanAndCovarianceMatrix (*input_, *indices_, covariance_matrix, xyz_centroid);
00063 
00064   EIGEN_ALIGN16 Eigen::Vector3f eigen_values;
00065   pcl::eigen33 (covariance_matrix, eigen_values);
00066 
00067   if (eigen_values[0] / eigen_values[2] < 1.0e-3)
00068     dimension_ = 2;
00069   else
00070     dimension_ = 3;
00071 }
00072 
00074 template <typename PointInT> void
00075 pcl::ConvexHull<PointInT>::performReconstruction2D (PointCloud &hull, std::vector<pcl::Vertices> &polygons,
00076                                                     bool)
00077 {
00078   int dimension = 2;
00079   bool xy_proj_safe = true;
00080   bool yz_proj_safe = true;
00081   bool xz_proj_safe = true;
00082 
00083   // Check the input's normal to see which projection to use
00084   PointInT p0 = input_->points[0];
00085   PointInT p1 = input_->points[indices_->size () - 1];
00086   PointInT p2 = input_->points[indices_->size () / 2];
00087   Eigen::Array4f dy1dy2 = (p1.getArray4fMap () - p0.getArray4fMap ()) / (p2.getArray4fMap () - p0.getArray4fMap ());
00088   while (!( (dy1dy2[0] != dy1dy2[1]) || (dy1dy2[2] != dy1dy2[1]) ) )
00089   {
00090     p0 = input_->points[rand () % indices_->size ()];
00091     p1 = input_->points[rand () % indices_->size ()];
00092     p2 = input_->points[rand () % indices_->size ()];
00093     dy1dy2 = (p1.getArray4fMap () - p0.getArray4fMap ()) / (p2.getArray4fMap () - p0.getArray4fMap ());
00094   }
00095     
00096   pcl::PointCloud<PointInT> normal_calc_cloud;
00097   normal_calc_cloud.points.resize (3);
00098   normal_calc_cloud.points[0] = p0;
00099   normal_calc_cloud.points[1] = p1;
00100   normal_calc_cloud.points[2] = p2;
00101     
00102   Eigen::Vector4f normal_calc_centroid;
00103   Eigen::Matrix3f normal_calc_covariance;
00104   pcl::computeMeanAndCovarianceMatrix (normal_calc_cloud, normal_calc_covariance, normal_calc_centroid);
00105   // Need to set -1 here. See eigen33 for explanations.
00106   Eigen::Vector3f::Scalar eigen_value;
00107   Eigen::Vector3f plane_params;
00108   pcl::eigen33 (normal_calc_covariance, eigen_value, plane_params);
00109   float theta_x = fabsf (plane_params.dot (x_axis_));
00110   float theta_y = fabsf (plane_params.dot (y_axis_));
00111   float theta_z = fabsf (plane_params.dot (z_axis_));
00112 
00113   // Check for degenerate cases of each projection
00114   // We must avoid projections in which the plane projects as a line
00115   if (theta_z > projection_angle_thresh_)
00116   {
00117     xz_proj_safe = false;
00118     yz_proj_safe = false;
00119   }
00120   if (theta_x > projection_angle_thresh_)
00121   {
00122     xz_proj_safe = false;
00123     xy_proj_safe = false;
00124   }
00125   if (theta_y > projection_angle_thresh_)
00126   {
00127     xy_proj_safe = false;
00128     yz_proj_safe = false;
00129   }
00130 
00131   // True if qhull should free points in qh_freeqhull() or reallocation
00132   boolT ismalloc = True;
00133   // output from qh_produce_output(), use NULL to skip qh_produce_output()
00134   FILE *outfile = NULL;
00135 
00136   if (compute_area_)
00137     outfile = stderr;
00138 
00139   // option flags for qhull, see qh_opt.htm
00140   const char* flags = qhull_flags.c_str ();
00141   // error messages from qhull code
00142   FILE *errfile = stderr;
00143 
00144   // Array of coordinates for each point
00145   coordT *points = reinterpret_cast<coordT*> (calloc (indices_->size () * dimension, sizeof (coordT)));
00146 
00147   // Build input data, using appropriate projection
00148   int j = 0;
00149   if (xy_proj_safe)
00150   {
00151     for (size_t i = 0; i < indices_->size (); ++i, j+=dimension)
00152     {
00153       points[j + 0] = static_cast<coordT> (input_->points[(*indices_)[i]].x);
00154       points[j + 1] = static_cast<coordT> (input_->points[(*indices_)[i]].y);
00155     }
00156   } 
00157   else if (yz_proj_safe)
00158   {
00159     for (size_t i = 0; i < input_->points.size (); ++i, j+=dimension)
00160     {
00161       points[j + 0] = static_cast<coordT> (input_->points[(*indices_)[i]].y);
00162       points[j + 1] = static_cast<coordT> (input_->points[(*indices_)[i]].z);
00163     }
00164   }
00165   else if (xz_proj_safe)
00166   {
00167     for (size_t i = 0; i < input_->points.size (); ++i, j+=dimension)
00168     {
00169       points[j + 0] = static_cast<coordT> (input_->points[(*indices_)[i]].x);
00170       points[j + 1] = static_cast<coordT> (input_->points[(*indices_)[i]].z);
00171     }
00172   }
00173   else
00174   {
00175     // This should only happen if we had invalid input
00176     PCL_ERROR ("[pcl::%s::performReconstruction2D] Invalid input!\n", getClassName ().c_str ());
00177   }
00178    
00179   // Compute convex hull
00180   int exitcode = qh_new_qhull (dimension, static_cast<int> (indices_->size ()), points, ismalloc, const_cast<char*> (flags), outfile, errfile);
00181     
00182   // 0 if no error from qhull
00183   if (exitcode != 0)
00184   {
00185     PCL_ERROR ("[pcl::%s::performReconstrution2D] ERROR: qhull was unable to compute a convex hull for the given point cloud (%zu)!\n", getClassName ().c_str (), indices_->size ());
00186 
00187     hull.points.resize (0);
00188     hull.width = hull.height = 0;
00189     polygons.resize (0);
00190 
00191     qh_freeqhull (!qh_ALL);
00192     int curlong, totlong;
00193     qh_memfreeshort (&curlong, &totlong);
00194 
00195     return;
00196   }
00197 
00198   // Qhull returns the area in volume for 2D
00199   if (compute_area_)
00200   {
00201     total_area_ = qh totvol;
00202     total_volume_ = 0.0;
00203   }
00204 
00205   int num_vertices = qh num_vertices;
00206   hull.points.resize (num_vertices);
00207   memset (&hull.points[0], static_cast<int> (hull.points.size ()), sizeof (PointInT));
00208 
00209   vertexT * vertex;
00210   int i = 0;
00211 
00212   std::vector<std::pair<int, Eigen::Vector4f>, Eigen::aligned_allocator<std::pair<int, Eigen::Vector4f> > > idx_points (num_vertices);
00213   idx_points.resize (hull.points.size ());
00214   memset (&idx_points[0], static_cast<int> (hull.points.size ()), sizeof (std::pair<int, Eigen::Vector4f>));
00215 
00216   FORALLvertices
00217   {
00218     hull.points[i] = input_->points[(*indices_)[qh_pointid (vertex->point)]];
00219     idx_points[i].first = qh_pointid (vertex->point);
00220     ++i;
00221   }
00222 
00223   // Sort
00224   Eigen::Vector4f centroid;
00225   pcl::compute3DCentroid (hull, centroid);
00226   if (xy_proj_safe)
00227   {
00228     for (size_t j = 0; j < hull.points.size (); j++)
00229     {
00230       idx_points[j].second[0] = hull.points[j].x - centroid[0];
00231       idx_points[j].second[1] = hull.points[j].y - centroid[1];
00232     }
00233   }
00234   else if (yz_proj_safe)
00235   {
00236     for (size_t j = 0; j < hull.points.size (); j++)
00237     {
00238       idx_points[j].second[0] = hull.points[j].y - centroid[1];
00239       idx_points[j].second[1] = hull.points[j].z - centroid[2];
00240     }
00241   }
00242   else if (xz_proj_safe)
00243   {
00244     for (size_t j = 0; j < hull.points.size (); j++)
00245     {
00246       idx_points[j].second[0] = hull.points[j].x - centroid[0];
00247       idx_points[j].second[1] = hull.points[j].z - centroid[2];
00248     }
00249   }
00250   std::sort (idx_points.begin (), idx_points.end (), comparePoints2D);
00251     
00252   polygons.resize (1);
00253   polygons[0].vertices.resize (hull.points.size () + 1);  
00254 
00255   for (int j = 0; j < static_cast<int> (hull.points.size ()); j++)
00256   {
00257     hull.points[j] = input_->points[(*indices_)[idx_points[j].first]];
00258     polygons[0].vertices[j] = static_cast<unsigned int> (j);
00259   }
00260   polygons[0].vertices[hull.points.size ()] = 0;
00261     
00262   qh_freeqhull (!qh_ALL);
00263   int curlong, totlong;
00264   qh_memfreeshort (&curlong, &totlong);
00265 
00266   hull.width = static_cast<uint32_t> (hull.points.size ());
00267   hull.height = 1;
00268   hull.is_dense = false;
00269   return;
00270 }
00271 
00272 #ifdef __GNUC__
00273 #pragma GCC diagnostic ignored "-Wold-style-cast"
00274 #endif
00275 
00276 template <typename PointInT> void
00277 pcl::ConvexHull<PointInT>::performReconstruction3D (
00278     PointCloud &hull, std::vector<pcl::Vertices> &polygons, bool fill_polygon_data)
00279 {
00280   int dimension = 3;
00281 
00282   // True if qhull should free points in qh_freeqhull() or reallocation
00283   boolT ismalloc = True;
00284   // output from qh_produce_output(), use NULL to skip qh_produce_output()
00285   FILE *outfile = NULL;
00286 
00287   if (compute_area_)
00288     outfile = stderr;
00289 
00290   // option flags for qhull, see qh_opt.htm
00291   const char *flags = qhull_flags.c_str ();
00292   // error messages from qhull code
00293   FILE *errfile = stderr;
00294 
00295   // Array of coordinates for each point
00296   coordT *points = reinterpret_cast<coordT*> (calloc (indices_->size () * dimension, sizeof (coordT)));
00297 
00298   int j = 0;
00299   for (size_t i = 0; i < indices_->size (); ++i, j+=dimension)
00300   {
00301     points[j + 0] = static_cast<coordT> (input_->points[(*indices_)[i]].x);
00302     points[j + 1] = static_cast<coordT> (input_->points[(*indices_)[i]].y);
00303     points[j + 2] = static_cast<coordT> (input_->points[(*indices_)[i]].z);
00304   }
00305 
00306   // Compute convex hull
00307   int exitcode = qh_new_qhull (dimension, static_cast<int> (indices_->size ()), points, ismalloc, const_cast<char*> (flags), outfile, errfile);
00308 
00309   // 0 if no error from qhull
00310   if (exitcode != 0)
00311   {
00312     PCL_ERROR ("[pcl::%s::performReconstrution3D] ERROR: qhull was unable to compute a convex hull for the given point cloud (%zu)!\n", getClassName ().c_str (), input_->points.size ());
00313 
00314     hull.points.resize (0);
00315     hull.width = hull.height = 0;
00316     polygons.resize (0);
00317 
00318     qh_freeqhull (!qh_ALL);
00319     int curlong, totlong;
00320     qh_memfreeshort (&curlong, &totlong);
00321 
00322     return;
00323   }
00324 
00325   qh_triangulate ();
00326 
00327   int num_facets = qh num_facets;
00328 
00329   int num_vertices = qh num_vertices;
00330   hull.points.resize (num_vertices);
00331 
00332   vertexT * vertex;
00333   int i = 0;
00334   // Max vertex id
00335   int max_vertex_id = 0;
00336   FORALLvertices
00337   {
00338     if (vertex->id + 1 > max_vertex_id)
00339       max_vertex_id = vertex->id + 1;
00340   }
00341 
00342   ++max_vertex_id;
00343   std::vector<int> qhid_to_pcidx (max_vertex_id);
00344 
00345   FORALLvertices
00346   {
00347     // Add vertices to hull point_cloud
00348     hull.points[i] = input_->points[(*indices_)[qh_pointid (vertex->point)]];
00349 
00350     qhid_to_pcidx[vertex->id] = i; // map the vertex id of qhull to the point cloud index
00351     ++i;
00352   }
00353 
00354   if (compute_area_)
00355   {
00356     total_area_  = qh totarea;
00357     total_volume_ = qh totvol;
00358   }
00359 
00360   if (fill_polygon_data)
00361   {
00362     polygons.resize (num_facets);
00363     int dd = 0;
00364 
00365     facetT * facet;
00366     FORALLfacets
00367     {
00368       polygons[dd].vertices.resize (3);
00369 
00370       // Needed by FOREACHvertex_i_
00371       int vertex_n, vertex_i;
00372       FOREACHvertex_i_ ((*facet).vertices)
00373       //facet_vertices.vertices.push_back (qhid_to_pcidx[vertex->id]);
00374       polygons[dd].vertices[vertex_i] = qhid_to_pcidx[vertex->id];
00375       ++dd;
00376     }
00377   }
00378   // Deallocates memory (also the points)
00379   qh_freeqhull (!qh_ALL);
00380   int curlong, totlong;
00381   qh_memfreeshort (&curlong, &totlong);
00382 
00383   hull.width = static_cast<uint32_t> (hull.points.size ());
00384   hull.height = 1;
00385   hull.is_dense = false;
00386 }
00387 #ifdef __GNUC__
00388 #pragma GCC diagnostic warning "-Wold-style-cast"
00389 #endif
00390 
00392 template <typename PointInT> void
00393 pcl::ConvexHull<PointInT>::performReconstruction (PointCloud &hull, std::vector<pcl::Vertices> &polygons,
00394                                                   bool fill_polygon_data)
00395 {
00396   if (dimension_ == 0)
00397     calculateInputDimension ();
00398   if (dimension_ == 2)
00399     performReconstruction2D (hull, polygons, fill_polygon_data);
00400   else if (dimension_ == 3)
00401     performReconstruction3D (hull, polygons, fill_polygon_data);
00402   else
00403     PCL_ERROR ("[pcl::%s::performReconstruction] Error: invalid input dimension requested: %d\n",getClassName ().c_str (),dimension_);
00404 }
00405 
00407 template <typename PointInT> void
00408 pcl::ConvexHull<PointInT>::reconstruct (PointCloud &output)
00409 {
00410   output.header = input_->header;
00411   if (!initCompute () || input_->points.empty () || indices_->empty ())
00412   {
00413     output.points.clear ();
00414     return;
00415   }
00416 
00417   // Perform the actual surface reconstruction
00418   std::vector<pcl::Vertices> polygons;
00419   performReconstruction (output, polygons, false);
00420 
00421   output.width = static_cast<uint32_t> (output.points.size ());
00422   output.height = 1;
00423   output.is_dense = true;
00424 
00425   deinitCompute ();
00426 }
00427 
00428 
00430 template <typename PointInT> void
00431 pcl::ConvexHull<PointInT>::performReconstruction (PolygonMesh &output)
00432 {
00433   // Perform reconstruction
00434   pcl::PointCloud<PointInT> hull_points;
00435   performReconstruction (hull_points, output.polygons, true);
00436 
00437   // Convert the PointCloud into a PointCloud2
00438   pcl::toROSMsg (hull_points, output.cloud);
00439 }
00440 
00442 template <typename PointInT> void
00443 pcl::ConvexHull<PointInT>::performReconstruction (std::vector<pcl::Vertices> &polygons)
00444 {
00445   pcl::PointCloud<PointInT> hull_points;
00446   performReconstruction (hull_points, polygons, true);
00447 }
00448 
00450 template <typename PointInT> void
00451 pcl::ConvexHull<PointInT>::reconstruct (PointCloud &points, std::vector<pcl::Vertices> &polygons)
00452 {
00453   points.header = input_->header;
00454   if (!initCompute () || input_->points.empty () || indices_->empty ())
00455   {
00456     points.points.clear ();
00457     return;
00458   }
00459 
00460   // Perform the actual surface reconstruction
00461   performReconstruction (points, polygons, true);
00462 
00463   points.width = static_cast<uint32_t> (points.points.size ());
00464   points.height = 1;
00465   points.is_dense = true;
00466 
00467   deinitCompute ();
00468 }
00469 
00470 #define PCL_INSTANTIATE_ConvexHull(T) template class PCL_EXPORTS pcl::ConvexHull<T>;
00471 
00472 #endif    // PCL_SURFACE_IMPL_CONVEX_HULL_H_
00473 #endif


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