Go to the documentation of this file.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
00036
00037
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
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 ())
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
00135 {
00136 mesh.vertices_.reserve (n_v);
00137 HalfEdgeIndex idx_ohe;
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
00158 {
00159 mesh.half_edges_.reserve (n_he);
00160 VertexIndex idx_tv;
00161 HalfEdgeIndex idx_nhe;
00162 HalfEdgeIndex idx_phe;
00163 FaceIndex idx_f;
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
00184 {
00185 mesh.faces_.reserve (n_f);
00186 HalfEdgeIndex idx_ihe;
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
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
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
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
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
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 }
00263 }
00264
00265 #endif // PCL_GEOMETRY_MESH_IO_H