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, loadPLY)
00031 {
00032         typedef PointMatcherIO<float> IO;
00033         std::istringstream is;
00034         
00035         is.str(
00036         ""
00037         );
00038 
00039         EXPECT_THROW(IO::loadPLY(is), runtime_error);
00040 
00041         is.clear();
00042         is.str(
00043         "ply\n"
00044         "format binary_big_endian 1.0\n"
00045         );
00046 
00047         EXPECT_THROW(IO::loadPLY(is), runtime_error);
00048         
00049         is.clear();
00050         is.str(
00051         "ply\n"
00052         "format ascii 2.0\n"
00053         );
00054         
00055         EXPECT_THROW(IO::loadPLY(is), runtime_error);
00056 
00057         is.clear();
00058         is.str(
00059         "ply\n"
00060         "format ascii 1.0\n"
00061         );
00062         
00063         EXPECT_THROW(IO::loadPLY(is), runtime_error);
00064 
00065         is.clear();
00066         is.str(
00067         "ply\n"
00068         "format ascii 1.0\n"
00069         "element vertex 5\n"
00070         "\n" 
00071         "property float z\n" 
00072         "property float y\n"
00073         "property float x\n"
00074         "property float grrrr\n" 
00075         "property float nz\n" 
00076         "property float ny\n"
00077         "property float nx\n"
00078         "end_header\n"
00079         "3 2 1 99 33 22 11\n"
00080         "3 2 1 99 33 22 11\n"
00081         "\n" 
00082         "3 2 1 99 33 22 11 3 2 1 99 33 22 11\n" 
00083         "3 2 1 99 33 22 11\n"
00084 
00085         );
00086         
00087         DP pointCloud = IO::loadPLY(is);
00088         
00089         
00090         EXPECT_TRUE(pointCloud.features.cols() == 5);
00091         EXPECT_TRUE(pointCloud.features.rows() == 4);
00092         EXPECT_TRUE(pointCloud.descriptors.cols() == 5);
00093         EXPECT_TRUE(pointCloud.descriptors.rows() == 3);
00094         
00095         
00096         EXPECT_TRUE(pointCloud.features(0, 0) == 1);
00097         EXPECT_TRUE(pointCloud.features(2, 2) == 3);
00098         EXPECT_TRUE(pointCloud.descriptors(1, 1) == 22);
00099         EXPECT_TRUE(pointCloud.descriptors(2, 4) == 33);
00100 
00101 }
00102 
00103 class IOLoadSaveTest : public testing::Test
00104 {
00105 
00106 public:
00107         virtual void SetUp()
00108         {
00109                 nbPts = 10;
00110                 addRandomFeature("x", 1);
00111                 addRandomFeature("y", 1);
00112                 addRandomFeature("z", 1);
00113                 ptCloud.addFeature("pad", PM::Matrix::Ones(1, nbPts));
00114 
00115                 addRandomDescriptor("normals",3);
00116                 addRandomDescriptor("eigValues",3);
00117                 addRandomDescriptor("eigVectors",9);
00118                 addRandomDescriptor("color",4);
00119         }
00120 
00121         void addRandomFeature(const string& featureName, const int rows)
00122         {
00123                 ptCloud.addFeature(featureName,PM::Matrix::Random(rows, nbPts));
00124         }
00125 
00126         void addRandomDescriptor(const string& descriptorName, const int rows)
00127         {
00128                 ptCloud.addDescriptor(descriptorName, PM::Matrix::Random(rows, nbPts));
00129         }
00130 
00131         virtual void loadSaveTest(const string& testFileName, bool plyFormat = false, const int nbPts = 10)
00132         {
00133                 this->testFileName = testFileName;
00134 
00135                 if (plyFormat) {
00136                         
00137                         int pointCount(ptCloud.features.cols());
00138                         int descRows(ptCloud.descriptors.rows());
00139                         bool datawithColor = ptCloud.descriptorExists("color");
00140                         int colorStartingRow = ptCloud.getDescriptorStartingRow("color");
00141                         int colorEndRow = colorStartingRow + ptCloud.getDescriptorDimension("color");
00142                         for (int p = 0; p < pointCount; ++p)
00143                         {
00144                                 for (int d = 0; d < descRows; ++d)
00145                                 {
00146                                         if (datawithColor && d >= colorStartingRow && d < colorEndRow) {
00147                                                 if (ptCloud.descriptors(d, p) < 0) { ptCloud.descriptors.coeffRef(d, p) = -(ptCloud.descriptors(d, p)); }
00148                                                 ptCloud.descriptors.coeffRef(d, p) = (static_cast<unsigned>(ptCloud.descriptors(d, p) * 255.0)) / 255.0;
00149                                         }
00150                                 }
00151                         }
00152                 }
00153 
00154                 ptCloud.save(testFileName);
00155 
00156                 ptCloudFromFile = DP::load(testFileName);
00157 
00158                 EXPECT_TRUE(ptCloudFromFile.features.cols() == ptCloud.features.cols());
00159                 EXPECT_TRUE(ptCloudFromFile.descriptorExists("normals",3));
00160                 EXPECT_TRUE(ptCloudFromFile.getDescriptorViewByName("normals").isApprox(ptCloud.getDescriptorViewByName("normals")));
00161                 EXPECT_TRUE(ptCloudFromFile.descriptorExists("eigValues",3));
00162                 EXPECT_TRUE(ptCloudFromFile.getDescriptorViewByName("eigValues").isApprox(ptCloud.getDescriptorViewByName("eigValues")));
00163                 EXPECT_TRUE(ptCloudFromFile.descriptorExists("eigVectors",9));
00164                 EXPECT_TRUE(ptCloudFromFile.getDescriptorViewByName("eigVectors").isApprox(ptCloud.getDescriptorViewByName("eigVectors")));
00165                 EXPECT_TRUE(ptCloudFromFile.descriptorExists("color",4));
00166                 if (plyFormat) {
00167                         EXPECT_TRUE(((ptCloudFromFile.getDescriptorViewByName("color") * 255.0)).isApprox((ptCloud.getDescriptorViewByName("color") * 255.0), 1.0));
00168                 } else {
00169                         EXPECT_TRUE(ptCloudFromFile.getDescriptorViewByName("color").isApprox(ptCloud.getDescriptorViewByName("color")));
00170                 }
00171 
00172                 EXPECT_TRUE(ptCloudFromFile.features.isApprox(ptCloud.features));
00173 
00174         }
00175 
00176         virtual void TearDown()
00177         {
00178                 EXPECT_TRUE(boost::filesystem::remove(boost::filesystem::path(testFileName)));
00179         }
00180 
00181 
00182 protected:
00183         int nbPts;
00184         DP::Labels featureLabels;
00185         DP ptCloud;
00186         DP ptCloudFromFile;
00187         string testFileName;
00188 
00189 };
00190 
00191 TEST_F(IOLoadSaveTest, VTK)
00192 {
00193         ptCloud.addDescriptor("genericScalar", PM::Matrix::Random(1, nbPts));
00194         ptCloud.addDescriptor("genericVector", PM::Matrix::Random(3, nbPts));
00195 
00196         loadSaveTest(dataPath + "unit_test.vtk");
00197 
00198         EXPECT_TRUE(ptCloudFromFile.descriptorExists("genericScalar",1));
00199         EXPECT_TRUE(ptCloudFromFile.descriptorExists("genericVector",3));
00200 
00201 }
00202 
00203 TEST_F(IOLoadSaveTest, PLY)
00204 {
00205         loadSaveTest(dataPath + "unit_test.ply", true);
00206 }
00207 
00208 TEST_F(IOLoadSaveTest, PCD)
00209 {
00210         loadSaveTest(dataPath + "unit_test.pcd");
00211 }
00212 
00213 TEST_F(IOLoadSaveTest, CSV)
00214 {
00215         loadSaveTest(dataPath + "unit_test.csv");
00216 }