Point Cloud Library (PCL)  1.11.1-dev
concave_hull.hpp
1 /**
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2011, Willow Garage, Inc.
6  *
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of Willow Garage, Inc. nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * $Id$
37  *
38  */
39 
40 #include <pcl/pcl_config.h>
41 #ifdef HAVE_QHULL
42 
43 #ifndef PCL_SURFACE_IMPL_CONCAVE_HULL_H_
44 #define PCL_SURFACE_IMPL_CONCAVE_HULL_H_
45 
46 #include <map>
47 #include <pcl/surface/concave_hull.h>
48 #include <pcl/common/common.h>
49 #include <pcl/common/eigen.h>
50 #include <pcl/common/centroid.h>
51 #include <pcl/common/transforms.h>
52 #include <pcl/common/io.h>
53 #include <cstdio>
54 #include <cstdlib>
55 #include <pcl/surface/qhull.h>
56 
57 //////////////////////////////////////////////////////////////////////////
58 template <typename PointInT> void
60 {
61  output.header = input_->header;
62  if (alpha_ <= 0)
63  {
64  PCL_ERROR ("[pcl::%s::reconstruct] Alpha parameter must be set to a positive number!\n", getClassName ().c_str ());
65  output.clear ();
66  return;
67  }
68 
69  if (!initCompute ())
70  {
71  output.clear ();
72  return;
73  }
74 
75  // Perform the actual surface reconstruction
76  std::vector<pcl::Vertices> polygons;
77  performReconstruction (output, polygons);
78 
79  output.width = output.size ();
80  output.height = 1;
81  output.is_dense = true;
82 
83  deinitCompute ();
84 }
85 
86 //////////////////////////////////////////////////////////////////////////
87 template <typename PointInT> void
88 pcl::ConcaveHull<PointInT>::reconstruct (PointCloud &output, std::vector<pcl::Vertices> &polygons)
89 {
90  output.header = input_->header;
91  if (alpha_ <= 0)
92  {
93  PCL_ERROR ("[pcl::%s::reconstruct] Alpha parameter must be set to a positive number!\n", getClassName ().c_str ());
94  output.clear ();
95  return;
96  }
97 
98  if (!initCompute ())
99  {
100  output.clear ();
101  return;
102  }
103 
104  // Perform the actual surface reconstruction
105  performReconstruction (output, polygons);
106 
107  output.width = output.size ();
108  output.height = 1;
109  output.is_dense = true;
110 
111  deinitCompute ();
112 }
113 
114 #ifdef __GNUC__
115 #pragma GCC diagnostic ignored "-Wold-style-cast"
116 #endif
117 //////////////////////////////////////////////////////////////////////////
118 template <typename PointInT> void
119 pcl::ConcaveHull<PointInT>::performReconstruction (PointCloud &alpha_shape, std::vector<pcl::Vertices> &polygons)
120 {
121  Eigen::Vector4d xyz_centroid;
122  compute3DCentroid (*input_, *indices_, xyz_centroid);
123  EIGEN_ALIGN16 Eigen::Matrix3d covariance_matrix = Eigen::Matrix3d::Zero ();
124  computeCovarianceMatrixNormalized (*input_, *indices_, xyz_centroid, covariance_matrix);
125 
126  // Check if the covariance matrix is finite or not.
127  for (int i = 0; i < 3; ++i)
128  for (int j = 0; j < 3; ++j)
129  if (!std::isfinite (covariance_matrix.coeffRef (i, j)))
130  return;
131 
132  EIGEN_ALIGN16 Eigen::Vector3d eigen_values;
133  EIGEN_ALIGN16 Eigen::Matrix3d eigen_vectors;
134  pcl::eigen33 (covariance_matrix, eigen_vectors, eigen_values);
135 
136  Eigen::Affine3d transform1;
137  transform1.setIdentity ();
138 
139  // If no input dimension is specified, determine automatically
140  if (dim_ == 0)
141  {
142  PCL_DEBUG ("[pcl::%s] WARNING: Input dimension not specified. Automatically determining input dimension.\n", getClassName ().c_str ());
143  if (std::abs (eigen_values[0]) < std::numeric_limits<double>::epsilon () || std::abs (eigen_values[0] / eigen_values[2]) < 1.0e-3)
144  dim_ = 2;
145  else
146  dim_ = 3;
147  }
148 
149  if (dim_ == 2)
150  {
151  // we have points laying on a plane, using 2d convex hull
152  // compute transformation bring eigen_vectors.col(i) to z-axis
153 
154  transform1 (2, 0) = eigen_vectors (0, 0);
155  transform1 (2, 1) = eigen_vectors (1, 0);
156  transform1 (2, 2) = eigen_vectors (2, 0);
157 
158  transform1 (1, 0) = eigen_vectors (0, 1);
159  transform1 (1, 1) = eigen_vectors (1, 1);
160  transform1 (1, 2) = eigen_vectors (2, 1);
161  transform1 (0, 0) = eigen_vectors (0, 2);
162  transform1 (0, 1) = eigen_vectors (1, 2);
163  transform1 (0, 2) = eigen_vectors (2, 2);
164  }
165  else
166  {
167  transform1.setIdentity ();
168  }
169 
170  PointCloud cloud_transformed;
171  pcl::demeanPointCloud (*input_, *indices_, xyz_centroid, cloud_transformed);
172  pcl::transformPointCloud (cloud_transformed, cloud_transformed, transform1);
173 
174  // True if qhull should free points in qh_freeqhull() or reallocation
175  boolT ismalloc = True;
176  // option flags for qhull, see qh_opt.htm
177  char flags[] = "qhull d QJ";
178  // output from qh_produce_output(), use NULL to skip qh_produce_output()
179  FILE *outfile = nullptr;
180  // error messages from qhull code
181  FILE *errfile = stderr;
182  // 0 if no error from qhull
183  int exitcode;
184 
185  // Array of coordinates for each point
186  coordT *points = reinterpret_cast<coordT*> (calloc (cloud_transformed.size () * dim_, sizeof(coordT)));
187 
188  for (std::size_t i = 0; i < cloud_transformed.size (); ++i)
189  {
190  points[i * dim_ + 0] = static_cast<coordT> (cloud_transformed[i].x);
191  points[i * dim_ + 1] = static_cast<coordT> (cloud_transformed[i].y);
192 
193  if (dim_ > 2)
194  points[i * dim_ + 2] = static_cast<coordT> (cloud_transformed[i].z);
195  }
196 
197  // Compute concave hull
198  exitcode = qh_new_qhull (dim_, static_cast<int> (cloud_transformed.size ()), points, ismalloc, flags, outfile, errfile);
199 
200  if (exitcode != 0)
201  {
202  PCL_ERROR("[pcl::%s::performReconstrution] ERROR: qhull was unable to compute a "
203  "concave hull for the given point cloud (%zu)!\n",
204  getClassName().c_str(),
205  static_cast<std::size_t>(cloud_transformed.size()));
206 
207  //check if it fails because of NaN values...
208  if (!cloud_transformed.is_dense)
209  {
210  bool NaNvalues = false;
211  for (std::size_t i = 0; i < cloud_transformed.size (); ++i)
212  {
213  if (!std::isfinite (cloud_transformed[i].x) ||
214  !std::isfinite (cloud_transformed[i].y) ||
215  !std::isfinite (cloud_transformed[i].z))
216  {
217  NaNvalues = true;
218  break;
219  }
220  }
221 
222  if (NaNvalues)
223  PCL_ERROR ("[pcl::%s::performReconstruction] ERROR: point cloud contains NaN values, consider running pcl::PassThrough filter first to remove NaNs!\n", getClassName ().c_str ());
224  }
225 
226  alpha_shape.resize (0);
227  alpha_shape.width = alpha_shape.height = 0;
228  polygons.resize (0);
229 
230  qh_freeqhull (!qh_ALL);
231  int curlong, totlong;
232  qh_memfreeshort (&curlong, &totlong);
233 
234  return;
235  }
236 
237  qh_setvoronoi_all ();
238 
239  int num_vertices = qh num_vertices;
240  alpha_shape.resize (num_vertices);
241 
242  vertexT *vertex;
243  // Max vertex id
244  int max_vertex_id = 0;
245  FORALLvertices
246  {
247  if (vertex->id + 1 > unsigned (max_vertex_id))
248  max_vertex_id = vertex->id + 1;
249  }
250 
251  facetT *facet; // set by FORALLfacets
252 
253  ++max_vertex_id;
254  std::vector<int> qhid_to_pcidx (max_vertex_id);
255 
256  int num_facets = qh num_facets;
257 
258  if (dim_ == 3)
259  {
260  setT *triangles_set = qh_settemp (4 * num_facets);
261  if (voronoi_centers_)
262  voronoi_centers_->points.resize (num_facets);
263 
264  int non_upper = 0;
265  FORALLfacets
266  {
267  // Facets are tetrahedrons (3d)
268  if (!facet->upperdelaunay)
269  {
270  vertexT *anyVertex = static_cast<vertexT*> (facet->vertices->e[0].p);
271  double *center = facet->center;
272  double r = qh_pointdist (anyVertex->point,center,dim_);
273 
274  if (voronoi_centers_)
275  {
276  (*voronoi_centers_)[non_upper].x = static_cast<float> (facet->center[0]);
277  (*voronoi_centers_)[non_upper].y = static_cast<float> (facet->center[1]);
278  (*voronoi_centers_)[non_upper].z = static_cast<float> (facet->center[2]);
279  }
280 
281  non_upper++;
282 
283  if (r <= alpha_)
284  {
285  // all triangles in tetrahedron are good, add them all to the alpha shape (triangles_set)
286  qh_makeridges (facet);
287  facet->good = true;
288  facet->visitid = qh visit_id;
289  ridgeT *ridge, **ridgep;
290  FOREACHridge_ (facet->ridges)
291  {
292  facetT *neighb = otherfacet_ (ridge, facet);
293  if ((neighb->visitid != qh visit_id))
294  qh_setappend (&triangles_set, ridge);
295  }
296  }
297  else
298  {
299  // consider individual triangles from the tetrahedron...
300  facet->good = false;
301  facet->visitid = qh visit_id;
302  qh_makeridges (facet);
303  ridgeT *ridge, **ridgep;
304  FOREACHridge_ (facet->ridges)
305  {
306  facetT *neighb;
307  neighb = otherfacet_ (ridge, facet);
308  if ((neighb->visitid != qh visit_id))
309  {
310  // check if individual triangle is good and add it to triangles_set
311 
312  PointInT a, b, c;
313  a.x = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[0].p))->point[0]);
314  a.y = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[0].p))->point[1]);
315  a.z = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[0].p))->point[2]);
316  b.x = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[1].p))->point[0]);
317  b.y = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[1].p))->point[1]);
318  b.z = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[1].p))->point[2]);
319  c.x = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[2].p))->point[0]);
320  c.y = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[2].p))->point[1]);
321  c.z = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[2].p))->point[2]);
322 
323  double r = pcl::getCircumcircleRadius (a, b, c);
324  if (r <= alpha_)
325  qh_setappend (&triangles_set, ridge);
326  }
327  }
328  }
329  }
330  }
331 
332  if (voronoi_centers_)
333  voronoi_centers_->points.resize (non_upper);
334 
335  // filter, add points to alpha_shape and create polygon structure
336 
337  int num_good_triangles = 0;
338  ridgeT *ridge, **ridgep;
339  FOREACHridge_ (triangles_set)
340  {
341  if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good)
342  num_good_triangles++;
343  }
344 
345  polygons.resize (num_good_triangles);
346 
347  int vertices = 0;
348  std::vector<bool> added_vertices (max_vertex_id, false);
349 
350  int triangles = 0;
351  FOREACHridge_ (triangles_set)
352  {
353  if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good)
354  {
355  polygons[triangles].vertices.resize (3);
356  int vertex_n, vertex_i;
357  FOREACHvertex_i_ ((*ridge).vertices) //3 vertices per ridge!
358  {
359  if (!added_vertices[vertex->id])
360  {
361  alpha_shape[vertices].x = static_cast<float> (vertex->point[0]);
362  alpha_shape[vertices].y = static_cast<float> (vertex->point[1]);
363  alpha_shape[vertices].z = static_cast<float> (vertex->point[2]);
364 
365  qhid_to_pcidx[vertex->id] = vertices; //map the vertex id of qhull to the point cloud index
366  added_vertices[vertex->id] = true;
367  vertices++;
368  }
369 
370  polygons[triangles].vertices[vertex_i] = qhid_to_pcidx[vertex->id];
371 
372  }
373 
374  triangles++;
375  }
376  }
377 
378  alpha_shape.resize (vertices);
379  alpha_shape.width = alpha_shape.size ();
380  alpha_shape.height = 1;
381  }
382  else
383  {
384  // Compute the alpha complex for the set of points
385  // Filters the delaunay triangles
386  setT *edges_set = qh_settemp (3 * num_facets);
387  if (voronoi_centers_)
388  voronoi_centers_->points.resize (num_facets);
389 
390  int dd = 0;
391  FORALLfacets
392  {
393  // Facets are the delaunay triangles (2d)
394  if (!facet->upperdelaunay)
395  {
396  // Check if the distance from any vertex to the facet->center
397  // (center of the voronoi cell) is smaller than alpha
398  vertexT *anyVertex = static_cast<vertexT*>(facet->vertices->e[0].p);
399  double r = (sqrt ((anyVertex->point[0] - facet->center[0]) *
400  (anyVertex->point[0] - facet->center[0]) +
401  (anyVertex->point[1] - facet->center[1]) *
402  (anyVertex->point[1] - facet->center[1])));
403  if (r <= alpha_)
404  {
405  pcl::Vertices facet_vertices; //TODO: is not used!!
406  qh_makeridges (facet);
407  facet->good = true;
408 
409  ridgeT *ridge, **ridgep;
410  FOREACHridge_ (facet->ridges)
411  qh_setappend (&edges_set, ridge);
412 
413  if (voronoi_centers_)
414  {
415  (*voronoi_centers_)[dd].x = static_cast<float> (facet->center[0]);
416  (*voronoi_centers_)[dd].y = static_cast<float> (facet->center[1]);
417  (*voronoi_centers_)[dd].z = 0.0f;
418  }
419 
420  ++dd;
421  }
422  else
423  facet->good = false;
424  }
425  }
426 
427  int vertices = 0;
428  std::vector<bool> added_vertices (max_vertex_id, false);
429  std::map<int, std::vector<int> > edges;
430 
431  ridgeT *ridge, **ridgep;
432  FOREACHridge_ (edges_set)
433  {
434  if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good)
435  {
436  int vertex_n, vertex_i;
437  int vertices_in_ridge=0;
438  std::vector<int> pcd_indices;
439  pcd_indices.resize (2);
440 
441  FOREACHvertex_i_ ((*ridge).vertices) //in 2-dim, 2 vertices per ridge!
442  {
443  if (!added_vertices[vertex->id])
444  {
445  alpha_shape[vertices].x = static_cast<float> (vertex->point[0]);
446  alpha_shape[vertices].y = static_cast<float> (vertex->point[1]);
447 
448  if (dim_ > 2)
449  alpha_shape[vertices].z = static_cast<float> (vertex->point[2]);
450  else
451  alpha_shape[vertices].z = 0;
452 
453  qhid_to_pcidx[vertex->id] = vertices; //map the vertex id of qhull to the point cloud index
454  added_vertices[vertex->id] = true;
455  pcd_indices[vertices_in_ridge] = vertices;
456  vertices++;
457  }
458  else
459  {
460  pcd_indices[vertices_in_ridge] = qhid_to_pcidx[vertex->id];
461  }
462 
463  vertices_in_ridge++;
464  }
465 
466  // make edges bidirectional and pointing to alpha_shape pointcloud...
467  edges[pcd_indices[0]].push_back (pcd_indices[1]);
468  edges[pcd_indices[1]].push_back (pcd_indices[0]);
469  }
470  }
471 
472  alpha_shape.resize (vertices);
473 
474  PointCloud alpha_shape_sorted;
475  alpha_shape_sorted.resize (vertices);
476 
477  // iterate over edges until they are empty!
478  std::map<int, std::vector<int> >::iterator curr = edges.begin ();
479  int next = - 1;
480  std::vector<bool> used (vertices, false); // used to decide which direction should we take!
481  std::vector<int> pcd_idx_start_polygons;
482  pcd_idx_start_polygons.push_back (0);
483 
484  // start following edges and removing elements
485  int sorted_idx = 0;
486  while (!edges.empty ())
487  {
488  alpha_shape_sorted[sorted_idx] = alpha_shape[(*curr).first];
489  // check where we can go from (*curr).first
490  for (const auto &i : (*curr).second)
491  {
492  if (!used[i])
493  {
494  // we can go there
495  next = i;
496  break;
497  }
498  }
499 
500  used[(*curr).first] = true;
501  edges.erase (curr); // remove edges starting from curr
502 
503  sorted_idx++;
504 
505  if (edges.empty ())
506  break;
507 
508  // reassign current
509  curr = edges.find (next); // if next is not found, then we have unconnected polygons.
510  if (curr == edges.end ())
511  {
512  // set current to any of the remaining in edge!
513  curr = edges.begin ();
514  pcd_idx_start_polygons.push_back (sorted_idx);
515  }
516  }
517 
518  pcd_idx_start_polygons.push_back (sorted_idx);
519 
520  alpha_shape.points = alpha_shape_sorted.points;
521 
522  polygons.reserve (pcd_idx_start_polygons.size () - 1);
523 
524  for (std::size_t poly_id = 0; poly_id < pcd_idx_start_polygons.size () - 1; poly_id++)
525  {
526  // Check if we actually have a polygon, and not some degenerated output from QHull
527  if (pcd_idx_start_polygons[poly_id + 1] - pcd_idx_start_polygons[poly_id] >= 3)
528  {
529  pcl::Vertices vertices;
530  vertices.vertices.resize (pcd_idx_start_polygons[poly_id + 1] - pcd_idx_start_polygons[poly_id]);
531  // populate points in the corresponding polygon
532  for (int j = pcd_idx_start_polygons[poly_id]; j < pcd_idx_start_polygons[poly_id + 1]; ++j)
533  vertices.vertices[j - pcd_idx_start_polygons[poly_id]] = static_cast<std::uint32_t> (j);
534 
535  polygons.push_back (vertices);
536  }
537  }
538 
539  if (voronoi_centers_)
540  voronoi_centers_->points.resize (dd);
541  }
542 
543  qh_freeqhull (!qh_ALL);
544  int curlong, totlong;
545  qh_memfreeshort (&curlong, &totlong);
546 
547  Eigen::Affine3d transInverse = transform1.inverse ();
548  pcl::transformPointCloud (alpha_shape, alpha_shape, transInverse);
549  xyz_centroid[0] = - xyz_centroid[0];
550  xyz_centroid[1] = - xyz_centroid[1];
551  xyz_centroid[2] = - xyz_centroid[2];
552  pcl::demeanPointCloud (alpha_shape, xyz_centroid, alpha_shape);
553 
554  // also transform voronoi_centers_...
555  if (voronoi_centers_)
556  {
557  pcl::transformPointCloud (*voronoi_centers_, *voronoi_centers_, transInverse);
558  pcl::demeanPointCloud (*voronoi_centers_, xyz_centroid, *voronoi_centers_);
559  }
560 
561  if (keep_information_)
562  {
563  // build a tree with the original points
564  pcl::KdTreeFLANN<PointInT> tree (true);
565  tree.setInputCloud (input_, indices_);
566 
567  pcl::Indices neighbor;
568  std::vector<float> distances;
569  neighbor.resize (1);
570  distances.resize (1);
571 
572  // for each point in the concave hull, search for the nearest neighbor in the original point cloud
573  hull_indices_.header = input_->header;
574  hull_indices_.indices.clear ();
575  hull_indices_.indices.reserve (alpha_shape.size ());
576 
577  for (const auto& point: alpha_shape)
578  {
579  tree.nearestKSearch (point, 1, neighbor, distances);
580  hull_indices_.indices.push_back (neighbor[0]);
581  }
582 
583  // replace point with the closest neighbor in the original point cloud
584  pcl::copyPointCloud (*input_, hull_indices_.indices, alpha_shape);
585  }
586 }
587 #ifdef __GNUC__
588 #pragma GCC diagnostic warning "-Wold-style-cast"
589 #endif
590 
591 //////////////////////////////////////////////////////////////////////////////////////////
592 template <typename PointInT> void
594 {
595  // Perform reconstruction
596  pcl::PointCloud<PointInT> hull_points;
597  performReconstruction (hull_points, output.polygons);
598 
599  // Convert the PointCloud into a PCLPointCloud2
600  pcl::toPCLPointCloud2 (hull_points, output.cloud);
601 }
602 
603 //////////////////////////////////////////////////////////////////////////////////////////
604 template <typename PointInT> void
605 pcl::ConcaveHull<PointInT>::performReconstruction (std::vector<pcl::Vertices> &polygons)
606 {
607  pcl::PointCloud<PointInT> hull_points;
608  performReconstruction (hull_points, polygons);
609 }
610 
611 //////////////////////////////////////////////////////////////////////////////////////////
612 template <typename PointInT> void
614 {
615  hull_point_indices = hull_indices_;
616 }
617 
618 #define PCL_INSTANTIATE_ConcaveHull(T) template class PCL_EXPORTS pcl::ConcaveHull<T>;
619 
620 #endif // PCL_SURFACE_IMPL_CONCAVE_HULL_H_
621 #endif
pcl::PolygonMesh::cloud
::pcl::PCLPointCloud2 cloud
Definition: PolygonMesh.h:21
pcl::PointCloud::height
std::uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:393
common.h
pcl::PointCloud::points
std::vector< PointT, Eigen::aligned_allocator< PointT > > points
The point data.
Definition: point_cloud.h:388
pcl::ConcaveHull::reconstruct
void reconstruct(PointCloud &points, std::vector< pcl::Vertices > &polygons)
Compute a concave hull for all points given.
Definition: concave_hull.hpp:88
pcl::PointCloud::erase
iterator erase(iterator position)
Erase a point in the cloud.
Definition: point_cloud.h:628
pcl::computeCovarianceMatrixNormalized
unsigned int computeCovarianceMatrixNormalized(const pcl::PointCloud< PointT > &cloud, const Eigen::Matrix< Scalar, 4, 1 > &centroid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix)
Compute normalized the 3x3 covariance matrix of a given set of points.
Definition: centroid.hpp:251
pcl::Vertices::vertices
Indices vertices
Definition: Vertices.h:19
pcl::getCircumcircleRadius
double getCircumcircleRadius(const PointT &pa, const PointT &pb, const PointT &pc)
Compute the radius of a circumscribed circle for a triangle formed of three points pa,...
Definition: common.hpp:443
pcl::demeanPointCloud
void demeanPointCloud(ConstCloudIterator< PointT > &cloud_iterator, const Eigen::Matrix< Scalar, 4, 1 > &centroid, pcl::PointCloud< PointT > &cloud_out, int npts=0)
Subtract a centroid from a point cloud and return the de-meaned representation.
Definition: centroid.hpp:627
pcl::PointCloud< PointInT >
pcl::eigen33
void eigen33(const Matrix &mat, typename Matrix::Scalar &eigenvalue, Vector &eigenvector)
determines the eigenvector and eigenvalue of the smallest eigenvalue of the symmetric positive semi d...
Definition: eigen.hpp:296
pcl::ConcaveHull::getHullPointIndices
void getHullPointIndices(pcl::PointIndices &hull_point_indices) const
Retrieve the indices of the input point cloud that for the convex hull.
Definition: concave_hull.hpp:613
pcl::copyPointCloud
void copyPointCloud(const pcl::PointCloud< PointInT > &cloud_in, pcl::PointCloud< PointOutT > &cloud_out)
Copy all the fields from a given point cloud into a new point cloud.
Definition: io.hpp:122
pcl::transformPointCloud
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const Eigen::Matrix< Scalar, 4, 4 > &transform, bool copy_all_fields)
Apply a rigid transform defined by a 4x4 matrix.
Definition: transforms.hpp:221
pcl::KdTreeFLANN::nearestKSearch
int nearestKSearch(const PointT &point, unsigned int k, std::vector< int > &k_indices, std::vector< float > &k_sqr_distances) const override
Search for k-nearest neighbors for the given query point.
Definition: kdtree_flann.hpp:132
pcl::PointCloud::width
std::uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:391
pcl::KdTreeFLANN
KdTreeFLANN is a generic type of 3D spatial locator using kD-tree structures.
Definition: kdtree_flann.h:64
pcl::PolygonMesh
Definition: PolygonMesh.h:14
pcl::PointCloud::is_dense
bool is_dense
True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields).
Definition: point_cloud.h:396
pcl::PointCloud::resize
void resize(std::size_t count)
Resizes the container to contain count elements.
Definition: point_cloud.h:455
pcl::PointIndices
Definition: PointIndices.h:11
pcl::PointCloud::header
pcl::PCLHeader header
The point cloud header.
Definition: point_cloud.h:385
pcl::Indices
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:131
pcl::PointCloud::size
std::size_t size() const
Definition: point_cloud.h:436
pcl::PointCloud::clear
void clear()
Removes all points in a cloud and sets the width and height to 0.
Definition: point_cloud.h:668
pcl::Vertices
Describes a set of vertices in a polygon mesh, by basically storing an array of indices.
Definition: Vertices.h:14
pcl::PolygonMesh::polygons
std::vector< ::pcl::Vertices > polygons
Definition: PolygonMesh.h:23
pcl::compute3DCentroid
unsigned int compute3DCentroid(ConstCloudIterator< PointT > &cloud_iterator, Eigen::Matrix< Scalar, 4, 1 > &centroid)
Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector.
Definition: centroid.hpp:56
pcl::toPCLPointCloud2
void toPCLPointCloud2(const pcl::PointCloud< PointT > &cloud, pcl::PCLPointCloud2 &msg)
Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
Definition: conversions.h:240
pcl::PointCloud::push_back
void push_back(const PointT &pt)
Insert a new point in the cloud, at the end of the container.
Definition: point_cloud.h:543
pcl::ConcaveHull::performReconstruction
void performReconstruction(PointCloud &points, std::vector< pcl::Vertices > &polygons)
The actual reconstruction method.
Definition: concave_hull.hpp:119
pcl::KdTreeFLANN::setInputCloud
void setInputCloud(const PointCloudConstPtr &cloud, const IndicesConstPtr &indices=IndicesConstPtr()) override
Provide a pointer to the input dataset.
Definition: kdtree_flann.hpp:92
centroid.h