00001 #include "../utest.h"
00002
00003 using namespace std;
00004 using namespace PointMatcherSupport;
00005
00006
00007
00008
00009
00010 TEST(IOTest, loadYaml)
00011 {
00012
00013
00014 std::ifstream ifs0((dataPath + "default-convert.yaml").c_str());
00015 EXPECT_NO_THROW(PM::DataPointsFilters filters(ifs0));
00016
00017
00018 PM::ICP icp;
00019
00020 std::ifstream ifs1((dataPath + "default.yaml").c_str());
00021 EXPECT_NO_THROW(icp.loadFromYaml(ifs1));
00022
00023 std::ifstream ifs2((dataPath + "unit_tests/badIcpConfig_InvalidParameter.yaml").c_str());
00024 EXPECT_THROW(icp.loadFromYaml(ifs2), PointMatcherSupport::Parametrizable::InvalidParameter);
00025
00026 std::ifstream ifs3((dataPath + "unit_tests/badIcpConfig_InvalidModuleType.yaml").c_str());
00027 EXPECT_THROW(icp.loadFromYaml(ifs3), PointMatcherSupport::InvalidModuleType);
00028 }
00029
00030 TEST(IOTest, loadCSV)
00031 {
00032 typedef PointMatcherIO<float> IO;
00033 std::istringstream is;
00034 std::ostringstream os;
00035 DP pts;
00036
00037
00038 os.clear();
00039 os.str("");
00040 os <<
00041 "x, y\n"
00042 "1, 2\n"
00043 "1, 2, 3\n"
00044 "1, 2\n"
00045 ;
00046
00047 is.clear();
00048 is.str(os.str());
00049 EXPECT_THROW(IO::loadCSV(is), runtime_error);
00050
00051
00052 os.clear();
00053 os.str("");
00054 os <<
00055 "x, y\n"
00056 "1, 2\n"
00057 "1, \n"
00058 "1, 2\n"
00059 ;
00060
00061 is.clear();
00062 is.str(os.str());
00063 EXPECT_THROW(IO::loadCSV(is), runtime_error);
00064
00065
00066 os.clear();
00067 os.str("");
00068 os <<
00069 "x, y\n"
00070 "1, 2\n"
00071 "1, 2\n"
00072 "8, 2\n"
00073 "1, 2\n"
00074 ;
00075
00076 is.clear();
00077 is.str(os.str());
00078 pts = IO::loadCSV(is);
00079 EXPECT_EQ(4u, pts.getNbPoints());
00080 EXPECT_EQ(2u, pts.getEuclideanDim());
00081 EXPECT_EQ(0u, pts.getDescriptorDim());
00082 EXPECT_EQ(0u, pts.getTimeDim());
00083 EXPECT_EQ(8.0, pts.features(0,2));
00084
00085
00086 os.clear();
00087 os.str("");
00088 os <<
00089 "x, y, z\n"
00090 "1, 2, 3\n"
00091 "1, 2, 3\n"
00092 "8, 2, 3\n"
00093 "1, 2, 3\n"
00094 ;
00095
00096 is.clear();
00097 is.str(os.str());
00098 pts = IO::loadCSV(is);
00099 EXPECT_EQ(4u, pts.getNbPoints());
00100 EXPECT_EQ(3u, pts.getEuclideanDim());
00101 EXPECT_EQ(0u, pts.getDescriptorDim());
00102 EXPECT_EQ(0u, pts.getTimeDim());
00103 EXPECT_EQ(8.0, pts.features(0,2));
00104
00105
00106 os.clear();
00107 os.str("");
00108 os <<
00109 "x, y, z, dummy\n"
00110 "1, 2, 3, 4\n"
00111 "1, 2, 3, 4\n"
00112 "8, 2, 3, 4\n"
00113 "1, 2, 3, 4\n"
00114 ;
00115
00116 is.clear();
00117 is.str(os.str());
00118 pts = IO::loadCSV(is);
00119 EXPECT_EQ(4u, pts.getNbPoints());
00120 EXPECT_EQ(3u, pts.getEuclideanDim());
00121 EXPECT_EQ(1u, pts.getDescriptorDim());
00122 EXPECT_EQ(0u, pts.getTimeDim());
00123 EXPECT_TRUE(pts.descriptorExists("dummy"));
00124
00125
00126 os.clear();
00127 os.str("");
00128 os <<
00129 "x, y, z, nx, ny, nz\n"
00130 "1, 2, 3, 4, 5, 6\n"
00131 "1, 2, 3, 4, 5, 6\n"
00132 "8, 2, 3, 4, 5, 6\n"
00133 "1, 2, 3, 4, 5, 6\n"
00134 ;
00135
00136 is.clear();
00137 is.str(os.str());
00138 pts = IO::loadCSV(is);
00139 EXPECT_EQ(4u, pts.getNbPoints());
00140 EXPECT_EQ(3u, pts.getEuclideanDim());
00141 EXPECT_EQ(3u, pts.getDescriptorDim());
00142 EXPECT_EQ(1u, pts.getNbGroupedDescriptors());
00143 EXPECT_EQ(0u, pts.getTimeDim());
00144 EXPECT_TRUE(pts.descriptorExists("normals"));
00145
00146
00147 int64_t time0 = 1410264593275569438;
00148 int64_t time1 = 1410264593325569391;
00149 int64_t time2 = 1410264593425569295;
00150 int64_t time3 = 1410264593522569417;
00151
00152 os.clear();
00153 os.str("");
00154 os <<
00155 "x, y, z, time\n"
00156 "1, 1, 1, " << time0 << "\n"
00157 "2, 1, 1, " << time1 << "\n"
00158 "3, 1, 1, " << time2 << "\n"
00159 "4, 1, 1, " << time3 << "\n"
00160 ;
00161
00162 is.clear();
00163 is.str(os.str());
00164
00165 pts = IO::loadCSV(is);
00166 EXPECT_EQ(4u, pts.getNbPoints());
00167 EXPECT_EQ(3u, pts.getEuclideanDim());
00168 EXPECT_EQ(0u, pts.getDescriptorDim());
00169 EXPECT_EQ(1u, pts.getTimeDim());
00170 EXPECT_EQ(time3, pts.times(0,3));
00171
00172
00173
00174
00175
00176
00177
00178
00179 }
00180
00181 TEST(IOTest, loadPLY)
00182 {
00183 typedef PointMatcherIO<float> IO;
00184 std::istringstream is;
00185
00186 is.str(
00187 ""
00188 );
00189
00190 EXPECT_THROW(IO::loadPLY(is), runtime_error);
00191
00192 is.clear();
00193 is.str(
00194 "ply\n"
00195 "format binary_big_endian 1.0\n"
00196 );
00197
00198 EXPECT_THROW(IO::loadPLY(is), runtime_error);
00199
00200 is.clear();
00201 is.str(
00202 "ply\n"
00203 "format ascii 2.0\n"
00204 );
00205
00206 EXPECT_THROW(IO::loadPLY(is), runtime_error);
00207
00208 is.clear();
00209 is.str(
00210 "ply\n"
00211 "format ascii 1.0\n"
00212 );
00213
00214 EXPECT_THROW(IO::loadPLY(is), runtime_error);
00215
00216 is.clear();
00217 is.str(
00218 "ply\n"
00219 "format ascii 1.0\n"
00220 "element vertex 5\n"
00221 "\n"
00222 "property float z\n"
00223 "property float y\n"
00224 "property float x\n"
00225 "property float grrrr\n"
00226 "property float nz\n"
00227 "property float ny\n"
00228 "property float nx\n"
00229 "end_header\n"
00230 "3 2 1 99 33 22 11\n"
00231 "3 2 1 99 33 22 11\n"
00232 "\n"
00233 "3 2 1 99 33 22 11 3 2 1 99 33 22 11\n"
00234 "3 2 1 99 33 22 11\n"
00235
00236 );
00237
00238 DP pointCloud = IO::loadPLY(is);
00239
00240
00241 EXPECT_TRUE(pointCloud.features.cols() == 5);
00242 EXPECT_TRUE(pointCloud.features.rows() == 4);
00243 EXPECT_TRUE(pointCloud.descriptors.cols() == 5);
00244 EXPECT_TRUE(pointCloud.descriptors.rows() == 4);
00245
00246
00247 EXPECT_TRUE(pointCloud.features(0, 0) == 1);
00248 EXPECT_TRUE(pointCloud.features(2, 2) == 3);
00249 EXPECT_TRUE(pointCloud.descriptors(1, 1) == 22);
00250 EXPECT_TRUE(pointCloud.descriptors(2, 4) == 33);
00251
00252 }
00253
00254
00255 TEST(IOTest, loadPCD)
00256 {
00257 typedef PointMatcherIO<float> IO;
00258 std::istringstream is;
00259
00260
00261 is.str(
00262 ""
00263 );
00264
00265 EXPECT_THROW(IO::loadPCD(is), runtime_error);
00266
00267
00268 is.clear();
00269 is.str(
00270 "# .PCD v.7 - Point Cloud Data file format\n"
00271 "VERSION .7\n"
00272 );
00273
00274 EXPECT_THROW(IO::loadPCD(is), runtime_error);
00275
00276
00277 is.clear();
00278 is.str(
00279 "# .PCD v.7 - Point Cloud Data file format\n"
00280 "VERSION .7\n"
00281 "FIELDS x y z\n"
00282 "SIZE 4 4 4\n"
00283 "TYPE F F F\n"
00284 "COUNT 1 1 1\n"
00285 "WIDTH 18\n"
00286 "HEIGHT 1\n"
00287 "VIEWPOINT 0 0 0 1 0 0 0\n"
00288 "POINTS 18\n"
00289 "DATA ascii\n"
00290 );
00291
00292 EXPECT_THROW(IO::loadPCD(is), runtime_error);
00293
00294
00295 is.clear();
00296 is.str(
00297 "# .PCD v.7 - Point Cloud Data file format\n"
00298 "VERSION .7\n"
00299 "FIELDS x y z grrr\n"
00300 "SIZE 4 4 4 4\n"
00301 "TYPE F F F F\n"
00302 "COUNT 1 1 1 1\n"
00303 "WIDTH 18\n"
00304 "HEIGHT 1\n"
00305 "VIEWPOINT 0 0 0 1 0 0 0\n"
00306 "POINTS 18\n"
00307 "DATA ascii\n"
00308 "0.44912094 0.49084857 1.153 22\n"
00309 "0.34907714 0.48914573 1.149 22\n"
00310 "0.33813429 0.48914573 1.149 22\n"
00311 "0.32833049 0.49084857 1.153 22\n"
00312 "0.24395333 0.42856666 0.98900002 22\n"
00313 "0.20816095 0.42856666 0.98900002 22\n"
00314 "0.1987419 0.42291525 0.98900002 22\n"
00315 "0.18178761 0.42291525 0.98900002 22\n"
00316 "0.17990381 0.42291525 0.98900002 22\n"
00317 "-0.035590474 0.42997143 1.01 22\n"
00318 "-0.035907622 0.43962574 1.0190001 22\n"
00319 "-0.043542858 0.43639618 1.016 22\n"
00320 "-0.15246001 0.36058003 0.84700006 22\n"
00321 "0.21956001 0.44007048 0.99800003 22\n"
00322 "-0.16635144 0.3699457 0.86900002 22\n"
00323 "-0.33879143 0.36143145 0.84900004 22\n"
00324 "-0.35055432 0.36853144 0.85800004 22\n"
00325 "-0.39932001 0.38058859 0.89400005 22\n"
00326 );
00327
00328 DP pointCloud = IO::loadPCD(is);
00329
00330
00331 EXPECT_TRUE(pointCloud.features.cols() == 18);
00332 EXPECT_TRUE(pointCloud.features.rows() == 4);
00333 EXPECT_TRUE(pointCloud.descriptors.cols() == 18);
00334 EXPECT_TRUE(pointCloud.descriptors.rows() == 1);
00335
00336
00337 EXPECT_NEAR(pointCloud.features(0, 0), 0.449121, 0.0000001);
00338 EXPECT_NEAR(pointCloud.features(2, 2), 1.149, 0.0000001);
00339 EXPECT_NEAR(pointCloud.descriptors(0, 10), 22, 0.0000001);
00340
00341 }
00342
00343 class IOLoadSaveTest : public testing::Test
00344 {
00345
00346 public:
00347 virtual void SetUp()
00348 {
00349 nbPts = 10;
00350 addRandomFeature("x", 1);
00351 addRandomFeature("y", 1);
00352 addRandomFeature("z", 1);
00353 ptCloud.addFeature("pad", PM::Matrix::Ones(1, nbPts));
00354
00355 addRandomDescriptor("normals",3);
00356 addRandomDescriptor("eigValues",3);
00357 addRandomDescriptor("eigVectors",9);
00358 addRandomDescriptor("color",4);
00359 }
00360
00361 void addRandomFeature(const string& featureName, const int rows)
00362 {
00363 ptCloud.addFeature(featureName,PM::Matrix::Random(rows, nbPts));
00364 }
00365
00366 void addRandomDescriptor(const string& descriptorName, const int rows)
00367 {
00368 ptCloud.addDescriptor(descriptorName, PM::Matrix::Random(rows, nbPts));
00369 }
00370
00371 virtual void loadSaveTest(const string& testFileName, bool plyFormat = false, const int nbPts = 10, bool binary = false)
00372 {
00373 this->testFileName = testFileName;
00374
00375 if (plyFormat || binary) {
00376
00377 int pointCount(ptCloud.features.cols());
00378 int descRows(ptCloud.descriptors.rows());
00379 bool datawithColor = ptCloud.descriptorExists("color");
00380 int colorStartingRow = ptCloud.getDescriptorStartingRow("color");
00381 int colorEndRow = colorStartingRow + ptCloud.getDescriptorDimension("color");
00382 for (int p = 0; p < pointCount; ++p)
00383 {
00384 for (int d = 0; d < descRows; ++d)
00385 {
00386 if (datawithColor && d >= colorStartingRow && d < colorEndRow) {
00387 if (ptCloud.descriptors(d, p) < 0) { ptCloud.descriptors.coeffRef(d, p) = -(ptCloud.descriptors(d, p)); }
00388 ptCloud.descriptors.coeffRef(d, p) = (static_cast<unsigned>(ptCloud.descriptors(d, p) * 255.0)) / 255.0;
00389 }
00390 }
00391 }
00392 }
00393
00394 ptCloud.save(testFileName, binary);
00395
00396 ptCloudFromFile = DP::load(testFileName);
00397
00398 EXPECT_TRUE(ptCloudFromFile.features.cols() == ptCloud.features.cols());
00399 EXPECT_TRUE(ptCloudFromFile.descriptorExists("normals",3));
00400 EXPECT_TRUE(ptCloudFromFile.getDescriptorViewByName("normals").isApprox(ptCloud.getDescriptorViewByName("normals")));
00401 EXPECT_TRUE(ptCloudFromFile.descriptorExists("eigValues",3));
00402 EXPECT_TRUE(ptCloudFromFile.getDescriptorViewByName("eigValues").isApprox(ptCloud.getDescriptorViewByName("eigValues")));
00403 EXPECT_TRUE(ptCloudFromFile.descriptorExists("eigVectors",9));
00404 EXPECT_TRUE(ptCloudFromFile.getDescriptorViewByName("eigVectors").isApprox(ptCloud.getDescriptorViewByName("eigVectors")));
00405 EXPECT_TRUE(ptCloudFromFile.descriptorExists("color",4));
00406 if (plyFormat || binary) {
00407 EXPECT_TRUE(((ptCloudFromFile.getDescriptorViewByName("color") * 255.0)).isApprox((ptCloud.getDescriptorViewByName("color") * 255.0), 1.0));
00408 } else {
00409 EXPECT_TRUE(ptCloudFromFile.getDescriptorViewByName("color").isApprox(ptCloud.getDescriptorViewByName("color")));
00410 }
00411
00412 EXPECT_TRUE(ptCloudFromFile.features.isApprox(ptCloud.features));
00413
00414 }
00415
00416 virtual void TearDown()
00417 {
00418 EXPECT_TRUE(boost::filesystem::remove(boost::filesystem::path(testFileName)));
00419 }
00420
00421
00422 protected:
00423 int nbPts;
00424 DP::Labels featureLabels;
00425 DP ptCloud;
00426 DP ptCloudFromFile;
00427 string testFileName;
00428
00429 };
00430
00431 TEST_F(IOLoadSaveTest, VTK)
00432 {
00433 ptCloud.addDescriptor("genericScalar", PM::Matrix::Random(1, nbPts));
00434 ptCloud.addDescriptor("genericVector", PM::Matrix::Random(3, nbPts));
00435 ptCloud.addTime("genericTime", PM::Int64Matrix::Random(1, nbPts));
00436
00437 loadSaveTest(dataPath + "unit_test.vtk");
00438
00439 EXPECT_TRUE(ptCloudFromFile.descriptorExists("genericScalar",1));
00440 EXPECT_TRUE(ptCloudFromFile.descriptorExists("genericVector",3));
00441 EXPECT_TRUE(ptCloudFromFile.timeExists("genericTime",1));
00442
00443 }
00444
00445 TEST_F(IOLoadSaveTest, VTKBinary)
00446 {
00447 ptCloud.addDescriptor("genericScalar", PM::Matrix::Random(1, nbPts));
00448 ptCloud.addDescriptor("genericVector", PM::Matrix::Random(3, nbPts));
00449 ptCloud.addTime("genericTime", PM::Int64Matrix::Random(1, nbPts));
00450
00451 loadSaveTest(dataPath + "unit_test.bin.vtk", false, 10, true);
00452
00453 EXPECT_TRUE(ptCloudFromFile.descriptorExists("genericScalar",1));
00454 EXPECT_TRUE(ptCloudFromFile.descriptorExists("genericVector",3));
00455 EXPECT_TRUE(ptCloudFromFile.timeExists("genericTime",1));
00456 }
00457
00458 TEST_F(IOLoadSaveTest, PLY)
00459 {
00460 loadSaveTest(dataPath + "unit_test.ply", true);
00461 }
00462
00463 TEST_F(IOLoadSaveTest, PCD)
00464 {
00465 loadSaveTest(dataPath + "unit_test.pcd");
00466 }
00467
00468 TEST_F(IOLoadSaveTest, CSV)
00469 {
00470 loadSaveTest(dataPath + "unit_test.csv");
00471 }