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_CONCAVE_HULL_H_
00039 #define PCL_SURFACE_IMPL_CONCAVE_HULL_H_
00040
00041 #include "pcl/surface/concave_hull.h"
00042 #include "pcl/common/common.h"
00043 #include "pcl/registration/transforms.h"
00044
00046 template<typename PointInT> void
00047 pcl::ConcaveHull<PointInT>::reconstruct (PointCloud &output)
00048 {
00049 output.header = input_->header;
00050 if (!initCompute ())
00051 {
00052 output.points.clear ();
00053 return;
00054 }
00055
00056
00057 std::vector<pcl::Vertices> polygons;
00058 performReconstruction (output, polygons);
00059
00060 output.width = output.points.size ();
00061 output.height = 1;
00062 output.is_dense = true;
00063
00064 deinitCompute ();
00065 }
00066
00068 template<typename PointInT> void
00069 pcl::ConcaveHull<PointInT>::reconstruct (PointCloud &points,
00070 std::vector<pcl::Vertices> &polygons)
00071 {
00072 points.header = input_->header;
00073 if (!initCompute ())
00074 {
00075 points.points.clear ();
00076 return;
00077 }
00078
00079
00080 performReconstruction (points, polygons);
00081
00082 points.width = points.points.size ();
00083 points.height = 1;
00084 points.is_dense = true;
00085
00086 deinitCompute ();
00087 }
00088
00090 template<typename PointInT>
00091 void
00092 pcl::ConcaveHull<PointInT>::performReconstruction (PointCloud &alpha_shape,
00093 std::vector<pcl::Vertices> &polygons)
00094 {
00095 EIGEN_ALIGN16 Eigen::Matrix3f covariance_matrix;
00096 Eigen::Vector4f xyz_centroid;
00097 compute3DCentroid (*input_, *indices_, xyz_centroid);
00098 computeCovarianceMatrix (*input_, *indices_, xyz_centroid, covariance_matrix);
00099 EIGEN_ALIGN16 Eigen::Vector3f eigen_values;
00100 EIGEN_ALIGN16 Eigen::Matrix3f eigen_vectors;
00101 pcl::eigen33 (covariance_matrix, eigen_vectors, eigen_values);
00102
00103 Eigen::Affine3f transform1;
00104 transform1.setIdentity();
00105 int dim = 3;
00106 if (eigen_values[0] / eigen_values[2] < 1.0e-5)
00107 {
00108
00109
00110
00111 eigen_vectors.col (2) = eigen_vectors.col(0).cross(eigen_vectors.col(1));
00112 eigen_vectors.col (1) = eigen_vectors.col(2).cross(eigen_vectors.col(0));
00113
00114 transform1 (0, 2) = eigen_vectors (0, 0);
00115 transform1 (1, 2) = eigen_vectors (1, 0);
00116 transform1 (2, 2) = eigen_vectors (2, 0);
00117
00118 transform1 (0, 1) = eigen_vectors (0, 1);
00119 transform1 (1, 1) = eigen_vectors (1, 1);
00120 transform1 (2, 1) = eigen_vectors (2, 1);
00121 transform1 (0, 0) = eigen_vectors (0, 2);
00122 transform1 (1, 0) = eigen_vectors (1, 2);
00123 transform1 (2, 0) = eigen_vectors (2, 2);
00124
00125
00126 transform1 = transform1.inverse ();
00127 dim = 2;
00128 }
00129 else
00130 {
00131 transform1.setIdentity ();
00132 }
00133
00134
00135 if (dim == 3)
00136 {
00137 ROS_WARN ("Alpha shapes for 3-dimensional point clouds not yet implemented..., returning empty PolygonMesh and alpha_shape_points");
00138 alpha_shape.points.resize (0);
00139 alpha_shape.width = alpha_shape.height = 0;
00140 polygons.resize (0);
00141 return;
00142 }
00143
00144 PointCloud cloud_transformed;
00145 pcl::demeanPointCloud(*input_, *indices_,xyz_centroid,cloud_transformed);
00146 pcl::transformPointCloud (cloud_transformed, cloud_transformed, transform1);
00147
00148
00149 boolT ismalloc = True;
00150
00151 char flags[] = "qhull d QJ";
00152
00153 FILE *outfile = NULL;
00154
00155 FILE *errfile = stderr;
00156
00157 int exitcode;
00158
00159
00160 coordT *points = (coordT *)calloc (cloud_transformed.points.size () * dim, sizeof (coordT));
00161
00162 for (size_t i = 0; i < cloud_transformed.points.size (); ++i)
00163 {
00164 points[i * dim + 0] = (coordT)cloud_transformed.points[i].x;
00165 points[i * dim + 1] = (coordT)cloud_transformed.points[i].y;
00166
00167 if (dim > 2)
00168 points[i * dim + 2] = (coordT)cloud_transformed.points[i].z;
00169 }
00170
00171
00172 exitcode = qh_new_qhull (dim, cloud_transformed.points.size (), points, ismalloc, flags,
00173 outfile, errfile);
00174 qh_setvoronoi_all ();
00175
00176 int num_vertices = qh num_vertices;
00177 alpha_shape.points.resize (num_vertices);
00178
00179 vertexT *vertex;
00180
00181 int max_vertex_id=-1;
00182 FORALLvertices
00183 {
00184 if (vertex->id > max_vertex_id)
00185 max_vertex_id = vertex->id;
00186 }
00187
00188 facetT *facet;
00189 int non_upperdelaunay=0;
00190 FORALLfacets
00191 {
00192 if (!facet->upperdelaunay)
00193 non_upperdelaunay++;
00194 }
00195
00196 ++max_vertex_id;
00197 std::vector<int> qhid_to_pcidx (max_vertex_id);
00198
00199 int num_facets = qh num_facets;
00200 int dd = 0;
00201
00202
00203 setT* edges_set = qh_settemp (3 * num_facets);
00204 voronoi_centers_.points.resize (num_facets);
00205 FORALLfacets
00206 {
00207
00208 if (!facet->upperdelaunay)
00209 {
00210
00211
00212 vertexT* anyVertex = (vertexT *)(facet->vertices->e[0].p);
00213 double r = computeDistVertexCenter2D (anyVertex, facet->center);
00214 if (r < alpha_)
00215 {
00216 pcl::Vertices facet_vertices;
00217 qh_makeridges (facet);
00218 facet->good = true;
00219
00220 ridgeT *ridge, **ridgep;
00221 FOREACHridge_(facet->ridges)
00222 qh_setappend (&edges_set, ridge);
00223
00224 voronoi_centers_.points[dd].x = facet->center[0];
00225 voronoi_centers_.points[dd].y = facet->center[1];
00226 voronoi_centers_.points[dd].z = 0;
00227 ++dd;
00228 }
00229 else
00230 facet->good = false;
00231 }
00232 }
00233
00234 int vertices = 0;
00235 std::vector<bool> added_vertices (max_vertex_id, false);
00236 ridgeT *ridge, **ridgep;
00237 FOREACHridge_(edges_set)
00238 {
00239 if (ridge->bottom->upperdelaunay || ridge->top->upperdelaunay || !ridge->top->good || !ridge->bottom->good)
00240 {
00241 int vertex_n, vertex_i;
00242 FOREACHvertex_i_((*ridge).vertices)
00243 {
00244 if (!added_vertices[vertex->id])
00245 {
00246 alpha_shape.points[vertices].x = vertex->point[0];
00247 alpha_shape.points[vertices].y = vertex->point[1];
00248
00249 if (dim > 2)
00250 alpha_shape.points[vertices].z = vertex->point[2];
00251 else
00252 alpha_shape.points[vertices].z = 0;
00253
00254 qhid_to_pcidx[vertex->id] = vertices;
00255 added_vertices[vertex->id] = true;
00256 vertices++;
00257 }
00258 }
00259 }
00260 }
00261
00262 alpha_shape.points.resize (vertices);
00263 polygons.resize (dd);
00264 voronoi_centers_.points.resize (dd);
00265
00266 if (dim == 2)
00267 {
00268 Eigen::Affine3f transInverse = transform1.inverse ();
00269 pcl::transformPointCloud (alpha_shape, alpha_shape, transInverse);
00270 xyz_centroid[0] = -xyz_centroid[0];
00271 xyz_centroid[1] = -xyz_centroid[1];
00272 xyz_centroid[2] = -xyz_centroid[2];
00273 pcl::demeanPointCloud(alpha_shape,xyz_centroid,alpha_shape);
00274 }
00275 }
00276
00277 #define PCL_INSTANTIATE_ConcaveHull(T) template class pcl::ConcaveHull<T>;
00278
00279 #endif // PCL_SURFACE_IMPL_CONCAVE_HULL_H_