00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef PCL_SURFACE_IMPL_CONVEX_HULL_H_
00039 #define PCL_SURFACE_IMPL_CONVEX_HULL_H_
00040
00041 #include "pcl/surface/convex_hull.h"
00042 #include "pcl/common/common.h"
00043 #include "pcl/registration/transforms.h"
00044
00045
00047 template<typename PointInT> void
00048 pcl::ConvexHull<PointInT>::performReconstruction (PointCloud &hull,
00049 std::vector<pcl::Vertices> &polygons,
00050 bool fill_polygon_data)
00051 {
00052
00053 EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00054 Eigen::Vector4f xyz_centroid;
00055 compute3DCentroid (*input_, *indices_, xyz_centroid);
00056 computeCovarianceMatrix (*input_, *indices_, xyz_centroid, covariance_matrix);
00057 EIGEN_ALIGN16 Eigen::Vector3f eigen_values;
00058 EIGEN_ALIGN16 Eigen::Matrix3f eigen_vectors;
00059 pcl::eigen33 (covariance_matrix, eigen_vectors, eigen_values);
00060
00061 Eigen::Affine3f transform1;
00062 transform1.setIdentity ();
00063 int dim = 3;
00064
00065 if (eigen_values[0] / eigen_values[2] < 1.0e-5)
00066 {
00067
00068
00069
00070 eigen_vectors.col (2) = eigen_vectors.col (0).cross (eigen_vectors.col (1));
00071 eigen_vectors.col (1) = eigen_vectors.col (2).cross (eigen_vectors.col (0));
00072
00073 transform1 (0, 2) = eigen_vectors (0, 0);
00074 transform1 (1, 2) = eigen_vectors (1, 0);
00075 transform1 (2, 2) = eigen_vectors (2, 0);
00076
00077 transform1 (0, 1) = eigen_vectors (0, 1);
00078 transform1 (1, 1) = eigen_vectors (1, 1);
00079 transform1 (2, 1) = eigen_vectors (2, 1);
00080 transform1 (0, 0) = eigen_vectors (0, 2);
00081 transform1 (1, 0) = eigen_vectors (1, 2);
00082 transform1 (2, 0) = eigen_vectors (2, 2);
00083
00084 transform1 = transform1.inverse ();
00085 dim = 2;
00086 }
00087 else
00088 transform1.setIdentity ();
00089
00090 PointCloud cloud_transformed;
00091 pcl::demeanPointCloud (*input_, *indices_, xyz_centroid, cloud_transformed);
00092 pcl::transformPointCloud (cloud_transformed, cloud_transformed, transform1);
00093
00094
00095 boolT ismalloc = True;
00096
00097 char flags[] = "qhull Tc";
00098
00099 FILE *outfile = NULL;
00100
00101 FILE *errfile = stderr;
00102
00103 int exitcode;
00104
00105
00106 coordT *points = (coordT *)calloc (cloud_transformed.points.size () * dim, sizeof (coordT));
00107
00108 for (size_t i = 0; i < cloud_transformed.points.size (); ++i)
00109 {
00110 points[i * dim + 0] = (coordT)cloud_transformed.points[i].x;
00111 points[i * dim + 1] = (coordT)cloud_transformed.points[i].y;
00112
00113 if (dim > 2)
00114 points[i * dim + 2] = (coordT)cloud_transformed.points[i].z;
00115 }
00116
00117
00118 exitcode = qh_new_qhull (dim, cloud_transformed.points.size (), points, ismalloc, flags, outfile, errfile);
00119 qh_triangulate ();
00120
00121 int num_facets = qh num_facets;
00122
00123 int num_vertices = qh num_vertices;
00124 hull.points.resize (num_vertices);
00125
00126 vertexT *vertex;
00127 int i = 0;
00128
00129 int max_vertex_id = -1;
00130 FORALLvertices
00131 {
00132 if (vertex->id > max_vertex_id)
00133 max_vertex_id = vertex->id;
00134 }
00135
00136 ++max_vertex_id;
00137 std::vector<int> qhid_to_pcidx (max_vertex_id);
00138
00139 FORALLvertices
00140 {
00141
00142 hull.points[i].x = vertex->point[0];
00143 hull.points[i].y = vertex->point[1];
00144
00145 if (dim>2)
00146 hull.points[i].z = vertex->point[2];
00147 else
00148 hull.points[i].z = 0;
00149
00150 qhid_to_pcidx[vertex->id] = i;
00151 ++i;
00152 }
00153
00154 if (fill_polygon_data)
00155 {
00156 if (dim == 3)
00157 {
00158 polygons.resize (num_facets);
00159 int dd = 0;
00160
00161 facetT *facet;
00162 FORALLfacets
00163 {
00164 polygons[dd].vertices.resize (3);
00165
00166
00167 int vertex_n, vertex_i;
00168 FOREACHvertex_i_((*facet).vertices)
00169
00170 polygons[dd].vertices[vertex_i] = qhid_to_pcidx[vertex->id];
00171
00172 ++dd;
00173 }
00174 }
00175 else
00176 {
00177
00178
00179
00180
00181
00182 Eigen::Vector4f centroid;
00183 pcl::compute3DCentroid (hull, centroid);
00184 centroid[3] = 0;
00185 polygons.resize (1);
00186
00187 int num_vertices = qh num_vertices, dd = 0;
00188
00189
00190 std::vector<std::pair<int, Eigen::Vector4f>, Eigen::aligned_allocator<std::pair<int, Eigen::Vector4f> > > idx_points (num_vertices);
00191
00192 FORALLvertices
00193 {
00194 idx_points[dd].first = qhid_to_pcidx[vertex->id];
00195 idx_points[dd].second = hull.points[idx_points[dd].first].getVector4fMap () - centroid;
00196 ++dd;
00197 }
00198
00199
00200 std::sort (idx_points.begin (), idx_points.end (), comparePoints2D);
00201 polygons[0].vertices.resize (idx_points.size () + 1);
00202
00203
00204 PointCloud hull_sorted;
00205 hull_sorted.points.resize (hull.points.size ());
00206
00207 for (size_t j = 0; j < idx_points.size (); ++j)
00208 hull_sorted.points[j] = hull.points[idx_points[j].first];
00209
00210 hull.points = hull_sorted.points;
00211
00212
00213 for (size_t j = 0; j < idx_points.size (); ++j)
00214 polygons[0].vertices[j] = j;
00215
00216 polygons[0].vertices[idx_points.size ()] = 0;
00217 }
00218 }
00219 else
00220 {
00221 if (dim == 2)
00222 {
00223
00224 Eigen::Vector4f centroid;
00225 pcl::compute3DCentroid (hull, centroid);
00226 centroid[3] = 0;
00227 polygons.resize (1);
00228
00229 int num_vertices = qh num_vertices, dd = 0;
00230
00231
00232 std::vector<std::pair<int, Eigen::Vector4f>, Eigen::aligned_allocator<std::pair<int, Eigen::Vector4f> > > idx_points (num_vertices);
00233
00234 FORALLvertices
00235 {
00236 idx_points[dd].first = qhid_to_pcidx[vertex->id];
00237 idx_points[dd].second = hull.points[idx_points[dd].first].getVector4fMap () - centroid;
00238 ++dd;
00239 }
00240
00241
00242 std::sort (idx_points.begin (), idx_points.end (), comparePoints2D);
00243
00244
00245 PointCloud hull_sorted;
00246 hull_sorted.points.resize (hull.points.size ());
00247
00248 for (size_t j = 0; j < idx_points.size (); ++j)
00249 hull_sorted.points[j] = hull.points[idx_points[j].first];
00250
00251 hull.points = hull_sorted.points;
00252 }
00253 }
00254
00255
00256 qh_freeqhull (!qh_ALL);
00257 fclose (errfile);
00258
00259
00260
00261 if (dim == 2)
00262 {
00263 Eigen::Affine3f transInverse = transform1.inverse ();
00264 pcl::transformPointCloud (hull, hull, transInverse);
00265 xyz_centroid[0] = -xyz_centroid[0];
00266 xyz_centroid[1] = -xyz_centroid[1];
00267 xyz_centroid[2] = -xyz_centroid[2];
00268 pcl::demeanPointCloud (hull, xyz_centroid, hull);
00269 }
00270
00271 hull.width = hull.points.size ();
00272 hull.height = 1;
00273 hull.is_dense = true;
00274 }
00275
00277 template<typename PointInT> void
00278 pcl::ConvexHull<PointInT>::reconstruct (PointCloud &output)
00279 {
00280 output.header = input_->header;
00281 if (!initCompute ())
00282 {
00283 output.points.clear ();
00284 return;
00285 }
00286
00287
00288 std::vector<pcl::Vertices> polygons;
00289 performReconstruction (output, polygons, false);
00290
00291 output.width = output.points.size ();
00292 output.height = 1;
00293 output.is_dense = true;
00294
00295 deinitCompute ();
00296 }
00297
00299 template<typename PointInT> void
00300 pcl::ConvexHull<PointInT>::reconstruct (PointCloud &points,
00301 std::vector<pcl::Vertices> &polygons)
00302 {
00303 points.header = input_->header;
00304 if (!initCompute ())
00305 {
00306 points.points.clear ();
00307 return;
00308 }
00309
00310
00311 performReconstruction (points, polygons, true);
00312
00313 points.width = points.points.size ();
00314 points.height = 1;
00315 points.is_dense = true;
00316
00317 deinitCompute ();
00318 }
00319
00320 #define PCL_INSTANTIATE_ConvexHull(T) template class pcl::ConvexHull<T>;
00321
00322 #endif // PCL_SURFACE_IMPL_CONVEX_HULL_H_