obj_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, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id$
00037  *
00038  */
00039 #include <pcl/io/obj_io.h>
00040 #include <fstream>
00041 #include <iostream>
00042 #include <pcl/common/io.h>
00043 
00044 int
00045 pcl::io::saveOBJFile (const std::string &file_name,
00046                       const pcl::TextureMesh &tex_mesh, unsigned precision)
00047 {
00048   if (tex_mesh.cloud.data.empty ())
00049   {
00050     PCL_ERROR ("[pcl::io::saveOBJFile] Input point cloud has no data!\n");
00051     return (-1);
00052   }
00053   // Open file
00054   std::ofstream fs;
00055   fs.precision (precision);
00056   fs.open (file_name.c_str ());
00057 
00058   // Define material file
00059   std::string mtl_file_name = file_name.substr (0, file_name.find_last_of (".")) + ".mtl";
00060   // Strip path for "mtllib" command
00061   std::string mtl_file_name_nopath = mtl_file_name;
00062   mtl_file_name_nopath.erase (0, mtl_file_name.find_last_of ('/') + 1);
00063 
00064   /* Write 3D information */
00065   // number of points
00066   unsigned nr_points  = tex_mesh.cloud.width * tex_mesh.cloud.height;
00067   unsigned point_size = static_cast<unsigned> (tex_mesh.cloud.data.size () / nr_points);
00068 
00069   // mesh size
00070   unsigned nr_meshes = static_cast<unsigned> (tex_mesh.tex_polygons.size ());
00071   // number of faces for header
00072   unsigned nr_faces = 0;
00073   for (unsigned m = 0; m < nr_meshes; ++m)
00074     nr_faces += static_cast<unsigned> (tex_mesh.tex_polygons[m].size ());
00075 
00076   // Write the header information
00077   fs << "####" << std::endl;
00078   fs << "# OBJ dataFile simple version. File name: " << file_name << std::endl;
00079   fs << "# Vertices: " << nr_points << std::endl;
00080   fs << "# Faces: " <<nr_faces << std::endl;
00081   fs << "# Material information:" << std::endl;
00082   fs << "mtllib " << mtl_file_name_nopath << std::endl;
00083   fs << "####" << std::endl;
00084 
00085   // Write vertex coordinates
00086   fs << "# Vertices" << std::endl;
00087   for (unsigned i = 0; i < nr_points; ++i)
00088   {
00089     int xyz = 0;
00090     // "v" just be written one
00091     bool v_written = false;
00092     for (size_t d = 0; d < tex_mesh.cloud.fields.size (); ++d)
00093     {
00094       int count = tex_mesh.cloud.fields[d].count;
00095       if (count == 0)
00096         count = 1;          // we simply cannot tolerate 0 counts (coming from older converter code)
00097       int c = 0;
00098       // adding vertex
00099       if ((tex_mesh.cloud.fields[d].datatype == pcl::PCLPointField::FLOAT32) && (
00100           tex_mesh.cloud.fields[d].name == "x" ||
00101           tex_mesh.cloud.fields[d].name == "y" ||
00102           tex_mesh.cloud.fields[d].name == "z"))
00103       {
00104         if (!v_written)
00105         {
00106            // write vertices beginning with v
00107           fs << "v ";
00108           v_written = true;
00109         }
00110         float value;
00111         memcpy (&value, &tex_mesh.cloud.data[i * point_size + tex_mesh.cloud.fields[d].offset + c * sizeof (float)], sizeof (float));
00112         fs << value;
00113         if (++xyz == 3)
00114           break;
00115         fs << " ";
00116       }
00117     }
00118     if (xyz != 3)
00119     {
00120       PCL_ERROR ("[pcl::io::saveOBJFile] Input point cloud has no XYZ data!\n");
00121       return (-2);
00122     }
00123     fs << std::endl;
00124   }
00125   fs << "# "<< nr_points <<" vertices" << std::endl;
00126 
00127   // Write vertex normals
00128   for (unsigned i = 0; i < nr_points; ++i)
00129   {
00130     int xyz = 0;
00131     // "vn" just be written one
00132     bool v_written = false;
00133     for (size_t d = 0; d < tex_mesh.cloud.fields.size (); ++d)
00134     {
00135       int count = tex_mesh.cloud.fields[d].count;
00136       if (count == 0)
00137         count = 1;          // we simply cannot tolerate 0 counts (coming from older converter code)
00138       int c = 0;
00139       // adding vertex
00140       if ((tex_mesh.cloud.fields[d].datatype == pcl::PCLPointField::FLOAT32) && (
00141           tex_mesh.cloud.fields[d].name == "normal_x" ||
00142           tex_mesh.cloud.fields[d].name == "normal_y" ||
00143           tex_mesh.cloud.fields[d].name == "normal_z"))
00144       {
00145           if (!v_written)
00146           {
00147           // write vertices beginning with vn
00148           fs << "vn ";
00149           v_written = true;
00150           }
00151         float value;
00152         memcpy (&value, &tex_mesh.cloud.data[i * point_size + tex_mesh.cloud.fields[d].offset + c * sizeof (float)], sizeof (float));
00153         fs << value;
00154         if (++xyz == 3)
00155           break;
00156         fs << " ";
00157       }
00158     }
00159     if (xyz != 3)
00160     {
00161       PCL_ERROR ("[pcl::io::saveOBJFile] Input point cloud has no normals!\n");
00162       return (-2);
00163     }
00164     fs << std::endl;
00165   }
00166   // Write vertex texture with "vt" (adding latter)
00167 
00168   for (unsigned m = 0; m < nr_meshes; ++m)
00169   {
00170     fs << "# " << tex_mesh.tex_coordinates[m].size() << " vertex textures in submesh " << m <<  std::endl;
00171     for (size_t i = 0; i < tex_mesh.tex_coordinates[m].size (); ++i)
00172     {
00173       fs << "vt ";
00174       fs <<  tex_mesh.tex_coordinates[m][i][0] << " " << tex_mesh.tex_coordinates[m][i][1] << std::endl;
00175     }
00176   }
00177 
00178   unsigned f_idx = 0;
00179 
00180   // int idx_vt =0;
00181   for (unsigned m = 0; m < nr_meshes; ++m)
00182   {
00183     if (m > 0) f_idx += static_cast<unsigned> (tex_mesh.tex_polygons[m-1].size ());
00184 
00185     fs << "# The material will be used for mesh " << m << std::endl;
00186     fs << "usemtl " <<  tex_mesh.tex_materials[m].tex_name << std::endl;
00187     fs << "# Faces" << std::endl;
00188 
00189     for (size_t i = 0; i < tex_mesh.tex_polygons[m].size(); ++i)
00190     {
00191       // Write faces with "f"
00192       fs << "f";
00193       size_t j = 0;
00194       // There's one UV per vertex per face, i.e., the same vertex can have
00195       // different UV depending on the face.
00196       for (j = 0; j < tex_mesh.tex_polygons[m][i].vertices.size (); ++j) 
00197       {
00198         uint32_t idx = tex_mesh.tex_polygons[m][i].vertices[j] + 1;
00199         fs << " " << idx
00200            << "/" << tex_mesh.tex_polygons[m][i].vertices.size () * (i+f_idx) +j+1
00201            << "/" << idx; // vertex index in obj file format starting with 1
00202       }
00203       fs << std::endl;
00204     }
00205     fs << "# "<< tex_mesh.tex_polygons[m].size() << " faces in mesh " << m << std::endl;
00206   }
00207   fs << "# End of File";
00208 
00209   // Close obj file
00210   fs.close ();
00211 
00212   /* Write material defination for OBJ file*/
00213   // Open file
00214 
00215   std::ofstream m_fs;
00216   m_fs.precision (precision);
00217   m_fs.open (mtl_file_name.c_str ());
00218 
00219   // default
00220   m_fs << "#" << std::endl;
00221   m_fs << "# Wavefront material file" << std::endl;
00222   m_fs << "#" << std::endl;
00223   for(unsigned m = 0; m < nr_meshes; ++m)
00224   {
00225     m_fs << "newmtl " << tex_mesh.tex_materials[m].tex_name << std::endl;
00226     m_fs << "Ka "<< tex_mesh.tex_materials[m].tex_Ka.r << " " << tex_mesh.tex_materials[m].tex_Ka.g << " " << tex_mesh.tex_materials[m].tex_Ka.b << std::endl; // defines the ambient color of the material to be (r,g,b).
00227     m_fs << "Kd "<< tex_mesh.tex_materials[m].tex_Kd.r << " " << tex_mesh.tex_materials[m].tex_Kd.g << " " << tex_mesh.tex_materials[m].tex_Kd.b << std::endl; // defines the diffuse color of the material to be (r,g,b).
00228     m_fs << "Ks "<< tex_mesh.tex_materials[m].tex_Ks.r << " " << tex_mesh.tex_materials[m].tex_Ks.g << " " << tex_mesh.tex_materials[m].tex_Ks.b << std::endl; // defines the specular color of the material to be (r,g,b). This color shows up in highlights.
00229     m_fs << "d " << tex_mesh.tex_materials[m].tex_d << std::endl; // defines the transparency of the material to be alpha.
00230     m_fs << "Ns "<< tex_mesh.tex_materials[m].tex_Ns  << std::endl; // defines the shininess of the material to be s.
00231     m_fs << "illum "<< tex_mesh.tex_materials[m].tex_illum << std::endl; // denotes the illumination model used by the material.
00232                                             // illum = 1 indicates a flat material with no specular highlights, so the value of Ks is not used.
00233                                             // illum = 2 denotes the presence of specular highlights, and so a specification for Ks is required.
00234     m_fs << "map_Kd " << tex_mesh.tex_materials[m].tex_file << std::endl;
00235     m_fs << "###" << std::endl;
00236   }
00237   m_fs.close ();
00238   return (0);
00239 }
00240 
00241 int
00242 pcl::io::saveOBJFile (const std::string &file_name,
00243                       const pcl::PolygonMesh &mesh, unsigned precision)
00244 {
00245   if (mesh.cloud.data.empty ())
00246   {
00247     PCL_ERROR ("[pcl::io::saveOBJFile] Input point cloud has no data!\n");
00248     return (-1);
00249   }
00250   // Open file
00251   std::ofstream fs;
00252   fs.precision (precision);
00253   fs.open (file_name.c_str ());
00254 
00255   /* Write 3D information */
00256   // number of points
00257   int nr_points  = mesh.cloud.width * mesh.cloud.height;
00258   // point size
00259   unsigned point_size = static_cast<unsigned> (mesh.cloud.data.size () / nr_points);
00260   // number of faces for header
00261   unsigned nr_faces = static_cast<unsigned> (mesh.polygons.size ());
00262   // Do we have vertices normals?
00263   int normal_index = getFieldIndex (mesh.cloud, "normal_x");
00264 
00265   // Write the header information
00266   fs << "####" << std::endl;
00267   fs << "# OBJ dataFile simple version. File name: " << file_name << std::endl;
00268   fs << "# Vertices: " << nr_points << std::endl;
00269   if (normal_index != -1)
00270     fs << "# Vertices normals : " << nr_points << std::endl;
00271   fs << "# Faces: " <<nr_faces << std::endl;
00272   fs << "####" << std::endl;
00273 
00274   // Write vertex coordinates
00275   fs << "# List of Vertices, with (x,y,z) coordinates, w is optional." << std::endl;
00276   for (int i = 0; i < nr_points; ++i)
00277   {
00278     int xyz = 0;
00279     for (size_t d = 0; d < mesh.cloud.fields.size (); ++d)
00280     {
00281       int c = 0;
00282       // adding vertex
00283       if ((mesh.cloud.fields[d].datatype == pcl::PCLPointField::FLOAT32) && (
00284           mesh.cloud.fields[d].name == "x" ||
00285           mesh.cloud.fields[d].name == "y" ||
00286           mesh.cloud.fields[d].name == "z"))
00287       {
00288         if (mesh.cloud.fields[d].name == "x")
00289            // write vertices beginning with v
00290           fs << "v ";
00291 
00292         float value;
00293         memcpy (&value, &mesh.cloud.data[i * point_size + mesh.cloud.fields[d].offset + c * sizeof (float)], sizeof (float));
00294         fs << value;
00295         if (++xyz == 3)
00296           break;
00297         fs << " ";
00298       }
00299     }
00300     if (xyz != 3)
00301     {
00302       PCL_ERROR ("[pcl::io::saveOBJFile] Input point cloud has no XYZ data!\n");
00303       return (-2);
00304     }
00305     fs << std::endl;
00306   }
00307 
00308   fs << "# "<< nr_points <<" vertices" << std::endl;
00309 
00310   if(normal_index != -1)
00311   {    
00312     fs << "# Normals in (x,y,z) form; normals might not be unit." <<  std::endl;
00313     // Write vertex normals
00314     for (int i = 0; i < nr_points; ++i)
00315     {
00316       int nxyz = 0;
00317       for (size_t d = 0; d < mesh.cloud.fields.size (); ++d)
00318       {
00319         int c = 0;
00320         // adding vertex
00321         if ((mesh.cloud.fields[d].datatype == pcl::PCLPointField::FLOAT32) && (
00322               mesh.cloud.fields[d].name == "normal_x" ||
00323               mesh.cloud.fields[d].name == "normal_y" ||
00324               mesh.cloud.fields[d].name == "normal_z"))
00325         {
00326           if (mesh.cloud.fields[d].name == "normal_x")
00327             // write vertices beginning with vn
00328             fs << "vn ";
00329           
00330           float value;
00331           memcpy (&value, &mesh.cloud.data[i * point_size + mesh.cloud.fields[d].offset + c * sizeof (float)], sizeof (float));
00332           fs << value;
00333           if (++nxyz == 3)
00334             break;
00335           fs << " ";
00336         }
00337       }
00338       if (nxyz != 3)
00339       {
00340         PCL_ERROR ("[pcl::io::saveOBJFile] Input point cloud has no normals!\n");
00341         return (-2);
00342       }
00343       fs << std::endl;
00344     }
00345 
00346     fs << "# "<< nr_points <<" vertices normals" << std::endl;
00347   }
00348 
00349   fs << "# Face Definitions" << std::endl;
00350   // Write down faces
00351   if(normal_index == -1)
00352   {
00353     for(unsigned i = 0; i < nr_faces; i++)
00354     {
00355       fs << "f ";
00356       size_t j = 0;    
00357       for (; j < mesh.polygons[i].vertices.size () - 1; ++j)
00358         fs << mesh.polygons[i].vertices[j] + 1 << " ";
00359       fs << mesh.polygons[i].vertices[j] + 1 << std::endl;
00360     }
00361   }
00362   else
00363   {
00364     for(unsigned i = 0; i < nr_faces; i++)
00365     {
00366       fs << "f ";
00367       size_t j = 0;    
00368       for (; j < mesh.polygons[i].vertices.size () - 1; ++j)
00369         fs << mesh.polygons[i].vertices[j] + 1 << "//" << mesh.polygons[i].vertices[j] + 1;
00370       fs << mesh.polygons[i].vertices[j] + 1 << "//" << mesh.polygons[i].vertices[j] + 1 << std::endl;
00371     }
00372   }
00373   fs << "# End of File" << std::endl;
00374 
00375   // Close obj file
00376   fs.close ();  
00377   return 0;
00378 }


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