Point Cloud Library (PCL)  1.14.0-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  qhT qh_qh;
198  qhT* qh = &qh_qh;
199  QHULL_LIB_CHECK
200  qh_zero(qh, errfile);
201 
202  // Compute concave hull
203  exitcode = qh_new_qhull (qh, dim_, static_cast<int> (cloud_transformed.size ()), points, ismalloc, flags, outfile, errfile);
204 
205  if (exitcode != 0)
206  {
207  PCL_ERROR("[pcl::%s::performReconstrution] ERROR: qhull was unable to compute a "
208  "concave hull for the given point cloud (%zu)!\n",
209  getClassName().c_str(),
210  static_cast<std::size_t>(cloud_transformed.size()));
211 
212  //check if it fails because of NaN values...
213  if (!cloud_transformed.is_dense)
214  {
215  bool NaNvalues = false;
216  for (std::size_t i = 0; i < cloud_transformed.size (); ++i)
217  {
218  if (!std::isfinite (cloud_transformed[i].x) ||
219  !std::isfinite (cloud_transformed[i].y) ||
220  !std::isfinite (cloud_transformed[i].z))
221  {
222  NaNvalues = true;
223  break;
224  }
225  }
226 
227  if (NaNvalues)
228  PCL_ERROR ("[pcl::%s::performReconstruction] ERROR: point cloud contains NaN values, consider running pcl::PassThrough filter first to remove NaNs!\n", getClassName ().c_str ());
229  }
230 
231  alpha_shape.resize (0);
232  alpha_shape.width = alpha_shape.height = 0;
233  polygons.resize (0);
234 
235  qh_freeqhull (qh, !qh_ALL);
236  int curlong, totlong;
237  qh_memfreeshort (qh, &curlong, &totlong);
238 
239  return;
240  }
241 
242  qh_setvoronoi_all (qh);
243 
244  int num_vertices = qh->num_vertices;
245  alpha_shape.resize (num_vertices);
246 
247  vertexT *vertex;
248  // Max vertex id
249  int max_vertex_id = 0;
250  FORALLvertices
251  {
252  if (vertex->id + 1 > static_cast<unsigned>(max_vertex_id))
253  max_vertex_id = vertex->id + 1;
254  }
255 
256  facetT *facet; // set by FORALLfacets
257 
258  ++max_vertex_id;
259  std::vector<int> qhid_to_pcidx (max_vertex_id);
260 
261  int num_facets = qh->num_facets;
262 
263  if (dim_ == 3)
264  {
265  setT *triangles_set = qh_settemp (qh, 4 * num_facets);
266  if (voronoi_centers_)
267  voronoi_centers_->points.resize (num_facets);
268 
269  int non_upper = 0;
270  FORALLfacets
271  {
272  // Facets are tetrahedrons (3d)
273  if (!facet->upperdelaunay)
274  {
275  auto *anyVertex = static_cast<vertexT*> (facet->vertices->e[0].p);
276  double *center = facet->center;
277  double r = qh_pointdist (anyVertex->point,center,dim_);
278 
279  if (voronoi_centers_)
280  {
281  (*voronoi_centers_)[non_upper].x = static_cast<float> (facet->center[0]);
282  (*voronoi_centers_)[non_upper].y = static_cast<float> (facet->center[1]);
283  (*voronoi_centers_)[non_upper].z = static_cast<float> (facet->center[2]);
284  }
285 
286  non_upper++;
287 
288  if (r <= alpha_)
289  {
290  // all triangles in tetrahedron are good, add them all to the alpha shape (triangles_set)
291  qh_makeridges (qh, facet);
292  facet->good = true;
293  facet->visitid = qh->visit_id;
294  ridgeT *ridge, **ridgep;
295  FOREACHridge_ (facet->ridges)
296  {
297  facetT *neighb = otherfacet_ (ridge, facet);
298  if ((neighb->visitid != qh->visit_id))
299  qh_setappend (qh, &triangles_set, ridge);
300  }
301  }
302  else
303  {
304  // consider individual triangles from the tetrahedron...
305  facet->good = false;
306  facet->visitid = qh->visit_id;
307  qh_makeridges (qh, facet);
308  ridgeT *ridge, **ridgep;
309  FOREACHridge_ (facet->ridges)
310  {
311  facetT *neighb;
312  neighb = otherfacet_ (ridge, facet);
313  if ((neighb->visitid != qh->visit_id))
314  {
315  // check if individual triangle is good and add it to triangles_set
316 
317  PointInT a, b, c;
318  a.x = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[0].p))->point[0]);
319  a.y = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[0].p))->point[1]);
320  a.z = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[0].p))->point[2]);
321  b.x = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[1].p))->point[0]);
322  b.y = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[1].p))->point[1]);
323  b.z = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[1].p))->point[2]);
324  c.x = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[2].p))->point[0]);
325  c.y = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[2].p))->point[1]);
326  c.z = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[2].p))->point[2]);
327 
328  double r = pcl::getCircumcircleRadius (a, b, c);
329  if (r <= alpha_)
330  qh_setappend (qh, &triangles_set, ridge);
331  }
332  }
333  }
334  }
335  }
336 
337  if (voronoi_centers_)
338  voronoi_centers_->points.resize (non_upper);
339 
340  // filter, add points to alpha_shape and create polygon structure
341 
342  int num_good_triangles = 0;
343  ridgeT *ridge, **ridgep;
344  FOREACHridge_ (triangles_set)
345  {
346  if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good)
347  num_good_triangles++;
348  }
349 
350  polygons.resize (num_good_triangles);
351 
352  int vertices = 0;
353  std::vector<bool> added_vertices (max_vertex_id, false);
354 
355  int triangles = 0;
356  FOREACHridge_ (triangles_set)
357  {
358  if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good)
359  {
360  polygons[triangles].vertices.resize (3);
361  int vertex_n, vertex_i;
362  FOREACHvertex_i_ (qh, (*ridge).vertices) //3 vertices per ridge!
363  {
364  if (!added_vertices[vertex->id])
365  {
366  alpha_shape[vertices].x = static_cast<float> (vertex->point[0]);
367  alpha_shape[vertices].y = static_cast<float> (vertex->point[1]);
368  alpha_shape[vertices].z = static_cast<float> (vertex->point[2]);
369 
370  qhid_to_pcidx[vertex->id] = vertices; //map the vertex id of qhull to the point cloud index
371  added_vertices[vertex->id] = true;
372  vertices++;
373  }
374 
375  polygons[triangles].vertices[vertex_i] = qhid_to_pcidx[vertex->id];
376 
377  }
378 
379  triangles++;
380  }
381  }
382 
383  alpha_shape.resize (vertices);
384  alpha_shape.width = alpha_shape.size ();
385  alpha_shape.height = 1;
386  }
387  else
388  {
389  // Compute the alpha complex for the set of points
390  // Filters the delaunay triangles
391  setT *edges_set = qh_settemp (qh, 3 * num_facets);
392  if (voronoi_centers_)
393  voronoi_centers_->points.resize (num_facets);
394 
395  int dd = 0;
396  FORALLfacets
397  {
398  // Facets are the delaunay triangles (2d)
399  if (!facet->upperdelaunay)
400  {
401  // Check if the distance from any vertex to the facet->center
402  // (center of the voronoi cell) is smaller than alpha
403  auto *anyVertex = static_cast<vertexT*>(facet->vertices->e[0].p);
404  double r = (sqrt ((anyVertex->point[0] - facet->center[0]) *
405  (anyVertex->point[0] - facet->center[0]) +
406  (anyVertex->point[1] - facet->center[1]) *
407  (anyVertex->point[1] - facet->center[1])));
408  if (r <= alpha_)
409  {
410  pcl::Vertices facet_vertices; //TODO: is not used!!
411  qh_makeridges (qh, facet);
412  facet->good = true;
413 
414  ridgeT *ridge, **ridgep;
415  FOREACHridge_ (facet->ridges)
416  qh_setappend (qh, &edges_set, ridge);
417 
418  if (voronoi_centers_)
419  {
420  (*voronoi_centers_)[dd].x = static_cast<float> (facet->center[0]);
421  (*voronoi_centers_)[dd].y = static_cast<float> (facet->center[1]);
422  (*voronoi_centers_)[dd].z = 0.0f;
423  }
424 
425  ++dd;
426  }
427  else
428  facet->good = false;
429  }
430  }
431 
432  int vertices = 0;
433  std::vector<bool> added_vertices (max_vertex_id, false);
434  std::map<int, std::vector<int> > edges;
435 
436  ridgeT *ridge, **ridgep;
437  FOREACHridge_ (edges_set)
438  {
439  if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good)
440  {
441  int vertex_n, vertex_i;
442  int vertices_in_ridge=0;
443  std::vector<int> pcd_indices;
444  pcd_indices.resize (2);
445 
446  FOREACHvertex_i_ (qh, (*ridge).vertices) //in 2-dim, 2 vertices per ridge!
447  {
448  if (!added_vertices[vertex->id])
449  {
450  alpha_shape[vertices].x = static_cast<float> (vertex->point[0]);
451  alpha_shape[vertices].y = static_cast<float> (vertex->point[1]);
452 
453  if (dim_ > 2)
454  alpha_shape[vertices].z = static_cast<float> (vertex->point[2]);
455  else
456  alpha_shape[vertices].z = 0;
457 
458  qhid_to_pcidx[vertex->id] = vertices; //map the vertex id of qhull to the point cloud index
459  added_vertices[vertex->id] = true;
460  pcd_indices[vertices_in_ridge] = vertices;
461  vertices++;
462  }
463  else
464  {
465  pcd_indices[vertices_in_ridge] = qhid_to_pcidx[vertex->id];
466  }
467 
468  vertices_in_ridge++;
469  }
470 
471  // make edges bidirectional and pointing to alpha_shape pointcloud...
472  edges[pcd_indices[0]].push_back (pcd_indices[1]);
473  edges[pcd_indices[1]].push_back (pcd_indices[0]);
474  }
475  }
476 
477  alpha_shape.resize (vertices);
478 
479  PointCloud alpha_shape_sorted;
480  alpha_shape_sorted.resize (vertices);
481 
482  // iterate over edges until they are empty!
483  auto curr = edges.begin ();
484  int next = - 1;
485  std::vector<bool> used (vertices, false); // used to decide which direction should we take!
486  std::vector<int> pcd_idx_start_polygons;
487  pcd_idx_start_polygons.push_back (0);
488 
489  // start following edges and removing elements
490  int sorted_idx = 0;
491  while (!edges.empty ())
492  {
493  alpha_shape_sorted[sorted_idx] = alpha_shape[(*curr).first];
494  // check where we can go from (*curr).first
495  for (const auto &i : (*curr).second)
496  {
497  if (!used[i])
498  {
499  // we can go there
500  next = i;
501  break;
502  }
503  }
504 
505  used[(*curr).first] = true;
506  edges.erase (curr); // remove edges starting from curr
507 
508  sorted_idx++;
509 
510  if (edges.empty ())
511  break;
512 
513  // reassign current
514  curr = edges.find (next); // if next is not found, then we have unconnected polygons.
515  if (curr == edges.end ())
516  {
517  // set current to any of the remaining in edge!
518  curr = edges.begin ();
519  pcd_idx_start_polygons.push_back (sorted_idx);
520  }
521  }
522 
523  pcd_idx_start_polygons.push_back (sorted_idx);
524 
525  alpha_shape.points = alpha_shape_sorted.points;
526 
527  polygons.reserve (pcd_idx_start_polygons.size () - 1);
528 
529  for (std::size_t poly_id = 0; poly_id < pcd_idx_start_polygons.size () - 1; poly_id++)
530  {
531  // Check if we actually have a polygon, and not some degenerated output from QHull
532  if (pcd_idx_start_polygons[poly_id + 1] - pcd_idx_start_polygons[poly_id] >= 3)
533  {
534  pcl::Vertices vertices;
535  vertices.vertices.resize (pcd_idx_start_polygons[poly_id + 1] - pcd_idx_start_polygons[poly_id]);
536  // populate points in the corresponding polygon
537  for (int j = pcd_idx_start_polygons[poly_id]; j < pcd_idx_start_polygons[poly_id + 1]; ++j)
538  vertices.vertices[j - pcd_idx_start_polygons[poly_id]] = static_cast<std::uint32_t> (j);
539 
540  polygons.push_back (vertices);
541  }
542  }
543 
544  if (voronoi_centers_)
545  voronoi_centers_->points.resize (dd);
546  }
547 
548  qh_freeqhull (qh, !qh_ALL);
549  int curlong, totlong;
550  qh_memfreeshort (qh, &curlong, &totlong);
551 
552  Eigen::Affine3d transInverse = transform1.inverse ();
553  pcl::transformPointCloud (alpha_shape, alpha_shape, transInverse);
554  xyz_centroid[0] = - xyz_centroid[0];
555  xyz_centroid[1] = - xyz_centroid[1];
556  xyz_centroid[2] = - xyz_centroid[2];
557  pcl::demeanPointCloud (alpha_shape, xyz_centroid, alpha_shape);
558 
559  // also transform voronoi_centers_...
560  if (voronoi_centers_)
561  {
562  pcl::transformPointCloud (*voronoi_centers_, *voronoi_centers_, transInverse);
563  pcl::demeanPointCloud (*voronoi_centers_, xyz_centroid, *voronoi_centers_);
564  }
565 
566  if (keep_information_)
567  {
568  // build a tree with the original points
569  pcl::KdTreeFLANN<PointInT> tree (true);
570  tree.setInputCloud (input_, indices_);
571 
572  pcl::Indices neighbor;
573  std::vector<float> distances;
574  neighbor.resize (1);
575  distances.resize (1);
576 
577  // for each point in the concave hull, search for the nearest neighbor in the original point cloud
578  hull_indices_.header = input_->header;
579  hull_indices_.indices.clear ();
580  hull_indices_.indices.reserve (alpha_shape.size ());
581 
582  for (const auto& point: alpha_shape)
583  {
584  tree.nearestKSearch (point, 1, neighbor, distances);
585  hull_indices_.indices.push_back (neighbor[0]);
586  }
587 
588  // replace point with the closest neighbor in the original point cloud
589  pcl::copyPointCloud (*input_, hull_indices_.indices, alpha_shape);
590  }
591 }
592 #ifdef __GNUC__
593 #pragma GCC diagnostic warning "-Wold-style-cast"
594 #endif
595 
596 //////////////////////////////////////////////////////////////////////////////////////////
597 template <typename PointInT> void
599 {
600  // Perform reconstruction
601  pcl::PointCloud<PointInT> hull_points;
602  performReconstruction (hull_points, output.polygons);
603 
604  // Convert the PointCloud into a PCLPointCloud2
605  pcl::toPCLPointCloud2 (hull_points, output.cloud);
606 }
607 
608 //////////////////////////////////////////////////////////////////////////////////////////
609 template <typename PointInT> void
610 pcl::ConcaveHull<PointInT>::performReconstruction (std::vector<pcl::Vertices> &polygons)
611 {
612  pcl::PointCloud<PointInT> hull_points;
613  performReconstruction (hull_points, polygons);
614 }
615 
616 //////////////////////////////////////////////////////////////////////////////////////////
617 template <typename PointInT> void
619 {
620  hull_point_indices = hull_indices_;
621 }
622 
623 #define PCL_INSTANTIATE_ConcaveHull(T) template class PCL_EXPORTS pcl::ConcaveHull<T>;
624 
625 #endif // PCL_SURFACE_IMPL_CONCAVE_HULL_H_
626 #endif
Define methods for centroid estimation and covariance matrix calculus.
void reconstruct(PointCloud &points, std::vector< pcl::Vertices > &polygons)
Compute a concave hull for all points given.
void getHullPointIndices(pcl::PointIndices &hull_point_indices) const
Retrieve the indices of the input point cloud that for the convex hull.
void performReconstruction(PointCloud &points, std::vector< pcl::Vertices > &polygons)
The actual reconstruction method.
KdTreeFLANN is a generic type of 3D spatial locator using kD-tree structures.
Definition: kdtree_flann.h:132
int nearestKSearch(const PointT &point, unsigned int k, Indices &k_indices, std::vector< float > &k_sqr_distances) const override
Search for k-nearest neighbors for the given query point.
void setInputCloud(const PointCloudConstPtr &cloud, const IndicesConstPtr &indices=IndicesConstPtr()) override
Provide a pointer to the input dataset.
iterator erase(iterator position)
Erase a point in the cloud.
Definition: point_cloud.h:820
void push_back(const PointT &pt)
Insert a new point in the cloud, at the end of the container.
Definition: point_cloud.h:663
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:403
void resize(std::size_t count)
Resizes the container to contain count elements.
Definition: point_cloud.h:462
std::uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:398
pcl::PCLHeader header
The point cloud header.
Definition: point_cloud.h:392
std::uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:400
void clear()
Removes all points in a cloud and sets the width and height to 0.
Definition: point_cloud.h:885
std::size_t size() const
Definition: point_cloud.h:443
std::vector< PointT, Eigen::aligned_allocator< PointT > > points
The point data.
Definition: point_cloud.h:395
Define standard C methods and C++ classes that are common to all methods.
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:933
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:269
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:383
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
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:295
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:57
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:142
void toPCLPointCloud2(const pcl::PointCloud< PointT > &cloud, pcl::PCLPointCloud2 &msg, bool padding)
Convert a pcl::PointCloud<T> object to a PCLPointCloud2 binary data blob.
Definition: conversions.h:305
IndicesAllocator<> Indices
Type used for indices in PCL.
Definition: types.h:133
std::vector< ::pcl::Vertices > polygons
Definition: PolygonMesh.h:22
::pcl::PCLPointCloud2 cloud
Definition: PolygonMesh.h:20
Describes a set of vertices in a polygon mesh, by basically storing an array of indices.
Definition: Vertices.h:15
Indices vertices
Definition: Vertices.h:18