mesh_io.h
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) 2009-2012, 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$
00038  *
00039  */
00040 
00041 #ifndef PCL_GEOMETRY_MESH_IO_H
00042 #define PCL_GEOMETRY_MESH_IO_H
00043 
00044 #include <fstream>
00045 #include <string>
00046 #include <sstream>
00047 #include <iostream>
00048 
00049 namespace pcl
00050 {
00051   namespace geometry
00052   {
00062     template <class MeshT>
00063     class MeshIO
00064     {
00065       public:
00066 
00067         typedef MeshT Mesh;
00068 
00069         typedef typename Mesh::Vertex   Vertex;
00070         typedef typename Mesh::HalfEdge HalfEdge;
00071         typedef typename Mesh::Face     Face;
00072 
00073         typedef typename Mesh::Vertices  Vertices;
00074         typedef typename Mesh::HalfEdges HalfEdges;
00075         typedef typename Mesh::Faces     Faces;
00076 
00077         typedef typename Mesh::VertexIndex   VertexIndex;
00078         typedef typename Mesh::HalfEdgeIndex HalfEdgeIndex;
00079         typedef typename Mesh::FaceIndex     FaceIndex;
00080 
00082         MeshIO ()
00083         {
00084         }
00085 
00091         bool
00092         read (const std::string& filename, Mesh& mesh) const
00093         {
00094           std::ifstream file (filename.c_str ());
00095 
00096           if (!file.is_open ())
00097           {
00098             std::cerr << "Error in MeshIO::read: Could not open the file '" << filename << "'\n";
00099             return (false);
00100           }
00101 
00102           // Read the header
00103           std::string line;
00104           unsigned int line_number = 1;
00105           int n_v = -1, n_he = -1, n_f = -1;
00106 
00107           if (!std::getline (file, line) || line.compare ("PCL half-edge mesh") != 0)
00108           {
00109             std::cerr << "Error loading '" << filename << "' (line " << line_number << "): Wrong file format.\n";
00110             return (false);
00111           }
00112           ++line_number;
00113 
00114           if (!std::getline (file, line))
00115           {
00116             std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Number of vertices / half-edges / faces not found.\n";
00117             return (false);
00118           }
00119           {
00120             std::istringstream iss (line);
00121             if (!(iss >> n_v >> n_he >> n_f) || iss.good ()) // Don't allow more than 3 en
00122             {
00123               std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Could not read the number of vertices / half-edges / faces.\n";
00124               return (false);
00125             }
00126           }
00127           if (n_v < 0 || n_he < 0 || n_f < 0)
00128           {
00129             std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Invalid number of vertices / half-edges / faces.\n";
00130             return (false);
00131           }
00132           ++line_number;
00133 
00134           // Read the vertices.
00135           {
00136             mesh.vertices_.reserve (n_v);
00137             HalfEdgeIndex idx_ohe; // Outgoing half-edge;
00138 
00139             for (int i=0; i<n_v; ++i, ++line_number)
00140             {
00141               if (!std::getline (file, line))
00142               {
00143                 std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Could not read the line.\n";
00144                 return (false);
00145               }
00146 
00147               std::istringstream iss (line);
00148               if (!(iss >> idx_ohe) || iss.good ())
00149               {
00150                 std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Could not read the vertex.\n";
00151                 return (false);
00152               }
00153               mesh.vertices_.push_back (Vertex (idx_ohe));
00154             }
00155           }
00156 
00157           // Read the half-edges.
00158           {
00159             mesh.half_edges_.reserve (n_he);
00160             VertexIndex   idx_tv;  // Terminating vertex.
00161             HalfEdgeIndex idx_nhe; // Next half-edge;
00162             HalfEdgeIndex idx_phe; // Previous half-edge.
00163             FaceIndex     idx_f;   // Face.
00164 
00165             for (int i=0; i<n_he; ++i, ++line_number)
00166             {
00167               if (!std::getline (file, line))
00168               {
00169                 std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Could not read the line.\n";
00170                 return (false);
00171               }
00172 
00173               std::istringstream iss (line);
00174               if (!(iss >> idx_tv >> idx_nhe >> idx_phe >> idx_f) || iss.good ())
00175               {
00176                 std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Could not read the half-edge.\n";
00177                 return (false);
00178               }
00179               mesh.half_edges_.push_back (HalfEdge (idx_tv, idx_nhe, idx_phe, idx_f));
00180             }
00181           }
00182 
00183           // Read the faces.
00184           {
00185             mesh.faces_.reserve (n_f);
00186             HalfEdgeIndex idx_ihe; // Inner half-edge.
00187 
00188             for (int i=0; i<n_f; ++i, ++line_number)
00189             {
00190               if (!std::getline (file, line))
00191               {
00192                 std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Could not read the line.\n";
00193                 return (false);
00194               }
00195 
00196               std::istringstream iss (line);
00197               if (!(iss >> idx_ihe) || iss.good ())
00198               {
00199                 std::cerr << "Error loading '" << filename << "'' (line " << line_number << "): Could not read the face.\n";
00200                 return (false);
00201               }
00202               mesh.faces_.push_back (Face (idx_ihe));
00203             }
00204           }
00205 
00206           // Set the data
00207           if (Mesh::HasVertexData::value)   mesh.vertex_data_cloud_.   resize (n_v);
00208           if (Mesh::HasHalfEdgeData::value) mesh.half_edge_data_cloud_.resize (n_he);
00209           if (Mesh::HasEdgeData::value)     mesh.edge_data_cloud_.     resize (n_he / 2);
00210           if (Mesh::HasFaceData::value)     mesh.face_data_cloud_.     resize (n_f);
00211 
00212           return (true);
00213         }
00214 
00220         bool
00221         write (const std::string& filename, const Mesh& mesh) const
00222         {
00223           std::ofstream file (filename.c_str ());
00224 
00225           // Write the header
00226           if (!file.is_open ())
00227           {
00228             std::cerr << "Error in MeshIO::write: Could not open the file '" << filename << "'\n";
00229             return (false);
00230           }
00231 
00232           file << "PCL half-edge mesh\n";
00233           file << mesh.sizeVertices ()  << " "
00234                << mesh.sizeHalfEdges () << " "
00235                << mesh.sizeFaces ()     << "\n";
00236 
00237           // Write the vertices
00238           for (typename Vertices::const_iterator it=mesh.vertices_.begin (); it!=mesh.vertices_.end (); ++it)
00239           {
00240             file << it->idx_outgoing_half_edge_ << "\n";
00241           }
00242 
00243           // Write the half-edges
00244           for (typename HalfEdges::const_iterator it=mesh.half_edges_.begin (); it!=mesh.half_edges_.end (); ++it)
00245           {
00246             file << it->idx_terminating_vertex_ << " "
00247                  << it->idx_next_half_edge_     << " "
00248                  << it->idx_prev_half_edge_     << " "
00249                  << it->idx_face_               << "\n";
00250           }
00251 
00252           // Write the faces
00253           for (typename Faces::const_iterator it=mesh.faces_.begin (); it!=mesh.faces_.end (); ++it)
00254           {
00255             file << it->idx_inner_half_edge_ << "\n";
00256           }
00257 
00258           return (true);
00259         }
00260     };
00261 
00262   } // End namespace geometry
00263 } // End namespace pcl
00264 
00265 #endif // PCL_GEOMETRY_MESH_IO_H


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:25:32