mesh_loader.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include "mesh_loader.h"
00031 #include <resource_retriever/retriever.h>
00032 
00033 #include <boost/filesystem.hpp>
00034 
00035 #include <ogre_tools/stl_loader.h>
00036 
00037 #include <OGRE/OgreMeshManager.h>
00038 #include <OGRE/OgreTextureManager.h>
00039 #include <OGRE/OgreMaterialManager.h>
00040 #include <OGRE/OgreTexture.h>
00041 #include <OGRE/OgrePass.h>
00042 #include <OGRE/OgreTechnique.h>
00043 #include <OGRE/OgreMaterial.h>
00044 #include <OGRE/OgreTextureUnitState.h>
00045 #include <OGRE/OgreMeshSerializer.h>
00046 #include <OGRE/OgreSubMesh.h>
00047 #include <OGRE/OgreHardwareBufferManager.h>
00048 
00049 #include <ros/assert.h>
00050 
00051 #include <assimp/assimp.hpp>
00052 #include <assimp/aiScene.h>
00053 #include <assimp/aiPostProcess.h>
00054 #include <assimp/IOStream.h>
00055 #include <assimp/IOSystem.h>
00056 
00057 
00058 namespace fs = boost::filesystem;
00059 
00060 namespace rviz
00061 {
00062 
00063 class ResourceIOStream : public Assimp::IOStream
00064 {
00065 public:
00066   ResourceIOStream(const resource_retriever::MemoryResource& res)
00067   : res_(res)
00068   , pos_(res.data.get())
00069   {}
00070 
00071   ~ResourceIOStream()
00072   {}
00073 
00074   size_t Read(void* buffer, size_t size, size_t count)
00075   {
00076     size_t to_read = size * count;
00077     if (pos_ + to_read > res_.data.get() + res_.size)
00078     {
00079       to_read = res_.size - (pos_ - res_.data.get());
00080     }
00081 
00082     memcpy(buffer, pos_, to_read);
00083     pos_ += to_read;
00084 
00085     return to_read;
00086   }
00087 
00088   size_t Write( const void* buffer, size_t size, size_t count) { ROS_BREAK(); return 0; }
00089 
00090   aiReturn Seek( size_t offset, aiOrigin origin)
00091   {
00092     uint8_t* new_pos = 0;
00093     switch (origin)
00094     {
00095     case aiOrigin_SET:
00096       new_pos = res_.data.get() + offset;
00097       break;
00098     case aiOrigin_CUR:
00099       new_pos = pos_ + offset; // TODO is this right?  can offset really not be negative
00100       break;
00101     case aiOrigin_END:
00102       new_pos = res_.data.get() + res_.size - offset; // TODO is this right?
00103       break;
00104     default:
00105       ROS_BREAK();
00106     }
00107 
00108     if (new_pos < res_.data.get() || new_pos > res_.data.get() + res_.size)
00109     {
00110       return aiReturn_FAILURE;
00111     }
00112 
00113     pos_ = new_pos;
00114     return aiReturn_SUCCESS;
00115   }
00116 
00117   size_t Tell() const
00118   {
00119     return pos_ - res_.data.get();
00120   }
00121 
00122   size_t FileSize() const
00123   {
00124     return res_.size;
00125   }
00126 
00127   void Flush() {}
00128 
00129 private:
00130   resource_retriever::MemoryResource res_;
00131   uint8_t* pos_;
00132 };
00133 
00134 class ResourceIOSystem : public Assimp::IOSystem
00135 {
00136 public:
00137   ResourceIOSystem()
00138   {
00139   }
00140 
00141   ~ResourceIOSystem()
00142   {
00143   }
00144 
00145   // Check whether a specific file exists
00146   bool Exists(const char* file) const
00147   {
00148     // Ugly -- two retrievals where there should be one (Exists + Open)
00149     // resource_retriever needs a way of checking for existence
00150     // TODO: cache this
00151     resource_retriever::MemoryResource res;
00152     try
00153     {
00154       res = retriever_.get(file);
00155     }
00156     catch (resource_retriever::Exception& e)
00157     {
00158       return false;
00159     }
00160 
00161     return true;
00162   }
00163 
00164   // Get the path delimiter character we'd like to see
00165   char getOsSeparator() const
00166   {
00167     return '/';
00168   }
00169 
00170   // ... and finally a method to open a custom stream
00171   Assimp::IOStream* Open(const char* file, const char* mode)
00172   {
00173     ROS_ASSERT(mode == std::string("r") || mode == std::string("rb"));
00174 
00175     // Ugly -- two retrievals where there should be one (Exists + Open)
00176     // resource_retriever needs a way of checking for existence
00177     resource_retriever::MemoryResource res;
00178     try
00179     {
00180       res = retriever_.get(file);
00181     }
00182     catch (resource_retriever::Exception& e)
00183     {
00184       return 0;
00185     }
00186 
00187     return new ResourceIOStream(res);
00188   }
00189 
00190   void Close(Assimp::IOStream* stream) { delete stream; }
00191 
00192 private:
00193   mutable resource_retriever::Retriever retriever_;
00194 };
00195 
00196 // Mostly stolen from gazebo
00197 void buildMesh(const aiScene* scene, const aiNode* node, const Ogre::MeshPtr& mesh, Ogre::AxisAlignedBox& aabb, float& radius)
00198 {
00199   if (!node)
00200   {
00201     return;
00202   }
00203 
00204   aiMatrix4x4 transform = node->mTransformation;
00205   aiNode *pnode = node->mParent;
00206   while (pnode)
00207   {
00208     // Don't convert to y-up orientation, which is what the root node in
00209     // Assimp does
00210     if (pnode->mParent != NULL)
00211       transform = pnode->mTransformation * transform;
00212     pnode = pnode->mParent;
00213   }
00214 
00215   aiMatrix3x3 rotation(transform);
00216   aiMatrix3x3 inverse_transpose_rotation(rotation);
00217   inverse_transpose_rotation.Inverse();
00218   inverse_transpose_rotation.Transpose();
00219 
00220   for (uint32_t i = 0; i < node->mNumMeshes; i++)
00221   {
00222     aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]];
00223 
00224     Ogre::SubMesh* submesh = mesh->createSubMesh();
00225     submesh->useSharedVertices = false;
00226     submesh->vertexData = new Ogre::VertexData();
00227     Ogre::VertexData* vertex_data = submesh->vertexData;
00228     Ogre::VertexDeclaration* vertex_decl = vertex_data->vertexDeclaration;
00229 
00230     size_t offset = 0;
00231     // positions
00232     vertex_decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_POSITION);
00233     offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
00234 
00235     // normals
00236     if (input_mesh->HasNormals())
00237     {
00238       vertex_decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_NORMAL);
00239       offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
00240     }
00241 
00242     // texture coordinates (only support 1 for now)
00243     if (input_mesh->HasTextureCoords(0))
00244     {
00245       vertex_decl->addElement(0, offset, Ogre::VET_FLOAT2, Ogre::VES_TEXTURE_COORDINATES, 0);
00246       offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT2);
00247     }
00248 
00249     // todo vertex colors
00250 
00251     // allocate the vertex buffer
00252     vertex_data->vertexCount = input_mesh->mNumVertices;
00253     Ogre::HardwareVertexBufferSharedPtr vbuf = Ogre::HardwareBufferManager::getSingleton().createVertexBuffer(vertex_decl->getVertexSize(0),
00254                                                                           vertex_data->vertexCount,
00255                                                                           Ogre::HardwareBuffer::HBU_STATIC_WRITE_ONLY,
00256                                                                           false);
00257 
00258     vertex_data->vertexBufferBinding->setBinding(0, vbuf);
00259     float* vertices = static_cast<float*>(vbuf->lock(Ogre::HardwareBuffer::HBL_DISCARD));
00260 
00261     // Add the vertices
00262     for (uint32_t j = 0; j < input_mesh->mNumVertices; j++)
00263     {
00264       aiVector3D p = input_mesh->mVertices[j];
00265       p *= transform;
00266       *vertices++ = p.x;
00267       *vertices++ = p.y;
00268       *vertices++ = p.z;
00269 
00270       Ogre::Vector3 v(p.x, p.y, p.z);
00271       aabb.merge(v);
00272       float dist = v.length();
00273       if (dist > radius)
00274       {
00275         radius = dist;
00276       }
00277 
00278       if (input_mesh->HasNormals())
00279       {
00280               aiVector3D n = inverse_transpose_rotation * input_mesh->mNormals[j];
00281         *vertices++ = n.x;
00282         *vertices++ = n.y;
00283         *vertices++ = n.z;
00284       }
00285 
00286       if (input_mesh->HasTextureCoords(0))
00287       {
00288         *vertices++ = input_mesh->mTextureCoords[0][j].x;
00289         *vertices++ = input_mesh->mTextureCoords[0][j].y;
00290       }
00291     }
00292 
00293     // calculate index count
00294     submesh->indexData->indexCount = 0;
00295     for (uint32_t j = 0; j < input_mesh->mNumFaces; j++)
00296     {
00297       aiFace& face = input_mesh->mFaces[j];
00298       submesh->indexData->indexCount += face.mNumIndices;
00299     }
00300 
00301     // allocate index buffer
00302     submesh->indexData->indexBuffer = Ogre::HardwareBufferManager::getSingleton().createIndexBuffer(
00303                                              Ogre::HardwareIndexBuffer::IT_16BIT,
00304                                              submesh->indexData->indexCount,
00305                                              Ogre::HardwareBuffer::HBU_STATIC_WRITE_ONLY,
00306                                              false);
00307 
00308     Ogre::HardwareIndexBufferSharedPtr ibuf = submesh->indexData->indexBuffer;
00309     uint16_t* indices = static_cast<uint16_t*>(ibuf->lock(Ogre::HardwareBuffer::HBL_DISCARD));
00310 
00311     // add the indices
00312     for (uint32_t j = 0; j < input_mesh->mNumFaces; j++)
00313     {
00314       aiFace& face = input_mesh->mFaces[j];
00315       for (uint32_t k = 0; k < face.mNumIndices; ++k)
00316       {
00317         *indices++ = face.mIndices[k];
00318       }
00319     }
00320 
00321     // Unlock
00322     vbuf->unlock();
00323     ibuf->unlock();
00324   }
00325 
00326   for (uint32_t i=0; i < node->mNumChildren; ++i)
00327   {
00328     buildMesh(scene, node->mChildren[i], mesh, aabb, radius);
00329   }
00330 }
00331 
00332 void loadTexture(const std::string& resource_path)
00333 {
00334   if (!Ogre::TextureManager::getSingleton().resourceExists(resource_path))
00335   {
00336     resource_retriever::Retriever retriever;
00337     resource_retriever::MemoryResource res;
00338     try
00339     {
00340       res = retriever.get(resource_path);
00341     }
00342     catch (resource_retriever::Exception& e)
00343     {
00344       ROS_ERROR("%s", e.what());
00345     }
00346 
00347     if (res.size != 0)
00348     {
00349       Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size));
00350       Ogre::Image image;
00351       std::string extension = fs::extension(fs::path(resource_path));
00352 
00353       if (extension[0] == '.')
00354       {
00355         extension = extension.substr(1, extension.size() - 1);
00356       }
00357 
00358       try
00359       {
00360         image.load(stream, extension);
00361         Ogre::TextureManager::getSingleton().loadImage(resource_path, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, image);
00362       }
00363       catch (Ogre::Exception& e)
00364       {
00365         ROS_ERROR("Could not load texture [%s]: %s", resource_path.c_str(), e.what());
00366       }
00367     }
00368   }
00369 }
00370 
00371 // Mostly cribbed from gazebo
00372 void loadMaterialsForMesh(const std::string& resource_path, const aiScene* scene, const Ogre::MeshPtr& mesh)
00373 {
00374   std::vector<Ogre::MaterialPtr> material_lookup;
00375 
00376   for (uint32_t i = 0; i < scene->mNumMaterials; i++)
00377   {
00378     std::stringstream ss;
00379     ss << resource_path << "Material" << i;
00380     Ogre::MaterialPtr mat = Ogre::MaterialManager::getSingleton().create(ss.str(), ROS_PACKAGE_NAME, true);
00381     material_lookup.push_back(mat);
00382 
00383     Ogre::Technique* tech = mat->getTechnique(0);
00384     Ogre::Pass* pass = tech->getPass(0);
00385 
00386     aiMaterial *amat = scene->mMaterials[i];
00387 
00388     Ogre::ColourValue diffuse(1.0, 1.0, 1.0, 1.0);
00389     Ogre::ColourValue specular(1.0, 1.0, 1.0, 1.0);
00390     Ogre::ColourValue ambient(0.5, 0.5, 0.5, 1.0);
00391 
00392     for (uint32_t j=0; j < amat->mNumProperties; j++)
00393     {
00394       aiMaterialProperty *prop = amat->mProperties[j];
00395       std::string propKey = prop->mKey.data;
00396 
00397       if (propKey == "$tex.file")
00398       {
00399         aiString texName;
00400         aiTextureMapping mapping;
00401         uint32_t uvIndex;
00402         amat->GetTexture(aiTextureType_DIFFUSE,0, &texName, &mapping, &uvIndex);
00403 
00404         // Assume textures are in paths relative to the mesh
00405         std::string texture_path = fs::path(resource_path).parent_path().string() + "/" + texName.data;
00406         loadTexture(texture_path);
00407         Ogre::TextureUnitState* tu = pass->createTextureUnitState();
00408         tu->setTextureName(texture_path);
00409       }
00410       else if (propKey == "$clr.diffuse")
00411       {
00412         aiColor3D clr;
00413         amat->Get(AI_MATKEY_COLOR_DIFFUSE, clr);
00414         diffuse = Ogre::ColourValue(clr.r, clr.g, clr.b);
00415       }
00416       else if (propKey == "$clr.ambient")
00417       {
00418         aiColor3D clr;
00419         amat->Get(AI_MATKEY_COLOR_AMBIENT, clr);
00420 
00421         // Most of are DAE files don't have ambient color defined
00422         if (clr.r > 0 && clr.g > 0 && clr.b > 0)
00423         {
00424           ambient = Ogre::ColourValue(clr.r, clr.g, clr.b);
00425         }
00426       }
00427       else if (propKey == "$clr.specular")
00428       {
00429         aiColor3D clr;
00430         amat->Get(AI_MATKEY_COLOR_SPECULAR, clr);
00431         specular = Ogre::ColourValue(clr.r, clr.g, clr.b);
00432       }
00433       else if (propKey == "$clr.emissive")
00434       {
00435         aiColor3D clr;
00436         amat->Get(AI_MATKEY_COLOR_EMISSIVE, clr);
00437         mat->setSelfIllumination(clr.r, clr.g, clr.b);
00438       }
00439       else if (propKey == "$clr.opacity")
00440       {
00441         float o;
00442         amat->Get(AI_MATKEY_OPACITY, o);
00443         diffuse.a = o;
00444       }
00445       else if (propKey == "$mat.shininess")
00446       {
00447         float s;
00448         amat->Get(AI_MATKEY_SHININESS, s);
00449         mat->setShininess(s);
00450       }
00451       else if (propKey == "$mat.shadingm")
00452       {
00453         int model;
00454         amat->Get(AI_MATKEY_SHADING_MODEL, model);
00455         switch(model)
00456         {
00457           case aiShadingMode_Flat:
00458             mat->setShadingMode(Ogre::SO_FLAT);
00459             break;
00460           case aiShadingMode_Phong:
00461             mat->setShadingMode(Ogre::SO_PHONG);
00462             break;
00463           case aiShadingMode_Gouraud:
00464           default:
00465             mat->setShadingMode(Ogre::SO_GOURAUD);
00466             break;
00467         }
00468       }
00469     }
00470 
00471     int mode = aiBlendMode_Default;
00472     amat->Get(AI_MATKEY_BLEND_FUNC, mode);
00473     switch(mode)
00474     {
00475       case aiBlendMode_Additive:
00476         mat->setSceneBlending(Ogre::SBT_ADD);
00477         break;
00478       case aiBlendMode_Default:
00479       default:
00480         {
00481           if (diffuse.a < 0.99)
00482           {
00483             pass->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
00484           }
00485           else
00486           {
00487             pass->setSceneBlending(Ogre::SBT_REPLACE);
00488           }
00489         }
00490         break;
00491     }
00492 
00493     mat->setAmbient(ambient);
00494     mat->setDiffuse(diffuse);
00495     specular.a = diffuse.a;
00496     mat->setSpecular(specular);
00497   }
00498 
00499   for (uint32_t i = 0; i < mesh->getNumSubMeshes(); ++i)
00500   {
00501     mesh->getSubMesh(i)->setMaterialName(material_lookup[scene->mMeshes[i]->mMaterialIndex]->getName());
00502   }
00503 }
00504 
00505 Ogre::MeshPtr meshFromAssimpScene(const std::string& name, const aiScene* scene)
00506 {
00507   if (!scene->HasMeshes())
00508   {
00509     ROS_ERROR("No meshes found in file [%s]", name.c_str());
00510     return Ogre::MeshPtr();
00511   }
00512 
00513   Ogre::MeshPtr mesh = Ogre::MeshManager::getSingleton().createManual(name, ROS_PACKAGE_NAME);
00514 
00515   Ogre::AxisAlignedBox aabb(Ogre::AxisAlignedBox::EXTENT_NULL);
00516   float radius = 0.0f;
00517   buildMesh(scene, scene->mRootNode, mesh, aabb, radius);
00518 
00519   mesh->_setBounds(aabb);
00520   mesh->_setBoundingSphereRadius(radius);
00521   mesh->buildEdgeList();
00522 
00523   loadMaterialsForMesh(name, scene, mesh);
00524 
00525   mesh->load();
00526 
00527   return mesh;
00528 }
00529 
00530 Ogre::MeshPtr loadMeshFromResource(const std::string& resource_path)
00531 {
00532   if (Ogre::MeshManager::getSingleton().resourceExists(resource_path))
00533   {
00534     return Ogre::MeshManager::getSingleton().getByName(resource_path);
00535   }
00536   else
00537   {
00538     fs::path model_path(resource_path);
00539 #if BOOST_FILESYSTEM_VERSION == 3
00540     std::string ext = model_path.extension().string();
00541 #else
00542     std::string ext = model_path.extension();
00543 #endif
00544     if (ext == ".mesh" || ext == ".MESH")
00545     {
00546       resource_retriever::Retriever retriever;
00547       resource_retriever::MemoryResource res;
00548       try
00549       {
00550         res = retriever.get(resource_path);
00551       }
00552       catch (resource_retriever::Exception& e)
00553       {
00554         ROS_ERROR("%s", e.what());
00555         return Ogre::MeshPtr();
00556       }
00557 
00558       if (res.size == 0)
00559       {
00560         return Ogre::MeshPtr();
00561       }
00562 
00563       Ogre::MeshSerializer ser;
00564       Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size));
00565       Ogre::MeshPtr mesh = Ogre::MeshManager::getSingleton().createManual(resource_path, "rviz");
00566       ser.importMesh(stream, mesh.get());
00567 
00568       return mesh;
00569     }
00570     else if (ext == ".stl" || ext == ".STL" || ext == ".stlb" || ext == ".STLB")
00571     {
00572       resource_retriever::Retriever retriever;
00573       resource_retriever::MemoryResource res;
00574       try
00575       {
00576         res = retriever.get(resource_path);
00577       }
00578       catch (resource_retriever::Exception& e)
00579       {
00580         ROS_ERROR("%s", e.what());
00581         return Ogre::MeshPtr();
00582       }
00583 
00584       if (res.size == 0)
00585       {
00586         return Ogre::MeshPtr();
00587       }
00588 
00589       ogre_tools::STLLoader loader;
00590       if (!loader.load(res.data.get()))
00591       {
00592         ROS_ERROR("Failed to load file [%s]", resource_path.c_str());
00593         return Ogre::MeshPtr();
00594       }
00595 
00596       return loader.toMesh(resource_path);
00597     }
00598     else
00599     {
00600       Assimp::Importer importer;
00601       importer.SetIOHandler(new ResourceIOSystem());
00602       const aiScene* scene = importer.ReadFile(resource_path, aiProcess_SortByPType|aiProcess_GenNormals|aiProcess_Triangulate|aiProcess_GenUVCoords|aiProcess_FlipUVs);
00603       if (!scene)
00604       {
00605         ROS_ERROR("Could not load resource [%s]: %s", resource_path.c_str(), importer.GetErrorString());
00606         return Ogre::MeshPtr();
00607       }
00608 
00609       return meshFromAssimpScene(resource_path, scene);
00610     }
00611   }
00612 
00613   return Ogre::MeshPtr();
00614 }
00615 
00616 }


rviz_qt
Author(s): Dave Hershberger
autogenerated on Fri Dec 6 2013 20:56:52