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 #include <pcl/io/pcd_io.h>
00048 #include <boost/property_tree/ptree.hpp>
00049 #include <boost/property_tree/xml_parser.hpp>
00050
00051
00052 using namespace std;
00053 using namespace pcl;
00054
00055 boost::property_tree::ptree xml_property_tree;
00056
00057
00058 PointCloud<PointXYZ>::Ptr cloud_in (new PointCloud<PointXYZ> ());
00059
00060 struct MyPoint : public PointXYZ
00061 {
00062 MyPoint (float x, float y, float z) {this->x=x; this->y=y; this->z=z;}
00063 };
00064
00065 PointCloud<MyPoint> cloud, cloud_big;
00066
00067
00068 #include <pcl/kdtree/impl/kdtree_flann.hpp>
00069
00070 void
00071 init ()
00072 {
00073 float resolution = 0.1f;
00074 for (float z = -0.5f; z <= 0.5f; z += resolution)
00075 for (float y = -0.5f; y <= 0.5f; y += resolution)
00076 for (float x = -0.5f; x <= 0.5f; x += resolution)
00077 cloud.points.push_back (MyPoint (x, y, z));
00078 cloud.width = static_cast<uint32_t> (cloud.points.size ());
00079 cloud.height = 1;
00080
00081 cloud_big.width = 640;
00082 cloud_big.height = 480;
00083 srand (static_cast<unsigned int> (time (NULL)));
00084
00085 for (size_t i = 0; i < cloud_big.width * cloud_big.height; ++i)
00086 cloud_big.points.push_back (MyPoint (static_cast<float> (1024 * rand () / (RAND_MAX + 1.0)),
00087 static_cast<float> (1024 * rand () / (RAND_MAX + 1.0)),
00088 static_cast<float> (1024 * rand () / (RAND_MAX + 1.0))));
00089 }
00090
00092 TEST (PCL, KdTreeFLANN_radiusSearch)
00093 {
00094 KdTreeFLANN<MyPoint> kdtree;
00095 kdtree.setInputCloud (cloud.makeShared ());
00096 MyPoint test_point(0.0f, 0.0f, 0.0f);
00097 double max_dist = 0.15;
00098 set<int> brute_force_result;
00099 for (unsigned int i=0; i<cloud.points.size(); ++i)
00100 if (euclideanDistance(cloud.points[i], test_point) < max_dist)
00101 brute_force_result.insert(i);
00102 vector<int> k_indices;
00103 vector<float> k_distances;
00104 kdtree.radiusSearch (test_point, max_dist, k_indices, k_distances, 100);
00105
00106
00107
00108 for (size_t i = 0; i < k_indices.size (); ++i)
00109 {
00110 set<int>::iterator brute_force_result_it = brute_force_result.find (k_indices[i]);
00111 bool ok = brute_force_result_it != brute_force_result.end ();
00112
00113
00114 EXPECT_EQ (ok, true);
00115 if (ok)
00116 brute_force_result.erase (brute_force_result_it);
00117 }
00118
00119
00120
00121 bool error = brute_force_result.size () > 0;
00122
00123 EXPECT_EQ (error, false);
00124
00125 {
00126 KdTreeFLANN<MyPoint> kdtree;
00127 kdtree.setInputCloud (cloud_big.makeShared ());
00128
00129 ScopeTime scopeTime ("FLANN radiusSearch");
00130 {
00131 for (size_t i = 0; i < cloud_big.points.size (); ++i)
00132 kdtree.radiusSearch (cloud_big.points[i], 0.1, k_indices, k_distances);
00133 }
00134 }
00135
00136 {
00137 KdTreeFLANN<MyPoint> kdtree;
00138 kdtree.setInputCloud (cloud_big.makeShared ());
00139
00140 ScopeTime scopeTime ("FLANN radiusSearch (max neighbors in radius)");
00141 {
00142 for (size_t i = 0; i < cloud_big.points.size (); ++i)
00143 kdtree.radiusSearch (cloud_big.points[i], 0.1, k_indices, k_distances, 10);
00144 }
00145 }
00146
00147
00148 {
00149 KdTreeFLANN<MyPoint> kdtree (false);
00150 kdtree.setInputCloud (cloud_big.makeShared ());
00151
00152 ScopeTime scopeTime ("FLANN radiusSearch (unsorted results)");
00153 {
00154 for (size_t i = 0; i < cloud_big.points.size (); ++i)
00155 kdtree.radiusSearch (cloud_big.points[i], 0.1, k_indices, k_distances);
00156 }
00157 }
00158 }
00159
00161 TEST (PCL, KdTreeFLANN_nearestKSearch)
00162 {
00163 KdTreeFLANN<MyPoint> kdtree;
00164 kdtree.setInputCloud (cloud.makeShared ());
00165 MyPoint test_point (0.01f, 0.01f, 0.01f);
00166 unsigned int no_of_neighbors = 20;
00167 multimap<float, int> sorted_brute_force_result;
00168 for (size_t i = 0; i < cloud.points.size (); ++i)
00169 {
00170 float distance = euclideanDistance (cloud.points[i], test_point);
00171 sorted_brute_force_result.insert (make_pair (distance, static_cast<int> (i)));
00172 }
00173 float max_dist = 0.0f;
00174 unsigned int counter = 0;
00175 for (multimap<float, int>::iterator it = sorted_brute_force_result.begin (); it != sorted_brute_force_result.end () && counter < no_of_neighbors; ++it)
00176 {
00177 max_dist = max (max_dist, it->first);
00178 ++counter;
00179 }
00180
00181 vector<int> k_indices;
00182 k_indices.resize (no_of_neighbors);
00183 vector<float> k_distances;
00184 k_distances.resize (no_of_neighbors);
00185 kdtree.nearestKSearch (test_point, no_of_neighbors, k_indices, k_distances);
00186
00187 EXPECT_EQ (k_indices.size (), no_of_neighbors);
00188
00189
00190 for (size_t i = 0; i < k_indices.size (); ++i)
00191 {
00192 const MyPoint& point = cloud.points[k_indices[i]];
00193 bool ok = euclideanDistance (test_point, point) <= max_dist;
00194 if (!ok)
00195 ok = (fabs (euclideanDistance (test_point, point)) - max_dist) <= 1e-6;
00196
00197
00198 EXPECT_EQ (ok, true);
00199 }
00200
00201 ScopeTime scopeTime ("FLANN nearestKSearch");
00202 {
00203 KdTreeFLANN<MyPoint> kdtree;
00204 kdtree.setInputCloud (cloud_big.makeShared ());
00205 for (size_t i = 0; i < cloud_big.points.size (); ++i)
00206 kdtree.nearestKSearch (cloud_big.points[i], no_of_neighbors, k_indices, k_distances);
00207 }
00208 }
00209
00211 class MyPointRepresentationXY : public PointRepresentation<MyPoint>
00212 {
00213 public:
00214 MyPointRepresentationXY ()
00215 {
00216 this->nr_dimensions_ = 2;
00217 }
00218
00219 void copyToFloatArray (const MyPoint &p, float *out) const
00220 {
00221 out[0] = p.x;
00222 out[1] = p.y;
00223 }
00224 };
00225
00226 TEST (PCL, KdTreeFLANN_setPointRepresentation)
00227 {
00228 PointCloud<MyPoint>::Ptr random_cloud (new PointCloud<MyPoint> ());
00229 random_cloud->points.push_back (MyPoint (86.6f, 42.1f, 92.4f));
00230 random_cloud->points.push_back (MyPoint (63.1f, 18.4f, 22.3f));
00231 random_cloud->points.push_back (MyPoint (35.5f, 72.5f, 37.3f));
00232 random_cloud->points.push_back (MyPoint (99.7f, 37.0f, 8.7f));
00233 random_cloud->points.push_back (MyPoint (22.4f, 84.1f, 64.0f));
00234 random_cloud->points.push_back (MyPoint (65.2f, 73.4f, 18.0f));
00235 random_cloud->points.push_back (MyPoint (60.4f, 57.1f, 4.5f));
00236 random_cloud->points.push_back (MyPoint (38.7f, 17.6f, 72.3f));
00237 random_cloud->points.push_back (MyPoint (14.2f, 95.7f, 34.7f));
00238 random_cloud->points.push_back (MyPoint ( 2.5f, 26.5f, 66.0f));
00239
00240 KdTreeFLANN<MyPoint> kdtree;
00241 kdtree.setInputCloud (random_cloud);
00242 MyPoint p (50.0f, 50.0f, 50.0f);
00243
00244
00245 const int k = 10;
00246 vector<int> k_indices (k);
00247 vector<float> k_distances (k);
00248 kdtree.nearestKSearch (p, k, k_indices, k_distances);
00249 for (int i = 0; i < k; ++i)
00250 {
00251
00252 static const int gt_indices[10] = {2, 7, 5, 1, 4, 6, 9, 0, 8, 3};
00253 static const float gt_distances[10] =
00254 {877.8f, 1674.7f, 1802.6f, 1937.5f, 2120.6f, 2228.8f, 3064.5f, 3199.7f, 3604.2f, 4344.8f};
00255 EXPECT_EQ (k_indices[i], gt_indices[i]);
00256 EXPECT_NEAR (k_distances[i], gt_distances[i], 0.1);
00257 }
00258
00259
00260 boost::shared_ptr<MyPointRepresentationXY> ptrep (new MyPointRepresentationXY);
00261 kdtree.setPointRepresentation (ptrep);
00262 kdtree.nearestKSearch (p, k, k_indices, k_distances);
00263 for (int i = 0; i < k; ++i)
00264 {
00265
00266 static const int gt_indices[10] = {6, 2, 5, 1, 7, 0, 4, 3, 9, 8};
00267 static const float gt_distances[10] =
00268 {158.6f, 716.5f, 778.6f, 1170.2f, 1177.5f, 1402.0f, 1924.6f, 2639.1f, 2808.5f, 3370.1f};
00269 EXPECT_EQ (k_indices[i], gt_indices[i]);
00270 EXPECT_NEAR (k_distances[i], gt_distances[i], 0.1);
00271 }
00272
00273
00274 DefaultPointRepresentation<MyPoint> point_rep;
00275 float alpha[3] = {1.0f, 2.0f, 3.0f};
00276 point_rep.setRescaleValues(alpha);
00277 kdtree.setPointRepresentation (point_rep.makeShared ());
00278 kdtree.nearestKSearch (p, k, k_indices, k_distances);
00279 for (int i = 0; i < k; ++i)
00280 {
00281
00282 static const int gt_indices[10] = {2, 9, 4, 7, 1, 5, 8, 0, 3, 6};
00283 static const float gt_distances[10] =
00284 {3686.9f, 6769.2f, 7177.0f, 8802.3f, 11071.5f, 11637.3f, 11742.4f, 17769.0f, 18497.3f, 18942.0f};
00285 EXPECT_EQ (k_indices[i], gt_indices[i]);
00286 EXPECT_NEAR (k_distances[i], gt_distances[i], 0.1);
00287 }
00288 }
00289
00290
00292 TEST (PCL, KdTreeFLANN_32_vs_64_bit)
00293 {
00294 KdTreeFLANN<PointXYZ> tree;
00295 tree.setInputCloud (cloud_in);
00296
00297 std::vector<std::vector<int> > nn_indices_vector;
00298 for (size_t i = 0; i < cloud_in->size (); ++i)
00299 if (isFinite ((*cloud_in)[i]))
00300 {
00301 std::vector<int> nn_indices;
00302 std::vector<float> nn_dists;
00303 tree.radiusSearch ((*cloud_in)[i], 0.02, nn_indices, nn_dists);
00304
00305 nn_indices_vector.push_back (nn_indices);
00306 }
00307
00308
00309
00310 for (size_t vec_i = 0; vec_i < nn_indices_vector.size (); ++vec_i)
00311 {
00312 char str[512];
00313 sprintf (str, "point_%d", int (vec_i));
00314 boost::optional<boost::property_tree::ptree&> tree = xml_property_tree.get_child_optional (str);
00315 if (!tree)
00316 FAIL ();
00317
00318 int vec_size = tree.get ().get<int> ("size");
00319 EXPECT_EQ (vec_size, nn_indices_vector[vec_i].size ());
00320
00321 for (size_t n_i = 0; n_i < nn_indices_vector[vec_i].size (); ++n_i)
00322 {
00323 sprintf (str, "nn_%d", int (n_i));
00324 int neighbor_index = tree.get ().get<int> (str);
00325 EXPECT_EQ (neighbor_index, nn_indices_vector[vec_i][n_i]);
00326 }
00327 }
00328 }
00329
00330
00331 int
00332 main (int argc, char** argv)
00333 {
00334
00335 if (argc < 3)
00336 {
00337 std::cerr << "No test file given. Please download `sac_plane_test.pcd` and 'kdtree_unit_test_results.xml' pass them path to the test." << std::endl;
00338 return (-1);
00339 }
00340
00341
00342 io::loadPCDFile (argv[1], *cloud_in);
00343
00344 std::ifstream xml_file_input_stream (argv[2], std::ifstream::in);
00345 read_xml (xml_file_input_stream, xml_property_tree, boost::property_tree::xml_parser::trim_whitespace);
00346
00347 testing::InitGoogleTest (&argc, argv);
00348
00349 init ();
00350 return (RUN_ALL_TESTS ());
00351 }
00352