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
00037 #include <gtest/gtest.h>
00038 #include <pcl/pcl_tests.h>
00039
00040 #include <pcl/io/pcd_io.h>
00041 #include <pcl/keypoints/iss_3d.h>
00042
00043 using namespace pcl;
00044 using namespace pcl::io;
00045
00046
00047
00048
00049 double cloud_resolution (0.0058329);
00050 PointCloud<PointXYZ>::Ptr cloud (new PointCloud<PointXYZ> ());
00051 search::KdTree<PointXYZ>::Ptr tree (new search::KdTree<PointXYZ> ());
00052
00053
00055 TEST (PCL, ISSKeypoint3D_WBE)
00056 {
00057 PointCloud<PointXYZ> keypoints;
00058
00059
00060
00061
00062 ISSKeypoint3D<PointXYZ, PointXYZ> iss_detector;
00063 iss_detector.setSearchMethod (tree);
00064 iss_detector.setSalientRadius (6 * cloud_resolution);
00065 iss_detector.setNonMaxRadius (4 * cloud_resolution);
00066
00067 iss_detector.setThreshold21 (0.975);
00068 iss_detector.setThreshold32 (0.975);
00069 iss_detector.setMinNeighbors (5);
00070 iss_detector.setNumberOfThreads (1);
00071 iss_detector.setInputCloud (cloud);
00072 iss_detector.compute (keypoints);
00073
00074
00075
00076
00077 const size_t correct_nr_keypoints = 6;
00078 const float correct_keypoints[correct_nr_keypoints][3] =
00079 {
00080
00081 {-0.071112f, 0.137670f, 0.047518f},
00082 {-0.041733f, 0.127960f, 0.016650f},
00083 {-0.011943f, 0.086771f, 0.057009f},
00084 { 0.031733f, 0.099372f, 0.038505f},
00085 {-0.062116f, 0.045145f, 0.037802f},
00086 {-0.048250f, 0.167480f, -0.000152f}
00087 };
00088
00089
00090 ASSERT_EQ (keypoints.points.size (), correct_nr_keypoints);
00091
00092 for (size_t i = 0; i < correct_nr_keypoints; ++i)
00093 {
00094 EXPECT_NEAR (keypoints.points[i].x, correct_keypoints[i][0], 1e-6);
00095 EXPECT_NEAR (keypoints.points[i].y, correct_keypoints[i][1], 1e-6);
00096 EXPECT_NEAR (keypoints.points[i].z, correct_keypoints[i][2], 1e-6);
00097 }
00098
00099 tree.reset (new search::KdTree<PointXYZ> ());
00100 }
00101
00103 TEST (PCL, ISSKeypoint3D_BE)
00104 {
00105 PointCloud<PointXYZ> keypoints;
00106
00107
00108
00109
00110
00111 ISSKeypoint3D<PointXYZ, PointXYZ> iss_detector;
00112
00113 iss_detector.setSearchMethod (tree);
00114 iss_detector.setSalientRadius (6 * cloud_resolution);
00115 iss_detector.setNonMaxRadius (4 * cloud_resolution);
00116
00117 iss_detector.setNormalRadius (4 * cloud_resolution);
00118 iss_detector.setBorderRadius (4 * cloud_resolution);
00119
00120 iss_detector.setThreshold21 (0.975);
00121 iss_detector.setThreshold32 (0.975);
00122 iss_detector.setMinNeighbors (5);
00123 iss_detector.setAngleThreshold (static_cast<float> (M_PI) / 3.0);
00124 iss_detector.setNumberOfThreads (1);
00125
00126 iss_detector.setInputCloud (cloud);
00127 iss_detector.compute (keypoints);
00128
00129
00130
00131
00132
00133 const size_t correct_nr_keypoints = 5;
00134 const float correct_keypoints[correct_nr_keypoints][3] =
00135 {
00136
00137 {-0.052037f, 0.116800f, 0.034582f},
00138 { 0.027420f, 0.096386f, 0.043312f},
00139 {-0.011943f, 0.086771f, 0.057009f},
00140 {-0.070344f, 0.087352f, 0.041908f},
00141 {-0.030035f, 0.066130f, 0.038942f}
00142 };
00143
00144 ASSERT_EQ (keypoints.points.size (), correct_nr_keypoints);
00145
00146 for (size_t i = 0; i < correct_nr_keypoints; ++i)
00147 {
00148 EXPECT_NEAR (keypoints.points[i].x, correct_keypoints[i][0], 1e-6);
00149 EXPECT_NEAR (keypoints.points[i].y, correct_keypoints[i][1], 1e-6);
00150 EXPECT_NEAR (keypoints.points[i].z, correct_keypoints[i][2], 1e-6);
00151 }
00152
00153 tree.reset (new search::KdTree<PointXYZ> ());
00154 }
00155
00156
00157 int
00158 main (int argc, char** argv)
00159 {
00160 if (argc < 2)
00161 {
00162 std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00163 return (-1);
00164 }
00165
00166
00167 if (io::loadPCDFile (argv[1], *cloud) < 0)
00168 {
00169 std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00170 return (-1);
00171 }
00172
00173 testing::InitGoogleTest (&argc, argv);
00174 return (RUN_ALL_TESTS ());
00175 }
00176