Point Cloud Library (PCL)  1.5.1
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
concave_hull.hpp
Go to the documentation of this file.
00001 
00040 #include <pcl/pcl_config.h>
00041 #ifdef HAVE_QHULL
00042 
00043 #ifndef PCL_SURFACE_IMPL_CONCAVE_HULL_H_
00044 #define PCL_SURFACE_IMPL_CONCAVE_HULL_H_
00045 
00046 #include <map>
00047 #include <pcl/surface/concave_hull.h>
00048 #include <pcl/common/common.h>
00049 #include <pcl/common/eigen.h>
00050 #include <pcl/common/centroid.h>
00051 #include <pcl/common/transforms.h>
00052 #include <pcl/kdtree/kdtree_flann.h>
00053 #include <pcl/common/io.h>
00054 #include <stdio.h>
00055 #include <stdlib.h>
00056 
00057 extern "C"
00058 {
00059 #ifdef HAVE_QHULL_2011
00060 #  include "libqhull/libqhull.h"
00061 #  include "libqhull/mem.h"
00062 #  include "libqhull/qset.h"
00063 #  include "libqhull/geom.h"
00064 #  include "libqhull/merge.h"
00065 #  include "libqhull/poly.h"
00066 #  include "libqhull/io.h"
00067 #  include "libqhull/stat.h"
00068 #else
00069 #  include "qhull/qhull.h"
00070 #  include "qhull/mem.h"
00071 #  include "qhull/qset.h"
00072 #  include "qhull/geom.h"
00073 #  include "qhull/merge.h"
00074 #  include "qhull/poly.h"
00075 #  include "qhull/io.h"
00076 #  include "qhull/stat.h"
00077 #endif
00078 }
00079 
00081 template <typename PointInT> void
00082 pcl::ConcaveHull<PointInT>::reconstruct (PointCloud &output)
00083 {
00084   output.header = input_->header;
00085   if (alpha_ <= 0)
00086   {
00087     PCL_ERROR ("[pcl::%s::reconstruct] Alpha parameter must be set to a positive number!\n", getClassName ().c_str ());
00088     output.points.clear ();
00089     return;
00090   }
00091 
00092   if (!initCompute ())
00093   {
00094     output.points.clear ();
00095     return;
00096   }
00097 
00098   // Perform the actual surface reconstruction
00099   std::vector<pcl::Vertices> polygons;
00100   performReconstruction (output, polygons);
00101 
00102   output.width = output.points.size ();
00103   output.height = 1;
00104   output.is_dense = true;
00105 
00106   deinitCompute ();
00107 }
00108 
00110 template <typename PointInT> void
00111 pcl::ConcaveHull<PointInT>::reconstruct (PointCloud &output, std::vector<pcl::Vertices> &polygons)
00112 {
00113   output.header = input_->header;
00114   if (alpha_ <= 0)
00115   {
00116     PCL_ERROR ("[pcl::%s::reconstruct] Alpha parameter must be set to a positive number!\n", getClassName ().c_str ());
00117     output.points.clear ();
00118     return;
00119   }
00120 
00121   if (!initCompute ())
00122   {
00123     output.points.clear ();
00124     return;
00125   }
00126 
00127   // Perform the actual surface reconstruction
00128   performReconstruction (output, polygons);
00129 
00130   output.width = output.points.size ();
00131   output.height = 1;
00132   output.is_dense = true;
00133 
00134   deinitCompute ();
00135 }
00136 
00138 template <typename PointInT> void
00139 pcl::ConcaveHull<PointInT>::performReconstruction (PointCloud &alpha_shape, std::vector<pcl::Vertices> &polygons)
00140 {
00141   EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00142   Eigen::Vector4f xyz_centroid;
00143   computeMeanAndCovarianceMatrix (*input_, *indices_, covariance_matrix, xyz_centroid);
00144 
00145   // Check if the covariance matrix is finite or not.
00146   for (int i = 0; i < 3; ++i)
00147     for (int j = 0; j < 3; ++j)
00148       if (!pcl_isfinite (covariance_matrix.coeffRef (i, j)))
00149           return;
00150 
00151   EIGEN_ALIGN16 Eigen::Vector3f eigen_values;
00152   EIGEN_ALIGN16 Eigen::Matrix3f eigen_vectors;
00153   pcl::eigen33 (covariance_matrix, eigen_vectors, eigen_values);
00154 
00155   Eigen::Affine3f transform1;
00156   transform1.setIdentity ();
00157   int dim = 3;
00158   if (eigen_values[0] / eigen_values[2] < 1.0e-5)
00159   {
00160     // we have points laying on a plane, using 2d convex hull
00161     // compute transformation bring eigen_vectors.col(i) to z-axis
00162 
00163     transform1 (2, 0) = eigen_vectors (0, 0);
00164     transform1 (2, 1) = eigen_vectors (1, 0);
00165     transform1 (2, 2) = eigen_vectors (2, 0);
00166 
00167     transform1 (1, 0) = eigen_vectors (0, 1);
00168     transform1 (1, 1) = eigen_vectors (1, 1);
00169     transform1 (1, 2) = eigen_vectors (2, 1);
00170     transform1 (0, 0) = eigen_vectors (0, 2);
00171     transform1 (0, 1) = eigen_vectors (1, 2);
00172     transform1 (0, 2) = eigen_vectors (2, 2);
00173     dim = 2;
00174   }
00175   else
00176   {
00177     transform1.setIdentity ();
00178   }
00179 
00180   dim_ = dim;
00181 
00182   PointCloud cloud_transformed;
00183   pcl::demeanPointCloud (*input_, *indices_, xyz_centroid, cloud_transformed);
00184   pcl::transformPointCloud (cloud_transformed, cloud_transformed, transform1);
00185 
00186   // True if qhull should free points in qh_freeqhull() or reallocation
00187   boolT ismalloc = True;
00188   // option flags for qhull, see qh_opt.htm
00189   char flags[] = "qhull d QJ";
00190   // output from qh_produce_output(), use NULL to skip qh_produce_output()
00191   FILE *outfile = NULL;
00192   // error messages from qhull code
00193   FILE *errfile = stderr;
00194   // 0 if no error from qhull
00195   int exitcode;
00196 
00197   // Array of coordinates for each point
00198   coordT *points = (coordT*)calloc (cloud_transformed.points.size () * dim, sizeof(coordT));
00199 
00200   for (size_t i = 0; i < cloud_transformed.points.size (); ++i)
00201   {
00202     points[i * dim + 0] = (coordT)cloud_transformed.points[i].x;
00203     points[i * dim + 1] = (coordT)cloud_transformed.points[i].y;
00204 
00205     if (dim > 2)
00206       points[i * dim + 2] = (coordT)cloud_transformed.points[i].z;
00207   }
00208 
00209   // Compute concave hull
00210   exitcode = qh_new_qhull (dim, cloud_transformed.points.size (), points, ismalloc, flags, outfile, errfile);
00211 
00212   if (exitcode != 0)
00213   {
00214     PCL_ERROR ("[pcl::%s::performReconstrution] ERROR: qhull was unable to compute a concave hull for the given point cloud (%lu)!\n", getClassName ().c_str (), (unsigned long) cloud_transformed.points.size ());
00215 
00216     //check if it fails because of NaN values...
00217     if (!cloud_transformed.is_dense)
00218     {
00219       bool NaNvalues = false;
00220       for (size_t i = 0; i < cloud_transformed.size (); ++i)
00221       {
00222         if (!pcl_isfinite (cloud_transformed.points[i].x) ||
00223             !pcl_isfinite (cloud_transformed.points[i].y) ||
00224             !pcl_isfinite (cloud_transformed.points[i].z))
00225         {
00226           NaNvalues = true;
00227           break;
00228         }
00229       }
00230 
00231       if (NaNvalues)
00232         PCL_ERROR ("[pcl::%s::performReconstruction] ERROR: point cloud contains NaN values, consider running pcl::PassThrough filter first to remove NaNs!\n", getClassName ().c_str ());
00233     }
00234 
00235     alpha_shape.points.resize (0);
00236     alpha_shape.width = alpha_shape.height = 0;
00237     polygons.resize (0);
00238 
00239     qh_freeqhull (!qh_ALL);
00240     int curlong, totlong;
00241     qh_memfreeshort (&curlong, &totlong);
00242 
00243     return;
00244   }
00245 
00246   qh_setvoronoi_all ();
00247 
00248   int num_vertices = qh num_vertices;
00249   alpha_shape.points.resize (num_vertices);
00250 
00251   vertexT *vertex;
00252   // Max vertex id
00253   int max_vertex_id = - 1;
00254   FORALLvertices
00255   {
00256     if ((int)vertex->id > max_vertex_id)
00257       max_vertex_id = vertex->id;
00258   }
00259 
00260   facetT *facet;    // set by FORALLfacets
00261 
00262   ++max_vertex_id;
00263   std::vector<int> qhid_to_pcidx (max_vertex_id);
00264 
00265   int num_facets = qh num_facets;
00266   int dd = 0;
00267 
00268   if (dim == 3)
00269   {
00270     setT *triangles_set = qh_settemp (4 * num_facets);
00271     if (voronoi_centers_)
00272       voronoi_centers_->points.resize (num_facets);
00273 
00274     int non_upper = 0;
00275     FORALLfacets
00276     {
00277       // Facets are tetrahedrons (3d)
00278       if (!facet->upperdelaunay)
00279       {
00280         vertexT *anyVertex = (vertexT*)(facet->vertices->e[0].p);
00281         double *center = facet->center;
00282         double r = qh_pointdist (anyVertex->point,center,dim);
00283         facetT *neighb;
00284 
00285         if (voronoi_centers_)
00286         {
00287           voronoi_centers_->points[non_upper].x = facet->center[0];
00288           voronoi_centers_->points[non_upper].y = facet->center[1];
00289           voronoi_centers_->points[non_upper].z = facet->center[2];
00290         }
00291 
00292         non_upper++;
00293 
00294         if (r <= alpha_)
00295         {
00296           // all triangles in tetrahedron are good, add them all to the alpha shape (triangles_set)
00297           qh_makeridges (facet);
00298           facet->good = true;
00299           facet->visitid = qh visit_id;
00300           ridgeT *ridge, **ridgep;
00301           FOREACHridge_ (facet->ridges)
00302           {
00303             neighb = otherfacet_ (ridge, facet);
00304             if ((neighb->visitid != qh visit_id))
00305               qh_setappend (&triangles_set, ridge);
00306           }
00307         }
00308         else
00309         {
00310           // consider individual triangles from the tetrahedron...
00311           facet->good = false;
00312           facet->visitid = qh visit_id;
00313           qh_makeridges (facet);
00314           ridgeT *ridge, **ridgep;
00315           FOREACHridge_ (facet->ridges)
00316           {
00317             facetT *neighb;
00318             neighb = otherfacet_ (ridge, facet);
00319             if ((neighb->visitid != qh visit_id))
00320             {
00321               // check if individual triangle is good and add it to triangles_set
00322 
00323               PointInT a, b, c;
00324               a.x = ((vertexT*)(ridge->vertices->e[0].p))->point[0];
00325               a.y = ((vertexT*)(ridge->vertices->e[0].p))->point[1];
00326               a.z = ((vertexT*)(ridge->vertices->e[0].p))->point[2];
00327               b.x = ((vertexT*)(ridge->vertices->e[1].p))->point[0];
00328               b.y = ((vertexT*)(ridge->vertices->e[1].p))->point[1];
00329               b.z = ((vertexT*)(ridge->vertices->e[1].p))->point[2];
00330               c.x = ((vertexT*)(ridge->vertices->e[2].p))->point[0];
00331               c.y = ((vertexT*)(ridge->vertices->e[2].p))->point[1];
00332               c.z = ((vertexT*)(ridge->vertices->e[2].p))->point[2];
00333 
00334               double r = pcl::getCircumcircleRadius (a, b, c);
00335               if (r <= alpha_)
00336                 qh_setappend (&triangles_set, ridge);
00337             }
00338           }
00339         }
00340       }
00341     }
00342 
00343     if (voronoi_centers_)
00344       voronoi_centers_->points.resize (non_upper);
00345 
00346     // filter, add points to alpha_shape and create polygon structure
00347 
00348     int num_good_triangles = 0;
00349     ridgeT *ridge, **ridgep;
00350     FOREACHridge_ (triangles_set)
00351     {
00352       if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good)
00353         num_good_triangles++;
00354     }
00355 
00356     polygons.resize (num_good_triangles);
00357 
00358     int vertices = 0;
00359     std::vector<bool> added_vertices (max_vertex_id, false);
00360 
00361     int triangles = 0;
00362     FOREACHridge_ (triangles_set)
00363     {
00364       if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good)
00365       {
00366         polygons[triangles].vertices.resize (3);
00367         int vertex_n, vertex_i;
00368         FOREACHvertex_i_ ((*ridge).vertices)  //3 vertices per ridge!
00369         {
00370           if (!added_vertices[vertex->id])
00371           {
00372             alpha_shape.points[vertices].x = vertex->point[0];
00373             alpha_shape.points[vertices].y = vertex->point[1];
00374             alpha_shape.points[vertices].z = vertex->point[2];
00375 
00376             qhid_to_pcidx[vertex->id] = vertices;   //map the vertex id of qhull to the point cloud index
00377             added_vertices[vertex->id] = true;
00378             vertices++;
00379           }
00380 
00381           polygons[triangles].vertices[vertex_i] = qhid_to_pcidx[vertex->id];
00382 
00383         }
00384 
00385         triangles++;
00386       }
00387     }
00388 
00389     alpha_shape.points.resize (vertices);
00390     alpha_shape.width = alpha_shape.points.size ();
00391     alpha_shape.height = 1;
00392   }
00393   else
00394   {
00395     // Compute the alpha complex for the set of points
00396     // Filters the delaunay triangles
00397     setT *edges_set = qh_settemp (3 * num_facets);
00398     if (voronoi_centers_)
00399       voronoi_centers_->points.resize (num_facets);
00400 
00401     FORALLfacets
00402     {
00403       // Facets are the delaunay triangles (2d)
00404       if (!facet->upperdelaunay)
00405       {
00406         // Check if the distance from any vertex to the facet->center
00407         // (center of the voronoi cell) is smaller than alpha
00408         vertexT *anyVertex = (vertexT*)(facet->vertices->e[0].p);
00409         double r = (sqrt ((anyVertex->point[0] - facet->center[0]) *
00410                           (anyVertex->point[0] - facet->center[0]) +
00411                           (anyVertex->point[1] - facet->center[1]) *
00412                           (anyVertex->point[1] - facet->center[1])));
00413         if (r <= alpha_)
00414         {
00415           pcl::Vertices facet_vertices;   //TODO: is not used!!
00416           qh_makeridges (facet);
00417           facet->good = true;
00418 
00419           ridgeT *ridge, **ridgep;
00420           FOREACHridge_ (facet->ridges)
00421           qh_setappend (&edges_set, ridge);
00422 
00423           if (voronoi_centers_)
00424           {
00425             voronoi_centers_->points[dd].x = facet->center[0];
00426             voronoi_centers_->points[dd].y = facet->center[1];
00427             voronoi_centers_->points[dd].z = 0;
00428           }
00429 
00430           ++dd;
00431         }
00432         else
00433           facet->good = false;
00434       }
00435     }
00436 
00437     int vertices = 0;
00438     std::vector<bool> added_vertices (max_vertex_id, false);
00439     std::map<int, std::vector<int> > edges;
00440 
00441     ridgeT *ridge, **ridgep;
00442     FOREACHridge_ (edges_set)
00443     {
00444       if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good)
00445       {
00446         int vertex_n, vertex_i;
00447         int vertices_in_ridge=0;
00448         std::vector<int> pcd_indices;
00449         pcd_indices.resize (2);
00450 
00451         FOREACHvertex_i_ ((*ridge).vertices)  //in 2-dim, 2 vertices per ridge!
00452         {
00453           if (!added_vertices[vertex->id])
00454           {
00455             alpha_shape.points[vertices].x = vertex->point[0];
00456             alpha_shape.points[vertices].y = vertex->point[1];
00457 
00458             if (dim > 2)
00459               alpha_shape.points[vertices].z = vertex->point[2];
00460             else
00461               alpha_shape.points[vertices].z = 0;
00462 
00463             qhid_to_pcidx[vertex->id] = vertices;   //map the vertex id of qhull to the point cloud index
00464             added_vertices[vertex->id] = true;
00465             pcd_indices[vertices_in_ridge] = vertices;
00466             vertices++;
00467           }
00468           else
00469           {
00470             pcd_indices[vertices_in_ridge] = qhid_to_pcidx[vertex->id];
00471           }
00472 
00473           vertices_in_ridge++;
00474         }
00475 
00476         // make edges bidirectional and pointing to alpha_shape pointcloud...
00477         edges[pcd_indices[0]].push_back (pcd_indices[1]);
00478         edges[pcd_indices[1]].push_back (pcd_indices[0]);
00479       }
00480     }
00481 
00482     alpha_shape.points.resize (vertices);
00483 
00484     std::vector<std::vector<int> > connected;
00485     PointCloud alpha_shape_sorted;
00486     alpha_shape_sorted.points.resize (vertices);
00487 
00488     // iterate over edges until they are empty!
00489     std::map<int, std::vector<int> >::iterator curr = edges.begin ();
00490     int next = - 1;
00491     std::vector<bool> used (vertices, false);   // used to decide which direction should we take!
00492     std::vector<int> pcd_idx_start_polygons;
00493     pcd_idx_start_polygons.push_back (0);
00494 
00495     // start following edges and removing elements
00496     int sorted_idx = 0;
00497     while (!edges.empty ())
00498     {
00499       alpha_shape_sorted.points[sorted_idx] = alpha_shape.points[(*curr).first];
00500       // check where we can go from (*curr).first
00501       for (size_t i = 0; i < (*curr).second.size (); i++)
00502       {
00503         if (!used[((*curr).second)[i]])
00504         {
00505           // we can go there
00506           next = ((*curr).second)[i];
00507           break;
00508         }
00509       }
00510 
00511       used[(*curr).first] = true;
00512       edges.erase (curr);   // remove edges starting from curr
00513 
00514       sorted_idx++;
00515 
00516       if (edges.empty ())
00517         break;
00518 
00519       // reassign current
00520       curr = edges.find (next);   // if next is not found, then we have unconnected polygons.
00521       if (curr == edges.end ())
00522       {
00523         // set current to any of the remaining in edge!
00524         curr = edges.begin ();
00525         pcd_idx_start_polygons.push_back (sorted_idx);
00526       }
00527     }
00528 
00529     pcd_idx_start_polygons.push_back (sorted_idx);
00530 
00531     alpha_shape.points = alpha_shape_sorted.points;
00532 
00533     polygons.resize (pcd_idx_start_polygons.size () - 1);
00534 
00535     for (size_t poly_id = 0; poly_id < polygons.size (); poly_id++)
00536     {
00537       polygons[poly_id].vertices.resize (pcd_idx_start_polygons[poly_id + 1] - pcd_idx_start_polygons[poly_id] + 1);
00538       // populate points in the corresponding polygon
00539       for (size_t j = (size_t)pcd_idx_start_polygons[poly_id]; j < (size_t)pcd_idx_start_polygons[poly_id + 1]; ++j)
00540         polygons[poly_id].vertices[j - pcd_idx_start_polygons[poly_id]] = j;
00541 
00542       polygons[poly_id].vertices[polygons[poly_id].vertices.size () - 1] = pcd_idx_start_polygons[poly_id];
00543     }
00544 
00545     if (voronoi_centers_)
00546       voronoi_centers_->points.resize (dd);
00547   }
00548 
00549   qh_freeqhull (!qh_ALL);
00550   int curlong, totlong;
00551   qh_memfreeshort (&curlong, &totlong);
00552 
00553   Eigen::Affine3f transInverse = transform1.inverse ();
00554   pcl::transformPointCloud (alpha_shape, alpha_shape, transInverse);
00555   xyz_centroid[0] = - xyz_centroid[0];
00556   xyz_centroid[1] = - xyz_centroid[1];
00557   xyz_centroid[2] = - xyz_centroid[2];
00558   pcl::demeanPointCloud (alpha_shape, xyz_centroid, alpha_shape);
00559 
00560   // also transform voronoi_centers_...
00561   if (voronoi_centers_)
00562   {
00563     pcl::transformPointCloud (*voronoi_centers_, *voronoi_centers_, transInverse);
00564     pcl::demeanPointCloud (*voronoi_centers_, xyz_centroid, *voronoi_centers_);
00565   }
00566 
00567   if (keep_information_)
00568   {
00569     // build a tree with the original points
00570     pcl::KdTreeFLANN<PointInT> tree (true);
00571     tree.setInputCloud (input_, indices_);
00572 
00573     std::vector<int> neighbor;
00574     std::vector<float> distances;
00575     neighbor.resize (1);
00576     distances.resize (1);
00577 
00578     // for each point in the concave hull, search for the nearest neighbor in the original point cloud
00579 
00580     std::vector<int> indices;
00581     indices.resize (alpha_shape.points.size ());
00582 
00583     for (size_t i = 0; i < alpha_shape.points.size (); i++)
00584     {
00585       tree.nearestKSearch (alpha_shape.points[i], 1, neighbor, distances);
00586       indices[i] = (*indices_)[neighbor[0]];
00587     }
00588 
00589     // replace point with the closest neighbor in the original point cloud
00590     pcl::copyPointCloud (*input_, indices, alpha_shape);
00591   }
00592 }
00593 
00594 template <typename PointInT> void
00595 pcl::ConcaveHull<PointInT>::performReconstruction (PolygonMesh &output)
00596 {
00597   // Perform reconstruction
00598   pcl::PointCloud<PointInT> hull_points;
00599   performReconstruction (hull_points, output.polygons);
00600 
00601   // Convert the PointCloud into a PointCloud2
00602   pcl::toROSMsg (hull_points, output.cloud);
00603 }
00604 
00605 template <typename PointInT> void
00606 pcl::ConcaveHull<PointInT>::performReconstruction (std::vector<pcl::Vertices> &polygons)
00607 {
00608   pcl::PointCloud<PointInT> hull_points;
00609   performReconstruction (hull_points, polygons);
00610 }
00611 
00612 
00613 #define PCL_INSTANTIATE_ConcaveHull(T) template class PCL_EXPORTS pcl::ConcaveHull<T>;
00614 
00615 #endif    // PCL_SURFACE_IMPL_CONCAVE_HULL_H_
00616 #endif