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 #include <pcl/surface/qhull.h>
00057
00059
00062 template <typename PointInT> int
00063 pcl::ConcaveHull<PointInT>::getDim () const
00064 {
00065 return (getDimension ());
00066 }
00067
00069 template <typename PointInT> void
00070 pcl::ConcaveHull<PointInT>::reconstruct (PointCloud &output)
00071 {
00072 output.header = input_->header;
00073 if (alpha_ <= 0)
00074 {
00075 PCL_ERROR ("[pcl::%s::reconstruct] Alpha parameter must be set to a positive number!\n", getClassName ().c_str ());
00076 output.points.clear ();
00077 return;
00078 }
00079
00080 if (!initCompute ())
00081 {
00082 output.points.clear ();
00083 return;
00084 }
00085
00086
00087 std::vector<pcl::Vertices> polygons;
00088 performReconstruction (output, polygons);
00089
00090 output.width = static_cast<uint32_t> (output.points.size ());
00091 output.height = 1;
00092 output.is_dense = true;
00093
00094 deinitCompute ();
00095 }
00096
00098 template <typename PointInT> void
00099 pcl::ConcaveHull<PointInT>::reconstruct (PointCloud &output, std::vector<pcl::Vertices> &polygons)
00100 {
00101 output.header = input_->header;
00102 if (alpha_ <= 0)
00103 {
00104 PCL_ERROR ("[pcl::%s::reconstruct] Alpha parameter must be set to a positive number!\n", getClassName ().c_str ());
00105 output.points.clear ();
00106 return;
00107 }
00108
00109 if (!initCompute ())
00110 {
00111 output.points.clear ();
00112 return;
00113 }
00114
00115
00116 performReconstruction (output, polygons);
00117
00118 output.width = static_cast<uint32_t> (output.points.size ());
00119 output.height = 1;
00120 output.is_dense = true;
00121
00122 deinitCompute ();
00123 }
00124
00125 #ifdef __GNUC__
00126 #pragma GCC diagnostic ignored "-Wold-style-cast"
00127 #endif
00128
00129 template <typename PointInT> void
00130 pcl::ConcaveHull<PointInT>::performReconstruction (PointCloud &alpha_shape, std::vector<pcl::Vertices> &polygons)
00131 {
00132 EIGEN_ALIGN16 Eigen::Matrix3d covariance_matrix;
00133 Eigen::Vector4d xyz_centroid;
00134 computeMeanAndCovarianceMatrix (*input_, *indices_, covariance_matrix, xyz_centroid);
00135
00136
00137 for (int i = 0; i < 3; ++i)
00138 for (int j = 0; j < 3; ++j)
00139 if (!pcl_isfinite (covariance_matrix.coeffRef (i, j)))
00140 return;
00141
00142 EIGEN_ALIGN16 Eigen::Vector3d eigen_values;
00143 EIGEN_ALIGN16 Eigen::Matrix3d eigen_vectors;
00144 pcl::eigen33 (covariance_matrix, eigen_vectors, eigen_values);
00145
00146 Eigen::Affine3d transform1;
00147 transform1.setIdentity ();
00148
00149
00150 if (dim_ == 0)
00151 {
00152 PCL_DEBUG ("[pcl::%s] WARNING: Input dimension not specified. Automatically determining input dimension.\n", getClassName ().c_str ());
00153 if (eigen_values[0] / eigen_values[2] < 1.0e-3)
00154 dim_ = 2;
00155 else
00156 dim_ = 3;
00157 }
00158
00159 if (dim_ == 2)
00160 {
00161
00162
00163
00164 transform1 (2, 0) = eigen_vectors (0, 0);
00165 transform1 (2, 1) = eigen_vectors (1, 0);
00166 transform1 (2, 2) = eigen_vectors (2, 0);
00167
00168 transform1 (1, 0) = eigen_vectors (0, 1);
00169 transform1 (1, 1) = eigen_vectors (1, 1);
00170 transform1 (1, 2) = eigen_vectors (2, 1);
00171 transform1 (0, 0) = eigen_vectors (0, 2);
00172 transform1 (0, 1) = eigen_vectors (1, 2);
00173 transform1 (0, 2) = eigen_vectors (2, 2);
00174 }
00175 else
00176 {
00177 transform1.setIdentity ();
00178 }
00179
00180 PointCloud cloud_transformed;
00181 pcl::demeanPointCloud (*input_, *indices_, xyz_centroid, cloud_transformed);
00182 pcl::transformPointCloud (cloud_transformed, cloud_transformed, transform1);
00183
00184
00185 boolT ismalloc = True;
00186
00187 char flags[] = "qhull d QJ";
00188
00189 FILE *outfile = NULL;
00190
00191 FILE *errfile = stderr;
00192
00193 int exitcode;
00194
00195
00196 coordT *points = reinterpret_cast<coordT*> (calloc (cloud_transformed.points.size () * dim_, sizeof(coordT)));
00197
00198 for (size_t i = 0; i < cloud_transformed.points.size (); ++i)
00199 {
00200 points[i * dim_ + 0] = static_cast<coordT> (cloud_transformed.points[i].x);
00201 points[i * dim_ + 1] = static_cast<coordT> (cloud_transformed.points[i].y);
00202
00203 if (dim_ > 2)
00204 points[i * dim_ + 2] = static_cast<coordT> (cloud_transformed.points[i].z);
00205 }
00206
00207
00208 exitcode = qh_new_qhull (dim_, static_cast<int> (cloud_transformed.points.size ()), points, ismalloc, flags, outfile, errfile);
00209
00210 if (exitcode != 0)
00211 {
00212 PCL_ERROR ("[pcl::%s::performReconstrution] ERROR: qhull was unable to compute a concave hull for the given point cloud (%zu)!\n", getClassName ().c_str (), cloud_transformed.points.size ());
00213
00214
00215 if (!cloud_transformed.is_dense)
00216 {
00217 bool NaNvalues = false;
00218 for (size_t i = 0; i < cloud_transformed.size (); ++i)
00219 {
00220 if (!pcl_isfinite (cloud_transformed.points[i].x) ||
00221 !pcl_isfinite (cloud_transformed.points[i].y) ||
00222 !pcl_isfinite (cloud_transformed.points[i].z))
00223 {
00224 NaNvalues = true;
00225 break;
00226 }
00227 }
00228
00229 if (NaNvalues)
00230 PCL_ERROR ("[pcl::%s::performReconstruction] ERROR: point cloud contains NaN values, consider running pcl::PassThrough filter first to remove NaNs!\n", getClassName ().c_str ());
00231 }
00232
00233 alpha_shape.points.resize (0);
00234 alpha_shape.width = alpha_shape.height = 0;
00235 polygons.resize (0);
00236
00237 qh_freeqhull (!qh_ALL);
00238 int curlong, totlong;
00239 qh_memfreeshort (&curlong, &totlong);
00240
00241 return;
00242 }
00243
00244 qh_setvoronoi_all ();
00245
00246 int num_vertices = qh num_vertices;
00247 alpha_shape.points.resize (num_vertices);
00248
00249 vertexT *vertex;
00250
00251 int max_vertex_id = 0;
00252 FORALLvertices
00253 {
00254 if (vertex->id + 1 > max_vertex_id)
00255 max_vertex_id = vertex->id + 1;
00256 }
00257
00258 facetT *facet;
00259
00260 ++max_vertex_id;
00261 std::vector<int> qhid_to_pcidx (max_vertex_id);
00262
00263 int num_facets = qh num_facets;
00264 int dd = 0;
00265
00266 if (dim_ == 3)
00267 {
00268 setT *triangles_set = qh_settemp (4 * num_facets);
00269 if (voronoi_centers_)
00270 voronoi_centers_->points.resize (num_facets);
00271
00272 int non_upper = 0;
00273 FORALLfacets
00274 {
00275
00276 if (!facet->upperdelaunay)
00277 {
00278 vertexT *anyVertex = static_cast<vertexT*> (facet->vertices->e[0].p);
00279 double *center = facet->center;
00280 double r = qh_pointdist (anyVertex->point,center,dim_);
00281 facetT *neighb;
00282
00283 if (voronoi_centers_)
00284 {
00285 voronoi_centers_->points[non_upper].x = static_cast<float> (facet->center[0]);
00286 voronoi_centers_->points[non_upper].y = static_cast<float> (facet->center[1]);
00287 voronoi_centers_->points[non_upper].z = static_cast<float> (facet->center[2]);
00288 }
00289
00290 non_upper++;
00291
00292 if (r <= alpha_)
00293 {
00294
00295 qh_makeridges (facet);
00296 facet->good = true;
00297 facet->visitid = qh visit_id;
00298 ridgeT *ridge, **ridgep;
00299 FOREACHridge_ (facet->ridges)
00300 {
00301 neighb = otherfacet_ (ridge, facet);
00302 if ((neighb->visitid != qh visit_id))
00303 qh_setappend (&triangles_set, ridge);
00304 }
00305 }
00306 else
00307 {
00308
00309 facet->good = false;
00310 facet->visitid = qh visit_id;
00311 qh_makeridges (facet);
00312 ridgeT *ridge, **ridgep;
00313 FOREACHridge_ (facet->ridges)
00314 {
00315 facetT *neighb;
00316 neighb = otherfacet_ (ridge, facet);
00317 if ((neighb->visitid != qh visit_id))
00318 {
00319
00320
00321 PointInT a, b, c;
00322 a.x = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[0].p))->point[0]);
00323 a.y = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[0].p))->point[1]);
00324 a.z = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[0].p))->point[2]);
00325 b.x = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[1].p))->point[0]);
00326 b.y = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[1].p))->point[1]);
00327 b.z = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[1].p))->point[2]);
00328 c.x = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[2].p))->point[0]);
00329 c.y = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[2].p))->point[1]);
00330 c.z = static_cast<float> ((static_cast<vertexT*>(ridge->vertices->e[2].p))->point[2]);
00331
00332 double r = pcl::getCircumcircleRadius (a, b, c);
00333 if (r <= alpha_)
00334 qh_setappend (&triangles_set, ridge);
00335 }
00336 }
00337 }
00338 }
00339 }
00340
00341 if (voronoi_centers_)
00342 voronoi_centers_->points.resize (non_upper);
00343
00344
00345
00346 int num_good_triangles = 0;
00347 ridgeT *ridge, **ridgep;
00348 FOREACHridge_ (triangles_set)
00349 {
00350 if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good)
00351 num_good_triangles++;
00352 }
00353
00354 polygons.resize (num_good_triangles);
00355
00356 int vertices = 0;
00357 std::vector<bool> added_vertices (max_vertex_id, false);
00358
00359 int triangles = 0;
00360 FOREACHridge_ (triangles_set)
00361 {
00362 if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good)
00363 {
00364 polygons[triangles].vertices.resize (3);
00365 int vertex_n, vertex_i;
00366 FOREACHvertex_i_ ((*ridge).vertices)
00367 {
00368 if (!added_vertices[vertex->id])
00369 {
00370 alpha_shape.points[vertices].x = static_cast<float> (vertex->point[0]);
00371 alpha_shape.points[vertices].y = static_cast<float> (vertex->point[1]);
00372 alpha_shape.points[vertices].z = static_cast<float> (vertex->point[2]);
00373
00374 qhid_to_pcidx[vertex->id] = vertices;
00375 added_vertices[vertex->id] = true;
00376 vertices++;
00377 }
00378
00379 polygons[triangles].vertices[vertex_i] = qhid_to_pcidx[vertex->id];
00380
00381 }
00382
00383 triangles++;
00384 }
00385 }
00386
00387 alpha_shape.points.resize (vertices);
00388 alpha_shape.width = static_cast<uint32_t> (alpha_shape.points.size ());
00389 alpha_shape.height = 1;
00390 }
00391 else
00392 {
00393
00394
00395 setT *edges_set = qh_settemp (3 * num_facets);
00396 if (voronoi_centers_)
00397 voronoi_centers_->points.resize (num_facets);
00398
00399 FORALLfacets
00400 {
00401
00402 if (!facet->upperdelaunay)
00403 {
00404
00405
00406 vertexT *anyVertex = static_cast<vertexT*>(facet->vertices->e[0].p);
00407 double r = (sqrt ((anyVertex->point[0] - facet->center[0]) *
00408 (anyVertex->point[0] - facet->center[0]) +
00409 (anyVertex->point[1] - facet->center[1]) *
00410 (anyVertex->point[1] - facet->center[1])));
00411 if (r <= alpha_)
00412 {
00413 pcl::Vertices facet_vertices;
00414 qh_makeridges (facet);
00415 facet->good = true;
00416
00417 ridgeT *ridge, **ridgep;
00418 FOREACHridge_ (facet->ridges)
00419 qh_setappend (&edges_set, ridge);
00420
00421 if (voronoi_centers_)
00422 {
00423 voronoi_centers_->points[dd].x = static_cast<float> (facet->center[0]);
00424 voronoi_centers_->points[dd].y = static_cast<float> (facet->center[1]);
00425 voronoi_centers_->points[dd].z = 0.0f;
00426 }
00427
00428 ++dd;
00429 }
00430 else
00431 facet->good = false;
00432 }
00433 }
00434
00435 int vertices = 0;
00436 std::vector<bool> added_vertices (max_vertex_id, false);
00437 std::map<int, std::vector<int> > edges;
00438
00439 ridgeT *ridge, **ridgep;
00440 FOREACHridge_ (edges_set)
00441 {
00442 if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good)
00443 {
00444 int vertex_n, vertex_i;
00445 int vertices_in_ridge=0;
00446 std::vector<int> pcd_indices;
00447 pcd_indices.resize (2);
00448
00449 FOREACHvertex_i_ ((*ridge).vertices)
00450 {
00451 if (!added_vertices[vertex->id])
00452 {
00453 alpha_shape.points[vertices].x = static_cast<float> (vertex->point[0]);
00454 alpha_shape.points[vertices].y = static_cast<float> (vertex->point[1]);
00455
00456 if (dim_ > 2)
00457 alpha_shape.points[vertices].z = static_cast<float> (vertex->point[2]);
00458 else
00459 alpha_shape.points[vertices].z = 0;
00460
00461 qhid_to_pcidx[vertex->id] = vertices;
00462 added_vertices[vertex->id] = true;
00463 pcd_indices[vertices_in_ridge] = vertices;
00464 vertices++;
00465 }
00466 else
00467 {
00468 pcd_indices[vertices_in_ridge] = qhid_to_pcidx[vertex->id];
00469 }
00470
00471 vertices_in_ridge++;
00472 }
00473
00474
00475 edges[pcd_indices[0]].push_back (pcd_indices[1]);
00476 edges[pcd_indices[1]].push_back (pcd_indices[0]);
00477 }
00478 }
00479
00480 alpha_shape.points.resize (vertices);
00481
00482 std::vector<std::vector<int> > connected;
00483 PointCloud alpha_shape_sorted;
00484 alpha_shape_sorted.points.resize (vertices);
00485
00486
00487 std::map<int, std::vector<int> >::iterator curr = edges.begin ();
00488 int next = - 1;
00489 std::vector<bool> used (vertices, false);
00490 std::vector<int> pcd_idx_start_polygons;
00491 pcd_idx_start_polygons.push_back (0);
00492
00493
00494 int sorted_idx = 0;
00495 while (!edges.empty ())
00496 {
00497 alpha_shape_sorted.points[sorted_idx] = alpha_shape.points[(*curr).first];
00498
00499 for (size_t i = 0; i < (*curr).second.size (); i++)
00500 {
00501 if (!used[((*curr).second)[i]])
00502 {
00503
00504 next = ((*curr).second)[i];
00505 break;
00506 }
00507 }
00508
00509 used[(*curr).first] = true;
00510 edges.erase (curr);
00511
00512 sorted_idx++;
00513
00514 if (edges.empty ())
00515 break;
00516
00517
00518 curr = edges.find (next);
00519 if (curr == edges.end ())
00520 {
00521
00522 curr = edges.begin ();
00523 pcd_idx_start_polygons.push_back (sorted_idx);
00524 }
00525 }
00526
00527 pcd_idx_start_polygons.push_back (sorted_idx);
00528
00529 alpha_shape.points = alpha_shape_sorted.points;
00530
00531 polygons.reserve (pcd_idx_start_polygons.size () - 1);
00532
00533 for (size_t poly_id = 0; poly_id < pcd_idx_start_polygons.size () - 1; poly_id++)
00534 {
00535
00536 if (pcd_idx_start_polygons[poly_id + 1] - pcd_idx_start_polygons[poly_id] >= 3)
00537 {
00538 pcl::Vertices vertices;
00539 vertices.vertices.resize (pcd_idx_start_polygons[poly_id + 1] - pcd_idx_start_polygons[poly_id]);
00540
00541 for (int j = pcd_idx_start_polygons[poly_id]; j < pcd_idx_start_polygons[poly_id + 1]; ++j)
00542 vertices.vertices[j - pcd_idx_start_polygons[poly_id]] = static_cast<uint32_t> (j);
00543
00544 polygons.push_back (vertices);
00545 }
00546 }
00547
00548 if (voronoi_centers_)
00549 voronoi_centers_->points.resize (dd);
00550 }
00551
00552 qh_freeqhull (!qh_ALL);
00553 int curlong, totlong;
00554 qh_memfreeshort (&curlong, &totlong);
00555
00556 Eigen::Affine3d transInverse = transform1.inverse ();
00557 pcl::transformPointCloud (alpha_shape, alpha_shape, transInverse);
00558 xyz_centroid[0] = - xyz_centroid[0];
00559 xyz_centroid[1] = - xyz_centroid[1];
00560 xyz_centroid[2] = - xyz_centroid[2];
00561 pcl::demeanPointCloud (alpha_shape, xyz_centroid, alpha_shape);
00562
00563
00564 if (voronoi_centers_)
00565 {
00566 pcl::transformPointCloud (*voronoi_centers_, *voronoi_centers_, transInverse);
00567 pcl::demeanPointCloud (*voronoi_centers_, xyz_centroid, *voronoi_centers_);
00568 }
00569
00570 if (keep_information_)
00571 {
00572
00573 pcl::KdTreeFLANN<PointInT> tree (true);
00574 tree.setInputCloud (input_, indices_);
00575
00576 std::vector<int> neighbor;
00577 std::vector<float> distances;
00578 neighbor.resize (1);
00579 distances.resize (1);
00580
00581
00582
00583 std::vector<int> indices;
00584 indices.resize (alpha_shape.points.size ());
00585
00586 for (size_t i = 0; i < alpha_shape.points.size (); i++)
00587 {
00588 tree.nearestKSearch (alpha_shape.points[i], 1, neighbor, distances);
00589 indices[i] = neighbor[0];
00590 }
00591
00592
00593 pcl::copyPointCloud (*input_, indices, alpha_shape);
00594 }
00595 }
00596 #ifdef __GNUC__
00597 #pragma GCC diagnostic warning "-Wold-style-cast"
00598 #endif
00599
00601 template <typename PointInT> void
00602 pcl::ConcaveHull<PointInT>::performReconstruction (PolygonMesh &output)
00603 {
00604
00605 pcl::PointCloud<PointInT> hull_points;
00606 performReconstruction (hull_points, output.polygons);
00607
00608
00609 pcl::toPCLPointCloud2 (hull_points, output.cloud);
00610 }
00611
00613 template <typename PointInT> void
00614 pcl::ConcaveHull<PointInT>::performReconstruction (std::vector<pcl::Vertices> &polygons)
00615 {
00616 pcl::PointCloud<PointInT> hull_points;
00617 performReconstruction (hull_points, polygons);
00618 }
00619
00620
00621 #define PCL_INSTANTIATE_ConcaveHull(T) template class PCL_EXPORTS pcl::ConcaveHull<T>;
00622
00623 #endif // PCL_SURFACE_IMPL_CONCAVE_HULL_H_
00624 #endif