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 #include <gtest/gtest.h>
00037
00038 #include <iostream>
00039
00040 #include <pcl/PCLPointCloud2.h>
00041 #include <pcl/io/pcd_io.h>
00042 #include <pcl/features/feature.h>
00043 #include <pcl/common/eigen.h>
00044 #include <pcl/point_types.h>
00045 #include <pcl/point_cloud.h>
00046 #include <pcl/common/transforms.h>
00047
00048 using namespace pcl;
00049 using namespace pcl::io;
00050 using namespace std;
00051
00052 const float PI = 3.14159265f;
00053 const float rho = sqrtf (2.0f) / 2.0f;
00054
00055 PointCloud<PointXYZ> cloud;
00056 pcl::PCLPointCloud2 cloud_blob;
00057
00058 void
00059 init ()
00060 {
00061 PointXYZ p0 (0, 0, 0);
00062 PointXYZ p1 (1, 0, 0);
00063 PointXYZ p2 (0, 1, 0);
00064 PointXYZ p3 (0, 0, 1);
00065 cloud.points.push_back (p0);
00066 cloud.points.push_back (p1);
00067 cloud.points.push_back (p2);
00068 cloud.points.push_back (p3);
00069 }
00070
00072 TEST (PCL, DeMean)
00073 {
00074 PointCloud<PointXYZ> cloud, cloud_demean;
00075 fromPCLPointCloud2 (cloud_blob, cloud);
00076
00077 Eigen::Vector4f centroid;
00078 compute3DCentroid (cloud, centroid);
00079 EXPECT_NEAR (centroid[0], -0.0290809, 1e-4);
00080 EXPECT_NEAR (centroid[1], 0.102653, 1e-4);
00081 EXPECT_NEAR (centroid[2], 0.027302, 1e-4);
00082 EXPECT_NEAR (centroid[3], 0, 1e-4);
00083
00084
00085 demeanPointCloud (cloud, centroid, cloud_demean);
00086 EXPECT_EQ (cloud_demean.is_dense, cloud.is_dense);
00087 EXPECT_EQ (cloud_demean.width, cloud.width);
00088 EXPECT_EQ (cloud_demean.height, cloud.height);
00089 EXPECT_EQ (cloud_demean.points.size (), cloud.points.size ());
00090
00091 EXPECT_NEAR (cloud_demean.points[0].x, 0.034503, 1e-4);
00092 EXPECT_NEAR (cloud_demean.points[0].y, 0.010837, 1e-4);
00093 EXPECT_NEAR (cloud_demean.points[0].z, 0.013447, 1e-4);
00094
00095 EXPECT_NEAR (cloud_demean.points[cloud_demean.points.size () - 1].x, -0.048849, 1e-4);
00096 EXPECT_NEAR (cloud_demean.points[cloud_demean.points.size () - 1].y, 0.072507, 1e-4);
00097 EXPECT_NEAR (cloud_demean.points[cloud_demean.points.size () - 1].z, -0.071702, 1e-4);
00098
00099 vector<int> indices (cloud.points.size ());
00100 for (int i = 0; i < static_cast<int> (indices.size ()); ++i) { indices[i] = i; }
00101
00102
00103 demeanPointCloud (cloud, indices, centroid, cloud_demean);
00104 EXPECT_EQ (cloud_demean.is_dense, cloud.is_dense);
00105 EXPECT_EQ (cloud_demean.width, cloud.width);
00106 EXPECT_EQ (cloud_demean.height, cloud.height);
00107 EXPECT_EQ (cloud_demean.points.size (), cloud.points.size ());
00108
00109 EXPECT_NEAR (cloud_demean.points[0].x, 0.034503, 1e-4);
00110 EXPECT_NEAR (cloud_demean.points[0].y, 0.010837, 1e-4);
00111 EXPECT_NEAR (cloud_demean.points[0].z, 0.013447, 1e-4);
00112
00113 EXPECT_NEAR (cloud_demean.points[cloud_demean.points.size () - 1].x, -0.048849, 1e-4);
00114 EXPECT_NEAR (cloud_demean.points[cloud_demean.points.size () - 1].y, 0.072507, 1e-4);
00115 EXPECT_NEAR (cloud_demean.points[cloud_demean.points.size () - 1].z, -0.071702, 1e-4);
00116
00117
00118 Eigen::MatrixXf mat_demean;
00119 demeanPointCloud (cloud, centroid, mat_demean);
00120 EXPECT_EQ (mat_demean.cols (), int (cloud.points.size ()));
00121 EXPECT_EQ (mat_demean.rows (), 4);
00122
00123 EXPECT_NEAR (mat_demean (0, 0), 0.034503, 1e-4);
00124 EXPECT_NEAR (mat_demean (1, 0), 0.010837, 1e-4);
00125 EXPECT_NEAR (mat_demean (2, 0), 0.013447, 1e-4);
00126
00127 EXPECT_NEAR (mat_demean (0, cloud_demean.points.size () - 1), -0.048849, 1e-4);
00128 EXPECT_NEAR (mat_demean (1, cloud_demean.points.size () - 1), 0.072507, 1e-4);
00129 EXPECT_NEAR (mat_demean (2, cloud_demean.points.size () - 1), -0.071702, 1e-4);
00130
00131
00132 demeanPointCloud (cloud, indices, centroid, mat_demean);
00133 EXPECT_EQ (mat_demean.cols (), int (cloud.points.size ()));
00134 EXPECT_EQ (mat_demean.rows (), 4);
00135
00136 EXPECT_NEAR (mat_demean (0, 0), 0.034503, 1e-4);
00137 EXPECT_NEAR (mat_demean (1, 0), 0.010837, 1e-4);
00138 EXPECT_NEAR (mat_demean (2, 0), 0.013447, 1e-4);
00139
00140 EXPECT_NEAR (mat_demean (0, cloud_demean.points.size () - 1), -0.048849, 1e-4);
00141 EXPECT_NEAR (mat_demean (1, cloud_demean.points.size () - 1), 0.072507, 1e-4);
00142 EXPECT_NEAR (mat_demean (2, cloud_demean.points.size () - 1), -0.071702, 1e-4);
00143 }
00144
00146 TEST (PCL, Transform)
00147 {
00148 Eigen::Vector3f offset (100, 0, 0);
00149 float angle = PI/4;
00150 Eigen::Quaternionf rotation (cos (angle / 2), 0, 0, sin (angle / 2));
00151
00152 PointCloud<PointXYZ> cloud_out;
00153 const vector<PointXYZ, Eigen::aligned_allocator<PointXYZ> > &points (cloud_out.points);
00154 transformPointCloud (cloud, cloud_out, offset, rotation);
00155
00156 EXPECT_EQ (cloud.points.size (), cloud_out.points.size ());
00157 EXPECT_EQ (100, points[0].x);
00158 EXPECT_EQ (0, points[0].y);
00159 EXPECT_EQ (0, points[0].z);
00160 EXPECT_NEAR (100+rho, points[1].x, 1e-4);
00161 EXPECT_NEAR (rho, points[1].y, 1e-4);
00162 EXPECT_EQ (0, points[1].z);
00163 EXPECT_NEAR (100-rho, points[2].x, 1e-4);
00164 EXPECT_NEAR (rho, points[2].y, 1e-4);
00165 EXPECT_EQ (0, points[2].z);
00166 EXPECT_EQ (100, points[3].x);
00167 EXPECT_EQ (0, points[3].y);
00168 EXPECT_EQ (1, points[3].z);
00169
00170 PointCloud<PointXYZ> cloud_out2;
00171 const vector<PointXYZ, Eigen::aligned_allocator<PointXYZ> > &points2 (cloud_out2.points);
00172 Eigen::Translation3f translation (offset);
00173 Eigen::Affine3f transform;
00174 transform = translation * rotation;
00175 transformPointCloud (cloud, cloud_out2, transform);
00176
00177 EXPECT_EQ (cloud.points.size (), cloud_out2.points.size ());
00178 EXPECT_EQ (100, points2[0].x);
00179 EXPECT_EQ (0, points2[0].y);
00180 EXPECT_EQ (0, points2[0].z);
00181 EXPECT_NEAR (100+rho, points2[1].x, 1e-4);
00182 EXPECT_NEAR (rho, points2[1].y, 1e-4);
00183 EXPECT_EQ (0, points2[1].z);
00184 EXPECT_NEAR (100-rho, points2[2].x, 1e-4);
00185 EXPECT_NEAR (rho, points2[2].y, 1e-4);
00186 EXPECT_EQ (0, points2[2].z);
00187 EXPECT_EQ (100, points2[3].x);
00188 EXPECT_EQ (0, points2[3].y);
00189 EXPECT_EQ (1, points2[3].z);
00190 }
00191
00193 TEST (PCL, Matrix4Affine3Transform)
00194 {
00195 float rot_x = 2.8827f;
00196 float rot_y = -0.31190f;
00197 float rot_z = -0.93058f;
00198 Eigen::Affine3f affine;
00199 pcl::getTransformation (0, 0, 0, rot_x, rot_y, rot_z, affine);
00200
00201 EXPECT_NEAR (affine (0, 0), 0.56854731f, 1e-4); EXPECT_NEAR (affine (0, 1), -0.82217032f, 1e-4); EXPECT_NEAR (affine (0, 2), -0.028107658f, 1e-4);
00202 EXPECT_NEAR (affine (1, 0), -0.76327348f, 1e-4); EXPECT_NEAR (affine (1, 1), -0.51445758f, 1e-4); EXPECT_NEAR (affine (1, 2), -0.39082864f, 1e-4);
00203 EXPECT_NEAR (affine (2, 0), 0.30686751f, 1e-4); EXPECT_NEAR (affine (2, 1), 0.24365838f, 1e-4); EXPECT_NEAR (affine (2, 2), -0.920034f, 1e-4);
00204
00205
00206 Eigen::Matrix3f rotation = affine.rotation ();
00207
00208 EXPECT_NEAR (rotation (0, 0), 0.56854731f, 1e-4); EXPECT_NEAR (rotation (0, 1), -0.82217032f, 1e-4); EXPECT_NEAR (rotation (0, 2), -0.028107658f, 1e-4);
00209 EXPECT_NEAR (rotation (1, 0), -0.76327348f, 1e-4); EXPECT_NEAR (rotation (1, 1), -0.51445758f, 1e-4); EXPECT_NEAR (rotation (1, 2), -0.39082864f, 1e-4);
00210 EXPECT_NEAR (rotation (2, 0), 0.30686751f, 1e-4); EXPECT_NEAR (rotation (2, 1), 0.24365838f, 1e-4); EXPECT_NEAR (rotation (2, 2), -0.920034f, 1e-4);
00211
00212 float trans_x, trans_y, trans_z;
00213 pcl::getTransformation (0.1f, 0.2f, 0.3f, rot_x, rot_y, rot_z, affine);
00214 pcl::getTranslationAndEulerAngles (affine, trans_x, trans_y, trans_z, rot_x, rot_y, rot_z);
00215 EXPECT_FLOAT_EQ (trans_x, 0.1f);
00216 EXPECT_FLOAT_EQ (trans_y, 0.2f);
00217 EXPECT_FLOAT_EQ (trans_z, 0.3f);
00218 EXPECT_FLOAT_EQ (rot_x, 2.8827f);
00219 EXPECT_FLOAT_EQ (rot_y, -0.31190f);
00220 EXPECT_FLOAT_EQ (rot_z, -0.93058f);
00221
00222 Eigen::Matrix4f transformation (Eigen::Matrix4f::Identity ());
00223 transformation.block<3, 3> (0, 0) = affine.rotation ();
00224 transformation.block<3, 1> (0, 3) = affine.translation ();
00225
00226 PointXYZ p (1.f, 2.f, 3.f);
00227 Eigen::Vector3f v3 = p.getVector3fMap ();
00228 Eigen::Vector4f v4 = p.getVector4fMap ();
00229
00230 Eigen::Vector3f v3t (affine * v3);
00231 Eigen::Vector4f v4t (transformation * v4);
00232
00233 PointXYZ pt = pcl::transformPoint (p, affine);
00234
00235 EXPECT_NEAR (pt.x, v3t.x (), 1e-4); EXPECT_NEAR (pt.x, v4t.x (), 1e-4);
00236 EXPECT_NEAR (pt.y, v3t.y (), 1e-4); EXPECT_NEAR (pt.y, v4t.y (), 1e-4);
00237 EXPECT_NEAR (pt.z, v3t.z (), 1e-4); EXPECT_NEAR (pt.z, v4t.z (), 1e-4);
00238
00239 PointCloud<PointXYZ> c, ct;
00240 c.push_back (p);
00241 pcl::transformPointCloud (c, ct, affine);
00242 EXPECT_FLOAT_EQ (pt.x, ct[0].x);
00243 EXPECT_FLOAT_EQ (pt.y, ct[0].y);
00244 EXPECT_FLOAT_EQ (pt.z, ct[0].z);
00245
00246 pcl::transformPointCloud (c, ct, transformation);
00247 EXPECT_FLOAT_EQ (pt.x, ct[0].x);
00248 EXPECT_FLOAT_EQ (pt.y, ct[0].y);
00249 EXPECT_FLOAT_EQ (pt.z, ct[0].z);
00250
00251 affine = transformation;
00252
00253 std::vector<int> indices (1); indices[0] = 0;
00254
00255 pcl::transformPointCloud (c, indices, ct, affine);
00256 EXPECT_FLOAT_EQ (pt.x, ct[0].x);
00257 EXPECT_FLOAT_EQ (pt.y, ct[0].y);
00258 EXPECT_FLOAT_EQ (pt.z, ct[0].z);
00259
00260 pcl::transformPointCloud (c, indices, ct, transformation);
00261 EXPECT_FLOAT_EQ (pt.x, ct[0].x);
00262 EXPECT_FLOAT_EQ (pt.y, ct[0].y);
00263 EXPECT_FLOAT_EQ (pt.z, ct[0].z);
00264 }
00265
00267 TEST (PCL, commonTransform)
00268 {
00269 Eigen::Vector3f xaxis (1,0,0), yaxis (0,1,0), zaxis (0,0,1);
00270 Eigen::Affine3f trans = pcl::getTransFromUnitVectorsZY (zaxis, yaxis);
00271 Eigen::Vector3f xaxistrans=trans*xaxis, yaxistrans=trans*yaxis, zaxistrans=trans*zaxis;
00272
00273 EXPECT_NEAR ((xaxistrans-xaxis).norm(), 0.0f, 1e-6);
00274 EXPECT_NEAR ((yaxistrans-yaxis).norm(), 0.0f, 1e-6);
00275 EXPECT_NEAR ((zaxistrans-zaxis).norm(), 0.0f, 1e-6);
00276
00277 trans = pcl::getTransFromUnitVectorsXY (xaxis, yaxis);
00278 xaxistrans=trans*xaxis, yaxistrans=trans*yaxis, zaxistrans=trans*zaxis;
00279
00280 EXPECT_NEAR ((xaxistrans-xaxis).norm(), 0.0f, 1e-6);
00281 EXPECT_NEAR ((yaxistrans-yaxis).norm(), 0.0f, 1e-6);
00282 EXPECT_NEAR ((zaxistrans-zaxis).norm(), 0.0f, 1e-6);
00283 }
00284
00285
00286 int
00287 main (int argc, char** argv)
00288 {
00289 if (argc < 2)
00290 {
00291 std::cerr << "No test file given. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00292 return (-1);
00293 }
00294 if (loadPCDFile (argv[1], cloud_blob) < 0)
00295 {
00296 std::cerr << "Failed to read test file. Please download `bun0.pcd` and pass its path to the test." << std::endl;
00297 return (-1);
00298 }
00299
00300 testing::InitGoogleTest (&argc, argv);
00301 init();
00302 return (RUN_ALL_TESTS ());
00303 }
00304