|
Point Cloud Library (PCL)
1.5.1
|
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Point Cloud Library (PCL) - www.pointclouds.org 00005 * Copyright (c) 2010-2012, Willow Garage, Inc. 00006 * 00007 * All rights reserved. 00008 * 00009 * Redistribution and use in source and binary forms, with or without 00010 * modification, are permitted provided that the following conditions 00011 * are met: 00012 * 00013 * * Redistributions of source code must retain the above copyright 00014 * notice, this list of conditions and the following disclaimer. 00015 * * Redistributions in binary form must reproduce the above 00016 * copyright notice, this list of conditions and the following 00017 * disclaimer in the documentation and/or other materials provided 00018 * with the distribution. 00019 * * Neither the name of Willow Garage, Inc. nor the names of its 00020 * contributors may be used to endorse or promote products derived 00021 * from this software without specific prior written permission. 00022 * 00023 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00024 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00025 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00026 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00027 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00028 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00029 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00030 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00031 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00032 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00033 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00034 * POSSIBILITY OF SUCH DAMAGE. 00035 * 00036 * $Id: convex_hull.hpp 4702 2012-02-23 09:39:33Z gedikli $ 00037 * 00038 */ 00039 00040 #include <pcl/pcl_config.h> 00041 #ifdef HAVE_QHULL 00042 00043 #ifndef PCL_SURFACE_IMPL_CONVEX_HULL_H_ 00044 #define PCL_SURFACE_IMPL_CONVEX_HULL_H_ 00045 00046 #include "pcl/surface/convex_hull.h" 00047 #include <pcl/common/common.h> 00048 #include <pcl/common/eigen.h> 00049 #include <pcl/common/transforms.h> 00050 #include <pcl/common/io.h> 00051 #include <stdio.h> 00052 #include <stdlib.h> 00053 00054 extern "C" 00055 { 00056 #ifdef HAVE_QHULL_2011 00057 # include "libqhull/libqhull.h" 00058 # include "libqhull/mem.h" 00059 # include "libqhull/qset.h" 00060 # include "libqhull/geom.h" 00061 # include "libqhull/merge.h" 00062 # include "libqhull/poly.h" 00063 # include "libqhull/io.h" 00064 # include "libqhull/stat.h" 00065 #else 00066 # include "qhull/qhull.h" 00067 # include "qhull/mem.h" 00068 # include "qhull/qset.h" 00069 # include "qhull/geom.h" 00070 # include "qhull/merge.h" 00071 # include "qhull/poly.h" 00072 # include "qhull/io.h" 00073 # include "qhull/stat.h" 00074 #endif 00075 } 00076 00078 template <typename PointInT> void 00079 pcl::ConvexHull<PointInT>::calculateInputDimension () 00080 { 00081 PCL_WARN ("[pcl::%s::calculateInputDimension] WARNING: Input dimension not specified. Automatically determining input dimension.\n", getClassName ().c_str ()); 00082 EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix; 00083 Eigen::Vector4f xyz_centroid; 00084 computeMeanAndCovarianceMatrix (*input_, *indices_, covariance_matrix, xyz_centroid); 00085 00086 EIGEN_ALIGN16 Eigen::Vector3f eigen_values; 00087 pcl::eigen33 (covariance_matrix, eigen_values); 00088 00089 if (eigen_values[0] / eigen_values[2] < 1.0e-3) 00090 dimension_ = 2; 00091 else 00092 dimension_ = 3; 00093 } 00094 00096 template <typename PointInT> void 00097 pcl::ConvexHull<PointInT>::performReconstruction2D (PointCloud &hull, std::vector<pcl::Vertices> &polygons, 00098 bool fill_polygon_data) 00099 { 00100 int dimension = 2; 00101 bool xy_proj_safe = true; 00102 bool yz_proj_safe = true; 00103 bool xz_proj_safe = true; 00104 00105 // Check the input's normal to see which projection to use 00106 PointInT p0 = input_->points[0]; 00107 PointInT p1 = input_->points[input_->points.size () - 1]; 00108 PointInT p2 = input_->points[input_->points.size () / 2]; 00109 Eigen::Array4f dy1dy2 = (p1.getArray4fMap () - p0.getArray4fMap ()) / (p2.getArray4fMap () - p0.getArray4fMap ()); 00110 while (!( (dy1dy2[0] != dy1dy2[1]) || (dy1dy2[2] != dy1dy2[1]) ) ) 00111 { 00112 p0 = input_->points[rand () % input_->points.size ()]; 00113 p1 = input_->points[rand () % input_->points.size ()]; 00114 p2 = input_->points[rand () % input_->points.size ()]; 00115 dy1dy2 = (p1.getArray4fMap () - p0.getArray4fMap ()) / (p2.getArray4fMap () - p0.getArray4fMap ()); 00116 } 00117 00118 pcl::PointCloud<PointInT> normal_calc_cloud; 00119 normal_calc_cloud.points.resize (3); 00120 normal_calc_cloud.points[0] = p0; 00121 normal_calc_cloud.points[1] = p1; 00122 normal_calc_cloud.points[2] = p2; 00123 00124 Eigen::Vector4f normal_calc_centroid; 00125 Eigen::Matrix3f normal_calc_covariance; 00126 pcl::computeMeanAndCovarianceMatrix (normal_calc_cloud, normal_calc_covariance, normal_calc_centroid); 00127 // Need to set -1 here. See eigen33 for explanations. 00128 Eigen::Vector3f::Scalar eigen_value; 00129 Eigen::Vector3f plane_params; 00130 pcl::eigen33 (normal_calc_covariance, eigen_value, plane_params); 00131 float theta_x = fabs (plane_params.dot (x_axis_)); 00132 float theta_y = fabs (plane_params.dot (y_axis_)); 00133 float theta_z = fabs (plane_params.dot (z_axis_)); 00134 00135 // Check for degenerate cases of each projection 00136 // We must avoid projections in which the plane projects as a line 00137 if (theta_z > projection_angle_thresh_) 00138 { 00139 xz_proj_safe = false; 00140 yz_proj_safe = false; 00141 } 00142 if (theta_x > projection_angle_thresh_) 00143 { 00144 xz_proj_safe = false; 00145 xy_proj_safe = false; 00146 } 00147 if (theta_y > projection_angle_thresh_) 00148 { 00149 xy_proj_safe = false; 00150 yz_proj_safe = false; 00151 } 00152 00153 // True if qhull should free points in qh_freeqhull() or reallocation 00154 boolT ismalloc = True; 00155 // output from qh_produce_output(), use NULL to skip qh_produce_output() 00156 FILE *outfile = NULL; 00157 00158 if (compute_area_) 00159 outfile = stderr; 00160 00161 // option flags for qhull, see qh_opt.htm 00162 char * flags = (char *)qhull_flags.c_str (); 00163 // error messages from qhull code 00164 FILE *errfile = stderr; 00165 00166 // Array of coordinates for each point 00167 coordT *points = (coordT *)calloc (input_->points.size () * dimension, sizeof(coordT)); 00168 00169 // Build input data, using appropriate projection 00170 int j = 0; 00171 if (xy_proj_safe) 00172 { 00173 for (size_t i = 0; i < input_->points.size (); ++i, j+=dimension) 00174 { 00175 points[j + 0] = (coordT)input_->points[i].x; 00176 points[j + 1] = (coordT)input_->points[i].y; 00177 } 00178 } 00179 else if (yz_proj_safe) 00180 { 00181 for (size_t i = 0; i < input_->points.size (); ++i, j+=dimension) 00182 { 00183 points[j + 0] = (coordT)input_->points[i].y; 00184 points[j + 1] = (coordT)input_->points[i].z; 00185 } 00186 } 00187 else if (xz_proj_safe) 00188 { 00189 for (size_t i = 0; i < input_->points.size (); ++i, j+=dimension) 00190 { 00191 points[j + 0] = (coordT)input_->points[i].x; 00192 points[j + 1] = (coordT)input_->points[i].z; 00193 } 00194 } 00195 else 00196 { 00197 // This should only happen if we had invalid input 00198 PCL_ERROR ("[pcl::%s::performReconstruction2D] Invalid input!\n", getClassName ().c_str ()); 00199 } 00200 00201 // Compute convex hull 00202 int exitcode = qh_new_qhull (dimension, input_->points.size (), points, ismalloc, flags, outfile, errfile); 00203 00204 // 0 if no error from qhull 00205 if (exitcode != 0) 00206 { 00207 PCL_ERROR ("[pcl::%s::performReconstrution2D] ERROR: qhull was unable to compute a convex hull for the given point cloud (%lu)!\n", getClassName ().c_str (), (unsigned long) input_->points.size ()); 00208 00209 hull.points.resize (0); 00210 hull.width = hull.height = 0; 00211 polygons.resize (0); 00212 00213 qh_freeqhull (!qh_ALL); 00214 int curlong, totlong; 00215 qh_memfreeshort (&curlong, &totlong); 00216 00217 return; 00218 } 00219 00220 // Qhull returns the area in volume for 2D 00221 if (compute_area_) 00222 { 00223 total_area_ = qh totvol; 00224 total_volume_ = 0.0; 00225 } 00226 00227 int num_vertices = qh num_vertices; 00228 hull.points.resize (num_vertices); 00229 memset (&hull.points[0], hull.points.size (), sizeof (PointInT)); 00230 00231 vertexT * vertex; 00232 int i = 0; 00233 00234 std::vector<std::pair<int, Eigen::Vector4f>, Eigen::aligned_allocator<std::pair<int, Eigen::Vector4f> > > idx_points (num_vertices); 00235 idx_points.resize (hull.points.size ()); 00236 memset (&idx_points[0], hull.points.size (), sizeof (std::pair<int, Eigen::Vector4f>)); 00237 00238 FORALLvertices 00239 { 00240 hull.points[i] = input_->points[qh_pointid (vertex->point)]; 00241 idx_points[i].first = qh_pointid (vertex->point); 00242 ++i; 00243 } 00244 00245 // Sort 00246 Eigen::Vector4f centroid; 00247 pcl::compute3DCentroid (hull, centroid); 00248 if (xy_proj_safe) 00249 { 00250 for (size_t j = 0; j < hull.points.size (); j++) 00251 { 00252 idx_points[j].second[0] = hull.points[j].x - centroid[0]; 00253 idx_points[j].second[1] = hull.points[j].y - centroid[1]; 00254 } 00255 } 00256 else if (yz_proj_safe) 00257 { 00258 for (size_t j = 0; j < hull.points.size (); j++) 00259 { 00260 idx_points[j].second[0] = hull.points[j].y - centroid[0]; 00261 idx_points[j].second[1] = hull.points[j].z - centroid[1]; 00262 } 00263 } 00264 else if (xz_proj_safe) 00265 { 00266 for (size_t j = 0; j < hull.points.size (); j++) 00267 { 00268 idx_points[j].second[0] = hull.points[j].x - centroid[0]; 00269 idx_points[j].second[1] = hull.points[j].z - centroid[1]; 00270 } 00271 } 00272 std::sort (idx_points.begin (), idx_points.end (), comparePoints2D); 00273 00274 polygons.resize (1); 00275 polygons[0].vertices.resize (hull.points.size () + 1); 00276 00277 for (size_t j = 0; j < hull.points.size (); j++) 00278 { 00279 hull.points[j] = input_->points[idx_points[j].first]; 00280 polygons[0].vertices[j] = j; 00281 } 00282 polygons[0].vertices[hull.points.size ()] = 0; 00283 00284 qh_freeqhull (!qh_ALL); 00285 int curlong, totlong; 00286 qh_memfreeshort (&curlong, &totlong); 00287 00288 hull.width = hull.points.size (); 00289 hull.height = 1; 00290 hull.is_dense = false; 00291 return; 00292 } 00293 00295 template <typename PointInT> void 00296 pcl::ConvexHull<PointInT>::performReconstruction3D ( 00297 PointCloud &hull, std::vector<pcl::Vertices> &polygons, bool fill_polygon_data) 00298 { 00299 int dimension = 3; 00300 00301 // True if qhull should free points in qh_freeqhull() or reallocation 00302 boolT ismalloc = True; 00303 // output from qh_produce_output(), use NULL to skip qh_produce_output() 00304 FILE *outfile = NULL; 00305 00306 if (compute_area_) 00307 outfile = stderr; 00308 00309 // option flags for qhull, see qh_opt.htm 00310 char * flags = (char *)qhull_flags.c_str (); 00311 // error messages from qhull code 00312 FILE *errfile = stderr; 00313 00314 // Array of coordinates for each point 00315 coordT *points = (coordT *)calloc (input_->points.size () * dimension, sizeof (coordT)); 00316 00317 int j = 0; 00318 for (size_t i = 0; i < input_->points.size (); ++i, j+=dimension) 00319 { 00320 points[j + 0] = (coordT)input_->points[i].x; 00321 points[j + 1] = (coordT)input_->points[i].y; 00322 points[j + 2] = (coordT)input_->points[i].z; 00323 } 00324 00325 // Compute convex hull 00326 int exitcode = qh_new_qhull (dimension, input_->points.size (), points, ismalloc, flags, outfile, errfile); 00327 00328 // 0 if no error from qhull 00329 if (exitcode != 0) 00330 { 00331 PCL_ERROR ("[pcl::%s::performReconstrution3D] ERROR: qhull was unable to compute a convex hull for the given point cloud (%lu)!\n", getClassName ().c_str (), (unsigned long) input_->points.size ()); 00332 00333 //check if it fails because of NaN values... 00334 if (!input_->is_dense) 00335 PCL_ERROR ("[pcl::%s::performReconstruction3D] ERROR: point cloud contains NaN values, consider running pcl::PassThrough filter first to remove NaNs!\n", getClassName ().c_str ()); 00336 00337 hull.points.resize (0); 00338 hull.width = hull.height = 0; 00339 polygons.resize (0); 00340 00341 qh_freeqhull (!qh_ALL); 00342 int curlong, totlong; 00343 qh_memfreeshort (&curlong, &totlong); 00344 00345 return; 00346 } 00347 00348 qh_triangulate (); 00349 00350 int num_facets = qh num_facets; 00351 00352 int num_vertices = qh num_vertices; 00353 hull.points.resize (num_vertices); 00354 00355 vertexT * vertex; 00356 int i = 0; 00357 // Max vertex id 00358 int max_vertex_id = -1; 00359 FORALLvertices 00360 { 00361 if ((int)vertex->id > max_vertex_id) 00362 max_vertex_id = vertex->id; 00363 } 00364 00365 ++max_vertex_id; 00366 std::vector<int> qhid_to_pcidx (max_vertex_id); 00367 00368 FORALLvertices 00369 { 00370 // Add vertices to hull point_cloud 00371 hull.points[i] = input_->points[qh_pointid (vertex->point)]; 00372 00373 qhid_to_pcidx[vertex->id] = i; // map the vertex id of qhull to the point cloud index 00374 ++i; 00375 } 00376 00377 if (compute_area_) 00378 { 00379 total_area_ = qh totarea; 00380 total_volume_ = qh totvol; 00381 } 00382 00383 if (fill_polygon_data) 00384 { 00385 polygons.resize (num_facets); 00386 int dd = 0; 00387 00388 facetT * facet; 00389 FORALLfacets 00390 { 00391 polygons[dd].vertices.resize (3); 00392 00393 // Needed by FOREACHvertex_i_ 00394 int vertex_n, vertex_i; 00395 FOREACHvertex_i_ ((*facet).vertices) 00396 //facet_vertices.vertices.push_back (qhid_to_pcidx[vertex->id]); 00397 polygons[dd].vertices[vertex_i] = qhid_to_pcidx[vertex->id]; 00398 ++dd; 00399 } 00400 } 00401 // Deallocates memory (also the points) 00402 qh_freeqhull (!qh_ALL); 00403 int curlong, totlong; 00404 qh_memfreeshort (&curlong, &totlong); 00405 00406 hull.width = hull.points.size (); 00407 hull.height = 1; 00408 hull.is_dense = false; 00409 } 00410 00412 template <typename PointInT> void 00413 pcl::ConvexHull<PointInT>::performReconstruction (PointCloud &hull, std::vector<pcl::Vertices> &polygons, 00414 bool fill_polygon_data) 00415 { 00416 if (dimension_ == 0) 00417 calculateInputDimension (); 00418 if (dimension_ == 2) 00419 performReconstruction2D (hull, polygons, fill_polygon_data); 00420 else if (dimension_ == 3) 00421 performReconstruction3D (hull, polygons, fill_polygon_data); 00422 else 00423 PCL_ERROR ("[pcl::%s::performReconstruction] Error: invalid input dimension requested: %d\n",getClassName ().c_str (),dimension_); 00424 } 00425 00427 template <typename PointInT> void 00428 pcl::ConvexHull<PointInT>::reconstruct (PointCloud &output) 00429 { 00430 output.header = input_->header; 00431 if (!initCompute () || input_->points.empty ()) 00432 { 00433 output.points.clear (); 00434 return; 00435 } 00436 00437 // Perform the actual surface reconstruction 00438 std::vector<pcl::Vertices> polygons; 00439 performReconstruction (output, polygons, false); 00440 00441 output.width = output.points.size (); 00442 output.height = 1; 00443 output.is_dense = true; 00444 00445 deinitCompute (); 00446 } 00447 00448 00450 template <typename PointInT> void 00451 pcl::ConvexHull<PointInT>::performReconstruction (PolygonMesh &output) 00452 { 00453 // Perform reconstruction 00454 pcl::PointCloud<PointInT> hull_points; 00455 performReconstruction (hull_points, output.polygons, true); 00456 00457 // Convert the PointCloud into a PointCloud2 00458 pcl::toROSMsg (hull_points, output.cloud); 00459 } 00460 00462 template <typename PointInT> void 00463 pcl::ConvexHull<PointInT>::performReconstruction (std::vector<pcl::Vertices> &polygons) 00464 { 00465 pcl::PointCloud<PointInT> hull_points; 00466 performReconstruction (hull_points, polygons, true); 00467 } 00468 00470 template <typename PointInT> void 00471 pcl::ConvexHull<PointInT>::reconstruct (PointCloud &points, std::vector<pcl::Vertices> &polygons) 00472 { 00473 points.header = input_->header; 00474 if (!initCompute () || input_->points.empty ()) 00475 { 00476 points.points.clear (); 00477 return; 00478 } 00479 00480 // Perform the actual surface reconstruction 00481 performReconstruction (points, polygons, true); 00482 00483 points.width = points.points.size (); 00484 points.height = 1; 00485 points.is_dense = true; 00486 00487 deinitCompute (); 00488 } 00489 00490 #define PCL_INSTANTIATE_ConvexHull(T) template class PCL_EXPORTS pcl::ConvexHull<T>; 00491 00492 #endif // PCL_SURFACE_IMPL_CONVEX_HULL_H_ 00493 #endif
1.8.0