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 
00039 
00040 #include <gtest/gtest.h>
00041 
00042 #include <pcl/point_types.h>
00043 #include <pcl/io/pcd_io.h>
00044 #include <pcl/io/vtk_io.h>
00045 #include <pcl/features/normal_3d.h>
00046 #include <pcl/surface/convex_hull.h>
00047 #include <pcl/common/common.h>
00048 #include <pcl/sample_consensus/sac_model_plane.h>
00049 #include <pcl/filters/project_inliers.h>
00050 
00051 using namespace pcl;
00052 using namespace pcl::io;
00053 using namespace std;
00054 
00055 PointCloud<PointXYZ>::Ptr cloud (new PointCloud<PointXYZ>);
00056 PointCloud<PointNormal>::Ptr cloud_with_normals (new PointCloud<PointNormal>);
00057 search::KdTree<PointXYZ>::Ptr tree;
00058 search::KdTree<PointNormal>::Ptr tree2;
00059 
00060 
00061 PointCloud<PointXYZ>::Ptr cloud1 (new PointCloud<PointXYZ>);
00062 PointCloud<PointNormal>::Ptr cloud_with_normals1 (new PointCloud<PointNormal>);
00063 search::KdTree<PointXYZ>::Ptr tree3;
00064 search::KdTree<PointNormal>::Ptr tree4;
00065 
00067 TEST (PCL, ConvexHull_bunny)
00068 {
00069   pcl::PointCloud<pcl::PointXYZ> hull;
00070   std::vector<pcl::Vertices> polygons;
00071 
00072   pcl::ConvexHull<pcl::PointXYZ> chull;
00073   chull.setInputCloud (cloud);
00074   chull.reconstruct (hull, polygons);
00075 
00076   
00077   
00078   
00079   
00080 
00081   EXPECT_EQ (polygons.size (), 206);
00082 
00083   
00084   Eigen::Vector4f min_pt_hull, max_pt_hull;
00085   pcl::getMinMax3D (hull, min_pt_hull, max_pt_hull);
00086 
00087   Eigen::Vector4f min_pt, max_pt;
00088   pcl::getMinMax3D (hull, min_pt, max_pt);
00089 
00090   EXPECT_NEAR ((min_pt - max_pt).norm (), (min_pt_hull - max_pt_hull).norm (), 1e-5);
00091 
00092   
00093   
00094   
00095 
00096   
00097   std::vector<pcl::Vertices> polygons2;
00098   chull.reconstruct (polygons2);
00099 
00100   
00101   ASSERT_EQ (polygons.size (), polygons2.size ());
00102   for (size_t i = 0; i < polygons.size (); ++i)
00103   {
00104     const pcl::Vertices & face1 = polygons[i];
00105     const pcl::Vertices & face2 = polygons2[i];
00106     ASSERT_EQ (face1.vertices.size (), face2.vertices.size ());
00107     for (size_t j = 0; j < face1.vertices.size (); ++j)
00108     {
00109       ASSERT_EQ (face1.vertices[j], face2.vertices[j]);
00110     }
00111   }
00112 
00113 
00114   
00115   
00116   
00117 
00118   
00119   PolygonMesh mesh;
00120   chull.reconstruct (mesh);
00121 
00122   
00123   PointCloud<pcl::PointXYZ> hull2;
00124   pcl::fromPCLPointCloud2 (mesh.cloud, hull2);
00125 
00126   
00127   ASSERT_EQ (hull.points.size (), hull2.points.size ());
00128   for (size_t i = 0; i < hull.points.size (); ++i)
00129   {
00130     const PointXYZ & p1 = hull.points[i];
00131     const PointXYZ & p2 = hull2.points[i];
00132     ASSERT_EQ (p1.x, p2.x);
00133     ASSERT_EQ (p1.y, p2.y);
00134     ASSERT_EQ (p1.z, p2.z);
00135   }
00136 
00137   
00138   ASSERT_EQ (polygons.size (), mesh.polygons.size ());
00139   for (size_t i = 0; i < polygons.size (); ++i)
00140   {
00141     const pcl::Vertices & face1 = polygons[i];
00142     const pcl::Vertices & face2 = mesh.polygons[i];
00143     ASSERT_EQ (face1.vertices.size (), face2.vertices.size ());
00144     for (size_t j = 0; j < face1.vertices.size (); ++j)
00145     {
00146       ASSERT_EQ (face1.vertices[j], face2.vertices[j]);
00147     }
00148   }    
00149 }
00150 
00152 TEST (PCL, ConvexHull_planar_bunny)
00153 {
00154   ConvexHull<PointXYZ> convex_hull_3d;
00155   convex_hull_3d.setInputCloud (cloud);
00156   PointCloud<PointXYZ> hull_3d;
00157   convex_hull_3d.reconstruct (hull_3d);
00158 
00159   EXPECT_EQ (convex_hull_3d.getDimension (), 3);
00160 
00161 
00162   ModelCoefficients::Ptr plane_coefficients (new ModelCoefficients ());
00163   plane_coefficients->values.resize (4);
00164   plane_coefficients->values[0] = -0.010666f;
00165   plane_coefficients->values[1] = -0.793771f;
00166   plane_coefficients->values[2] = -0.607779f;
00167   plane_coefficients->values[3] = 0.993252f;
00168 
00170   ProjectInliers<PointXYZ> project_inliers_filter;
00171   project_inliers_filter.setInputCloud (cloud);
00172   project_inliers_filter.setModelType (SACMODEL_PLANE);
00173   project_inliers_filter.setModelCoefficients (plane_coefficients);
00174   PointCloud<PointXYZ>::Ptr cloud_projected (new PointCloud<PointXYZ> ());
00175   project_inliers_filter.filter (*cloud_projected);
00176 
00177   ConvexHull<PointXYZ> convex_hull_2d;
00178   convex_hull_2d.setInputCloud (cloud_projected);
00179   PointCloud<PointXYZ> hull_2d;
00180   convex_hull_2d.reconstruct (hull_2d);
00181 
00182   EXPECT_EQ (convex_hull_2d.getDimension (), 2);
00183 }
00184 
00186 TEST (PCL, ConvexHull_LTable)
00187 {
00188   
00189   pcl::PointCloud<pcl::PointXYZ> cloud_out_ltable;
00190   cloud_out_ltable.points.resize (100);
00191 
00192   int npoints = 0;
00193   for (size_t i = 0; i < 8; i++)
00194   {
00195     for (size_t j = 0; j <= 2; j++)
00196     {
00197       cloud_out_ltable.points[npoints].x = float (i) * 0.5f;
00198       cloud_out_ltable.points[npoints].y = -float (j) * 0.5f;
00199       cloud_out_ltable.points[npoints].z = 0.f;
00200       npoints++;
00201     }
00202   }
00203 
00204   for (size_t i = 0; i <= 2; i++)
00205   {
00206     for (size_t j = 3; j < 8; j++)
00207     {
00208       cloud_out_ltable.points[npoints].x = float (i) * 0.5f;
00209       cloud_out_ltable.points[npoints].y = -float (j) * 0.5f;
00210       cloud_out_ltable.points[npoints].z = 0.f;
00211       npoints++;
00212     }
00213   }
00214 
00215   
00216   cloud_out_ltable.points[npoints].x = -0.5f;
00217   cloud_out_ltable.points[npoints].y = 0.5f;
00218   cloud_out_ltable.points[npoints].z = 0.f;
00219   npoints++;
00220 
00221   cloud_out_ltable.points[npoints].x = 4.5f;
00222   cloud_out_ltable.points[npoints].y = 0.5f;
00223   cloud_out_ltable.points[npoints].z = 0.f;
00224   npoints++;
00225 
00226   cloud_out_ltable.points[npoints].x = 4.5f;
00227   cloud_out_ltable.points[npoints].y = -1.0f;
00228   cloud_out_ltable.points[npoints].z = 0.f;
00229   npoints++;
00230 
00231   cloud_out_ltable.points[npoints].x = 1.0f;
00232   cloud_out_ltable.points[npoints].y = -4.5f;
00233   cloud_out_ltable.points[npoints].z = 0.f;
00234   npoints++;
00235 
00236   cloud_out_ltable.points[npoints].x = -0.5f;
00237   cloud_out_ltable.points[npoints].y = -4.5f;
00238   cloud_out_ltable.points[npoints].z = 0.f;
00239   npoints++;
00240 
00241   cloud_out_ltable.points.resize (npoints);
00242 
00243   pcl::PointCloud<pcl::PointXYZ> hull;
00244   std::vector<pcl::Vertices> polygons;
00245   pcl::PointCloud<pcl::PointXYZ>::ConstPtr cloudptr (new pcl::PointCloud<pcl::PointXYZ> (cloud_out_ltable));
00246   pcl::ConvexHull<pcl::PointXYZ> chull;
00247   chull.setInputCloud (cloudptr);
00248   chull.reconstruct (hull, polygons);
00249 
00250   EXPECT_EQ (polygons.size (), 1);
00251   EXPECT_EQ (hull.points.size (), 5);
00252 
00253 
00254   
00255   
00256   
00257 
00258   
00259   std::vector<pcl::Vertices> polygons2;
00260   chull.reconstruct (polygons2);
00261 
00262   
00263   ASSERT_EQ (polygons.size (), polygons2.size ());
00264   for (size_t i = 0; i < polygons.size (); ++i)
00265   {
00266     const pcl::Vertices & face1 = polygons[i];
00267     const pcl::Vertices & face2 = polygons2[i];
00268     ASSERT_EQ (face1.vertices.size (), face2.vertices.size ());
00269     for (size_t j = 0; j < face1.vertices.size (); ++j)
00270     {
00271       ASSERT_EQ (face1.vertices[j], face2.vertices[j]);
00272     }
00273   }
00274 
00275 
00276   
00277   
00278   
00279 
00280   
00281   PolygonMesh mesh;
00282   chull.reconstruct (mesh);
00283 
00284   
00285   PointCloud<pcl::PointXYZ> hull2;
00286   pcl::fromPCLPointCloud2 (mesh.cloud, hull2);
00287 
00288   
00289   ASSERT_EQ (hull.points.size (), hull2.points.size ());
00290   for (size_t i = 0; i < hull.points.size (); ++i)
00291   {
00292     const PointXYZ & p1 = hull.points[i];
00293     const PointXYZ & p2 = hull2.points[i];
00294     ASSERT_EQ (p1.x, p2.x);
00295     ASSERT_EQ (p1.y, p2.y);
00296     ASSERT_EQ (p1.z, p2.z);
00297   }
00298 
00299   
00300   ASSERT_EQ (polygons.size (), mesh.polygons.size ());
00301   for (size_t i = 0; i < polygons.size (); ++i)
00302   {
00303     const pcl::Vertices & face1 = polygons[i];
00304     const pcl::Vertices & face2 = mesh.polygons[i];
00305     ASSERT_EQ (face1.vertices.size (), face2.vertices.size ());
00306     for (size_t j = 0; j < face1.vertices.size (); ++j)
00307     {
00308       ASSERT_EQ (face1.vertices[j], face2.vertices[j]);
00309     }
00310   }    
00311 
00312 }
00313 
00315 TEST (PCL, ConvexHull_2dsquare)
00316 {
00317   
00318   pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZ> ());
00319   input_cloud->width = 1000000;
00320   input_cloud->height = 1;
00321   input_cloud->points.resize (input_cloud->width * input_cloud->height);
00322   
00323   
00324   boost::mt19937 rng_alg;
00325   boost::uniform_01<boost::mt19937> rng (rng_alg);
00326   rng.base ().seed (12345u);
00327 
00328   for (size_t i = 0; i < input_cloud->points.size (); i++)
00329   {
00330     input_cloud->points[i].x = (2.0f * float (rng ()))-1.0f;
00331     input_cloud->points[i].y = (2.0f * float (rng ()))-1.0f;
00332     input_cloud->points[i].z = 1.0f;
00333   }
00334 
00335   
00336   pcl::PointCloud<pcl::PointXYZ> hull;
00337   pcl::ConvexHull<pcl::PointXYZ> chull;
00338   chull.setInputCloud (input_cloud);
00339   
00340   chull.reconstruct (hull);
00341 
00342   
00343   ASSERT_EQ (2, chull.getDimension ());
00344   
00345   
00346   
00347   Eigen::Vector4f plane_normal (0.0, 0.0, -1.0, 1.0);
00348 
00349   
00350   std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> > facets;
00351   facets.push_back (Eigen::Vector4f (-1.0, 0.0, 0.0, 1.0));
00352   facets.push_back (Eigen::Vector4f (-1.0, 0.0, 0.0, -1.0));
00353   facets.push_back (Eigen::Vector4f (0.0, -1.0, 0.0, 1.0));
00354   facets.push_back (Eigen::Vector4f (0.0, -1.0, 0.0, -1.0));
00355 
00356   
00357   for (size_t i = 0; i < hull.points.size (); i++)
00358   {
00359     float dist = fabs (hull.points[i].getVector4fMap ().dot (plane_normal));
00360     EXPECT_NEAR (dist, 0.0, 1e-2);
00361 
00362     float min_dist = std::numeric_limits<float>::infinity ();
00363     for (size_t j = 0; j < facets.size (); j++)
00364     {
00365       float d2 = fabs (hull.points[i].getVector4fMap ().dot (facets[j]));
00366       
00367       if (d2 < min_dist)
00368         min_dist = d2;
00369     }
00370     EXPECT_NEAR (min_dist, 0.0, 1e-2);
00371   }
00372 }
00373 
00375 TEST (PCL, ConvexHull_3dcube)
00376 {
00377   
00378   pcl::PointCloud<pcl::PointXYZ>::Ptr input_cloud (new pcl::PointCloud<pcl::PointXYZ> ());
00379   input_cloud->width = 10000000;
00380   input_cloud->height = 1;
00381   input_cloud->points.resize (input_cloud->width * input_cloud->height);
00382   
00383   
00384   boost::mt19937 rng_alg;
00385   boost::uniform_01<boost::mt19937> rng (rng_alg);
00386   rng.base ().seed (12345u);
00387 
00388   for (size_t i = 0; i < input_cloud->points.size (); i++)
00389   {
00390     input_cloud->points[i].x =  (2.0f * float (rng ()))-1.0f;
00391     input_cloud->points[i].y =  (2.0f * float (rng ()))-1.0f;
00392     input_cloud->points[i].z =  (2.0f * float (rng ()))-1.0f;
00393   }
00394 
00395   
00396   pcl::PointCloud<pcl::PointXYZ> hull;
00397   pcl::ConvexHull<pcl::PointXYZ> chull;
00398   chull.setInputCloud (input_cloud);
00399   
00400   chull.reconstruct (hull);
00401 
00402   
00403   ASSERT_EQ (3, chull.getDimension ());
00404   
00405   
00406   std::vector<Eigen::Vector4f, Eigen::aligned_allocator<Eigen::Vector4f> > facets;
00407   facets.push_back (Eigen::Vector4f (-1.0f, 0.0f, 0.0f, 1.0f));
00408   facets.push_back (Eigen::Vector4f (-1.0f, 0.0f, 0.0f, -1.0f));
00409   facets.push_back (Eigen::Vector4f (0.0f, -1.0f, 0.0f, 1.0f));
00410   facets.push_back (Eigen::Vector4f (0.0f, -1.0f, 0.0f, -1.0f));
00411   facets.push_back (Eigen::Vector4f (0.0f, 0.0f, -1.0f, 1.0f));
00412   facets.push_back (Eigen::Vector4f (0.0f, 0.0f, -1.0f, -1.0f));
00413 
00414   
00415   for (size_t i = 0; i < hull.points.size (); i++)
00416   {
00417     float min_dist = std::numeric_limits<float>::infinity ();
00418     for (size_t j = 0; j < facets.size (); j++)
00419     {
00420       float dist = fabs (hull.points[i].getVector4fMap ().dot (facets[j]));
00421       
00422       if (dist < min_dist)
00423         min_dist = dist;
00424     }
00425     EXPECT_NEAR (min_dist, 0.0, 1e-2);
00426   }
00427 }
00428 
00429 TEST (PCL, ConvexHull_4points)
00430 {
00431   pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_4 (new pcl::PointCloud<pcl::PointXYZ> ());
00432   pcl::PointXYZ p;
00433   p.x = p.y = p.z = 0.f;
00434   cloud_4->push_back (p);
00435 
00436   p.x = 1.f;
00437   p.y = 0.f;
00438   p.z = 0.f;
00439   cloud_4->push_back (p);
00440 
00441   p.x = 0.f;
00442   p.y = 1.f;
00443   p.z = 0.f;
00444   cloud_4->push_back (p);
00445 
00446   p.x = 1.f;
00447   p.y = 1.f;
00448   p.z = 0.f;
00449   cloud_4->push_back (p);
00450 
00451   cloud_4->height = 1;
00452   cloud_4->width = uint32_t (cloud_4->size ());
00453 
00454   ConvexHull<PointXYZ> convex_hull;
00455   convex_hull.setComputeAreaVolume (true);
00456   convex_hull.setInputCloud (cloud_4);
00457   PolygonMesh mesh;
00458   convex_hull.reconstruct (mesh);
00459 
00460   EXPECT_EQ (mesh.polygons.size (), 1);
00461 
00463    EXPECT_EQ (mesh.polygons[0].vertices.size (), 4);
00464 
00465   PointCloud<PointXYZ> mesh_cloud;
00466   fromPCLPointCloud2 (mesh.cloud, mesh_cloud);
00467 
00468   EXPECT_NEAR (mesh_cloud[0].x, 0.f, 1e-6);
00469   EXPECT_NEAR (mesh_cloud[0].y, 1.f, 1e-6);
00470   EXPECT_NEAR (mesh_cloud[0].z, 0.f, 1e-6);
00471 
00472   EXPECT_NEAR (mesh_cloud[1].x, 1.f, 1e-6);
00473   EXPECT_NEAR (mesh_cloud[1].y, 1.f, 1e-6);
00474   EXPECT_NEAR (mesh_cloud[1].z, 0.f, 1e-6);
00475 
00476   EXPECT_NEAR (mesh_cloud[2].x, 1.f, 1e-6);
00477   EXPECT_NEAR (mesh_cloud[2].y, 0.f, 1e-6);
00478   EXPECT_NEAR (mesh_cloud[2].z, 0.f, 1e-6);
00479 
00480   EXPECT_NEAR (mesh_cloud[3].x, 0.f, 1e-6);
00481   EXPECT_NEAR (mesh_cloud[3].y, 0.f, 1e-6);
00482   EXPECT_NEAR (mesh_cloud[3].z, 0.f, 1e-6);
00483 
00484   EXPECT_NEAR (convex_hull.getTotalArea (), 1.0f, 1e-6);
00485 }
00486 
00487 
00488 int
00489 main (int argc, char** argv)
00490 {
00491   if (argc < 2)
00492   {
00493     std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00494     return (-1);
00495   }
00496 
00497   
00498   pcl::PCLPointCloud2 cloud_blob;
00499   loadPCDFile (argv[1], cloud_blob);
00500   fromPCLPointCloud2 (cloud_blob, *cloud);
00501 
00502   
00503   tree.reset (new search::KdTree<PointXYZ> (false));
00504   tree->setInputCloud (cloud);
00505 
00506   
00507   NormalEstimation<PointXYZ, Normal> n;
00508   PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00509   n.setInputCloud (cloud);
00510   
00511   n.setSearchMethod (tree);
00512   n.setKSearch (20);
00513   n.compute (*normals);
00514 
00515   
00516   pcl::concatenateFields (*cloud, *normals, *cloud_with_normals);
00517       
00518   
00519   tree2.reset (new search::KdTree<PointNormal>);
00520   tree2->setInputCloud (cloud_with_normals);
00521 
00522   
00523   if (argc == 3)
00524   {
00525     pcl::PCLPointCloud2 cloud_blob1;
00526     loadPCDFile (argv[2], cloud_blob1);
00527     fromPCLPointCloud2 (cloud_blob1, *cloud1);
00528         
00529     tree3.reset (new search::KdTree<PointXYZ> (false));
00530     tree3->setInputCloud (cloud1);
00531 
00532     
00533     NormalEstimation<PointXYZ, Normal> n1;
00534     PointCloud<Normal>::Ptr normals1 (new PointCloud<Normal> ());
00535     n1.setInputCloud (cloud1);
00536 
00537     n1.setSearchMethod (tree3);
00538     n1.setKSearch (20);
00539     n1.compute (*normals1);
00540 
00541     
00542     pcl::concatenateFields (*cloud1, *normals1, *cloud_with_normals1);
00543     
00544     tree4.reset (new search::KdTree<PointNormal>);
00545     tree4->setInputCloud (cloud_with_normals1);
00546   }
00547 
00548   
00549   testing::InitGoogleTest (&argc, argv);
00550   return (RUN_ALL_TESTS ());
00551 }
00552