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
00040 #include <gtest/gtest.h>
00041 #include <pcl/point_cloud.h>
00042 #include <pcl/features/normal_3d.h>
00043 #include <pcl/features/normal_3d_omp.h>
00044 #include <pcl/io/pcd_io.h>
00045
00046 using namespace pcl;
00047 using namespace pcl::io;
00048 using namespace std;
00049
00050 typedef search::KdTree<PointXYZ>::Ptr KdTreePtr;
00051
00052 PointCloud<PointXYZ> cloud;
00053 vector<int> indices;
00054 KdTreePtr tree;
00055
00057 TEST (PCL, NormalEstimation)
00058 {
00059 Eigen::Vector4f plane_parameters;
00060 float curvature;
00061
00062 NormalEstimation<PointXYZ, Normal> n;
00063
00064
00065 computePointNormal (cloud, indices, plane_parameters, curvature);
00066 EXPECT_NEAR (fabs (plane_parameters[0]), 0.035592, 1e-4);
00067 EXPECT_NEAR (fabs (plane_parameters[1]), 0.369596, 1e-4);
00068 EXPECT_NEAR (fabs (plane_parameters[2]), 0.928511, 1e-4);
00069 EXPECT_NEAR (fabs (plane_parameters[3]), 0.0622552, 1e-4);
00070 EXPECT_NEAR (curvature, 0.0693136, 1e-4);
00071
00072 float nx, ny, nz;
00073
00074 n.computePointNormal (cloud, indices, nx, ny, nz, curvature);
00075 EXPECT_NEAR (fabs (nx), 0.035592, 1e-4);
00076 EXPECT_NEAR (fabs (ny), 0.369596, 1e-4);
00077 EXPECT_NEAR (fabs (nz), 0.928511, 1e-4);
00078 EXPECT_NEAR (curvature, 0.0693136, 1e-4);
00079
00080
00081 computePointNormal (cloud, plane_parameters, curvature);
00082 EXPECT_NEAR (plane_parameters[0], 0.035592, 1e-4);
00083 EXPECT_NEAR (plane_parameters[1], 0.369596, 1e-4);
00084 EXPECT_NEAR (plane_parameters[2], 0.928511, 1e-4);
00085 EXPECT_NEAR (plane_parameters[3], -0.0622552, 1e-4);
00086 EXPECT_NEAR (curvature, 0.0693136, 1e-4);
00087
00088
00089 flipNormalTowardsViewpoint (cloud.points[0], 0, 0, 0, plane_parameters);
00090 EXPECT_NEAR (plane_parameters[0], -0.035592, 1e-4);
00091 EXPECT_NEAR (plane_parameters[1], -0.369596, 1e-4);
00092 EXPECT_NEAR (plane_parameters[2], -0.928511, 1e-4);
00093 EXPECT_NEAR (plane_parameters[3], 0.0799743, 1e-4);
00094
00095
00096 flipNormalTowardsViewpoint (cloud.points[0], 0, 0, 0, nx, ny, nz);
00097 EXPECT_NEAR (nx, -0.035592, 1e-4);
00098 EXPECT_NEAR (ny, -0.369596, 1e-4);
00099 EXPECT_NEAR (nz, -0.928511, 1e-4);
00100
00101
00102 PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00103
00104
00105 PointCloud<PointXYZ>::Ptr cloudptr = cloud.makeShared ();
00106 n.setInputCloud (cloudptr);
00107 EXPECT_EQ (n.getInputCloud (), cloudptr);
00108 boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices));
00109 n.setIndices (indicesptr);
00110 EXPECT_EQ (n.getIndices (), indicesptr);
00111 n.setSearchMethod (tree);
00112 EXPECT_EQ (n.getSearchMethod (), tree);
00113 n.setKSearch (static_cast<int> (indices.size ()));
00114
00115
00116 n.compute (*normals);
00117 EXPECT_EQ (normals->points.size (), indices.size ());
00118
00119 for (size_t i = 0; i < normals->points.size (); ++i)
00120 {
00121 EXPECT_NEAR (normals->points[i].normal[0], -0.035592, 1e-4);
00122 EXPECT_NEAR (normals->points[i].normal[1], -0.369596, 1e-4);
00123 EXPECT_NEAR (normals->points[i].normal[2], -0.928511, 1e-4);
00124 EXPECT_NEAR (normals->points[i].curvature, 0.0693136, 1e-4);
00125 }
00126
00127 PointCloud<PointXYZ>::Ptr surfaceptr = cloudptr;
00128 n.setSearchSurface (surfaceptr);
00129 EXPECT_EQ (n.getSearchSurface (), surfaceptr);
00130
00131
00132 surfaceptr.reset (new PointCloud<PointXYZ>);
00133 *surfaceptr = *cloudptr;
00134 surfaceptr->points.resize (640 * 480);
00135 surfaceptr->width = 640;
00136 surfaceptr->height = 480;
00137 EXPECT_EQ (surfaceptr->points.size (), surfaceptr->width * surfaceptr->height);
00138 n.setSearchSurface (surfaceptr);
00139 tree.reset ();
00140 n.setSearchMethod (tree);
00141
00142
00143 n.compute (*normals);
00144 EXPECT_EQ (normals->points.size (), indices.size ());
00145 }
00146
00148 TEST (PCL, NormalEstimationOpenMP)
00149 {
00150 NormalEstimationOMP<PointXYZ, Normal> n (4);
00151
00152
00153 PointCloud<Normal>::Ptr normals (new PointCloud<Normal> ());
00154
00155
00156 PointCloud<PointXYZ>::Ptr cloudptr = cloud.makeShared ();
00157 n.setInputCloud (cloudptr);
00158 EXPECT_EQ (n.getInputCloud (), cloudptr);
00159 boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices));
00160 n.setIndices (indicesptr);
00161 EXPECT_EQ (n.getIndices (), indicesptr);
00162 n.setSearchMethod (tree);
00163 EXPECT_EQ (n.getSearchMethod (), tree);
00164 n.setKSearch (static_cast<int> (indices.size ()));
00165
00166
00167 n.compute (*normals);
00168 EXPECT_EQ (normals->points.size (), indices.size ());
00169
00170 for (size_t i = 0; i < normals->points.size (); ++i)
00171 {
00172 EXPECT_NEAR (normals->points[i].normal[0], -0.035592, 1e-4);
00173 EXPECT_NEAR (normals->points[i].normal[1], -0.369596, 1e-4);
00174 EXPECT_NEAR (normals->points[i].normal[2], -0.928511, 1e-4);
00175 EXPECT_NEAR (normals->points[i].curvature, 0.0693136, 1e-4);
00176 }
00177 }
00178
00179 #ifndef PCL_ONLY_CORE_POINT_TYPES
00180
00181 TEST (PCL, NormalEstimationEigen)
00182 {
00183 Eigen::Vector4f plane_parameters;
00184 float curvature;
00185
00186 NormalEstimation<PointXYZ, Eigen::MatrixXf> n;
00187
00188
00189 computePointNormal (cloud, indices, plane_parameters, curvature);
00190 EXPECT_NEAR (fabs (plane_parameters[0]), 0.035592, 1e-4);
00191 EXPECT_NEAR (fabs (plane_parameters[1]), 0.369596, 1e-4);
00192 EXPECT_NEAR (fabs (plane_parameters[2]), 0.928511, 1e-4);
00193 EXPECT_NEAR (fabs (plane_parameters[3]), 0.0622552, 1e-4);
00194 EXPECT_NEAR (curvature, 0.0693136, 1e-4);
00195
00196 float nx, ny, nz;
00197
00198 n.computePointNormal (cloud, indices, nx, ny, nz, curvature);
00199 EXPECT_NEAR (fabs (nx), 0.035592, 1e-4);
00200 EXPECT_NEAR (fabs (ny), 0.369596, 1e-4);
00201 EXPECT_NEAR (fabs (nz), 0.928511, 1e-4);
00202 EXPECT_NEAR (curvature, 0.0693136, 1e-4);
00203
00204
00205 computePointNormal (cloud, plane_parameters, curvature);
00206 EXPECT_NEAR (plane_parameters[0], 0.035592, 1e-4);
00207 EXPECT_NEAR (plane_parameters[1], 0.369596, 1e-4);
00208 EXPECT_NEAR (plane_parameters[2], 0.928511, 1e-4);
00209 EXPECT_NEAR (plane_parameters[3], -0.0622552, 1e-4);
00210 EXPECT_NEAR (curvature, 0.0693136, 1e-4);
00211
00212
00213 flipNormalTowardsViewpoint (cloud.points[0], 0, 0, 0, plane_parameters);
00214 EXPECT_NEAR (plane_parameters[0], -0.035592, 1e-4);
00215 EXPECT_NEAR (plane_parameters[1], -0.369596, 1e-4);
00216 EXPECT_NEAR (plane_parameters[2], -0.928511, 1e-4);
00217 EXPECT_NEAR (plane_parameters[3], 0.0799743, 1e-4);
00218
00219
00220 flipNormalTowardsViewpoint (cloud.points[0], 0, 0, 0, nx, ny, nz);
00221 EXPECT_NEAR (nx, -0.035592, 1e-4);
00222 EXPECT_NEAR (ny, -0.369596, 1e-4);
00223 EXPECT_NEAR (nz, -0.928511, 1e-4);
00224
00225
00226 PointCloud<Eigen::MatrixXf>::Ptr normals (new PointCloud<Eigen::MatrixXf> ());
00227
00228
00229 PointCloud<PointXYZ>::Ptr cloudptr = cloud.makeShared ();
00230 n.setInputCloud (cloudptr);
00231 EXPECT_EQ (n.getInputCloud (), cloudptr);
00232 boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices));
00233 n.setIndices (indicesptr);
00234 EXPECT_EQ (n.getIndices (), indicesptr);
00235 n.setSearchMethod (tree);
00236 EXPECT_EQ (n.getSearchMethod (), tree);
00237 n.setKSearch (static_cast<int> (indices.size ()));
00238
00239
00240 n.computeEigen (*normals);
00241 EXPECT_EQ (normals->points.rows (), indices.size ());
00242
00243 for (int i = 0; i < normals->points.rows (); ++i)
00244 {
00245 EXPECT_NEAR (normals->points.row (i)[0], -0.035592, 1e-4);
00246 EXPECT_NEAR (normals->points.row (i)[1], -0.369596, 1e-4);
00247 EXPECT_NEAR (normals->points.row (i)[2], -0.928511, 1e-4);
00248 EXPECT_NEAR (normals->points.row (i)[3], 0.0693136, 1e-4);
00249 }
00250
00251 PointCloud<PointXYZ>::Ptr surfaceptr = cloudptr;
00252 n.setSearchSurface (surfaceptr);
00253 EXPECT_EQ (n.getSearchSurface (), surfaceptr);
00254
00255
00256 surfaceptr.reset (new PointCloud<PointXYZ>);
00257 *surfaceptr = *cloudptr;
00258 surfaceptr->points.resize (640 * 480);
00259 surfaceptr->width = 640;
00260 surfaceptr->height = 480;
00261 EXPECT_EQ (surfaceptr->points.size (), surfaceptr->width * surfaceptr->height);
00262 n.setSearchSurface (surfaceptr);
00263 tree.reset ();
00264 n.setSearchMethod (tree);
00265
00266
00267 n.computeEigen (*normals);
00268 EXPECT_EQ (normals->points.rows (), indices.size ());
00269 }
00270
00272 TEST (PCL, NormalEstimationOpenMPEigen)
00273 {
00274 NormalEstimationOMP<PointXYZ, Eigen::MatrixXf> n (4);
00275
00276
00277 PointCloud<Eigen::MatrixXf>::Ptr normals (new PointCloud<Eigen::MatrixXf>);
00278
00279
00280 PointCloud<PointXYZ>::Ptr cloudptr = cloud.makeShared ();
00281 n.setInputCloud (cloudptr);
00282 EXPECT_EQ (n.getInputCloud (), cloudptr);
00283 boost::shared_ptr<vector<int> > indicesptr (new vector<int> (indices));
00284 n.setIndices (indicesptr);
00285 EXPECT_EQ (n.getIndices (), indicesptr);
00286 n.setSearchMethod (tree);
00287 EXPECT_EQ (n.getSearchMethod (), tree);
00288 n.setKSearch (static_cast<int> (indices.size ()));
00289
00290
00291 n.computeEigen (*normals);
00292 EXPECT_EQ (normals->points.rows (), indices.size ());
00293
00294 for (int i = 0; i < normals->points.rows (); ++i)
00295 {
00296 EXPECT_NEAR (normals->points.row (i)[0], -0.035592, 1e-4);
00297 EXPECT_NEAR (normals->points.row (i)[1], -0.369596, 1e-4);
00298 EXPECT_NEAR (normals->points.row (i)[2], -0.928511, 1e-4);
00299 EXPECT_NEAR (normals->points.row (i)[3], 0.0693136, 1e-4);
00300 }
00301 }
00302 #endif
00303
00304
00305 int
00306 main (int argc, char** argv)
00307 {
00308 if (argc < 2)
00309 {
00310 std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00311 return (-1);
00312 }
00313
00314 if (loadPCDFile<PointXYZ> (argv[1], cloud) < 0)
00315 {
00316 std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00317 return (-1);
00318 }
00319
00320 indices.resize (cloud.points.size ());
00321 for (int i = 0; i < static_cast<int> (indices.size ()); ++i)
00322 indices[i] = i;
00323
00324 tree.reset (new search::KdTree<PointXYZ> (false));
00325 tree->setInputCloud (cloud.makeShared ());
00326
00327 testing::InitGoogleTest (&argc, argv);
00328 return (RUN_ALL_TESTS ());
00329 }
00330