test_ply_mesh_io.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2011, Willow Garage, Inc.
00006  *  Copyright (c) 2012-, Open Perception, Inc.
00007  *
00008  *  All rights reserved.
00009  *
00010  *  Redistribution and use in source and binary forms, with or without
00011  *  modification, are permitted provided that the following conditions
00012  *  are met:
00013  *
00014  *   * Redistributions of source code must retain the above copyright
00015  *     notice, this list of conditions and the following disclaimer.
00016  *   * Redistributions in binary form must reproduce the above
00017  *     copyright notice, this list of conditions and the following
00018  *     disclaimer in the documentation and/or other materials provided
00019  *     with the distribution.
00020  *   * Neither the name of the copyright holder(s) nor the names of its
00021  *     contributors may be used to endorse or promote products derived
00022  *     from this software without specific prior written permission.
00023  *
00024  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00025  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00026  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00027  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00028  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00029  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00030  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00031  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00032  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00033  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00034  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00035  *  POSSIBILITY OF SUCH DAMAGE.
00036  *
00037  * $Id: test_mesh_io.cpp 8543 2013-01-17 23:31:01Z sdmiller $
00038  *
00039  */
00040 
00041 #include <gtest/gtest.h>
00042 #include <pcl/PCLPointCloud2.h>
00043 #include <pcl/point_traits.h>
00044 #include <pcl/point_types.h>
00045 #include <pcl/common/io.h>
00046 #include <pcl/console/print.h>
00047 #include <pcl/io/ply_io.h>
00048 #include <pcl/io/ascii_io.h>
00049 #include <pcl/io/vtk_lib_io.h>
00050 #include <fstream>
00051 #include <locale>
00052 #include <stdexcept>
00053 
00054 std::string mesh_file_vtk_;
00055 
00056 
00057 TEST (PCL, PLYPolygonMeshIO)
00058 {
00059   pcl::PolygonMesh mesh;
00060   pcl::io::loadPolygonFileVTK (mesh_file_vtk_, mesh);
00061   // Save ascii
00062   pcl::io::savePLYFile ("test_mesh_ascii.ply", mesh);
00063   // Save binary
00064   pcl::io::savePLYFileBinary ("test_mesh_binary.ply", mesh);
00065   // Load both
00066   pcl::PolygonMesh mesh_ascii;
00067   pcl::io::loadPolygonFilePLY ("test_mesh_ascii.ply", mesh_ascii);
00068   pcl::PolygonMesh mesh_binary;
00069   pcl::io::loadPolygonFilePLY ("test_mesh_binary.ply", mesh_binary);
00070   // Compare the 3
00071   pcl::PointCloud<pcl::PointXYZ> verts, verts_ascii, verts_binary;
00072   pcl::fromPCLPointCloud2 (mesh.cloud, verts);
00073   pcl::fromPCLPointCloud2 (mesh_ascii.cloud, verts_ascii);
00074   pcl::fromPCLPointCloud2 (mesh_binary.cloud, verts_binary);
00075   EXPECT_EQ (verts_ascii.size (), verts.size ());
00076   EXPECT_EQ (verts_binary.size (), verts.size ());
00077   for (size_t i = 0; i < verts.size (); i++)
00078   {
00079     EXPECT_NEAR (verts_ascii.at (i).x, verts.at (i).x, 1E-2);
00080     EXPECT_NEAR (verts_ascii.at (i).y, verts.at (i).y, 1E-2);
00081     EXPECT_NEAR (verts_ascii.at (i).z, verts.at (i).z, 1E-2);
00082     EXPECT_NEAR (verts_binary.at (i).x, verts.at (i).x, 1E-4);
00083     EXPECT_NEAR (verts_binary.at (i).y, verts.at (i).y, 1E-4);
00084     EXPECT_NEAR (verts_binary.at (i).z, verts.at (i).z, 1E-4);
00085   }
00086   ASSERT_EQ (mesh_ascii.polygons.size (), mesh.polygons.size ());
00087   ASSERT_EQ (mesh_binary.polygons.size (), mesh.polygons.size ());
00088   for (size_t i = 0; i < mesh.polygons.size (); i++)
00089   {
00090     ASSERT_EQ (mesh_ascii.polygons[i].vertices.size (), mesh.polygons[i].vertices.size ());
00091     ASSERT_EQ (mesh_binary.polygons[i].vertices.size (), mesh.polygons[i].vertices.size ());
00092     for (size_t j = 0; j < mesh.polygons[i].vertices.size (); j++)
00093     {
00094       EXPECT_EQ (mesh_ascii.polygons[i].vertices[j], mesh.polygons[i].vertices[j]);
00095       EXPECT_EQ (mesh_binary.polygons[i].vertices[j], mesh.polygons[i].vertices[j]);
00096     }
00097   }
00098 }
00099 
00100 TEST (PCL, PLYPolygonMeshColoredIO)
00101 {
00102   pcl::PolygonMesh mesh;
00103   pcl::io::loadPolygonFileVTK (mesh_file_vtk_, mesh);
00104   // Artificially color
00105   pcl::PolygonMesh mesh_rgb;
00106   pcl::PolygonMesh mesh_rgba;
00107   pcl::PointCloud<pcl::PointXYZRGB> vertices_rgb;
00108   pcl::PointCloud<pcl::PointXYZRGBA> vertices_rgba;
00109   pcl::fromPCLPointCloud2 (mesh.cloud, vertices_rgb);
00110   pcl::fromPCLPointCloud2 (mesh.cloud, vertices_rgba);
00111   mesh_rgb.polygons = mesh.polygons;
00112   mesh_rgba.polygons = mesh.polygons;
00113   for (size_t i = 0; i < vertices_rgb.size (); ++i)
00114   {
00115     pcl::PointXYZRGB &pt_rgb = vertices_rgb.at (i);
00116     pcl::PointXYZRGBA &pt_rgba = vertices_rgba.at (i);
00117     pt_rgb.r = pt_rgba.r = static_cast<uint8_t> (rand () % 256);
00118     pt_rgb.g = pt_rgba.g = static_cast<uint8_t> (rand () % 256);
00119     pt_rgb.b = pt_rgba.b = static_cast<uint8_t> (rand () % 256);
00120     pt_rgba.a = static_cast<uint8_t> (rand () % 256);
00121   }
00122   pcl::toPCLPointCloud2 (vertices_rgb, mesh_rgb.cloud);
00123   pcl::toPCLPointCloud2 (vertices_rgba, mesh_rgba.cloud);
00124   // Save ascii
00125   pcl::io::savePLYFile ("test_mesh_rgb_ascii.ply", mesh_rgb);
00126   pcl::io::savePLYFile ("test_mesh_rgba_ascii.ply", mesh_rgba);
00127   // Save binary
00128   pcl::io::savePLYFileBinary ("test_mesh_rgb_binary.ply", mesh_rgb);
00129   pcl::io::savePLYFileBinary ("test_mesh_rgba_binary.ply", mesh_rgba);
00130   // Load both
00131   pcl::PolygonMesh mesh_rgb_ascii;
00132   pcl::PolygonMesh mesh_rgba_ascii;
00133   pcl::io::loadPolygonFilePLY ("test_mesh_rgb_ascii.ply", mesh_rgb_ascii);
00134   pcl::io::loadPolygonFilePLY ("test_mesh_rgba_ascii.ply", mesh_rgba_ascii);
00135   pcl::PolygonMesh mesh_rgb_binary;
00136   pcl::PolygonMesh mesh_rgba_binary;
00137   pcl::io::loadPolygonFilePLY ("test_mesh_rgb_binary.ply", mesh_rgb_binary);
00138   pcl::io::loadPolygonFilePLY ("test_mesh_rgba_binary.ply", mesh_rgba_binary);
00139   // Compare the 5
00140   pcl::PointCloud<pcl::PointXYZRGBA> verts_rgba_ascii, verts_rgba_binary;
00141   pcl::PointCloud<pcl::PointXYZRGB> verts_rgb_ascii, verts_rgb_binary;
00142   pcl::fromPCLPointCloud2 (mesh_rgb_ascii.cloud,  verts_rgb_ascii);
00143   pcl::fromPCLPointCloud2 (mesh_rgba_ascii.cloud,  verts_rgba_ascii);
00144   pcl::fromPCLPointCloud2 (mesh_rgb_binary.cloud, verts_rgb_binary);
00145   pcl::fromPCLPointCloud2 (mesh_rgba_binary.cloud, verts_rgba_binary);
00146   ASSERT_EQ (verts_rgb_ascii.size (), vertices_rgba.size ());
00147   ASSERT_EQ (verts_rgba_ascii.size (), vertices_rgba.size ());
00148   ASSERT_EQ (verts_rgb_binary.size (), vertices_rgba.size ());
00149   ASSERT_EQ (verts_rgba_binary.size (), vertices_rgba.size ());
00150   for (size_t i = 0; i < vertices_rgba.size (); i++)
00151   {
00152     EXPECT_NEAR (verts_rgba_ascii.at (i).x, vertices_rgba.at (i).x, 1E-2);
00153     EXPECT_NEAR (verts_rgba_ascii.at (i).y, vertices_rgba.at (i).y, 1E-2);
00154     EXPECT_NEAR (verts_rgba_ascii.at (i).z, vertices_rgba.at (i).z, 1E-2);
00155     EXPECT_EQ   (verts_rgba_ascii.at (i).r, vertices_rgba.at (i).r);
00156     EXPECT_EQ   (verts_rgba_ascii.at (i).g, vertices_rgba.at (i).g);
00157     EXPECT_EQ   (verts_rgba_ascii.at (i).b, vertices_rgba.at (i).b);
00158     EXPECT_NEAR (verts_rgba_binary.at (i).x, vertices_rgba.at (i).x, 1E-4);
00159     EXPECT_NEAR (verts_rgba_binary.at (i).y, vertices_rgba.at (i).y, 1E-4);
00160     EXPECT_NEAR (verts_rgba_binary.at (i).z, vertices_rgba.at (i).z, 1E-4);
00161     EXPECT_EQ   (verts_rgba_binary.at (i).r, vertices_rgba.at (i).r);
00162     EXPECT_EQ   (verts_rgba_binary.at (i).g, vertices_rgba.at (i).g);
00163     EXPECT_EQ   (verts_rgba_binary.at (i).b, vertices_rgba.at (i).b);
00164     EXPECT_NEAR (verts_rgb_ascii.at (i).x, vertices_rgba.at (i).x, 1E-2);
00165     EXPECT_NEAR (verts_rgb_ascii.at (i).y, vertices_rgba.at (i).y, 1E-2);
00166     EXPECT_NEAR (verts_rgb_ascii.at (i).z, vertices_rgba.at (i).z, 1E-2);
00167     EXPECT_EQ   (verts_rgb_ascii.at (i).r, vertices_rgba.at (i).r);
00168     EXPECT_EQ   (verts_rgb_ascii.at (i).g, vertices_rgba.at (i).g);
00169     EXPECT_EQ   (verts_rgb_ascii.at (i).b, vertices_rgba.at (i).b);
00170     EXPECT_NEAR (verts_rgb_binary.at (i).x, vertices_rgba.at (i).x, 1E-4);
00171     EXPECT_NEAR (verts_rgb_binary.at (i).y, vertices_rgba.at (i).y, 1E-4);
00172     EXPECT_NEAR (verts_rgb_binary.at (i).z, vertices_rgba.at (i).z, 1E-4);
00173     EXPECT_EQ   (verts_rgb_binary.at (i).r, vertices_rgba.at (i).r);
00174     EXPECT_EQ   (verts_rgb_binary.at (i).g, vertices_rgba.at (i).g);
00175     EXPECT_EQ   (verts_rgb_binary.at (i).b, vertices_rgba.at (i).b);
00176   }
00177   ASSERT_EQ (mesh_rgb_ascii.polygons.size (), mesh.polygons.size ());
00178   ASSERT_EQ (mesh_rgba_ascii.polygons.size (), mesh.polygons.size ());
00179   ASSERT_EQ (mesh_rgb_binary.polygons.size (), mesh.polygons.size ());
00180   ASSERT_EQ (mesh_rgba_binary.polygons.size (), mesh.polygons.size ());
00181   for (size_t i = 0; i < mesh.polygons.size (); i++)
00182   {
00183     ASSERT_EQ (mesh_rgb_ascii.polygons[i].vertices.size (), mesh.polygons[i].vertices.size ());
00184     ASSERT_EQ (mesh_rgba_ascii.polygons[i].vertices.size (), mesh.polygons[i].vertices.size ());
00185     ASSERT_EQ (mesh_rgb_binary.polygons[i].vertices.size (), mesh.polygons[i].vertices.size ());
00186     ASSERT_EQ (mesh_rgba_binary.polygons[i].vertices.size (), mesh.polygons[i].vertices.size ());
00187     for (size_t j = 0; j < mesh.polygons[i].vertices.size (); j++)
00188     {
00189       EXPECT_EQ (mesh_rgb_ascii.polygons[i].vertices[j], mesh.polygons[i].vertices[j]);
00190       EXPECT_EQ (mesh_rgba_ascii.polygons[i].vertices[j], mesh.polygons[i].vertices[j]);
00191       EXPECT_EQ (mesh_rgb_binary.polygons[i].vertices[j], mesh.polygons[i].vertices[j]);
00192       EXPECT_EQ (mesh_rgba_binary.polygons[i].vertices[j], mesh.polygons[i].vertices[j]);
00193     }
00194   }
00195 }
00196 
00197 /* ---[ */
00198 int
00199   main (int argc, char** argv)
00200 {
00201   testing::InitGoogleTest (&argc, argv);
00202   if (argc < 2)
00203   {
00204     std::cerr << "No test files were given. Please add the path to TUM_Rabbit.vtk to this test." << std::endl;
00205     return (-1);
00206   }
00207   mesh_file_vtk_ = argv[1]; //TODO
00208   return (RUN_ALL_TESTS ());
00209 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:35:30