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
00038 #include <gtest/gtest.h>
00039
00040 #include <iostream>
00041
00042 #include <sensor_msgs/PointCloud2.h>
00043 #include "pcl/io/pcd_io.h"
00044 #include "pcl/features/feature.h"
00045 #include <pcl/point_types.h>
00046 #include <pcl/point_cloud.h>
00047 #include <pcl/registration/transforms.h>
00048
00049 using namespace pcl;
00050 using namespace pcl::io;
00051 using namespace std;
00052
00053 const float PI = 3.14159265;
00054 const float rho = sqrt (2) / 2;
00055
00056 class MyPointXYZ : public PointXYZ
00057 {
00058 public:
00059 MyPointXYZ (float X, float Y, float Z)
00060 {
00061 x = X;
00062 y = Y;
00063 z = Z;
00064 }
00065 };
00066
00067 PointCloud<PointXYZ> cloud;
00068
00069 void
00070 init ()
00071 {
00072 MyPointXYZ p0 (0, 0, 0);
00073 MyPointXYZ p1 (1, 0, 0);
00074 MyPointXYZ p2 (0, 1, 0);
00075 MyPointXYZ p3 (0, 0, 1);
00076 cloud.points.push_back (p0);
00077 cloud.points.push_back (p1);
00078 cloud.points.push_back (p2);
00079 cloud.points.push_back (p3);
00080 }
00081
00083 TEST (PCL, DeMean)
00084 {
00085 PointCloud<PointXYZ> cloud, cloud_demean;
00086 sensor_msgs::PointCloud2 cloud_blob;
00087 loadPCDFile ("./test/bun0.pcd", cloud_blob);
00088 fromROSMsg (cloud_blob, cloud);
00089
00090 Eigen::Vector4f centroid;
00091 compute3DCentroid (cloud, centroid);
00092 EXPECT_NEAR (centroid[0], -0.0290809, 1e-4);
00093 EXPECT_NEAR (centroid[1], 0.102653, 1e-4);
00094 EXPECT_NEAR (centroid[2], 0.027302, 1e-4);
00095 EXPECT_NEAR (centroid[3], 0, 1e-4);
00096
00097
00098 demeanPointCloud (cloud, centroid, cloud_demean);
00099 EXPECT_EQ (cloud_demean.is_dense, cloud.is_dense);
00100 EXPECT_EQ (cloud_demean.width, cloud.width);
00101 EXPECT_EQ (cloud_demean.height, cloud.height);
00102 EXPECT_EQ (cloud_demean.points.size (), cloud.points.size ());
00103
00104 EXPECT_NEAR (cloud_demean.points[0].x, 0.034503, 1e-4);
00105 EXPECT_NEAR (cloud_demean.points[0].y, 0.010837, 1e-4);
00106 EXPECT_NEAR (cloud_demean.points[0].z, 0.013447, 1e-4);
00107
00108 EXPECT_NEAR (cloud_demean.points[cloud_demean.points.size () - 1].x, -0.048849, 1e-4);
00109 EXPECT_NEAR (cloud_demean.points[cloud_demean.points.size () - 1].y, 0.072507, 1e-4);
00110 EXPECT_NEAR (cloud_demean.points[cloud_demean.points.size () - 1].z, -0.071702, 1e-4);
00111
00112 vector<int> indices (cloud.points.size ());
00113 for (size_t i = 0; i < indices.size (); ++i) { indices[i] = i; }
00114
00115
00116 demeanPointCloud (cloud, indices, centroid, cloud_demean);
00117 EXPECT_EQ (cloud_demean.is_dense, cloud.is_dense);
00118 EXPECT_EQ (cloud_demean.width, cloud.width);
00119 EXPECT_EQ (cloud_demean.height, cloud.height);
00120 EXPECT_EQ (cloud_demean.points.size (), cloud.points.size ());
00121
00122 EXPECT_NEAR (cloud_demean.points[0].x, 0.034503, 1e-4);
00123 EXPECT_NEAR (cloud_demean.points[0].y, 0.010837, 1e-4);
00124 EXPECT_NEAR (cloud_demean.points[0].z, 0.013447, 1e-4);
00125
00126 EXPECT_NEAR (cloud_demean.points[cloud_demean.points.size () - 1].x, -0.048849, 1e-4);
00127 EXPECT_NEAR (cloud_demean.points[cloud_demean.points.size () - 1].y, 0.072507, 1e-4);
00128 EXPECT_NEAR (cloud_demean.points[cloud_demean.points.size () - 1].z, -0.071702, 1e-4);
00129
00130
00131 Eigen::MatrixXf mat_demean;
00132 demeanPointCloud (cloud, 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
00145 demeanPointCloud (cloud, indices, centroid, mat_demean);
00146 EXPECT_EQ (mat_demean.cols (), (int)cloud.points.size ());
00147 EXPECT_EQ (mat_demean.rows (), 4);
00148
00149 EXPECT_NEAR (mat_demean (0, 0), 0.034503, 1e-4);
00150 EXPECT_NEAR (mat_demean (1, 0), 0.010837, 1e-4);
00151 EXPECT_NEAR (mat_demean (2, 0), 0.013447, 1e-4);
00152
00153 EXPECT_NEAR (mat_demean (0, cloud_demean.points.size () - 1), -0.048849, 1e-4);
00154 EXPECT_NEAR (mat_demean (1, cloud_demean.points.size () - 1), 0.072507, 1e-4);
00155 EXPECT_NEAR (mat_demean (2, cloud_demean.points.size () - 1), -0.071702, 1e-4);
00156 }
00157
00159 TEST (PCL, Transform)
00160 {
00161 Eigen::Vector3f offset (100, 0, 0);
00162 float angle = PI/4;
00163 Eigen::Quaternionf rotation (cos (angle / 2), 0, 0, sin (angle / 2));
00164
00165 PointCloud<PointXYZ> cloud_out;
00166 const vector<PointXYZ, Eigen::aligned_allocator<PointXYZ> > &points (cloud_out.points);
00167 transformPointCloud (cloud, cloud_out, offset, rotation);
00168
00169 EXPECT_EQ (cloud.points.size (), cloud_out.points.size ());
00170 EXPECT_EQ (100, points[0].x);
00171 EXPECT_EQ (0, points[0].y);
00172 EXPECT_EQ (0, points[0].z);
00173 EXPECT_NEAR (100+rho, points[1].x, 1e-4);
00174 EXPECT_NEAR (rho, points[1].y, 1e-4);
00175 EXPECT_EQ (0, points[1].z);
00176 EXPECT_NEAR (100-rho, points[2].x, 1e-4);
00177 EXPECT_NEAR (rho, points[2].y, 1e-4);
00178 EXPECT_EQ (0, points[2].z);
00179 EXPECT_EQ (100, points[3].x);
00180 EXPECT_EQ (0, points[3].y);
00181 EXPECT_EQ (1, points[3].z);
00182
00183 PointCloud<PointXYZ> cloud_out2;
00184 const vector<PointXYZ, Eigen::aligned_allocator<PointXYZ> > &points2 (cloud_out2.points);
00185 Eigen::Translation3f translation (offset);
00186 Eigen::Affine3f transform;
00187 transform = translation * rotation;
00188 transformPointCloud (cloud, cloud_out2, transform);
00189
00190 EXPECT_EQ (cloud.points.size (), cloud_out2.points.size ());
00191 EXPECT_EQ (100, points2[0].x);
00192 EXPECT_EQ (0, points2[0].y);
00193 EXPECT_EQ (0, points2[0].z);
00194 EXPECT_NEAR (100+rho, points2[1].x, 1e-4);
00195 EXPECT_NEAR (rho, points2[1].y, 1e-4);
00196 EXPECT_EQ (0, points2[1].z);
00197 EXPECT_NEAR (100-rho, points2[2].x, 1e-4);
00198 EXPECT_NEAR (rho, points2[2].y, 1e-4);
00199 EXPECT_EQ (0, points2[2].z);
00200 EXPECT_EQ (100, points2[3].x);
00201 EXPECT_EQ (0, points2[3].y);
00202 EXPECT_EQ (1, points2[3].z);
00203 }
00204
00205
00206
00207 int
00208 main (int argc, char** argv)
00209 {
00210 testing::InitGoogleTest (&argc, argv);
00211 init();
00212 return (RUN_ALL_TESTS ());
00213 }
00214