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 #include <iostream>
00040 #include <gtest/gtest.h>
00041 #include <pcl/common/distances.h>
00042 #include <pcl/common/time.h>
00043 #include <pcl/search/pcl_search.h>
00044 #include <pcl/search/flann_search.h>
00045 #include <pcl/search/impl/flann_search.hpp>
00046 #include <pcl/point_cloud.h>
00047 #include <pcl/point_types.h>
00048 
00049 using namespace std;
00050 using namespace pcl;
00051 
00052 PointCloud<PointXYZ> cloud, cloud_big;
00053 
00054 void
00055 init ()
00056 {
00057   float resolution = 0.1f;
00058   for (float z = -0.5f; z <= 0.5f; z += resolution)
00059     for (float y = -0.5f; y <= 0.5f; y += resolution)
00060       for (float x = -0.5f; x <= 0.5f; x += resolution)
00061         cloud.points.push_back (PointXYZ (x, y, z));
00062   cloud.width = int (cloud.points.size ());
00063   cloud.height = 1;
00064 
00065   cloud_big.width = 640;
00066   cloud_big.height = 480;
00067   srand (int (time (NULL)));
00068   
00069   for (size_t i = 0; i < cloud_big.width * cloud_big.height; ++i)
00070     cloud_big.points.push_back (
00071                                 PointXYZ (
00072                                   float (1024 * rand () / (RAND_MAX + 1.0)),
00073                                   float (1024 * rand () / (RAND_MAX + 1.0)),
00074                                   float (1024 * rand () / (RAND_MAX + 1.0))));
00075 }
00076 
00077 
00078 
00079 TEST (PCL, FlannSearch_nearestKSearch)
00080 {
00081   pcl::search::Search<PointXYZ>* FlannSearch = new pcl::search::FlannSearch<PointXYZ> (new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00082   FlannSearch->setInputCloud (cloud.makeShared ());
00083   PointXYZ test_point (0.01f, 0.01f, 0.01f);
00084   unsigned int no_of_neighbors = 20;
00085   multimap<float, int> sorted_brute_force_result;
00086   for (size_t i = 0; i < cloud.points.size (); ++i)
00087   {
00088     float distance = euclideanDistance (cloud.points[i], test_point);
00089     sorted_brute_force_result.insert (make_pair (distance, int (i)));
00090   }
00091   float max_dist = 0.0f;
00092   unsigned int counter = 0;
00093   for (multimap<float, int>::iterator it = sorted_brute_force_result.begin (); it != sorted_brute_force_result.end ()
00094       && counter < no_of_neighbors; ++it)
00095   {
00096     max_dist = max (max_dist, it->first);
00097     ++counter;
00098   }
00099 
00100   vector<int> k_indices;
00101   k_indices.resize (no_of_neighbors);
00102   vector<float> k_distances;
00103   k_distances.resize (no_of_neighbors);
00104 
00105   FlannSearch->nearestKSearch (test_point, no_of_neighbors, k_indices, k_distances);
00106 
00107   
00108   EXPECT_EQ (k_indices.size (), no_of_neighbors);
00109 
00110   
00111   for (size_t i = 0; i < k_indices.size (); ++i)
00112   {
00113     const PointXYZ& point = cloud.points[k_indices[i]];
00114     bool ok = euclideanDistance (test_point, point) <= max_dist;
00115     if (!ok)
00116     ok = (fabs (euclideanDistance (test_point, point)) - max_dist) <= 1e-6;
00117     
00118     
00119     EXPECT_EQ (ok, true);
00120   }
00121 
00122   ScopeTime scopeTime ("FLANN nearestKSearch");
00123   {
00124     pcl::search::Search<PointXYZ>* FlannSearch = new pcl::search::FlannSearch<PointXYZ>( new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00125     
00126     FlannSearch->setInputCloud (cloud_big.makeShared ());
00127     for (size_t i = 0; i < cloud_big.points.size (); ++i)
00128       FlannSearch->nearestKSearch (cloud_big.points[i], no_of_neighbors, k_indices, k_distances);
00129   }
00130 }
00131 
00132 
00133 TEST (PCL, FlannSearch_differentPointT)
00134 {
00135 
00136   unsigned int no_of_neighbors = 20;
00137 
00138   pcl::search::Search<PointXYZ>* FlannSearch = new pcl::search::FlannSearch<PointXYZ> (new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00139   
00140   FlannSearch->setInputCloud (cloud_big.makeShared ());
00141 
00142   PointCloud<PointXYZRGB> cloud_rgb;
00143 
00144   copyPointCloud (cloud_big, cloud_rgb);
00145 
00146 
00147 
00148   std::vector< std::vector< float > > dists;
00149   std::vector< std::vector< int > > indices;
00150   FlannSearch->nearestKSearchT (cloud_rgb, std::vector<int> (),no_of_neighbors,indices,dists);
00151 
00152   vector<int> k_indices;
00153   k_indices.resize (no_of_neighbors);
00154   vector<float> k_distances;
00155   k_distances.resize (no_of_neighbors);
00156 
00157   
00158   
00159   
00160   
00161 
00162   for (size_t i = 0; i < cloud_rgb.points.size (); ++i)
00163   {
00164     
00165     FlannSearch->nearestKSearch (cloud_big.points[i], no_of_neighbors, k_indices, k_distances);
00166     EXPECT_EQ (k_indices.size (), indices[i].size ());
00167     EXPECT_EQ (k_distances.size (), dists[i].size ());
00168     for (size_t j = 0; j< no_of_neighbors; j++)
00169     {
00170       EXPECT_TRUE (k_indices[j] == indices[i][j] || k_distances[j] == dists[i][j]);
00171       
00172       
00173     }
00174 
00175   }
00176 }
00177 
00178 
00179 TEST (PCL, FlannSearch_multipointKnnSearch)
00180 {
00181 
00182   unsigned int no_of_neighbors = 20;
00183 
00184 
00185   pcl::search::Search<PointXYZ>* FlannSearch = new pcl::search::FlannSearch<PointXYZ> (new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00186   
00187   FlannSearch->setInputCloud (cloud_big.makeShared ());
00188 
00189   std::vector< std::vector< float > > dists;
00190   std::vector< std::vector< int > > indices;
00191   FlannSearch->nearestKSearch (cloud_big, std::vector<int>(),no_of_neighbors,indices,dists);
00192 
00193   vector<int> k_indices;
00194   k_indices.resize (no_of_neighbors);
00195   vector<float> k_distances;
00196   k_distances.resize (no_of_neighbors);
00197 
00198   for (size_t i = 0; i < cloud_big.points.size (); ++i)
00199   {
00200     FlannSearch->nearestKSearch (cloud_big.points[i], no_of_neighbors, k_indices, k_distances);
00201     EXPECT_EQ (k_indices.size (), indices[i].size ());
00202     EXPECT_EQ (k_distances.size (), dists[i].size ());
00203     for (size_t j = 0; j< no_of_neighbors; j++ )
00204     {
00205       EXPECT_TRUE (k_indices[j] == indices[i][j] || k_distances[j] == dists[i][j]);
00206     }
00207 
00208   }
00209 }
00210 
00211 
00212 TEST (PCL, FlannSearch_knnByIndex)
00213 {
00214 
00215   unsigned int no_of_neighbors = 3;
00216 
00217 
00218   pcl::search::Search<PointXYZ>* flann_search = new pcl::search::FlannSearch<PointXYZ> (new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00219   
00220   flann_search->setInputCloud (cloud_big.makeShared ());
00221 
00222   std::vector< std::vector< float > > dists;
00223   std::vector< std::vector< int > > indices;
00224   std::vector< int > query_indices;
00225   for (size_t i = 0; i<cloud_big.size (); i+=2)
00226   {
00227     query_indices.push_back (int (i));
00228   }
00229   flann_search->nearestKSearch (cloud_big, query_indices,no_of_neighbors,indices,dists);
00230 
00231   vector<int> k_indices;
00232   k_indices.resize (no_of_neighbors);
00233   vector<float> k_distances;
00234   k_distances.resize (no_of_neighbors);
00235 
00236   for (size_t i = 0; i < query_indices.size (); ++i)
00237   {
00238     flann_search->nearestKSearch (cloud_big[2*i], no_of_neighbors, k_indices, k_distances);
00239     EXPECT_EQ (k_indices.size (), indices[i].size ());
00240     EXPECT_EQ (k_distances.size (), dists[i].size ());
00241     for (size_t j = 0; j< no_of_neighbors; j++)
00242     {
00243       EXPECT_TRUE (k_indices[j] == indices[i][j] || k_distances[j] == dists[i][j]);
00244     }
00245     flann_search->nearestKSearch (cloud_big,query_indices[i], no_of_neighbors, k_indices, k_distances);
00246     EXPECT_EQ (k_indices.size (), indices[i].size ());
00247     EXPECT_EQ (k_distances.size (), dists[i].size ());
00248     for (size_t j = 0; j< no_of_neighbors; j++)
00249     {
00250       EXPECT_TRUE (k_indices[j] == indices[i][j] || k_distances[j] == dists[i][j]);
00251     }
00252 
00253   }
00254 }
00255 
00256 
00257 
00258 TEST (PCL, FlannSearch_compareToKdTreeFlann)
00259 {
00260 
00261   int no_of_neighbors=3;
00262   vector<int> k_indices;
00263   k_indices.resize (no_of_neighbors);
00264   vector<float> k_distances;
00265   k_distances.resize (no_of_neighbors);
00266 
00267   pcl::search::Search<PointXYZ> *flann_search, *kdtree_search;
00268 
00269   PointCloud<PointXYZ>::Ptr pc = cloud_big.makeShared();
00270   {
00271     ScopeTime scopeTime ("FLANN build");
00272     flann_search = new pcl::search::FlannSearch<PointXYZ> (new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00273     flann_search->setInputCloud (pc);
00274   }
00275 
00276   {
00277     ScopeTime scopeTime ("kdtree build");
00278     kdtree_search = new pcl::search::KdTree<PointXYZ> ();
00279     kdtree_search->setInputCloud (pc);
00280   }
00281 
00282 
00283 
00284   {
00285     ScopeTime scopeTime ("FLANN nearestKSearch");
00286     for (size_t i = 0; i < cloud_big.points.size (); ++i)
00287       flann_search->nearestKSearch (cloud_big.points[i], no_of_neighbors, k_indices, k_distances);
00288   }
00289   {
00290     ScopeTime scopeTime ("kd tree  nearestKSearch");
00291     for (size_t i = 0; i < cloud_big.points.size (); ++i)
00292       kdtree_search->nearestKSearch (cloud_big.points[i], no_of_neighbors, k_indices, k_distances);
00293   }
00294 
00295   vector<vector<int> > indices_flann;
00296   vector<vector<float> > dists_flann;
00297   vector<vector<int> > indices_tree;
00298   vector<vector<float> > dists_tree;
00299   indices_flann.resize (cloud_big.size ());
00300   dists_flann.resize (cloud_big.size ());
00301   indices_tree.resize (cloud_big.size ());
00302   dists_tree.resize (cloud_big.size ());
00303   for (size_t i = 0; i<cloud_big.size (); ++i)
00304   {
00305     indices_flann[i].resize (no_of_neighbors);
00306     dists_flann[i].resize (no_of_neighbors);
00307     indices_tree[i].resize (no_of_neighbors);
00308     dists_tree[i].resize (no_of_neighbors);
00309   }
00310 
00311   {
00312     ScopeTime scopeTime ("FLANN multi nearestKSearch");
00313     flann_search->nearestKSearch (cloud_big, std::vector<int> (), no_of_neighbors, indices_flann,dists_flann);
00314   }
00315   {
00316     ScopeTime scopeTime ("kd tree multi nearestKSearch");
00317     kdtree_search->nearestKSearch (cloud_big, std::vector<int> (), no_of_neighbors, indices_tree,dists_tree);
00318   }
00319 
00320   ASSERT_EQ (indices_flann.size (), dists_flann.size ());
00321   ASSERT_EQ (indices_flann.size (), indices_tree.size ());
00322   ASSERT_EQ (indices_flann.size (), dists_tree.size ());
00323 
00324   for (size_t i = 0; i<indices_flann.size ();i++)
00325   {
00326     ASSERT_EQ (indices_flann[i].size (), no_of_neighbors);
00327     ASSERT_EQ (indices_tree[i].size (), no_of_neighbors);
00328     ASSERT_EQ (dists_flann[i].size (), no_of_neighbors);
00329     ASSERT_EQ (dists_tree[i].size (), no_of_neighbors);
00330     for (int j = 0; j<no_of_neighbors; j++)
00331     {
00332 
00333       ASSERT_TRUE( indices_flann[i][j] == indices_tree[i][j] || dists_flann[i][j]==dists_tree[i][j]);
00334     }
00335   }
00336 
00337 
00338   vector<int> query_indices;
00339   for (size_t i = 0; i<cloud_big.size (); i+=2)
00340     query_indices.push_back (int (i));
00341 
00342   {
00343     ScopeTime scopeTime ("FLANN multi nearestKSearch with indices");
00344     flann_search->nearestKSearch (cloud_big, query_indices, no_of_neighbors, indices_flann,dists_flann);
00345   }
00346   {
00347     ScopeTime scopeTime ("kd tree multi nearestKSearch with indices");
00348     kdtree_search->nearestKSearch (cloud_big, query_indices, no_of_neighbors, indices_tree,dists_tree);
00349   }
00350   ASSERT_EQ (indices_flann.size (), dists_flann.size ());
00351   ASSERT_EQ (indices_flann.size (), indices_tree.size ());
00352   ASSERT_EQ (indices_flann.size (), dists_tree.size ());
00353 
00354   for (size_t i = 0; i<indices_flann.size ();i++)
00355   {
00356     ASSERT_EQ (indices_flann[i].size (), no_of_neighbors);
00357     ASSERT_EQ (indices_tree[i].size (), no_of_neighbors);
00358     ASSERT_EQ (dists_flann[i].size (), no_of_neighbors);
00359     ASSERT_EQ (dists_tree[i].size (), no_of_neighbors);
00360     for (size_t j = 0; j<no_of_neighbors; j++ )
00361     {
00362 
00363       ASSERT_TRUE( indices_flann[i][j] == indices_tree[i][j] || dists_flann[i][j]==dists_tree[i][j]);
00364     }
00365   }
00366 
00367   delete flann_search;
00368   delete kdtree_search;
00369 }
00370 
00371 int
00372 main (int argc, char** argv)
00373 {
00374   testing::InitGoogleTest (&argc, argv);
00375   init ();
00376 
00377   
00378   pcl::search::Search<PointXYZ>* FlannSearch = new pcl::search::FlannSearch<PointXYZ> ( new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00379   FlannSearch->setInputCloud (cloud.makeShared ());
00380 
00381   return (RUN_ALL_TESTS ());
00382 }