mesh_loader.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #include "mesh_loader.h"
00036 
00037 #include <iostream>
00038 
00039 namespace household_objects_database {
00040 
00041 const char *elem_names[] = { /* list of the kinds of elements in the user's object */
00042   "vertex", "face"
00043 };
00044 
00045 PlyProperty vert_props[] = { /* list of property information for a vertex */
00046   {"x", Float32, Float32, offsetof(Vertex,x), 0, 0, 0, 0},
00047   {"y", Float32, Float32, offsetof(Vertex,y), 0, 0, 0, 0},
00048   {"z", Float32, Float32, offsetof(Vertex,z), 0, 0, 0, 0},
00049 };
00050 
00051 PlyProperty face_props[] = { /* list of property information for a face */
00052   {"vertex_indices", Int32, Int32, offsetof(Face,verts),
00053    1, Uint8, Uint8, offsetof(Face,nverts)},
00054 };
00055 
00056 
00057 inline void PLYModelLoader::endian_swap(void* p)
00058 {
00059         unsigned int* x = (unsigned int*)p;
00060 
00061         *x = (*x>>24) |
00062                         ((*x<<8) & 0x00FF0000) |
00063                         ((*x>>8) & 0x0000FF00) |
00064                         (*x<<24);
00065 }
00066 
00067 
00068 int PLYModelLoader::readFromFile(const string& filename, std::vector<double> &vertices, 
00069                                  std::vector<int> &triangles)
00070 {
00071         int i,j;
00072         int elem_count;
00073         char *elem_name;
00074 
00075         /*** Read in the original PLY object ***/
00076         vertices.clear();
00077         triangles.clear();
00078 
00079         FILE* fin = fopen(filename.c_str(), "rb");
00080 
00081         if (fin==NULL)  {
00082           std::cerr << "Cannot read file: " << filename << "\n";
00083                 return -1;
00084         }
00085 
00086         in_ply = read_ply (fin);
00087 
00088         float version;
00089         int file_type;
00090         get_info_ply(in_ply, &version, &file_type);
00091 
00092         /* examine each element type that is in the file (vertex, face) */
00093 
00094         for (i = 0; i < in_ply->num_elem_types; i++) {
00095 
00096                 /* prepare to read the i'th list of elements */
00097                 elem_name = setup_element_read_ply (in_ply, i, &elem_count);
00098 
00099                 if (equal_strings ((char*)"vertex", elem_name)) {
00100                         nverts = elem_count;
00101                         vertices.reserve(3*nverts);
00102 
00103                         /* set up for getting vertex elements */
00104                         /* (we want x,y,z) */
00105 
00106                         setup_property_ply (in_ply, &vert_props[0]);
00107                         setup_property_ply (in_ply, &vert_props[1]);
00108                         setup_property_ply (in_ply, &vert_props[2]);
00109 
00110                         /* we also want normal information if it is there (nx,ny,nz) */
00111 
00112                         //                    for (j = 0; j < in_ply->elems[i]->nprops; j++) {
00113                         //                      PlyProperty *prop;
00114                         //                      prop = in_ply->elems[i]->props[j];
00115                         //                      if (equal_strings ("nx", prop->name)) {
00116                         //                        setup_property_ply (in_ply, &vert_props[3]);
00117                         //                        has_nx = 1;
00118                         //                      }
00119                         //                      if (equal_strings ("ny", prop->name)) {
00120                         //                        setup_property_ply (in_ply, &vert_props[4]);
00121                         //                        has_ny = 1;
00122                         //                      }
00123                         //                      if (equal_strings ("nz", prop->name)) {
00124                         //                        setup_property_ply (in_ply, &vert_props[5]);
00125                         //                        has_nz = 1;
00126                         //                      }
00127                         //                    }
00128 
00129                         /* also grab anything else that we don't need to know about */
00130 
00131                         vert_other = get_other_properties_ply (in_ply,
00132                                         offsetof(Vertex,other_props));
00133 
00134                         /* grab the vertex elements*/
00135                         for (j = 0; j < elem_count; j++) {
00136                                 get_element_ply (in_ply, (void *) &vertex);
00137                                 if (file_type==PLY_BINARY_BE) {
00138                                         endian_swap(&vertex.x);
00139                                         endian_swap(&vertex.y);
00140                                         endian_swap(&vertex.z);
00141                                 }
00142                                 vertices.push_back( vertex.x );
00143                                 vertices.push_back( vertex.y );
00144                                 vertices.push_back( vertex.z );
00145                         }
00146                 }
00147                 else if (equal_strings ((char*)"face", elem_name)) {
00148 
00149                         nfaces = elem_count;
00150                         triangles.reserve(nfaces*3);
00151 
00152                         /* set up for getting face elements */
00153                         /* (all we need are vertex indices) */
00154 
00155                         setup_property_ply (in_ply, &face_props[0]);
00156                         face_other = get_other_properties_ply (in_ply,
00157                                         offsetof(Face,other_props));
00158 
00159                         /* grab all the face elements and place them in our list */
00160 
00161                         for (j = 0; j < elem_count; j++) {
00162                                 get_element_ply (in_ply, (void *) &face);
00163                                 if (file_type==PLY_BINARY_BE) {
00164                                         for (int k=0;k<face.nverts;++k) {
00165                                                 endian_swap(&face.verts[k]);
00166                                         }
00167                                 }
00168 
00169 
00170                                 if (face.nverts!=3) {
00171                                   std::cerr << "Mesh contains non triangle faces!\n";
00172                                 }
00173                                 else {
00174                                         triangles.push_back(face.verts[0]);
00175                                         triangles.push_back(face.verts[1]);
00176                                         triangles.push_back(face.verts[2]);
00177                                 }
00178                         }
00179                 }
00180                 else  /* all non-vertex and non-face elements are grabbed here */
00181                         get_other_element_ply (in_ply);
00182         }
00183 
00184         close_ply (in_ply);
00185 
00186         return 0;
00187 }
00188 
00189 }


household_objects_database
Author(s): Matei Ciocarlie, except for source files individually marked otherwise
autogenerated on Thu Jan 2 2014 11:40:12