40 #include <pcl/pcl_config.h>
43 #ifndef PCL_SURFACE_IMPL_CONVEX_HULL_H_
44 #define PCL_SURFACE_IMPL_CONVEX_HULL_H_
46 #include <pcl/surface/convex_hull.h>
48 #include <pcl/common/eigen.h>
49 #include <pcl/common/transforms.h>
50 #include <pcl/common/io.h>
53 #include <pcl/surface/qhull.h>
56 template <
typename Po
intInT>
void
59 PCL_DEBUG (
"[pcl::%s::calculateInputDimension] WARNING: Input dimension not specified. Automatically determining input dimension.\n", getClassName ().c_str ());
60 Eigen::Vector4d xyz_centroid;
62 EIGEN_ALIGN16 Eigen::Matrix3d covariance_matrix = Eigen::Matrix3d::Zero ();
65 EIGEN_ALIGN16 Eigen::Vector3d eigen_values;
68 if (std::abs (eigen_values[0]) < std::numeric_limits<double>::epsilon () || std::abs (eigen_values[0] / eigen_values[2]) < 1.0e-3)
75 template <
typename Po
intInT>
void
80 bool xy_proj_safe =
true;
81 bool yz_proj_safe =
true;
82 bool xz_proj_safe =
true;
84 Eigen::Vector4d normal_calc_centroid;
85 Eigen::Matrix3d normal_calc_covariance;
88 PointInT p0 = (*input_)[(*indices_)[0]];
89 PointInT p1 = (*input_)[(*indices_)[indices_->size () - 1]];
90 PointInT p2 = (*input_)[(*indices_)[indices_->size () / 2]];
92 (p1.getVector3fMap() - p0.getVector3fMap())
93 .cross(p2.getVector3fMap() - p0.getVector3fMap())
94 .stableNorm() > Eigen::NumTraits<float>::dummy_precision()) {
96 normal_calc_cloud.
resize(3);
97 normal_calc_cloud[0] = p0;
98 normal_calc_cloud[1] = p1;
99 normal_calc_cloud[2] = p2;
103 normal_calc_cloud, normal_calc_centroid, normal_calc_covariance);
110 *input_, *indices_, normal_calc_centroid, normal_calc_covariance);
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_)));
123 if (theta_z > projection_angle_thresh_)
125 xz_proj_safe =
false;
126 yz_proj_safe =
false;
128 if (theta_x > projection_angle_thresh_)
130 xz_proj_safe =
false;
131 xy_proj_safe =
false;
133 if (theta_y > projection_angle_thresh_)
135 xy_proj_safe =
false;
136 yz_proj_safe =
false;
140 boolT ismalloc = True;
142 FILE *outfile =
nullptr;
148 const char* flags = qhull_flags.c_str ();
150 FILE *errfile = stderr;
153 coordT *points =
reinterpret_cast<coordT*
> (calloc (indices_->size () * dimension, sizeof (coordT)));
159 for (std::size_t i = 0; i < indices_->size (); ++i, j+=dimension)
161 points[j + 0] =
static_cast<coordT
> ((*input_)[(*indices_)[i]].x);
162 points[j + 1] =
static_cast<coordT
> ((*input_)[(*indices_)[i]].y);
165 else if (yz_proj_safe)
167 for (std::size_t i = 0; i < indices_->size (); ++i, j+=dimension)
169 points[j + 0] =
static_cast<coordT
> ((*input_)[(*indices_)[i]].y);
170 points[j + 1] =
static_cast<coordT
> ((*input_)[(*indices_)[i]].z);
173 else if (xz_proj_safe)
175 for (std::size_t i = 0; i < indices_->size (); ++i, j+=dimension)
177 points[j + 0] =
static_cast<coordT
> ((*input_)[(*indices_)[i]].x);
178 points[j + 1] =
static_cast<coordT
> ((*input_)[(*indices_)[i]].z);
184 PCL_ERROR (
"[pcl::%s::performReconstruction2D] Invalid input!\n", getClassName ().c_str ());
190 qh_zero(qh, errfile);
193 int exitcode = qh_new_qhull (qh, dimension,
static_cast<int> (indices_->size ()), points, ismalloc,
const_cast<char*
> (flags), outfile, errfile);
196 qh_prepare_output(qh);
200 if (exitcode != 0 || qh->num_vertices == 0)
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 ());
208 qh_freeqhull (qh, !qh_ALL);
209 int curlong, totlong;
210 qh_memfreeshort (qh, &curlong, &totlong);
218 total_area_ = qh->totvol;
222 int num_vertices = qh->num_vertices;
225 hull.
resize(num_vertices, PointInT{});
234 hull[i] = (*input_)[(*indices_)[qh_pointid (qh, vertex->point)]];
235 idx_points[i].first = qh_pointid (qh, vertex->point);
240 Eigen::Vector4f centroid;
244 for (std::size_t j = 0; j < hull.
size (); j++)
246 idx_points[j].second[0] = hull[j].x - centroid[0];
247 idx_points[j].second[1] = hull[j].y - centroid[1];
250 else if (yz_proj_safe)
252 for (std::size_t j = 0; j < hull.
size (); j++)
254 idx_points[j].second[0] = hull[j].y - centroid[1];
255 idx_points[j].second[1] = hull[j].z - centroid[2];
258 else if (xz_proj_safe)
260 for (std::size_t j = 0; j < hull.
size (); j++)
262 idx_points[j].second[0] = hull[j].x - centroid[0];
263 idx_points[j].second[1] = hull[j].z - centroid[2];
269 polygons[0].vertices.resize (hull.
size ());
271 hull_indices_.header = input_->header;
272 hull_indices_.indices.clear ();
273 hull_indices_.indices.reserve (hull.
size ());
275 for (
int j = 0; j < static_cast<int> (hull.
size ()); j++)
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);
282 qh_freeqhull (qh, !qh_ALL);
283 int curlong, totlong;
284 qh_memfreeshort (qh, &curlong, &totlong);
293 #pragma GCC diagnostic ignored "-Wold-style-cast"
296 template <
typename Po
intInT>
void
298 PointCloud &hull, std::vector<pcl::Vertices> &polygons,
bool fill_polygon_data)
303 boolT ismalloc = True;
305 FILE *outfile =
nullptr;
311 const char *flags = qhull_flags.c_str ();
313 FILE *errfile = stderr;
316 coordT *points =
reinterpret_cast<coordT*
> (calloc (indices_->size () * dimension, sizeof (coordT)));
319 for (std::size_t i = 0; i < indices_->size (); ++i, j+=dimension)
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);
329 qh_zero(qh, errfile);
332 int exitcode = qh_new_qhull (qh, dimension,
static_cast<int> (indices_->size ()), points, ismalloc,
const_cast<char*
> (flags), outfile, errfile);
335 qh_prepare_output(qh);
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()));
350 qh_freeqhull (qh, !qh_ALL);
351 int curlong, totlong;
352 qh_memfreeshort (qh, &curlong, &totlong);
359 int num_facets = qh->num_facets;
361 int num_vertices = qh->num_vertices;
362 hull.
resize (num_vertices);
367 unsigned int max_vertex_id = 0;
370 if (vertex->id + 1 > max_vertex_id)
371 max_vertex_id = vertex->id + 1;
375 std::vector<int> qhid_to_pcidx (max_vertex_id);
377 hull_indices_.header = input_->header;
378 hull_indices_.indices.clear ();
379 hull_indices_.indices.reserve (num_vertices);
384 hull_indices_.indices.push_back ((*indices_)[qh_pointid (qh, vertex->point)]);
385 hull[i] = (*input_)[hull_indices_.indices.back ()];
387 qhid_to_pcidx[vertex->id] = i;
393 total_area_ = qh->totarea;
394 total_volume_ = qh->totvol;
397 if (fill_polygon_data)
399 polygons.
resize (num_facets);
405 polygons[dd].vertices.resize (3);
408 int vertex_n, vertex_i;
409 FOREACHvertex_i_ (qh, (*facet).vertices)
411 polygons[dd].vertices[vertex_i] = qhid_to_pcidx[vertex->id];
416 qh_freeqhull (qh, !qh_ALL);
417 int curlong, totlong;
418 qh_memfreeshort (qh, &curlong, &totlong);
425 #pragma GCC diagnostic warning "-Wold-style-cast"
429 template <
typename Po
intInT>
void
431 bool fill_polygon_data)
434 calculateInputDimension ();
436 performReconstruction2D (hull, polygons, fill_polygon_data);
437 else if (dimension_ == 3)
438 performReconstruction3D (hull, polygons, fill_polygon_data);
440 PCL_ERROR (
"[pcl::%s::performReconstruction] Error: invalid input dimension requested: %d\n",getClassName ().c_str (),dimension_);
444 template <
typename Po
intInT>
void
447 points.
header = input_->header;
448 if (!initCompute () || input_->points.empty () || indices_->empty ())
455 std::vector<pcl::Vertices> polygons;
456 performReconstruction (points, polygons,
false);
467 template <
typename Po
intInT>
void
472 performReconstruction (hull_points, output.
polygons,
true);
479 template <
typename Po
intInT>
void
483 performReconstruction (hull_points, polygons,
true);
487 template <
typename Po
intInT>
void
490 points.
header = input_->header;
491 if (!initCompute () || input_->points.empty () || indices_->empty ())
498 performReconstruction (points, polygons,
true);
507 template <
typename Po
intInT>
void
510 hull_point_indices = hull_indices_;
513 #define PCL_INSTANTIATE_ConvexHull(T) template class PCL_EXPORTS pcl::ConvexHull<T>;
void calculateInputDimension()
Automatically determines the dimension of input data - 2D or 3D.
void performReconstruction2D(PointCloud &points, std::vector< pcl::Vertices > &polygons, bool fill_polygon_data=false)
The reconstruction method for 2D data.
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).
void resize(std::size_t count)
Resizes the container to contain count elements.
std::uint32_t width
The point cloud width (if organized as an image-structure).
pcl::PCLHeader header
The point cloud header.
std::uint32_t height
The point cloud height (if organized as an image-structure).
void clear()
Removes all points in a cloud and sets the width and height to 0.
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 > ¢roid, Eigen::Matrix< Scalar, 3, 3 > &covariance_matrix)
Compute normalized the 3x3 covariance matrix of a given set of points.
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...
unsigned int compute3DCentroid(ConstCloudIterator< PointT > &cloud_iterator, Eigen::Matrix< Scalar, 4, 1 > ¢roid)
Compute the 3D (X-Y-Z) centroid of a set of points and return it as a 3D vector.
bool comparePoints2D(const std::pair< int, Eigen::Vector4f > &p1, const std::pair< int, Eigen::Vector4f > &p2)
Sort 2D points in a vector structure.
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.
std::vector< T, Eigen::aligned_allocator< T > > AlignedVector
Type used for aligned vector of Eigen objects in PCL.
constexpr bool isXYZFinite(const PointT &) noexcept
std::vector< ::pcl::Vertices > polygons
::pcl::PCLPointCloud2 cloud