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
00039 #include <gtest/gtest.h>
00040
00041 #include <boost/make_shared.hpp>
00042 #include <pcl/point_types.h>
00043 #include <pcl/io/pcd_io.h>
00044 #include <pcl/kdtree/kdtree_flann.h>
00045 #include <pcl/surface/mls.h>
00046 #include <pcl/surface/gp3.h>
00047 #include <pcl/surface/grid_projection.h>
00048 #include <pcl/surface/convex_hull.h>
00049 #include <pcl/surface/concave_hull.h>
00050 #include <pcl/common/common.h>
00051
00052 using namespace pcl;
00053 using namespace pcl::io;
00054 using namespace std;
00055
00056 typedef KdTree<PointXYZ>::Ptr KdTreePtr;
00057
00058 PointCloud<PointXYZ> cloud;
00059 vector<int> indices;
00060 KdTreePtr tree;
00061
00063 TEST (PCL, MovingLeastSquares)
00064 {
00065
00066 PointCloud<PointXYZ> mls_points;
00067 PointCloud<Normal>::Ptr mls_normals (new PointCloud<Normal> ());
00068 MovingLeastSquares<PointXYZ, Normal> mls;
00069
00070
00071 mls.setInputCloud (cloud.makeShared ());
00072 mls.setOutputNormals (mls_normals);
00073 mls.setIndices (boost::make_shared <vector<int> > (indices));
00074 mls.setPolynomialFit (true);
00075 mls.setSearchMethod (tree);
00076 mls.setSearchRadius (0.03);
00077
00078
00079 mls.reconstruct (mls_points);
00080 EXPECT_NEAR (mls_points.points[0].x, 0.005, 1e-3);
00081 EXPECT_NEAR (mls_points.points[0].y, 0.111, 1e-3);
00082 EXPECT_NEAR (mls_points.points[0].z, 0.038, 1e-3);
00083 EXPECT_NEAR (fabs (mls_normals->points[0].normal[0]), 0.1176, 1e-3);
00084 EXPECT_NEAR (fabs (mls_normals->points[0].normal[1]), 0.6193, 1e-3);
00085 EXPECT_NEAR (fabs (mls_normals->points[0].normal[2]), 0.7762, 1e-3);
00086 EXPECT_NEAR (mls_normals->points[0].curvature, 0.012, 1e-3);
00087 }
00088
00090 TEST (PCL, GreedyProjectionTriangulation)
00091 {
00092
00093 PointCloud<PointNormal> cloud_with_normals;
00094 cloud_with_normals.height = 1;
00095 cloud_with_normals.is_dense = true;
00096 for (float x = 0; x <= 0.01; x += 0.01)
00097 {
00098 for (float y = 0; y <= 0.01; y += 0.01)
00099 {
00100 PointNormal p;
00101 p.x = x;
00102 p.y = y;
00103 p.z = 0;
00104 p.normal[0] = 0;
00105 p.normal[1] = 0;
00106 p.normal[2] = 1;
00107 p.curvature = 0;
00108 cloud_with_normals.points.push_back (p);
00109 }
00110 }
00111 cloud_with_normals.width = cloud_with_normals.points.size ();
00112 PointCloud<PointNormal>::ConstPtr cloud_ptr = cloud_with_normals.makeShared ();
00113
00114
00115 KdTree<PointNormal>::Ptr tree2 = boost::make_shared<KdTreeFLANN<PointNormal> > ();
00116 tree2->setInputCloud (cloud_ptr);
00117
00118
00119 PolygonMesh triangles;
00120 GreedyProjectionTriangulation<PointNormal> gp3;
00121
00122
00123 gp3.setInputCloud (cloud_ptr);
00124 gp3.setSearchMethod (tree2);
00125 gp3.setSearchRadius (0.02);
00126 gp3.setMu (2.5);
00127 gp3.setMaximumNearestNeighbors (50);
00128 gp3.setMaximumSurfaceAgle(M_PI/4);
00129 gp3.setMinimumAngle(M_PI/18);
00130 gp3.setMaximumAngle(2*M_PI/3);
00131 gp3.setNormalConsistency(false);
00132
00133
00134 gp3.reconstruct (triangles);
00135 EXPECT_EQ (triangles.cloud.width, cloud_with_normals.width);
00136 EXPECT_EQ (triangles.cloud.height, cloud_with_normals.height);
00137 EXPECT_EQ ((int)triangles.polygons.size(), 2);
00138 EXPECT_EQ ((int)triangles.polygons.at(0).vertices.size(), 3);
00139 EXPECT_EQ ((int)triangles.polygons.at(0).vertices.at(0), 0);
00140 EXPECT_EQ ((int)triangles.polygons.at(0).vertices.at(1), 1);
00141 EXPECT_EQ ((int)triangles.polygons.at(0).vertices.at(2), 2);
00142
00143
00144 std::vector<int> parts = gp3.getPartIDs();
00145 std::vector<int> states = gp3.getPointStates();
00146 int nr_points = cloud_with_normals.width * cloud_with_normals.height;
00147 EXPECT_EQ (parts.size (), nr_points);
00148 EXPECT_EQ (states.size (), nr_points);
00149 for (int i = 0; i < nr_points; i++)
00150 {
00151 EXPECT_EQ (parts[i], 0);
00152 EXPECT_EQ (states[i], gp3.BOUNDARY);
00153 }
00154 }
00155
00157 TEST (PCL, GridProjection)
00158 {
00159
00160 PointCloud<PointNormal> cloud_with_normals;
00161 cloud_with_normals.height = 1;
00162 cloud_with_normals.is_dense = true;
00163 for (float x = 0; x <= 0.01; x += 0.01)
00164 {
00165 for (float y = 0; y <= 0.01; y += 0.01)
00166 {
00167 PointNormal p;
00168 p.x = x;
00169 p.y = y;
00170 p.z = 0;
00171 p.normal[0] = 0;
00172 p.normal[1] = 0;
00173 p.normal[2] = 1;
00174 p.curvature = 0;
00175 cloud_with_normals.points.push_back (p);
00176 }
00177 }
00178 cloud_with_normals.width = cloud_with_normals.points.size ();
00179 PointCloud<PointNormal>::ConstPtr cloud_ptr = cloud_with_normals.makeShared ();
00180
00181
00182 KdTree<PointNormal>::Ptr tree2 = boost::make_shared<KdTreeFLANN<PointNormal> > ();
00183 tree2->setInputCloud (cloud_ptr);
00184
00185
00186 PolygonMesh triangles;
00187 GridProjection<PointNormal> gp3;
00188
00189
00190 gp3.setInputCloud (cloud_ptr);
00191 gp3.setSearchMethod (tree2);
00192 gp3.setResolution (0.1);
00193
00194
00195 gp3.reconstruct (triangles);
00196
00197
00198
00200
00201 }
00202
00204 TEST (PCL, ConvexHull_bunny)
00205 {
00206 pcl::PointCloud<pcl::PointXYZ> hull;
00207 std::vector<pcl::Vertices> polygons;
00208
00209 pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloudptr (new pcl::PointCloud<pcl::PointXYZ> (cloud));
00210 pcl::ConvexHull<pcl::PointXYZ> chull;
00211 chull.setInputCloud (cloudptr);
00212 chull.reconstruct (hull, polygons);
00213
00214 EXPECT_EQ (polygons.size (), 206);
00215
00216
00217 Eigen::Vector4f min_pt_hull, max_pt_hull;
00218 pcl::getMinMax3D (hull, min_pt_hull, max_pt_hull);
00219
00220 Eigen::Vector4f min_pt, max_pt;
00221 pcl::getMinMax3D (hull, min_pt, max_pt);
00222
00223 EXPECT_EQ((min_pt - max_pt).norm (), (min_pt_hull - max_pt_hull).norm ());
00224 }
00225
00227 TEST (PCL, ConvexHull_LTable)
00228 {
00229
00230 pcl::PointCloud<pcl::PointXYZ> cloud_out_ltable;
00231 cloud_out_ltable.points.resize (100);
00232
00233 int npoints = 0;
00234 for (size_t i = 0; i < 8; i++)
00235 {
00236 for (size_t j = 0; j <= 2; j++)
00237 {
00238 cloud_out_ltable.points[npoints].x = (double)(i)*0.5;
00239 cloud_out_ltable.points[npoints].y = -(double)(j)*0.5;
00240 cloud_out_ltable.points[npoints].z = 0;
00241 npoints++;
00242 }
00243 }
00244
00245 for (size_t i = 0; i <= 2; i++)
00246 {
00247 for (size_t j = 3; j < 8; j++)
00248 {
00249 cloud_out_ltable.points[npoints].x = (double)(i)*0.5;
00250 cloud_out_ltable.points[npoints].y = -(double)(j)*0.5;
00251 cloud_out_ltable.points[npoints].z = 0;
00252 npoints++;
00253 }
00254 }
00255
00256 cloud_out_ltable.points.resize (npoints);
00257
00258 pcl::PointCloud<pcl::PointXYZ> hull;
00259 std::vector<pcl::Vertices> polygons;
00260 pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloudptr (new pcl::PointCloud<pcl::PointXYZ> (cloud_out_ltable));
00261 pcl::ConvexHull<pcl::PointXYZ> chull;
00262 chull.setInputCloud (cloudptr);
00263 chull.reconstruct (hull, polygons);
00264
00265 EXPECT_EQ (polygons.size (), 1);
00266 EXPECT_EQ (hull.points.size (), 11);
00267 }
00268
00270 TEST (PCL, ConcaveHull_LTable)
00271 {
00272
00273 pcl::PointCloud<pcl::PointXYZ> cloud_out_ltable;
00274 cloud_out_ltable.points.resize (100);
00275
00276 int npoints = 0;
00277 for (size_t i = 0; i < 8; i++)
00278 {
00279 for (size_t j = 0; j <= 2; j++)
00280 {
00281 cloud_out_ltable.points[npoints].x = (double)(i)*0.5;
00282 cloud_out_ltable.points[npoints].y = -(double)(j)*0.5;
00283 cloud_out_ltable.points[npoints].z = 0;
00284 npoints++;
00285 }
00286 }
00287
00288 for (size_t i = 0; i <= 2; i++)
00289 {
00290 for(size_t j = 3; j < 8; j++)
00291 {
00292 cloud_out_ltable.points[npoints].x = (double)(i)*0.5;
00293 cloud_out_ltable.points[npoints].y = -(double)(j)*0.5;
00294 cloud_out_ltable.points[npoints].z = 0;
00295 npoints++;
00296 }
00297 }
00298
00299 cloud_out_ltable.points.resize (npoints);
00300
00301 pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloudptr (new pcl::PointCloud<pcl::PointXYZ> (cloud_out_ltable));
00302
00303 pcl::PointCloud<pcl::PointXYZ> alpha_shape, voronoi_centers;
00304 std::vector<pcl::Vertices> polygons_alpha;
00305
00306 pcl::ConcaveHull<pcl::PointXYZ> concave_hull;
00307 concave_hull.setInputCloud (cloudptr);
00308 concave_hull.setAlpha (0.5);
00309 concave_hull.setVoronoiCenters (voronoi_centers);
00310 concave_hull.reconstruct (alpha_shape, polygons_alpha);
00311
00312 EXPECT_EQ (alpha_shape.points.size (), 27);
00313
00314 pcl::PointCloud<pcl::PointXYZ> alpha_shape1, voronoi_centers1;
00315 std::vector<pcl::Vertices> polygons_alpha1;
00316
00317 pcl::ConcaveHull<pcl::PointXYZ> concave_hull1;
00318 concave_hull1.setInputCloud (cloudptr);
00319 concave_hull1.setAlpha (1.5);
00320 concave_hull1.setVoronoiCenters (voronoi_centers1);
00321 concave_hull1.reconstruct (alpha_shape1, polygons_alpha1);
00322
00323 EXPECT_EQ (alpha_shape1.points.size (), 23);
00324
00325 pcl::PointCloud<pcl::PointXYZ> alpha_shape2, voronoi_centers2;
00326 std::vector<pcl::Vertices> polygons_alpha2;
00327 pcl::ConcaveHull<pcl::PointXYZ> concave_hull2;
00328 concave_hull2.setInputCloud (cloudptr);
00329 concave_hull2.setAlpha (3);
00330 concave_hull2.setVoronoiCenters (voronoi_centers2);
00331 concave_hull2.reconstruct (alpha_shape2, polygons_alpha2);
00332
00333 EXPECT_EQ (alpha_shape2.points.size (), 19);
00334 }
00335
00336
00337 int
00338 main (int argc, char** argv)
00339 {
00340 sensor_msgs::PointCloud2 cloud_blob;
00341 loadPCDFile ("./test/bun0.pcd", cloud_blob);
00342 fromROSMsg (cloud_blob, cloud);
00343
00344 indices.resize (cloud.points.size ());
00345 for (size_t i = 0; i < indices.size (); ++i) { indices[i] = i; }
00346
00347 tree = boost::make_shared<KdTreeFLANN<PointXYZ> > (false);
00348 tree->setInputCloud (cloud.makeShared ());
00349
00350 testing::InitGoogleTest (&argc, argv);
00351 return (RUN_ALL_TESTS ());
00352 }
00353