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_helpers/stl_loader.h"
00036 
00037 #include <OgreMeshManager.h>
00038 #include <OgreTextureManager.h>
00039 #include <OgreMaterialManager.h>
00040 #include <OgreTexture.h>
00041 #include <OgrePass.h>
00042 #include <OgreTechnique.h>
00043 #include <OgreMaterial.h>
00044 #include <OgreTextureUnitState.h>
00045 #include <OgreMeshSerializer.h>
00046 #include <OgreSubMesh.h>
00047 #include <OgreHardwareBufferManager.h>
00048 #include <OgreSharedPtr.h>
00049 #include <OgreTechnique.h>
00050 
00051 #include <tinyxml.h>
00052 
00053 
00054 #include <ros/assert.h>
00055 
00056 #if defined(ASSIMP_UNIFIED_HEADER_NAMES)
00057 #include <assimp/Importer.hpp>
00058 #include <assimp/scene.h>
00059 #include <assimp/postprocess.h>
00060 #include <assimp/IOStream.hpp>
00061 #include <assimp/IOSystem.hpp>
00062 #else
00063 #include <assimp/assimp.hpp>
00064 #include <assimp/aiScene.h>
00065 #include <assimp/aiPostProcess.h>
00066 #include <assimp/IOStream.h>
00067 #include <assimp/IOSystem.h>
00068 #endif
00069 
00070 namespace fs = boost::filesystem;
00071 
00072 namespace rviz
00073 {
00074 
00075 class ResourceIOStream : public Assimp::IOStream
00076 {
00077 public:
00078   ResourceIOStream(const resource_retriever::MemoryResource& res)
00079   : res_(res)
00080   , pos_(res.data.get())
00081   {}
00082 
00083   ~ResourceIOStream()
00084   {}
00085 
00086   size_t Read(void* buffer, size_t size, size_t count)
00087   {
00088     size_t to_read = size * count;
00089     if (pos_ + to_read > res_.data.get() + res_.size)
00090     {
00091       to_read = res_.size - (pos_ - res_.data.get());
00092     }
00093 
00094     memcpy(buffer, pos_, to_read);
00095     pos_ += to_read;
00096 
00097     return to_read;
00098   }
00099 
00100   size_t Write( const void* buffer, size_t size, size_t count) { ROS_BREAK(); return 0; }
00101 
00102   aiReturn Seek( size_t offset, aiOrigin origin)
00103   {
00104     uint8_t* new_pos = 0;
00105     switch (origin)
00106     {
00107     case aiOrigin_SET:
00108       new_pos = res_.data.get() + offset;
00109       break;
00110     case aiOrigin_CUR:
00111       new_pos = pos_ + offset; // TODO is this right?  can offset really not be negative
00112       break;
00113     case aiOrigin_END:
00114       new_pos = res_.data.get() + res_.size - offset; // TODO is this right?
00115       break;
00116     default:
00117       ROS_BREAK();
00118     }
00119 
00120     if (new_pos < res_.data.get() || new_pos > res_.data.get() + res_.size)
00121     {
00122       return aiReturn_FAILURE;
00123     }
00124 
00125     pos_ = new_pos;
00126     return aiReturn_SUCCESS;
00127   }
00128 
00129   size_t Tell() const
00130   {
00131     return pos_ - res_.data.get();
00132   }
00133 
00134   size_t FileSize() const
00135   {
00136     return res_.size;
00137   }
00138 
00139   void Flush() {}
00140 
00141 private:
00142   resource_retriever::MemoryResource res_;
00143   uint8_t* pos_;
00144 };
00145 
00146 class ResourceIOSystem : public Assimp::IOSystem
00147 {
00148 public:
00149   ResourceIOSystem()
00150   {
00151   }
00152 
00153   ~ResourceIOSystem()
00154   {
00155   }
00156 
00157   // Check whether a specific file exists
00158   bool Exists(const char* file) const
00159   {
00160     // Ugly -- two retrievals where there should be one (Exists + Open)
00161     // resource_retriever needs a way of checking for existence
00162     // TODO: cache this
00163     resource_retriever::MemoryResource res;
00164     try
00165     {
00166       res = retriever_.get(file);
00167     }
00168     catch (resource_retriever::Exception& e)
00169     {
00170       return false;
00171     }
00172 
00173     return true;
00174   }
00175 
00176   // Get the path delimiter character we'd like to see
00177   char getOsSeparator() const
00178   {
00179     return '/';
00180   }
00181 
00182   // ... and finally a method to open a custom stream
00183   Assimp::IOStream* Open(const char* file, const char* mode = "rb")
00184   {
00185     ROS_ASSERT(mode == std::string("r") || mode == std::string("rb"));
00186 
00187     // Ugly -- two retrievals where there should be one (Exists + Open)
00188     // resource_retriever needs a way of checking for existence
00189     resource_retriever::MemoryResource res;
00190     try
00191     {
00192       res = retriever_.get(file);
00193     }
00194     catch (resource_retriever::Exception& e)
00195     {
00196       return 0;
00197     }
00198 
00199     return new ResourceIOStream(res);
00200   }
00201 
00202   void Close(Assimp::IOStream* stream);
00203 
00204 private:
00205   mutable resource_retriever::Retriever retriever_;
00206 };
00207 
00208 void ResourceIOSystem::Close(Assimp::IOStream* stream)
00209 {
00210   delete stream;
00211 }
00212 
00213 // Mostly stolen from gazebo
00218 void buildMesh( const aiScene* scene, const aiNode* node,
00219                 const Ogre::MeshPtr& mesh,
00220                 Ogre::AxisAlignedBox& aabb, float& radius, const float scale,
00221                 std::vector<Ogre::MaterialPtr>& material_table )
00222 {
00223   if (!node)
00224   {
00225     return;
00226   }
00227 
00228   aiMatrix4x4 transform = node->mTransformation;
00229   aiNode *pnode = node->mParent;
00230   while (pnode)
00231   {
00232     // Don't convert to y-up orientation, which is what the root node in
00233     // Assimp does
00234     if (pnode->mParent != NULL)
00235       transform = pnode->mTransformation * transform;
00236     pnode = pnode->mParent;
00237   }
00238 
00239   aiMatrix3x3 rotation(transform);
00240   aiMatrix3x3 inverse_transpose_rotation(rotation);
00241   inverse_transpose_rotation.Inverse();
00242   inverse_transpose_rotation.Transpose();
00243 
00244   for (uint32_t i = 0; i < node->mNumMeshes; i++)
00245   {
00246     aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]];
00247 
00248     Ogre::SubMesh* submesh = mesh->createSubMesh();
00249     submesh->useSharedVertices = false;
00250     submesh->vertexData = new Ogre::VertexData();
00251     Ogre::VertexData* vertex_data = submesh->vertexData;
00252     Ogre::VertexDeclaration* vertex_decl = vertex_data->vertexDeclaration;
00253 
00254     size_t offset = 0;
00255     // positions
00256     vertex_decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_POSITION);
00257     offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
00258 
00259     // normals
00260     if (input_mesh->HasNormals())
00261     {
00262       vertex_decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_NORMAL);
00263       offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
00264     }
00265 
00266     // texture coordinates (only support 1 for now)
00267     if (input_mesh->HasTextureCoords(0))
00268     {
00269       vertex_decl->addElement(0, offset, Ogre::VET_FLOAT2, Ogre::VES_TEXTURE_COORDINATES, 0);
00270       offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT2);
00271     }
00272 
00273     // todo vertex colors
00274 
00275     // allocate the vertex buffer
00276     vertex_data->vertexCount = input_mesh->mNumVertices;
00277     Ogre::HardwareVertexBufferSharedPtr vbuf = Ogre::HardwareBufferManager::getSingleton().createVertexBuffer(vertex_decl->getVertexSize(0),
00278                                                                           vertex_data->vertexCount,
00279                                                                           Ogre::HardwareBuffer::HBU_STATIC_WRITE_ONLY,
00280                                                                           false);
00281 
00282     vertex_data->vertexBufferBinding->setBinding(0, vbuf);
00283     float* vertices = static_cast<float*>(vbuf->lock(Ogre::HardwareBuffer::HBL_DISCARD));
00284 
00285     // Add the vertices
00286     for (uint32_t j = 0; j < input_mesh->mNumVertices; j++)
00287     {
00288       aiVector3D p = input_mesh->mVertices[j];
00289       p *= transform;
00290       p *= scale;
00291       *vertices++ = p.x;
00292       *vertices++ = p.y;
00293       *vertices++ = p.z;
00294 
00295       Ogre::Vector3 v(p.x, p.y, p.z);
00296       aabb.merge(v);
00297       float dist = v.length();
00298       if (dist > radius)
00299       {
00300         radius = dist;
00301       }
00302 
00303       if (input_mesh->HasNormals())
00304       {
00305         aiVector3D n = inverse_transpose_rotation * input_mesh->mNormals[j];
00306         n.Normalize();
00307         *vertices++ = n.x;
00308         *vertices++ = n.y;
00309         *vertices++ = n.z;
00310       }
00311 
00312       if (input_mesh->HasTextureCoords(0))
00313       {
00314         *vertices++ = input_mesh->mTextureCoords[0][j].x;
00315         *vertices++ = input_mesh->mTextureCoords[0][j].y;
00316       }
00317     }
00318 
00319     // calculate index count
00320     submesh->indexData->indexCount = 0;
00321     for (uint32_t j = 0; j < input_mesh->mNumFaces; j++)
00322     {
00323       aiFace& face = input_mesh->mFaces[j];
00324       submesh->indexData->indexCount += face.mNumIndices;
00325     }
00326 
00327     // If we have less than 65536 (2^16) vertices, we can use a 16-bit index buffer.
00328     if( vertex_data->vertexCount < (1<<16) )
00329     {
00330       // allocate index buffer
00331       submesh->indexData->indexBuffer = Ogre::HardwareBufferManager::getSingleton().createIndexBuffer(
00332         Ogre::HardwareIndexBuffer::IT_16BIT,
00333         submesh->indexData->indexCount,
00334         Ogre::HardwareBuffer::HBU_STATIC_WRITE_ONLY,
00335         false);
00336 
00337       Ogre::HardwareIndexBufferSharedPtr ibuf = submesh->indexData->indexBuffer;
00338       uint16_t* indices = static_cast<uint16_t*>(ibuf->lock(Ogre::HardwareBuffer::HBL_DISCARD));
00339 
00340       // add the indices
00341       for (uint32_t j = 0; j < input_mesh->mNumFaces; j++)
00342       {
00343         aiFace& face = input_mesh->mFaces[j];
00344         for (uint32_t k = 0; k < face.mNumIndices; ++k)
00345         {
00346           *indices++ = face.mIndices[k];
00347         }
00348       }
00349 
00350       ibuf->unlock();
00351     }
00352     else 
00353     {
00354       // Else we have more than 65536 (2^16) vertices, so we must
00355       // use a 32-bit index buffer (or subdivide the mesh, which
00356       // I'm too impatient to do right now)
00357 
00358       // allocate index buffer
00359       submesh->indexData->indexBuffer = Ogre::HardwareBufferManager::getSingleton().createIndexBuffer(
00360         Ogre::HardwareIndexBuffer::IT_32BIT,
00361         submesh->indexData->indexCount,
00362         Ogre::HardwareBuffer::HBU_STATIC_WRITE_ONLY,
00363         false);
00364 
00365       Ogre::HardwareIndexBufferSharedPtr ibuf = submesh->indexData->indexBuffer;
00366       uint32_t* indices = static_cast<uint32_t*>(ibuf->lock(Ogre::HardwareBuffer::HBL_DISCARD));
00367 
00368       // add the indices
00369       for (uint32_t j = 0; j < input_mesh->mNumFaces; j++)
00370       {
00371         aiFace& face = input_mesh->mFaces[j];
00372         for (uint32_t k = 0; k < face.mNumIndices; ++k)
00373         {
00374           *indices++ = face.mIndices[k];
00375         }
00376       }
00377 
00378       ibuf->unlock();
00379     }
00380     vbuf->unlock();
00381 
00382     submesh->setMaterialName(material_table[input_mesh->mMaterialIndex]->getName());
00383   }
00384 
00385   for (uint32_t i=0; i < node->mNumChildren; ++i)
00386   {
00387     buildMesh(scene, node->mChildren[i], mesh, aabb, radius, scale, material_table);
00388   }
00389 }
00390 
00391 void loadTexture(const std::string& resource_path)
00392 {
00393   if (!Ogre::TextureManager::getSingleton().resourceExists(resource_path))
00394   {
00395     resource_retriever::Retriever retriever;
00396     resource_retriever::MemoryResource res;
00397     try
00398     {
00399       res = retriever.get(resource_path);
00400     }
00401     catch (resource_retriever::Exception& e)
00402     {
00403       ROS_ERROR("%s", e.what());
00404     }
00405 
00406     if (res.size != 0)
00407     {
00408       Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size));
00409       Ogre::Image image;
00410       std::string extension = fs::extension(fs::path(resource_path));
00411 
00412       if (extension[0] == '.')
00413       {
00414         extension = extension.substr(1, extension.size() - 1);
00415       }
00416 
00417       try
00418       {
00419         image.load(stream, extension);
00420         Ogre::TextureManager::getSingleton().loadImage(resource_path, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, image);
00421       }
00422       catch (Ogre::Exception& e)
00423       {
00424         ROS_ERROR("Could not load texture [%s]: %s", resource_path.c_str(), e.what());
00425       }
00426     }
00427   }
00428 }
00429 
00430 // Mostly cribbed from gazebo
00437 void loadMaterials(const std::string& resource_path,
00438                    const aiScene* scene,
00439                    std::vector<Ogre::MaterialPtr>& material_table_out )
00440 {
00441   for (uint32_t i = 0; i < scene->mNumMaterials; i++)
00442   {
00443     std::stringstream ss;
00444     ss << resource_path << "Material" << i;
00445     Ogre::MaterialPtr mat = Ogre::MaterialManager::getSingleton().create(ss.str(), ROS_PACKAGE_NAME, true);
00446     material_table_out.push_back(mat);
00447 
00448     Ogre::Technique* tech = mat->getTechnique(0);
00449     Ogre::Pass* pass = tech->getPass(0);
00450 
00451     aiMaterial *amat = scene->mMaterials[i];
00452 
00453     Ogre::ColourValue diffuse(1.0, 1.0, 1.0, 1.0);
00454     Ogre::ColourValue specular(1.0, 1.0, 1.0, 1.0);
00455     Ogre::ColourValue ambient(0, 0, 0, 1.0);
00456 
00457     for (uint32_t j=0; j < amat->mNumProperties; j++)
00458     {
00459       aiMaterialProperty *prop = amat->mProperties[j];
00460       std::string propKey = prop->mKey.data;
00461 
00462       if (propKey == "$tex.file")
00463       {
00464         aiString texName;
00465         aiTextureMapping mapping;
00466         uint32_t uvIndex;
00467         amat->GetTexture(aiTextureType_DIFFUSE,0, &texName, &mapping, &uvIndex);
00468 
00469         // Assume textures are in paths relative to the mesh
00470         std::string texture_path = fs::path(resource_path).parent_path().string() + "/" + texName.data;
00471         loadTexture(texture_path);
00472         Ogre::TextureUnitState* tu = pass->createTextureUnitState();
00473         tu->setTextureName(texture_path);
00474       }
00475       else if (propKey == "$clr.diffuse")
00476       {
00477         aiColor3D clr;
00478         amat->Get(AI_MATKEY_COLOR_DIFFUSE, clr);
00479         diffuse = Ogre::ColourValue(clr.r, clr.g, clr.b);
00480       }
00481       else if (propKey == "$clr.ambient")
00482       {
00483         aiColor3D clr;
00484         amat->Get(AI_MATKEY_COLOR_AMBIENT, clr);
00485         ambient = Ogre::ColourValue(clr.r, clr.g, clr.b);
00486       }
00487       else if (propKey == "$clr.specular")
00488       {
00489         aiColor3D clr;
00490         amat->Get(AI_MATKEY_COLOR_SPECULAR, clr);
00491         specular = Ogre::ColourValue(clr.r, clr.g, clr.b);
00492       }
00493       else if (propKey == "$clr.emissive")
00494       {
00495         aiColor3D clr;
00496         amat->Get(AI_MATKEY_COLOR_EMISSIVE, clr);
00497         mat->setSelfIllumination(clr.r, clr.g, clr.b);
00498       }
00499       else if (propKey == "$clr.opacity")
00500       {
00501         float o;
00502         amat->Get(AI_MATKEY_OPACITY, o);
00503         diffuse.a = o;
00504       }
00505       else if (propKey == "$mat.shininess")
00506       {
00507         float s;
00508         amat->Get(AI_MATKEY_SHININESS, s);
00509         mat->setShininess(s);
00510       }
00511       else if (propKey == "$mat.shadingm")
00512       {
00513         int model;
00514         amat->Get(AI_MATKEY_SHADING_MODEL, model);
00515         switch(model)
00516         {
00517           case aiShadingMode_Flat:
00518             mat->setShadingMode(Ogre::SO_FLAT);
00519             break;
00520           case aiShadingMode_Phong:
00521             mat->setShadingMode(Ogre::SO_PHONG);
00522             break;
00523           case aiShadingMode_Gouraud:
00524           default:
00525             mat->setShadingMode(Ogre::SO_GOURAUD);
00526             break;
00527         }
00528       }
00529     }
00530 
00531     int mode = aiBlendMode_Default;
00532     amat->Get(AI_MATKEY_BLEND_FUNC, mode);
00533     switch(mode)
00534     {
00535       case aiBlendMode_Additive:
00536         mat->setSceneBlending(Ogre::SBT_ADD);
00537         break;
00538       case aiBlendMode_Default:
00539       default:
00540         {
00541           if (diffuse.a < 0.99)
00542           {
00543             pass->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
00544           }
00545           else
00546           {
00547             pass->setSceneBlending(Ogre::SBT_REPLACE);
00548           }
00549         }
00550         break;
00551     }
00552 
00553     mat->setAmbient(ambient * 0.5);
00554     mat->setDiffuse(diffuse);
00555     specular.a = diffuse.a;
00556     mat->setSpecular(specular);
00557   }
00558 }
00559 
00560 
00561 /*@brief - Get the scaling from units used in this mesh file to meters.
00562   
00563   This function applies only to Collada files. It is necessary because
00564   ASSIMP does not currently expose an api to retrieve the scaling factor.
00565   
00566   @Param[in] resource_path   -   The url of a resource containing a mesh.
00567   
00568   @Returns The scaling factor that converts the mesh to meters. Returns 1.0
00569   for meshes which do not explicitly encode such a scaling. 
00570   
00571 */
00572 
00573 float getMeshUnitRescale(const std::string& resource_path)
00574 {
00575   static std::map<std::string, float> rescale_cache;
00576 
00577    
00578 
00579   // Try to read unit to meter conversion ratio from mesh. Only valid in Collada XML formats. 
00580   TiXmlDocument xmlDoc;
00581   float unit_scale(1.0);
00582   resource_retriever::Retriever retriever;
00583   resource_retriever::MemoryResource res;
00584   try
00585   {
00586     res = retriever.get(resource_path);
00587   }
00588   catch (resource_retriever::Exception& e)
00589   {
00590     ROS_ERROR("%s", e.what());
00591     return unit_scale;
00592   }
00593   
00594   if (res.size == 0)
00595   {
00596     return unit_scale;
00597   }
00598 
00599 
00600   // Use the resource retriever to get the data.
00601   const char * data = reinterpret_cast<const char * > (res.data.get());
00602   xmlDoc.Parse(data);
00603 
00604   // Find the appropriate element if it exists
00605   if(!xmlDoc.Error())
00606   {
00607     TiXmlElement * colladaXml = xmlDoc.FirstChildElement("COLLADA");
00608     if(colladaXml)
00609     {
00610       TiXmlElement *assetXml = colladaXml->FirstChildElement("asset");
00611       if(assetXml)
00612       {
00613         TiXmlElement *unitXml = assetXml->FirstChildElement("unit");
00614         if (unitXml && unitXml->Attribute("meter"))
00615         {
00616           // Failing to convert leaves unit_scale as the default.
00617           if(unitXml->QueryFloatAttribute("meter", &unit_scale) != 0)
00618             ROS_WARN_STREAM("getMeshUnitRescale::Failed to convert unit element meter attribute to determine scaling. unit element: "
00619                             << *unitXml);
00620         }
00621       }
00622     }
00623   }
00624   return unit_scale;
00625 }
00626 
00627 
00628 
00629 Ogre::MeshPtr meshFromAssimpScene(const std::string& name, const aiScene* scene)
00630 {
00631   if (!scene->HasMeshes())
00632   {
00633     ROS_ERROR("No meshes found in file [%s]", name.c_str());
00634     return Ogre::MeshPtr();
00635   }
00636 
00637   std::vector<Ogre::MaterialPtr> material_table;
00638   loadMaterials(name, scene, material_table);
00639 
00640   Ogre::MeshPtr mesh = Ogre::MeshManager::getSingleton().createManual(name, ROS_PACKAGE_NAME);
00641 
00642   Ogre::AxisAlignedBox aabb(Ogre::AxisAlignedBox::EXTENT_NULL);
00643   float radius = 0.0f;
00644   float scale = getMeshUnitRescale(name);
00645   buildMesh(scene, scene->mRootNode, mesh, aabb, radius, scale, material_table);
00646 
00647   mesh->_setBounds(aabb);
00648   mesh->_setBoundingSphereRadius(radius);
00649   mesh->buildEdgeList();
00650 
00651   mesh->load();
00652 
00653   return mesh;
00654 }
00655 
00656 Ogre::MeshPtr loadMeshFromResource(const std::string& resource_path)
00657 {
00658   if (Ogre::MeshManager::getSingleton().resourceExists(resource_path))
00659   {
00660     return Ogre::MeshManager::getSingleton().getByName(resource_path);
00661   }
00662   else
00663   {
00664     fs::path model_path(resource_path);
00665 #if BOOST_FILESYSTEM_VERSION == 3
00666     std::string ext = model_path.extension().string();
00667 #else
00668     std::string ext = model_path.extension();
00669 #endif
00670     if (ext == ".mesh" || ext == ".MESH")
00671     {
00672       resource_retriever::Retriever retriever;
00673       resource_retriever::MemoryResource res;
00674       try
00675       {
00676         res = retriever.get(resource_path);
00677       }
00678       catch (resource_retriever::Exception& e)
00679       {
00680         ROS_ERROR("%s", e.what());
00681         return Ogre::MeshPtr();
00682       }
00683 
00684       if (res.size == 0)
00685       {
00686         return Ogre::MeshPtr();
00687       }
00688 
00689       Ogre::MeshSerializer ser;
00690       Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size));
00691       Ogre::MeshPtr mesh = Ogre::MeshManager::getSingleton().createManual(resource_path, "rviz");
00692       ser.importMesh(stream, mesh.get());
00693 
00694       return mesh;
00695     }
00696     else if (ext == ".stl" || ext == ".STL" || ext == ".stlb" || ext == ".STLB")
00697     {
00698       resource_retriever::Retriever retriever;
00699       resource_retriever::MemoryResource res;
00700       try
00701       {
00702         res = retriever.get(resource_path);
00703       }
00704       catch (resource_retriever::Exception& e)
00705       {
00706         ROS_ERROR("%s", e.what());
00707         return Ogre::MeshPtr();
00708       }
00709 
00710       if (res.size == 0)
00711       {
00712         return Ogre::MeshPtr();
00713       }
00714 
00715       ogre_tools::STLLoader loader;
00716       if (!loader.load(res.data.get(), res.size, resource_path))
00717       {
00718         ROS_ERROR("Failed to load file [%s]", resource_path.c_str());
00719         return Ogre::MeshPtr();
00720       }
00721 
00722       return loader.toMesh(resource_path);
00723     }
00724     else
00725     {
00726       Assimp::Importer importer;
00727       importer.SetIOHandler(new ResourceIOSystem());
00728       const aiScene* scene = importer.ReadFile(resource_path, aiProcess_SortByPType|aiProcess_GenNormals|aiProcess_Triangulate|aiProcess_GenUVCoords|aiProcess_FlipUVs);
00729       if (!scene)
00730       {
00731         ROS_ERROR("Could not load resource [%s]: %s", resource_path.c_str(), importer.GetErrorString());
00732         return Ogre::MeshPtr();
00733       }
00734 
00735       return meshFromAssimpScene(resource_path, scene);
00736     }
00737   }
00738 
00739   return Ogre::MeshPtr();
00740 }
00741   
00742 }


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Tue Oct 3 2017 03:19:31