test_flann_search.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  *
00037  */
00038 
00039 #include <iostream>
00040 #include <gtest/gtest.h>
00041 #include <pcl/common/time.h>
00042 #include <pcl/search/pcl_search.h>
00043 #include <pcl/search/flann_search.h>
00044 #include <pcl/search/impl/flann_search.hpp>
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/point_types.h>
00047 
00048 using namespace std;
00049 using namespace pcl;
00050 
00051 PointCloud<PointXYZ> cloud, cloud_big;
00052 
00053 void
00054 init ()
00055 {
00056   float resolution = 0.1;
00057   for (float z = -0.5f; z <= 0.5f; z += resolution)
00058     for (float y = -0.5f; y <= 0.5f; y += resolution)
00059       for (float x = -0.5f; x <= 0.5f; x += resolution)
00060         cloud.points.push_back (PointXYZ (x, y, z));
00061   cloud.width = cloud.points.size ();
00062   cloud.height = 1;
00063 
00064   cloud_big.width = 640;
00065   cloud_big.height = 480;
00066   srand (time (NULL));
00067   // Randomly create a new point cloud
00068   for (size_t i = 0; i < cloud_big.width * cloud_big.height; ++i)
00069     cloud_big.points.push_back (
00070                                 PointXYZ (1024 * rand () / (RAND_MAX + 1.0), 1024 * rand () / (RAND_MAX + 1.0),
00071                                           1024 * rand () / (RAND_MAX + 1.0)));
00072 };
00073 
00074 
00075 /* Test for FlannSearch nearestKSearch */TEST (PCL, FlannSearch_nearestKSearch)
00076 {
00077   pcl::search::Search<PointXYZ>* FlannSearch = new pcl::search::FlannSearch<PointXYZ> (new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00078   FlannSearch->setInputCloud (cloud.makeShared ());
00079   PointXYZ test_point (0.01f, 0.01f, 0.01f);
00080   unsigned int no_of_neighbors = 20;
00081   multimap<float, int> sorted_brute_force_result;
00082   for (size_t i = 0; i < cloud.points.size (); ++i)
00083   {
00084     float distance = euclideanDistance (cloud.points[i], test_point);
00085     sorted_brute_force_result.insert (make_pair (distance, (int)i));
00086   }
00087   float max_dist = 0.0f;
00088   unsigned int counter = 0;
00089   for (multimap<float, int>::iterator it = sorted_brute_force_result.begin (); it != sorted_brute_force_result.end ()
00090       && counter < no_of_neighbors; ++it)
00091   {
00092     max_dist = max (max_dist, it->first);
00093     ++counter;
00094   }
00095 
00096   vector<int> k_indices;
00097   k_indices.resize (no_of_neighbors);
00098   vector<float> k_distances;
00099   k_distances.resize (no_of_neighbors);
00100 
00101   FlannSearch->nearestKSearch (test_point, no_of_neighbors, k_indices, k_distances);
00102 
00103   //if (k_indices.size () != no_of_neighbors)  cerr << "Found "<<k_indices.size ()<<" instead of "<<no_of_neighbors<<" neighbors.\n";
00104   EXPECT_EQ (k_indices.size (), no_of_neighbors);
00105 
00106   // Check if all found neighbors have distance smaller than max_dist
00107   for (size_t i = 0; i < k_indices.size (); ++i)
00108   {
00109     const PointXYZ& point = cloud.points[k_indices[i]];
00110     bool ok = euclideanDistance (test_point, point) <= max_dist;
00111     if (!ok)
00112     ok = (fabs (euclideanDistance (test_point, point)) - max_dist) <= 1e-6;
00113     //if (!ok)  cerr << k_indices[i] << " is not correct...\n";
00114     //else      cerr << k_indices[i] << " is correct...\n";
00115     EXPECT_EQ (ok, true);
00116   }
00117 
00118   ScopeTime scopeTime ("FLANN nearestKSearch");
00119   {
00120     pcl::search::Search<PointXYZ>* FlannSearch = new pcl::search::FlannSearch<PointXYZ>( new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00121     //FlannSearch->initSearchDS ();
00122     FlannSearch->setInputCloud (cloud_big.makeShared ());
00123     for (size_t i = 0; i < cloud_big.points.size (); ++i)
00124       FlannSearch->nearestKSearch (cloud_big.points[i], no_of_neighbors, k_indices, k_distances);
00125   }
00126 }
00127 
00128 /* Test the templated NN search (for different query point types) */
00129 TEST (PCL, FlannSearch_differentPointT)
00130 {
00131 
00132   unsigned int no_of_neighbors = 20;
00133 
00134   pcl::search::Search<PointXYZ>* FlannSearch = new pcl::search::FlannSearch<PointXYZ> (new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00135   //FlannSearch->initSearchDS ();
00136   FlannSearch->setInputCloud (cloud_big.makeShared ());
00137 
00138   PointCloud<PointXYZRGB> cloud_rgb;
00139 
00140   copyPointCloud (cloud_big, cloud_rgb);
00141 
00142 
00143 
00144   std::vector< std::vector< float > > dists;
00145   std::vector< std::vector< int > > indices;
00146   FlannSearch->nearestKSearchT (cloud_rgb, std::vector<int> (),no_of_neighbors,indices,dists);
00147 
00148   vector<int> k_indices;
00149   k_indices.resize (no_of_neighbors);
00150   vector<float> k_distances;
00151   k_distances.resize (no_of_neighbors);
00152 
00153   vector<int> k_indices_t;
00154   k_indices_t.resize (no_of_neighbors);
00155   vector<float> k_distances_t;
00156   k_distances_t.resize (no_of_neighbors);
00157 
00158   for (size_t i = 0; i < cloud_rgb.points.size (); ++i)
00159   {
00160     FlannSearch->nearestKSearchT (cloud_rgb.points[i], no_of_neighbors, k_indices_t, k_distances_t);
00161     FlannSearch->nearestKSearch (cloud_big.points[i], no_of_neighbors, k_indices, k_distances);
00162     EXPECT_EQ (k_indices.size (), indices[i].size ());
00163     EXPECT_EQ (k_distances.size (), dists[i].size ());
00164     for (size_t j = 0; j< no_of_neighbors; j++)
00165     {
00166       EXPECT_TRUE (k_indices[j] == indices[i][j] || k_distances[j] == dists[i][j]);
00167       EXPECT_TRUE (k_indices[j] == k_indices_t[j]);
00168       EXPECT_TRUE (k_distances[j] == k_distances_t[j]);
00169     }
00170 
00171   }
00172 }
00173 
00174 /* Test for FlannSearch nearestKSearch with multiple query points */
00175 TEST (PCL, FlannSearch_multipointKnnSearch)
00176 {
00177 
00178   unsigned int no_of_neighbors = 20;
00179 
00180 
00181   pcl::search::Search<PointXYZ>* FlannSearch = new pcl::search::FlannSearch<PointXYZ> (new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00182   //FlannSearch->initSearchDS ();
00183   FlannSearch->setInputCloud (cloud_big.makeShared ());
00184 
00185   std::vector< std::vector< float > > dists;
00186   std::vector< std::vector< int > > indices;
00187   FlannSearch->nearestKSearch (cloud_big, std::vector<int>(),no_of_neighbors,indices,dists);
00188 
00189   vector<int> k_indices;
00190   k_indices.resize (no_of_neighbors);
00191   vector<float> k_distances;
00192   k_distances.resize (no_of_neighbors);
00193 
00194   for (size_t i = 0; i < cloud_big.points.size (); ++i)
00195   {
00196     FlannSearch->nearestKSearch (cloud_big.points[i], no_of_neighbors, k_indices, k_distances);
00197     EXPECT_EQ (k_indices.size (), indices[i].size ());
00198     EXPECT_EQ (k_distances.size (), dists[i].size ());
00199     for (size_t j = 0; j< no_of_neighbors; j++ )
00200     {
00201       EXPECT_TRUE (k_indices[j] == indices[i][j] || k_distances[j] == dists[i][j]);
00202     }
00203 
00204   }
00205 }
00206 
00207 /* Test for FlannSearch nearestKSearch with multiple query points */
00208 TEST (PCL, FlannSearch_knnByIndex)
00209 {
00210 
00211   unsigned int no_of_neighbors = 3;
00212 
00213 
00214   pcl::search::Search<PointXYZ>* flann_search = new pcl::search::FlannSearch<PointXYZ> (new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00215   //FlannSearch->initSearchDS ();
00216   flann_search->setInputCloud (cloud_big.makeShared ());
00217 
00218   std::vector< std::vector< float > > dists;
00219   std::vector< std::vector< int > > indices;
00220   std::vector< int > query_indices;
00221   for (size_t i = 0; i<cloud_big.size (); i+=2)
00222   {
00223     query_indices.push_back (i);
00224   }
00225   flann_search->nearestKSearch (cloud_big, query_indices,no_of_neighbors,indices,dists);
00226 
00227   vector<int> k_indices;
00228   k_indices.resize (no_of_neighbors);
00229   vector<float> k_distances;
00230   k_distances.resize (no_of_neighbors);
00231 
00232   for (size_t i = 0; i < query_indices.size (); ++i)
00233   {
00234     flann_search->nearestKSearch (cloud_big[2*i], no_of_neighbors, k_indices, k_distances);
00235     EXPECT_EQ (k_indices.size (), indices[i].size ());
00236     EXPECT_EQ (k_distances.size (), dists[i].size ());
00237     for (size_t j = 0; j< no_of_neighbors; j++)
00238     {
00239       EXPECT_TRUE (k_indices[j] == indices[i][j] || k_distances[j] == dists[i][j]);
00240     }
00241     flann_search->nearestKSearch (cloud_big,query_indices[i], no_of_neighbors, k_indices, k_distances);
00242     EXPECT_EQ (k_indices.size (), indices[i].size ());
00243     EXPECT_EQ (k_distances.size (), dists[i].size ());
00244     for (size_t j = 0; j< no_of_neighbors; j++)
00245     {
00246       EXPECT_TRUE (k_indices[j] == indices[i][j] || k_distances[j] == dists[i][j]);
00247     }
00248 
00249   }
00250 }
00251 
00252 
00253 /* Test for FlannSearch nearestKSearch */TEST (PCL, FlannSearch_compareToKdTreeFlann)
00254 {
00255 
00256   int no_of_neighbors=3;
00257   vector<int> k_indices;
00258   k_indices.resize (no_of_neighbors);
00259   vector<float> k_distances;
00260   k_distances.resize (no_of_neighbors);
00261 
00262   pcl::search::Search<PointXYZ> *flann_search, *kdtree_search;
00263 
00264   PointCloud<PointXYZ>::Ptr pc = cloud_big.makeShared();
00265   {
00266     ScopeTime scopeTime ("FLANN build");
00267     flann_search = new pcl::search::FlannSearch<PointXYZ> (new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00268     flann_search->setInputCloud (pc);
00269   }
00270 
00271   {
00272     ScopeTime scopeTime ("kdtree build");
00273     kdtree_search = new pcl::search::KdTree<PointXYZ> ();
00274     kdtree_search->setInputCloud (pc);
00275   }
00276 
00277 
00278 
00279   {
00280     ScopeTime scopeTime ("FLANN nearestKSearch");
00281     for (size_t i = 0; i < cloud_big.points.size (); ++i)
00282       flann_search->nearestKSearch (cloud_big.points[i], no_of_neighbors, k_indices, k_distances);
00283   }
00284   {
00285     ScopeTime scopeTime ("kd tree  nearestKSearch");
00286     for (size_t i = 0; i < cloud_big.points.size (); ++i)
00287       kdtree_search->nearestKSearch (cloud_big.points[i], no_of_neighbors, k_indices, k_distances);
00288   }
00289 
00290   vector<vector<int> > indices_flann;
00291   vector<vector<float> > dists_flann;
00292   vector<vector<int> > indices_tree;
00293   vector<vector<float> > dists_tree;
00294   indices_flann.resize (cloud_big.size ());
00295   dists_flann.resize (cloud_big.size ());
00296   indices_tree.resize (cloud_big.size ());
00297   dists_tree.resize (cloud_big.size ());
00298   for (size_t i = 0; i<cloud_big.size (); ++i)
00299   {
00300     indices_flann[i].resize (no_of_neighbors);
00301     dists_flann[i].resize (no_of_neighbors);
00302     indices_tree[i].resize (no_of_neighbors);
00303     dists_tree[i].resize (no_of_neighbors);
00304   }
00305 
00306   {
00307     ScopeTime scopeTime ("FLANN multi nearestKSearch");
00308     flann_search->nearestKSearch (cloud_big, std::vector<int> (), no_of_neighbors, indices_flann,dists_flann);
00309   }
00310   {
00311     ScopeTime scopeTime ("kd tree multi nearestKSearch");
00312     kdtree_search->nearestKSearch (cloud_big, std::vector<int> (), no_of_neighbors, indices_tree,dists_tree);
00313   }
00314 
00315   ASSERT_EQ (indices_flann.size (), dists_flann.size ());
00316   ASSERT_EQ (indices_flann.size (), indices_tree.size ());
00317   ASSERT_EQ (indices_flann.size (), dists_tree.size ());
00318 
00319   for (size_t i = 0; i<indices_flann.size ();i++)
00320   {
00321     ASSERT_EQ (indices_flann[i].size (), no_of_neighbors);
00322     ASSERT_EQ (indices_tree[i].size (), no_of_neighbors);
00323     ASSERT_EQ (dists_flann[i].size (), no_of_neighbors);
00324     ASSERT_EQ (dists_tree[i].size (), no_of_neighbors);
00325     for (int j = 0; j<no_of_neighbors; j++)
00326     {
00327 
00328       ASSERT_TRUE( indices_flann[i][j] == indices_tree[i][j] || dists_flann[i][j]==dists_tree[i][j]);
00329     }
00330   }
00331 
00332 
00333   vector<int> query_indices;
00334   for (size_t i = 0; i<cloud_big.size (); i+=2)
00335     query_indices.push_back (i);
00336 
00337   {
00338     ScopeTime scopeTime ("FLANN multi nearestKSearch with indices");
00339     flann_search->nearestKSearch (cloud_big, query_indices, no_of_neighbors, indices_flann,dists_flann);
00340   }
00341   {
00342     ScopeTime scopeTime ("kd tree multi nearestKSearch with indices");
00343     kdtree_search->nearestKSearch (cloud_big, query_indices, no_of_neighbors, indices_tree,dists_tree);
00344   }
00345   ASSERT_EQ (indices_flann.size (), dists_flann.size ());
00346   ASSERT_EQ (indices_flann.size (), indices_tree.size ());
00347   ASSERT_EQ (indices_flann.size (), dists_tree.size ());
00348 
00349   for (size_t i = 0; i<indices_flann.size ();i++)
00350   {
00351     ASSERT_EQ (indices_flann[i].size (), no_of_neighbors);
00352     ASSERT_EQ (indices_tree[i].size (), no_of_neighbors);
00353     ASSERT_EQ (dists_flann[i].size (), no_of_neighbors);
00354     ASSERT_EQ (dists_tree[i].size (), no_of_neighbors);
00355     for (size_t j = 0; j<no_of_neighbors; j++ )
00356     {
00357 
00358       ASSERT_TRUE( indices_flann[i][j] == indices_tree[i][j] || dists_flann[i][j]==dists_tree[i][j]);
00359     }
00360   }
00361 
00362   delete flann_search;
00363   delete kdtree_search;
00364 }
00365 
00366 int
00367 main (int argc, char** argv)
00368 {
00369   testing::InitGoogleTest (&argc, argv);
00370   init ();
00371 
00372   // Testing using explicit instantiation of inherited class
00373   pcl::search::Search<PointXYZ>* FlannSearch = new pcl::search::FlannSearch<PointXYZ> ( new search::FlannSearch<PointXYZ>::KdTreeIndexCreator);
00374   FlannSearch->setInputCloud (cloud.makeShared ());
00375 
00376   pthread_key_t t;
00377   pthread_key_create(&t,0);
00378 
00379   return (RUN_ALL_TESTS ());
00380 }
00381 ;


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:18:17