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 <gtest/gtest.h>
00040 #include <iostream>
00041 #include <map>
00042 #include <pcl/common/time.h>
00043 #include <pcl/kdtree/kdtree_flann.h>
00044 #include <pcl/point_cloud.h>
00045 #include <pcl/point_types.h>
00046 #include <pcl/common/distances.h>
00047
00048 using namespace std;
00049 using namespace pcl;
00050
00051 struct MyPoint : public PointXYZ
00052 {
00053 MyPoint (float x, float y, float z) {this->x=x; this->y=y; this->z=z;}
00054 };
00055
00056 PointCloud<MyPoint> cloud, cloud_big;
00057 PointCloud<Eigen::MatrixXf> cloud_eigen;
00058
00059
00060 #include <pcl/kdtree/impl/kdtree_flann.hpp>
00061
00062 void
00063 init ()
00064 {
00065 float resolution = 0.1f;
00066 for (float z = -0.5f; z <= 0.5f; z += resolution)
00067 for (float y = -0.5f; y <= 0.5f; y += resolution)
00068 for (float x = -0.5f; x <= 0.5f; x += resolution)
00069 cloud.points.push_back (MyPoint (x, y, z));
00070 cloud.width = static_cast<uint32_t> (cloud.points.size ());
00071 cloud.height = 1;
00072
00073 cloud_big.width = 640;
00074 cloud_big.height = 480;
00075 srand (static_cast<unsigned int> (time (NULL)));
00076
00077 for (size_t i = 0; i < cloud_big.width * cloud_big.height; ++i)
00078 cloud_big.points.push_back (MyPoint (static_cast<float> (1024 * rand () / (RAND_MAX + 1.0)),
00079 static_cast<float> (1024 * rand () / (RAND_MAX + 1.0)),
00080 static_cast<float> (1024 * rand () / (RAND_MAX + 1.0))));
00081 }
00082
00083 void
00084 initEigen ()
00085 {
00086 cloud_eigen.width = 640;
00087 cloud_eigen.height = 480;
00088 cloud_eigen.points.resize (cloud_eigen.width * cloud_eigen.height, 3);
00089 srand (static_cast<unsigned int> (time (NULL)));
00090
00091 for (int i = 0; i < cloud_eigen.points.rows (); ++i)
00092 {
00093 cloud_eigen.points (i, 0) = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00094 cloud_eigen.points (i, 1) = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00095 cloud_eigen.points (i, 2) = static_cast<float> (1024 * rand () / (RAND_MAX + 1.0));
00096 }
00097 }
00098
00100 TEST (PCL, KdTreeFLANN_radiusSearch)
00101 {
00102 KdTreeFLANN<MyPoint> kdtree;
00103 kdtree.setInputCloud (cloud.makeShared ());
00104 MyPoint test_point(0.0f, 0.0f, 0.0f);
00105 double max_dist = 0.15;
00106 set<int> brute_force_result;
00107 for (unsigned int i=0; i<cloud.points.size(); ++i)
00108 if (euclideanDistance(cloud.points[i], test_point) < max_dist)
00109 brute_force_result.insert(i);
00110 vector<int> k_indices;
00111 vector<float> k_distances;
00112 kdtree.radiusSearch (test_point, max_dist, k_indices, k_distances, 100);
00113
00114
00115
00116 for (size_t i = 0; i < k_indices.size (); ++i)
00117 {
00118 set<int>::iterator brute_force_result_it = brute_force_result.find (k_indices[i]);
00119 bool ok = brute_force_result_it != brute_force_result.end ();
00120
00121
00122 EXPECT_EQ (ok, true);
00123 if (ok)
00124 brute_force_result.erase (brute_force_result_it);
00125 }
00126
00127
00128
00129 bool error = brute_force_result.size () > 0;
00130
00131 EXPECT_EQ (error, false);
00132
00133 {
00134 KdTreeFLANN<MyPoint> kdtree;
00135 kdtree.setInputCloud (cloud_big.makeShared ());
00136
00137 ScopeTime scopeTime ("FLANN radiusSearch");
00138 {
00139 for (size_t i = 0; i < cloud_big.points.size (); ++i)
00140 kdtree.radiusSearch (cloud_big.points[i], 0.1, k_indices, k_distances);
00141 }
00142 }
00143
00144 {
00145 KdTreeFLANN<MyPoint> kdtree;
00146 kdtree.setInputCloud (cloud_big.makeShared ());
00147
00148 ScopeTime scopeTime ("FLANN radiusSearch (max neighbors in radius)");
00149 {
00150 for (size_t i = 0; i < cloud_big.points.size (); ++i)
00151 kdtree.radiusSearch (cloud_big.points[i], 0.1, k_indices, k_distances, 10);
00152 }
00153 }
00154
00155
00156 {
00157 KdTreeFLANN<MyPoint> kdtree (false);
00158 kdtree.setInputCloud (cloud_big.makeShared ());
00159
00160 ScopeTime scopeTime ("FLANN radiusSearch (unsorted results)");
00161 {
00162 for (size_t i = 0; i < cloud_big.points.size (); ++i)
00163 kdtree.radiusSearch (cloud_big.points[i], 0.1, k_indices, k_distances);
00164 }
00165 }
00166 }
00167
00169 TEST (PCL, KdTreeFLANN_radiusSearchEigen)
00170 {
00171 KdTreeFLANN<Eigen::MatrixXf> kdtree;
00172 kdtree.setInputCloud (cloud_eigen.makeShared ());
00173
00174 kdtree.setInputCloud (cloud_eigen.makeShared ());
00175 Eigen::VectorXf test_point = Eigen::Vector3f (0.0f, 0.0f, 0.0f);
00176 double max_dist = 0.15;
00177 set<int> brute_force_result;
00178 for (int i = 0; i < cloud_eigen.points.rows (); ++i)
00179 if ((cloud_eigen.points.row (i) - test_point.transpose ()).norm () < max_dist)
00180 brute_force_result.insert (i);
00181 vector<int> k_indices;
00182 vector<float> k_distances;
00183 kdtree.radiusSearch (test_point, max_dist, k_indices, k_distances);
00184
00185 for (size_t i = 0; i < k_indices.size (); ++i)
00186 {
00187 set<int>::iterator brute_force_result_it = brute_force_result.find (k_indices[i]);
00188 bool ok = brute_force_result_it != brute_force_result.end ();
00189 EXPECT_EQ (ok, true);
00190 if (ok)
00191 brute_force_result.erase (brute_force_result_it);
00192 }
00193
00194 bool error = brute_force_result.size () > 0;
00195 EXPECT_EQ (error, false);
00196
00197 {
00198 KdTreeFLANN<Eigen::MatrixXf> kdtree;
00199 kdtree.setInputCloud (cloud_eigen.makeShared ());
00200
00201 ScopeTime scopeTime ("FLANN radiusSearch");
00202 {
00203 for (int i = 0; i < cloud_eigen.points.rows (); ++i)
00204 kdtree.radiusSearch (cloud_eigen.points.row (i), 0.1, k_indices, k_distances);
00205 }
00206 }
00207
00208 {
00209 KdTreeFLANN<Eigen::MatrixXf> kdtree (false);
00210 kdtree.setInputCloud (cloud_eigen.makeShared ());
00211
00212 ScopeTime scopeTime ("FLANN radiusSearch (unsorted results)");
00213 {
00214 for (int i = 0; i < cloud_eigen.points.rows (); ++i)
00215 kdtree.radiusSearch (cloud_eigen.points.row (i), 0.1, k_indices, k_distances);
00216 }
00217 }
00218 }
00219
00221 TEST (PCL, KdTreeFLANN_nearestKSearch)
00222 {
00223 KdTreeFLANN<MyPoint> kdtree;
00224 kdtree.setInputCloud (cloud.makeShared ());
00225 MyPoint test_point (0.01f, 0.01f, 0.01f);
00226 unsigned int no_of_neighbors = 20;
00227 multimap<float, int> sorted_brute_force_result;
00228 for (size_t i = 0; i < cloud.points.size (); ++i)
00229 {
00230 float distance = euclideanDistance (cloud.points[i], test_point);
00231 sorted_brute_force_result.insert (make_pair (distance, static_cast<int> (i)));
00232 }
00233 float max_dist = 0.0f;
00234 unsigned int counter = 0;
00235 for (multimap<float, int>::iterator it = sorted_brute_force_result.begin (); it != sorted_brute_force_result.end () && counter < no_of_neighbors; ++it)
00236 {
00237 max_dist = max (max_dist, it->first);
00238 ++counter;
00239 }
00240
00241 vector<int> k_indices;
00242 k_indices.resize (no_of_neighbors);
00243 vector<float> k_distances;
00244 k_distances.resize (no_of_neighbors);
00245 kdtree.nearestKSearch (test_point, no_of_neighbors, k_indices, k_distances);
00246
00247 EXPECT_EQ (k_indices.size (), no_of_neighbors);
00248
00249
00250 for (size_t i = 0; i < k_indices.size (); ++i)
00251 {
00252 const MyPoint& point = cloud.points[k_indices[i]];
00253 bool ok = euclideanDistance (test_point, point) <= max_dist;
00254 if (!ok)
00255 ok = (fabs (euclideanDistance (test_point, point)) - max_dist) <= 1e-6;
00256
00257
00258 EXPECT_EQ (ok, true);
00259 }
00260
00261 ScopeTime scopeTime ("FLANN nearestKSearch");
00262 {
00263 KdTreeFLANN<MyPoint> kdtree;
00264 kdtree.setInputCloud (cloud_big.makeShared ());
00265 for (size_t i = 0; i < cloud_big.points.size (); ++i)
00266 kdtree.nearestKSearch (cloud_big.points[i], no_of_neighbors, k_indices, k_distances);
00267 }
00268 }
00269
00271 TEST (PCL, KdTreeFLANN_nearestKSearchEigen)
00272 {
00273 KdTreeFLANN<Eigen::MatrixXf> kdtree;
00274 kdtree.setInputCloud (cloud_eigen.makeShared ());
00275 Eigen::VectorXf test_point = Eigen::Vector3f (0.01f, 0.01f, 0.01f);
00276 unsigned int no_of_neighbors = 20;
00277 multimap<float, int> sorted_brute_force_result;
00278 for (int i = 0; i < cloud_eigen.points.rows (); ++i)
00279 {
00280 float distance = (cloud_eigen.points.row (i) - test_point.transpose ()).norm ();
00281 sorted_brute_force_result.insert (make_pair (distance, static_cast<int> (i)));
00282 }
00283 float max_dist = 0.0f;
00284 unsigned int counter = 0;
00285 for (multimap<float, int>::iterator it = sorted_brute_force_result.begin (); it != sorted_brute_force_result.end () && counter < no_of_neighbors; ++it)
00286 {
00287 max_dist = max (max_dist, it->first);
00288 ++counter;
00289 }
00290
00291 vector<int> k_indices;
00292 k_indices.resize (no_of_neighbors);
00293 vector<float> k_distances;
00294 k_distances.resize (no_of_neighbors);
00295 kdtree.nearestKSearch (test_point, no_of_neighbors, k_indices, k_distances);
00296
00297 EXPECT_EQ (k_indices.size (), no_of_neighbors);
00298
00299
00300 for (size_t i = 0; i < k_indices.size (); ++i)
00301 {
00302 const Eigen::VectorXf& point = cloud_eigen.points.row (k_indices[i]);
00303 bool ok = (test_point - point).norm () <= max_dist;
00304 if (!ok)
00305 ok = (fabs ((test_point - point).norm () - max_dist)) <= 1e-6;
00306
00307
00308 EXPECT_EQ (ok, true);
00309 }
00310
00311 ScopeTime scopeTime ("FLANN nearestKSearch");
00312 {
00313 KdTreeFLANN<Eigen::MatrixXf> kdtree;
00314 kdtree.setInputCloud (cloud_eigen.makeShared ());
00315 for (int i = 0; i < cloud_eigen.points.rows (); ++i)
00316 kdtree.nearestKSearch (cloud_eigen.points.row (i), no_of_neighbors, k_indices, k_distances);
00317 }
00318 }
00319
00321 class MyPointRepresentationXY : public PointRepresentation<MyPoint>
00322 {
00323 public:
00324 MyPointRepresentationXY ()
00325 {
00326 this->nr_dimensions_ = 2;
00327 }
00328
00329 void copyToFloatArray (const MyPoint &p, float *out) const
00330 {
00331 out[0] = p.x;
00332 out[1] = p.y;
00333 }
00334 };
00335
00336 TEST (PCL, KdTreeFLANN_setPointRepresentation)
00337 {
00338 PointCloud<MyPoint>::Ptr random_cloud (new PointCloud<MyPoint> ());
00339 random_cloud->points.push_back (MyPoint (86.6f, 42.1f, 92.4f));
00340 random_cloud->points.push_back (MyPoint (63.1f, 18.4f, 22.3f));
00341 random_cloud->points.push_back (MyPoint (35.5f, 72.5f, 37.3f));
00342 random_cloud->points.push_back (MyPoint (99.7f, 37.0f, 8.7f));
00343 random_cloud->points.push_back (MyPoint (22.4f, 84.1f, 64.0f));
00344 random_cloud->points.push_back (MyPoint (65.2f, 73.4f, 18.0f));
00345 random_cloud->points.push_back (MyPoint (60.4f, 57.1f, 4.5f));
00346 random_cloud->points.push_back (MyPoint (38.7f, 17.6f, 72.3f));
00347 random_cloud->points.push_back (MyPoint (14.2f, 95.7f, 34.7f));
00348 random_cloud->points.push_back (MyPoint ( 2.5f, 26.5f, 66.0f));
00349
00350 KdTreeFLANN<MyPoint> kdtree;
00351 kdtree.setInputCloud (random_cloud);
00352 MyPoint p (50.0f, 50.0f, 50.0f);
00353
00354
00355 const int k = 10;
00356 vector<int> k_indices (k);
00357 vector<float> k_distances (k);
00358 kdtree.nearestKSearch (p, k, k_indices, k_distances);
00359 for (int i = 0; i < k; ++i)
00360 {
00361
00362 static const int gt_indices[10] = {2, 7, 5, 1, 4, 6, 9, 0, 8, 3};
00363 static const float gt_distances[10] =
00364 {877.8f, 1674.7f, 1802.6f, 1937.5f, 2120.6f, 2228.8f, 3064.5f, 3199.7f, 3604.2f, 4344.8f};
00365 EXPECT_EQ (k_indices[i], gt_indices[i]);
00366 EXPECT_NEAR (k_distances[i], gt_distances[i], 0.1);
00367 }
00368
00369
00370 boost::shared_ptr<MyPointRepresentationXY> ptrep (new MyPointRepresentationXY);
00371 kdtree.setPointRepresentation (ptrep);
00372 kdtree.nearestKSearch (p, k, k_indices, k_distances);
00373 for (int i = 0; i < k; ++i)
00374 {
00375
00376 static const int gt_indices[10] = {6, 2, 5, 1, 7, 0, 4, 3, 9, 8};
00377 static const float gt_distances[10] =
00378 {158.6f, 716.5f, 778.6f, 1170.2f, 1177.5f, 1402.0f, 1924.6f, 2639.1f, 2808.5f, 3370.1f};
00379 EXPECT_EQ (k_indices[i], gt_indices[i]);
00380 EXPECT_NEAR (k_distances[i], gt_distances[i], 0.1);
00381 }
00382
00383
00384 DefaultPointRepresentation<MyPoint> point_rep;
00385 float alpha[3] = {1.0f, 2.0f, 3.0f};
00386 point_rep.setRescaleValues(alpha);
00387 kdtree.setPointRepresentation (point_rep.makeShared ());
00388 kdtree.nearestKSearch (p, k, k_indices, k_distances);
00389 for (int i = 0; i < k; ++i)
00390 {
00391
00392 static const int gt_indices[10] = {2, 9, 4, 7, 1, 5, 8, 0, 3, 6};
00393 static const float gt_distances[10] =
00394 {3686.9f, 6769.2f, 7177.0f, 8802.3f, 11071.5f, 11637.3f, 11742.4f, 17769.0f, 18497.3f, 18942.0f};
00395 EXPECT_EQ (k_indices[i], gt_indices[i]);
00396 EXPECT_NEAR (k_distances[i], gt_distances[i], 0.1);
00397 }
00398 }
00399
00400
00401 int
00402 main (int argc, char** argv)
00403 {
00404 testing::InitGoogleTest (&argc, argv);
00405 init ();
00406 initEigen ();
00407 return (RUN_ALL_TESTS ());
00408 }
00409