Point Cloud Library (PCL)  1.15.1-dev
convex_hull.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2012, 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_CONVEX_HULL_H_
44 #define PCL_SURFACE_IMPL_CONVEX_HULL_H_
45 
46 #include <pcl/surface/convex_hull.h>
47 #include <pcl/common/common.h>
48 #include <pcl/common/eigen.h>
49 #include <pcl/common/transforms.h>
50 #include <pcl/common/io.h>
51 #include <cstdio>
52 #include <cstdlib>
53 #include <pcl/surface/qhull.h>
54 
55 //////////////////////////////////////////////////////////////////////////
56 template <typename PointInT> void
58 {
59  PCL_DEBUG ("[pcl::%s::calculateInputDimension] WARNING: Input dimension not specified. Automatically determining input dimension.\n", getClassName ().c_str ());
60  Eigen::Vector4d xyz_centroid;
61  compute3DCentroid (*input_, *indices_, xyz_centroid);
62  EIGEN_ALIGN16 Eigen::Matrix3d covariance_matrix = Eigen::Matrix3d::Zero ();
63  computeCovarianceMatrixNormalized (*input_, *indices_, xyz_centroid, covariance_matrix);
64 
65  EIGEN_ALIGN16 Eigen::Vector3d eigen_values;
66  pcl::eigen33 (covariance_matrix, eigen_values);
67 
68  if (std::abs (eigen_values[0]) < std::numeric_limits<double>::epsilon () || std::abs (eigen_values[0] / eigen_values[2]) < 1.0e-3)
69  dimension_ = 2;
70  else
71  dimension_ = 3;
72 }
73 
74 //////////////////////////////////////////////////////////////////////////
75 template <typename PointInT> void
76 pcl::ConvexHull<PointInT>::performReconstruction2D (PointCloud &hull, std::vector<pcl::Vertices> &polygons,
77  bool)
78 {
79  int dimension = 2;
80  bool xy_proj_safe = true;
81  bool yz_proj_safe = true;
82  bool xz_proj_safe = true;
83 
84  Eigen::Vector4d normal_calc_centroid;
85  Eigen::Matrix3d normal_calc_covariance;
86 
87  // Check the input's normal to see which projection to use
88  PointInT p0 = (*input_)[(*indices_)[0]];
89  PointInT p1 = (*input_)[(*indices_)[indices_->size () - 1]];
90  PointInT p2 = (*input_)[(*indices_)[indices_->size () / 2]];
91  if (pcl::isXYZFinite(p0) && pcl::isXYZFinite(p1) && pcl::isXYZFinite(p2) &&
92  (p1.getVector3fMap() - p0.getVector3fMap())
93  .cross(p2.getVector3fMap() - p0.getVector3fMap())
94  .stableNorm() > Eigen::NumTraits<float>::dummy_precision()) {
95  pcl::PointCloud<PointInT> normal_calc_cloud;
96  normal_calc_cloud.resize(3);
97  normal_calc_cloud[0] = p0;
98  normal_calc_cloud[1] = p1;
99  normal_calc_cloud[2] = p2;
100 
101  pcl::compute3DCentroid(normal_calc_cloud, normal_calc_centroid);
103  normal_calc_cloud, normal_calc_centroid, normal_calc_covariance);
104  }
105  else {
106  // Three points do not form a valid triangle, fallback to use all points to
107  // calculate the covariance matrix
108  pcl::compute3DCentroid(*input_, *indices_, normal_calc_centroid);
110  *input_, *indices_, normal_calc_centroid, normal_calc_covariance);
111  }
112 
113  // Need to set -1 here. See eigen33 for explanations.
114  Eigen::Vector3d::Scalar eigen_value;
115  Eigen::Vector3d plane_params;
116  pcl::eigen33 (normal_calc_covariance, eigen_value, plane_params);
117  float theta_x = std::abs (static_cast<float> (plane_params.dot (x_axis_)));
118  float theta_y = std::abs (static_cast<float> (plane_params.dot (y_axis_)));
119  float theta_z = std::abs (static_cast<float> (plane_params.dot (z_axis_)));
120 
121  // Check for degenerate cases of each projection
122  // We must avoid projections in which the plane projects as a line
123  if (theta_z > projection_angle_thresh_)
124  {
125  xz_proj_safe = false;
126  yz_proj_safe = false;
127  }
128  if (theta_x > projection_angle_thresh_)
129  {
130  xz_proj_safe = false;
131  xy_proj_safe = false;
132  }
133  if (theta_y > projection_angle_thresh_)
134  {
135  xy_proj_safe = false;
136  yz_proj_safe = false;
137  }
138 
139  // True if qhull should free points in qh_freeqhull() or reallocation
140  boolT ismalloc = True;
141  // output from qh_produce_output(), use NULL to skip qh_produce_output()
142  FILE *outfile = nullptr;
143 
145  outfile = stderr;
146 
147  // option flags for qhull, see qh_opt.htm
148  const char* flags = qhull_flags.c_str ();
149  // error messages from qhull code
150  FILE *errfile = stderr;
151 
152  // Array of coordinates for each point
153  coordT *points = reinterpret_cast<coordT*> (calloc (indices_->size () * dimension, sizeof (coordT)));
154 
155  // Build input data, using appropriate projection
156  int j = 0;
157  if (xy_proj_safe)
158  {
159  for (std::size_t i = 0; i < indices_->size (); ++i, j+=dimension)
160  {
161  points[j + 0] = static_cast<coordT> ((*input_)[(*indices_)[i]].x);
162  points[j + 1] = static_cast<coordT> ((*input_)[(*indices_)[i]].y);
163  }
164  }
165  else if (yz_proj_safe)
166  {
167  for (std::size_t i = 0; i < indices_->size (); ++i, j+=dimension)
168  {
169  points[j + 0] = static_cast<coordT> ((*input_)[(*indices_)[i]].y);
170  points[j + 1] = static_cast<coordT> ((*input_)[(*indices_)[i]].z);
171  }
172  }
173  else if (xz_proj_safe)
174  {
175  for (std::size_t i = 0; i < indices_->size (); ++i, j+=dimension)
176  {
177  points[j + 0] = static_cast<coordT> ((*input_)[(*indices_)[i]].x);
178  points[j + 1] = static_cast<coordT> ((*input_)[(*indices_)[i]].z);
179  }
180  }
181  else
182  {
183  // This should only happen if we had invalid input
184  PCL_ERROR ("[pcl::%s::performReconstruction2D] Invalid input!\n", getClassName ().c_str ());
185  }
186 
187  qhT qh_qh;
188  qhT* qh = &qh_qh;
189  QHULL_LIB_CHECK
190  qh_zero(qh, errfile);
191 
192  // Compute convex hull
193  int exitcode = qh_new_qhull (qh, dimension, static_cast<int> (indices_->size ()), points, ismalloc, const_cast<char*> (flags), outfile, errfile);
194  if (compute_area_)
195  {
196  qh_prepare_output(qh);
197  }
198 
199  // 0 if no error from qhull or it doesn't find any vertices
200  if (exitcode != 0 || qh->num_vertices == 0)
201  {
202  PCL_ERROR ("[pcl::%s::performReconstrution2D] ERROR: qhull was unable to compute a convex hull for the given point cloud (%lu)!\n", getClassName ().c_str (), indices_->size ());
203 
204  hull.resize (0);
205  hull.width = hull.height = 0;
206  polygons.resize (0);
207 
208  qh_freeqhull (qh, !qh_ALL);
209  int curlong, totlong;
210  qh_memfreeshort (qh, &curlong, &totlong);
211 
212  return;
213  }
214 
215  // Qhull returns the area in volume for 2D
216  if (compute_area_)
217  {
218  total_area_ = qh->totvol;
219  total_volume_ = 0.0;
220  }
221 
222  int num_vertices = qh->num_vertices;
223 
224  hull.clear();
225  hull.resize(num_vertices, PointInT{});
226 
227  vertexT * vertex;
228  int i = 0;
229 
230  AlignedVector<std::pair<int, Eigen::Vector4f>> idx_points (num_vertices);
231 
232  FORALLvertices
233  {
234  hull[i] = (*input_)[(*indices_)[qh_pointid (qh, vertex->point)]];
235  idx_points[i].first = qh_pointid (qh, vertex->point);
236  ++i;
237  }
238 
239  // Sort
240  Eigen::Vector4f centroid;
241  pcl::compute3DCentroid (hull, centroid);
242  if (xy_proj_safe)
243  {
244  for (std::size_t j = 0; j < hull.size (); j++)
245  {
246  idx_points[j].second[0] = hull[j].x - centroid[0];
247  idx_points[j].second[1] = hull[j].y - centroid[1];
248  }
249  }
250  else if (yz_proj_safe)
251  {
252  for (std::size_t j = 0; j < hull.size (); j++)
253  {
254  idx_points[j].second[0] = hull[j].y - centroid[1];
255  idx_points[j].second[1] = hull[j].z - centroid[2];
256  }
257  }
258  else if (xz_proj_safe)
259  {
260  for (std::size_t j = 0; j < hull.size (); j++)
261  {
262  idx_points[j].second[0] = hull[j].x - centroid[0];
263  idx_points[j].second[1] = hull[j].z - centroid[2];
264  }
265  }
266  std::sort (idx_points.begin (), idx_points.end (), comparePoints2D);
267 
268  polygons.resize (1);
269  polygons[0].vertices.resize (hull.size ());
270 
271  hull_indices_.header = input_->header;
272  hull_indices_.indices.clear ();
273  hull_indices_.indices.reserve (hull.size ());
274 
275  for (int j = 0; j < static_cast<int> (hull.size ()); j++)
276  {
277  hull_indices_.indices.push_back ((*indices_)[idx_points[j].first]);
278  hull[j] = (*input_)[(*indices_)[idx_points[j].first]];
279  polygons[0].vertices[j] = static_cast<unsigned int> (j);
280  }
281 
282  qh_freeqhull (qh, !qh_ALL);
283  int curlong, totlong;
284  qh_memfreeshort (qh, &curlong, &totlong);
285 
286  hull.width = hull.size ();
287  hull.height = 1;
288  hull.is_dense = false;
289  return;
290 }
291 
292 #ifdef __GNUC__
293 #pragma GCC diagnostic ignored "-Wold-style-cast"
294 #endif
295 //////////////////////////////////////////////////////////////////////////
296 template <typename PointInT> void
298  PointCloud &hull, std::vector<pcl::Vertices> &polygons, bool fill_polygon_data)
299 {
300  int dimension = 3;
301 
302  // True if qhull should free points in qh_freeqhull() or reallocation
303  boolT ismalloc = True;
304  // output from qh_produce_output(), use NULL to skip qh_produce_output()
305  FILE *outfile = nullptr;
306 
308  outfile = stderr;
309 
310  // option flags for qhull, see qh_opt.htm
311  const char *flags = qhull_flags.c_str ();
312  // error messages from qhull code
313  FILE *errfile = stderr;
314 
315  // Array of coordinates for each point
316  coordT *points = reinterpret_cast<coordT*> (calloc (indices_->size () * dimension, sizeof (coordT)));
317 
318  int j = 0;
319  for (std::size_t i = 0; i < indices_->size (); ++i, j+=dimension)
320  {
321  points[j + 0] = static_cast<coordT> ((*input_)[(*indices_)[i]].x);
322  points[j + 1] = static_cast<coordT> ((*input_)[(*indices_)[i]].y);
323  points[j + 2] = static_cast<coordT> ((*input_)[(*indices_)[i]].z);
324  }
325 
326  qhT qh_qh;
327  qhT* qh = &qh_qh;
328  QHULL_LIB_CHECK
329  qh_zero(qh, errfile);
330 
331  // Compute convex hull
332  int exitcode = qh_new_qhull (qh, dimension, static_cast<int> (indices_->size ()), points, ismalloc, const_cast<char*> (flags), outfile, errfile);
333  if (compute_area_)
334  {
335  qh_prepare_output(qh);
336  }
337 
338  // 0 if no error from qhull
339  if (exitcode != 0)
340  {
341  PCL_ERROR("[pcl::%s::performReconstrution3D] ERROR: qhull was unable to compute a "
342  "convex hull for the given point cloud (%zu)!\n",
343  getClassName().c_str(),
344  static_cast<std::size_t>(input_->size()));
345 
346  hull.resize (0);
347  hull.width = hull.height = 0;
348  polygons.resize (0);
349 
350  qh_freeqhull (qh, !qh_ALL);
351  int curlong, totlong;
352  qh_memfreeshort (qh, &curlong, &totlong);
353 
354  return;
355  }
356 
357  qh_triangulate (qh);
358 
359  int num_facets = qh->num_facets;
360 
361  int num_vertices = qh->num_vertices;
362  hull.resize (num_vertices);
363 
364  vertexT * vertex;
365  int i = 0;
366  // Max vertex id
367  unsigned int max_vertex_id = 0;
368  FORALLvertices
369  {
370  if (vertex->id + 1 > max_vertex_id)
371  max_vertex_id = vertex->id + 1;
372  }
373 
374  ++max_vertex_id;
375  std::vector<int> qhid_to_pcidx (max_vertex_id);
376 
377  hull_indices_.header = input_->header;
378  hull_indices_.indices.clear ();
379  hull_indices_.indices.reserve (num_vertices);
380 
381  FORALLvertices
382  {
383  // Add vertices to hull point_cloud and store index
384  hull_indices_.indices.push_back ((*indices_)[qh_pointid (qh, vertex->point)]);
385  hull[i] = (*input_)[hull_indices_.indices.back ()];
386 
387  qhid_to_pcidx[vertex->id] = i; // map the vertex id of qhull to the point cloud index
388  ++i;
389  }
390 
391  if (compute_area_)
392  {
393  total_area_ = qh->totarea;
394  total_volume_ = qh->totvol;
395  }
396 
397  if (fill_polygon_data)
398  {
399  polygons.resize (num_facets);
400  int dd = 0;
401 
402  facetT * facet;
403  FORALLfacets
404  {
405  polygons[dd].vertices.resize (3);
406 
407  // Needed by FOREACHvertex_i_
408  int vertex_n, vertex_i;
409  FOREACHvertex_i_ (qh, (*facet).vertices)
410  //facet_vertices.vertices.push_back (qhid_to_pcidx[vertex->id]);
411  polygons[dd].vertices[vertex_i] = qhid_to_pcidx[vertex->id];
412  ++dd;
413  }
414  }
415  // Deallocates memory (also the points)
416  qh_freeqhull (qh, !qh_ALL);
417  int curlong, totlong;
418  qh_memfreeshort (qh, &curlong, &totlong);
419 
420  hull.width = hull.size ();
421  hull.height = 1;
422  hull.is_dense = false;
423 }
424 #ifdef __GNUC__
425 #pragma GCC diagnostic warning "-Wold-style-cast"
426 #endif
427 
428 //////////////////////////////////////////////////////////////////////////
429 template <typename PointInT> void
430 pcl::ConvexHull<PointInT>::performReconstruction (PointCloud &hull, std::vector<pcl::Vertices> &polygons,
431  bool fill_polygon_data)
432 {
433  if (dimension_ == 0)
434  calculateInputDimension ();
435  if (dimension_ == 2)
436  performReconstruction2D (hull, polygons, fill_polygon_data);
437  else if (dimension_ == 3)
438  performReconstruction3D (hull, polygons, fill_polygon_data);
439  else
440  PCL_ERROR ("[pcl::%s::performReconstruction] Error: invalid input dimension requested: %d\n",getClassName ().c_str (),dimension_);
441 }
442 
443 //////////////////////////////////////////////////////////////////////////
444 template <typename PointInT> void
446 {
447  points.header = input_->header;
448  if (!initCompute () || input_->points.empty () || indices_->empty ())
449  {
450  points.clear ();
451  return;
452  }
453 
454  // Perform the actual surface reconstruction
455  std::vector<pcl::Vertices> polygons;
456  performReconstruction (points, polygons, false);
457 
458  points.width = points.size ();
459  points.height = 1;
460  points.is_dense = true;
461 
462  deinitCompute ();
463 }
464 
465 
466 //////////////////////////////////////////////////////////////////////////
467 template <typename PointInT> void
469 {
470  // Perform reconstruction
471  pcl::PointCloud<PointInT> hull_points;
472  performReconstruction (hull_points, output.polygons, true);
473 
474  // Convert the PointCloud into a PCLPointCloud2
475  pcl::toPCLPointCloud2 (hull_points, output.cloud);
476 }
477 
478 //////////////////////////////////////////////////////////////////////////
479 template <typename PointInT> void
480 pcl::ConvexHull<PointInT>::performReconstruction (std::vector<pcl::Vertices> &polygons)
481 {
482  pcl::PointCloud<PointInT> hull_points;
483  performReconstruction (hull_points, polygons, true);
484 }
485 
486 //////////////////////////////////////////////////////////////////////////
487 template <typename PointInT> void
488 pcl::ConvexHull<PointInT>::reconstruct (PointCloud &points, std::vector<pcl::Vertices> &polygons)
489 {
490  points.header = input_->header;
491  if (!initCompute () || input_->points.empty () || indices_->empty ())
492  {
493  points.clear ();
494  return;
495  }
496 
497  // Perform the actual surface reconstruction
498  performReconstruction (points, polygons, true);
499 
500  points.width = points.size ();
501  points.height = 1;
502  points.is_dense = true;
503 
504  deinitCompute ();
505 }
506 //////////////////////////////////////////////////////////////////////////
507 template <typename PointInT> void
509 {
510  hull_point_indices = hull_indices_;
511 }
512 
513 #define PCL_INSTANTIATE_ConvexHull(T) template class PCL_EXPORTS pcl::ConvexHull<T>;
514 
515 #endif // PCL_SURFACE_IMPL_CONVEX_HULL_H_
516 #endif
void calculateInputDimension()
Automatically determines the dimension of input data - 2D or 3D.
Definition: convex_hull.hpp:57
void performReconstruction2D(PointCloud &points, std::vector< pcl::Vertices > &polygons, bool fill_polygon_data=false)
The reconstruction method for 2D data.
Definition: convex_hull.hpp:76
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, bool fill_polygon_data=false)
The actual reconstruction method.
void reconstruct(PointCloud &points, std::vector< pcl::Vertices > &polygons)
Compute a convex hull for all points given.
void performReconstruction3D(PointCloud &points, std::vector< pcl::Vertices > &polygons, bool fill_polygon_data=false)
The reconstruction method for 3D data.
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:404
void resize(std::size_t count)
Resizes the container to contain count elements.
Definition: point_cloud.h:463
std::uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:399
pcl::PCLHeader header
The point cloud header.
Definition: point_cloud.h:393
std::uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:401
void clear()
Removes all points in a cloud and sets the width and height to 0.
Definition: point_cloud.h:886
std::size_t size() const
Definition: point_cloud.h:444
Define standard C methods and C++ classes that are common to all methods.
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
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
bool comparePoints2D(const std::pair< int, Eigen::Vector4f > &p1, const std::pair< int, Eigen::Vector4f > &p2)
Sort 2D points in a vector structure.
Definition: convex_hull.h:59
PCL_EXPORTS bool isVerbosityLevelEnabled(VERBOSITY_LEVEL severity)
is verbosity level enabled?
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:372
std::vector< T, Eigen::aligned_allocator< T > > AlignedVector
Type used for aligned vector of Eigen objects in PCL.
Definition: types.h:139
constexpr bool isXYZFinite(const PointT &) noexcept
Definition: point_tests.h:125
std::vector< ::pcl::Vertices > polygons
Definition: PolygonMesh.h:22
::pcl::PCLPointCloud2 cloud
Definition: PolygonMesh.h:20