mesh_loader.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2010, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include "mesh_loader.h"
31 #include <OgrePrerequisites.h>
33 
34 #include <boost/filesystem.hpp>
35 #include <boost/algorithm/string.hpp>
36 
37 #include <OgreSkeleton.h>
38 #include <OgreSkeletonManager.h>
39 #include <OgreSkeletonSerializer.h>
40 #include <OgreMeshManager.h>
41 #include <OgreTextureManager.h>
42 #include <OgreMaterialManager.h>
43 #include <OgreTexture.h>
44 #include <OgrePass.h>
45 #include <OgreTechnique.h>
46 #include <OgreMaterial.h>
47 #include <OgreTextureUnitState.h>
48 #include <OgreMeshSerializer.h>
49 #include <OgreSubMesh.h>
50 #include <OgreHardwareBufferManager.h>
51 #include <OgreSharedPtr.h>
52 #include <OgreTechnique.h>
53 
54 #include <tinyxml2.h>
55 
56 #include <ros/assert.h>
57 
58 #include <assimp/Importer.hpp>
59 #include <assimp/scene.h>
60 #include <assimp/postprocess.h>
61 #include <assimp/IOStream.hpp>
62 #include <assimp/IOSystem.hpp>
63 #include <boost/filesystem/operations.hpp>
64 
65 namespace fs = boost::filesystem;
66 
67 namespace rviz
68 {
69 class ResourceIOStream : public Assimp::IOStream
70 {
71 public:
73  {
74  }
75 
76  ~ResourceIOStream() override
77  {
78  }
79 
80  size_t Read(void* buffer, size_t size, size_t count) override
81  {
82  size_t to_read = size * count;
83  if (pos_ + to_read > res_.data.get() + res_.size)
84  {
85  to_read = res_.size - (pos_ - res_.data.get());
86  }
87 
88  memcpy(buffer, pos_, to_read);
89  pos_ += to_read;
90 
91  return to_read;
92  }
93 
94  size_t Write(const void* /*buffer*/, size_t /*size*/, size_t /*count*/) override
95  {
96  ROS_BREAK();
97  return 0;
98  }
99 
100  aiReturn Seek(size_t offset, aiOrigin origin) override
101  {
102  uint8_t* new_pos = nullptr;
103  switch (origin)
104  {
105  case aiOrigin_SET:
106  new_pos = res_.data.get() + offset;
107  break;
108  case aiOrigin_CUR:
109  new_pos = pos_ + offset; // TODO is this right? can offset really not be negative
110  break;
111  case aiOrigin_END:
112  new_pos = res_.data.get() + res_.size - offset; // TODO is this right?
113  break;
114  default:
115  ROS_BREAK();
116  }
117 
118  if (new_pos < res_.data.get() || new_pos > res_.data.get() + res_.size)
119  {
120  return aiReturn_FAILURE;
121  }
122 
123  pos_ = new_pos;
124  return aiReturn_SUCCESS;
125  }
126 
127  size_t Tell() const override
128  {
129  return pos_ - res_.data.get();
130  }
131 
132  size_t FileSize() const override
133  {
134  return res_.size;
135  }
136 
137  void Flush() override
138  {
139  }
140 
141 private:
143  uint8_t* pos_;
144 };
145 
146 class ResourceIOSystem : public Assimp::IOSystem
147 {
148 public:
150  {
151  }
152 
153  ~ResourceIOSystem() override
154  {
155  }
156 
157  // Check whether a specific file exists
158  bool Exists(const char* file) const override
159  {
160  // Ugly -- two retrievals where there should be one (Exists + Open)
161  // resource_retriever needs a way of checking for existence
162  // TODO: cache this
164  try
165  {
166  res = retriever_.get(file);
167  }
169  {
170  return false;
171  }
172 
173  return true;
174  }
175 
176  // Get the path delimiter character we'd like to see
177  char getOsSeparator() const override
178  {
179  return '/';
180  }
181 
182  // ... and finally a method to open a custom stream
183  Assimp::IOStream* Open(const char* file, const char* mode = "rb") override
184  {
185  ROS_ASSERT(mode == std::string("r") || mode == std::string("rb"));
186  (void)mode;
187 
188  // Ugly -- two retrievals where there should be one (Exists + Open)
189  // resource_retriever needs a way of checking for existence
191  try
192  {
193  res = retriever_.get(file);
194  }
196  {
197  return nullptr;
198  }
199 
200  return new ResourceIOStream(res);
201  }
202 
203  void Close(Assimp::IOStream* stream) override;
204 
205 private:
207 };
208 
209 void ResourceIOSystem::Close(Assimp::IOStream* stream)
210 {
211  delete stream;
212 }
213 
214 // Mostly stolen from gazebo
220 void buildMesh(const aiScene* scene,
221  const aiNode* node,
222  const Ogre::MeshPtr& mesh,
223  Ogre::AxisAlignedBox& aabb,
224  float& radius,
225  std::vector<Ogre::MaterialPtr>& material_table,
226  aiMatrix4x4 transform = aiMatrix4x4())
227 {
228  if (!node)
229  return;
230 
231  if (node->mParent == nullptr)
232  {
233  // Use root node's transform
234  transform = node->mTransformation;
235  // but don't rotate to y-up orientation, which is *sometimes* done in assimp's root node
236  aiVector3D scaling, axis, pos;
237  float angle;
238  transform.Decompose(scaling, axis, angle, pos);
239  // drop rotation, but keep scaling and position
240  transform = aiMatrix4x4(scaling, aiQuaternion(), pos);
241  }
242  else
243  transform *= node->mTransformation;
244 
245  // rotation (+scaling) part of transform applied to normals
246  aiMatrix3x3 rotation(transform);
247 
248  for (uint32_t i = 0; i < node->mNumMeshes; i++)
249  {
250  aiMesh* input_mesh = scene->mMeshes[node->mMeshes[i]];
251 
252  Ogre::SubMesh* submesh = mesh->createSubMesh();
253  submesh->useSharedVertices = false;
254  submesh->vertexData = new Ogre::VertexData();
255  Ogre::VertexData* vertex_data = submesh->vertexData;
256  Ogre::VertexDeclaration* vertex_decl = vertex_data->vertexDeclaration;
257 
258  size_t offset = 0;
259  // positions
260  vertex_decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_POSITION);
261  offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
262 
263  // normals
264  if (input_mesh->HasNormals())
265  {
266  vertex_decl->addElement(0, offset, Ogre::VET_FLOAT3, Ogre::VES_NORMAL);
267  offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT3);
268  }
269 
270  // texture coordinates (only support 1 for now)
271  if (input_mesh->HasTextureCoords(0))
272  {
273  vertex_decl->addElement(0, offset, Ogre::VET_FLOAT2, Ogre::VES_TEXTURE_COORDINATES, 0);
274  // offset += Ogre::VertexElement::getTypeSize(Ogre::VET_FLOAT2);
275  }
276 
277  // todo vertex colors
278 
279  // allocate the vertex buffer
280  vertex_data->vertexCount = input_mesh->mNumVertices;
281  Ogre::HardwareVertexBufferSharedPtr vbuf =
282  Ogre::HardwareBufferManager::getSingleton().createVertexBuffer(
283  vertex_decl->getVertexSize(0), vertex_data->vertexCount,
284  Ogre::HardwareBuffer::HBU_STATIC_WRITE_ONLY, false);
285 
286  vertex_data->vertexBufferBinding->setBinding(0, vbuf);
287  float* vertices = static_cast<float*>(vbuf->lock(Ogre::HardwareBuffer::HBL_DISCARD));
288 
289  // Add the vertices
290  for (uint32_t j = 0; j < input_mesh->mNumVertices; j++)
291  {
292  aiVector3D p = input_mesh->mVertices[j];
293  p *= transform;
294  *vertices++ = p.x;
295  *vertices++ = p.y;
296  *vertices++ = p.z;
297 
298  Ogre::Vector3 v(p.x, p.y, p.z);
299  aabb.merge(v);
300  float dist = v.length();
301  if (dist > radius)
302  {
303  radius = dist;
304  }
305 
306  if (input_mesh->HasNormals())
307  {
308  aiVector3D n = input_mesh->mNormals[j];
309  n *= rotation;
310  n.Normalize();
311  *vertices++ = n.x;
312  *vertices++ = n.y;
313  *vertices++ = n.z;
314  }
315 
316  if (input_mesh->HasTextureCoords(0))
317  {
318  *vertices++ = input_mesh->mTextureCoords[0][j].x;
319  *vertices++ = input_mesh->mTextureCoords[0][j].y;
320  }
321  }
322 
323  // calculate index count
324  submesh->indexData->indexCount = 0;
325  for (uint32_t j = 0; j < input_mesh->mNumFaces; j++)
326  {
327  aiFace& face = input_mesh->mFaces[j];
328  submesh->indexData->indexCount += face.mNumIndices;
329  }
330 
331  // If we have less than 65536 (2^16) vertices, we can use a 16-bit index buffer.
332  if (vertex_data->vertexCount < (1 << 16))
333  {
334  // allocate index buffer
335  submesh->indexData->indexBuffer = Ogre::HardwareBufferManager::getSingleton().createIndexBuffer(
336  Ogre::HardwareIndexBuffer::IT_16BIT, submesh->indexData->indexCount,
337  Ogre::HardwareBuffer::HBU_STATIC_WRITE_ONLY, false);
338 
339  Ogre::HardwareIndexBufferSharedPtr ibuf = submesh->indexData->indexBuffer;
340  uint16_t* indices = static_cast<uint16_t*>(ibuf->lock(Ogre::HardwareBuffer::HBL_DISCARD));
341 
342  // add the indices
343  for (uint32_t j = 0; j < input_mesh->mNumFaces; j++)
344  {
345  aiFace& face = input_mesh->mFaces[j];
346  for (uint32_t k = 0; k < face.mNumIndices; ++k)
347  {
348  *indices++ = face.mIndices[k];
349  }
350  }
351 
352  ibuf->unlock();
353  }
354  else
355  {
356  // Else we have more than 65536 (2^16) vertices, so we must
357  // use a 32-bit index buffer (or subdivide the mesh, which
358  // I'm too impatient to do right now)
359 
360  // allocate index buffer
361  submesh->indexData->indexBuffer = Ogre::HardwareBufferManager::getSingleton().createIndexBuffer(
362  Ogre::HardwareIndexBuffer::IT_32BIT, submesh->indexData->indexCount,
363  Ogre::HardwareBuffer::HBU_STATIC_WRITE_ONLY, false);
364 
365  Ogre::HardwareIndexBufferSharedPtr ibuf = submesh->indexData->indexBuffer;
366  uint32_t* indices = static_cast<uint32_t*>(ibuf->lock(Ogre::HardwareBuffer::HBL_DISCARD));
367 
368  // add the indices
369  for (uint32_t j = 0; j < input_mesh->mNumFaces; j++)
370  {
371  aiFace& face = input_mesh->mFaces[j];
372  for (uint32_t k = 0; k < face.mNumIndices; ++k)
373  {
374  *indices++ = face.mIndices[k];
375  }
376  }
377 
378  ibuf->unlock();
379  }
380  vbuf->unlock();
381 
382  Ogre::MaterialPtr const& material = material_table[input_mesh->mMaterialIndex];
383  submesh->setMaterialName(material->getName(), material->getGroup());
384  }
385 
386  for (uint32_t i = 0; i < node->mNumChildren; ++i)
387  {
388  buildMesh(scene, node->mChildren[i], mesh, aabb, radius, material_table, transform);
389  }
390 }
391 
392 void loadTexture(const std::string& resource_path)
393 {
394  if (!Ogre::TextureManager::getSingleton().resourceExists(resource_path))
395  {
398  try
399  {
400  res = retriever.get(resource_path);
401  }
403  {
404  ROS_ERROR("%s", e.what());
405  }
406 
407  if (res.size != 0)
408  {
409  Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size));
410  Ogre::Image image;
411  std::string extension = fs::extension(fs::path(resource_path));
412 
413  if (extension[0] == '.')
414  {
415  extension = extension.substr(1, extension.size() - 1);
416  }
417 
418  try
419  {
420  image.load(stream, extension);
421  Ogre::TextureManager::getSingleton().loadImage(
422  resource_path, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, image);
423  }
424  catch (Ogre::Exception& e)
425  {
426  ROS_ERROR("Could not load texture [%s]: %s", resource_path.c_str(), e.what());
427  }
428  }
429  }
430 }
431 
432 // Mostly cribbed from gazebo
441 void loadMaterials(const std::string& resource_path,
442  const aiScene* scene,
443  std::vector<Ogre::MaterialPtr>& material_table_out)
444 {
445 #if BOOST_FILESYSTEM_VERSION == 3
446  std::string ext = fs::path(resource_path).extension().string();
447 #else
448  std::string ext = fs::path(resource_path).extension();
449 #endif
450  boost::algorithm::to_lower(ext);
451  if (ext == ".stl" ||
452  ext == ".stlb") // STL meshes don't support proper materials: use Ogre's default material
453  {
454  material_table_out.push_back(Ogre::MaterialManager::getSingleton().getByName("BaseWhiteNoLighting"));
455  return;
456  }
457 
458  for (uint32_t i = 0; i < scene->mNumMaterials; i++)
459  {
460  std::stringstream ss;
461  ss << resource_path << "Material" << i;
462  Ogre::MaterialPtr mat = Ogre::MaterialManager::getSingleton().create(
463  ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, true);
464  material_table_out.push_back(mat);
465 
466  Ogre::Technique* tech = mat->getTechnique(0);
467  Ogre::Pass* pass = tech->getPass(0);
468 
469  aiMaterial* amat = scene->mMaterials[i];
470 
471  Ogre::ColourValue diffuse(1.0, 1.0, 1.0, 1.0);
472  Ogre::ColourValue specular(1.0, 1.0, 1.0, 1.0);
473  Ogre::ColourValue ambient(0, 0, 0, 1.0);
474 
475  for (uint32_t j = 0; j < amat->mNumProperties; j++)
476  {
477  aiMaterialProperty* prop = amat->mProperties[j];
478  std::string propKey = prop->mKey.data;
479 
480  if (propKey == "$tex.file")
481  {
482  aiString texName;
483  aiTextureMapping mapping;
484  uint32_t uvIndex;
485  amat->GetTexture(aiTextureType_DIFFUSE, 0, &texName, &mapping, &uvIndex);
486 
487  // Assume textures are in paths relative to the mesh
488  std::string texture_path = fs::path(resource_path).parent_path().string() + "/" + texName.data;
489  loadTexture(texture_path);
490  Ogre::TextureUnitState* tu = pass->createTextureUnitState();
491  tu->setTextureName(texture_path);
492  }
493  else if (propKey == "$clr.diffuse")
494  {
495  aiColor3D clr;
496  amat->Get(AI_MATKEY_COLOR_DIFFUSE, clr);
497  diffuse = Ogre::ColourValue(clr.r, clr.g, clr.b);
498  }
499  else if (propKey == "$clr.ambient")
500  {
501  aiColor3D clr;
502  amat->Get(AI_MATKEY_COLOR_AMBIENT, clr);
503  ambient = Ogre::ColourValue(clr.r, clr.g, clr.b);
504  }
505  else if (propKey == "$clr.specular")
506  {
507  aiColor3D clr;
508  amat->Get(AI_MATKEY_COLOR_SPECULAR, clr);
509  specular = Ogre::ColourValue(clr.r, clr.g, clr.b);
510  }
511  else if (propKey == "$clr.emissive")
512  {
513  aiColor3D clr;
514  amat->Get(AI_MATKEY_COLOR_EMISSIVE, clr);
515  mat->setSelfIllumination(clr.r, clr.g, clr.b);
516  }
517  else if (propKey == "$clr.opacity")
518  {
519  float o;
520  amat->Get(AI_MATKEY_OPACITY, o);
521  diffuse.a = o;
522  }
523  else if (propKey == "$mat.shininess")
524  {
525  float s;
526  amat->Get(AI_MATKEY_SHININESS, s);
527  mat->setShininess(s);
528  }
529  else if (propKey == "$mat.shadingm")
530  {
531  int model;
532  amat->Get(AI_MATKEY_SHADING_MODEL, model);
533  switch (model)
534  {
535  case aiShadingMode_Flat:
536  mat->setShadingMode(Ogre::SO_FLAT);
537  break;
538  case aiShadingMode_Phong:
539  mat->setShadingMode(Ogre::SO_PHONG);
540  break;
541  case aiShadingMode_Gouraud:
542  default:
543  mat->setShadingMode(Ogre::SO_GOURAUD);
544  break;
545  }
546  }
547  }
548 
549  int mode = aiBlendMode_Default;
550  amat->Get(AI_MATKEY_BLEND_FUNC, mode);
551  switch (mode)
552  {
553  case aiBlendMode_Additive:
554  mat->setSceneBlending(Ogre::SBT_ADD);
555  break;
556  case aiBlendMode_Default:
557  default:
558  {
559  if (diffuse.a < 0.99)
560  {
561  pass->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
562  }
563  else
564  {
565  pass->setSceneBlending(Ogre::SBT_REPLACE);
566  }
567  }
568  break;
569  }
570 
571  mat->setAmbient(ambient * 0.5);
572  mat->setDiffuse(diffuse);
573  specular.a = diffuse.a;
574  mat->setSpecular(specular);
575  }
576 }
577 
578 Ogre::MeshPtr meshFromAssimpScene(const std::string& name, const aiScene* scene)
579 {
580  if (!scene->HasMeshes())
581  {
582  ROS_ERROR("No meshes found in file [%s]", name.c_str());
583  return Ogre::MeshPtr();
584  }
585 
586  std::vector<Ogre::MaterialPtr> material_table;
587  loadMaterials(name, scene, material_table);
588 
589  Ogre::MeshPtr mesh = Ogre::MeshManager::getSingleton().createManual(
590  name, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
591 
592  Ogre::AxisAlignedBox aabb(Ogre::AxisAlignedBox::EXTENT_NULL);
593  float radius = 0.0f;
594  buildMesh(scene, scene->mRootNode, mesh, aabb, radius, material_table);
595 
596  mesh->_setBounds(aabb);
597  mesh->_setBoundingSphereRadius(radius);
598  mesh->buildEdgeList();
599 
600  mesh->load();
601 
602  return mesh;
603 }
604 
605 Ogre::MeshPtr loadMeshFromResource(const std::string& resource_path)
606 {
607  if (Ogre::MeshManager::getSingleton().resourceExists(resource_path))
608  {
609  return Ogre::MeshManager::getSingleton().getByName(resource_path);
610  }
611  else
612  {
613  fs::path model_path(resource_path);
614 #if BOOST_FILESYSTEM_VERSION == 3
615  std::string ext = model_path.extension().string();
616 #else
617  std::string ext = model_path.extension();
618 #endif
619  boost::algorithm::to_lower(ext);
620  if (ext == ".mesh")
621  {
624  try
625  {
626  res = retriever.get(resource_path);
627  }
629  {
630  ROS_ERROR("%s", e.what());
631  return Ogre::MeshPtr();
632  }
633 
634  if (res.size == 0)
635  {
636  return Ogre::MeshPtr();
637  }
638  loadSkeletonFromResource(resource_path); // load skeleton to the resource manager
639 
640  Ogre::MeshSerializer ser;
641  Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size));
642  Ogre::MeshPtr mesh = Ogre::MeshManager::getSingleton().createManual(
643  resource_path, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
644  ser.importMesh(stream, mesh.get());
645 
646  return mesh;
647  }
648  else
649  {
650  Assimp::Importer importer;
651  importer.SetIOHandler(new ResourceIOSystem());
652  const aiScene* scene =
653  importer.ReadFile(resource_path, aiProcess_SortByPType | aiProcess_FindInvalidData |
654  aiProcess_GenNormals | aiProcess_Triangulate |
655  aiProcess_GenUVCoords | aiProcess_FlipUVs);
656  if (!scene)
657  {
658  ROS_ERROR("Could not load resource [%s]: %s", resource_path.c_str(), importer.GetErrorString());
659  return Ogre::MeshPtr();
660  }
661 
662  return meshFromAssimpScene(resource_path, scene);
663  }
664  }
665 
666  return Ogre::MeshPtr();
667 }
668 
669 // Try to load .skeleton file co-located with a .mesh file
670 Ogre::SkeletonPtr loadSkeletonFromResource(const std::string& resource_path)
671 {
672  std::string skeleton_resource_path = resource_path.substr(0, resource_path.length() - 4);
673  skeleton_resource_path.append("skeleton");
674 
675  if (Ogre::SkeletonManager::getSingleton().resourceExists(skeleton_resource_path))
676  {
677  return Ogre::SkeletonManager::getSingleton().getByName(skeleton_resource_path);
678  }
679  else
680  {
683  try
684  {
685  res = retriever.get(skeleton_resource_path);
686  }
688  { // often the .skeleton file will not exist -> debug msg only
689  ROS_DEBUG("%s", e.what());
690  return Ogre::SkeletonPtr();
691  }
692 
693  if (res.size == 0)
694  {
695  return Ogre::SkeletonPtr();
696  }
697 
698  fs::path skeleton_path(skeleton_resource_path);
699 
700  Ogre::SkeletonSerializer ser;
701  Ogre::DataStreamPtr stream(new Ogre::MemoryDataStream(res.data.get(), res.size));
702  Ogre::SkeletonPtr skeleton = Ogre::SkeletonManager::getSingleton().create(
703  skeleton_path.filename().string(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, true);
704  ser.importSkeleton(stream, skeleton.get());
705 
706  return skeleton;
707  }
708 
709  return Ogre::SkeletonPtr();
710 }
711 
712 } // namespace rviz
resource_retriever::MemoryResource::size
uint32_t size
ROS_BREAK
#define ROS_BREAK()
rviz::ResourceIOSystem::Open
Assimp::IOStream * Open(const char *file, const char *mode="rb") override
Definition: mesh_loader.cpp:183
rviz::ResourceIOSystem::Exists
bool Exists(const char *file) const override
Definition: mesh_loader.cpp:158
rviz::loadSkeletonFromResource
Ogre::SkeletonPtr loadSkeletonFromResource(const std::string &resource_path)
Definition: mesh_loader.cpp:670
rviz::ResourceIOStream::ResourceIOStream
ResourceIOStream(const resource_retriever::MemoryResource &res)
Definition: mesh_loader.cpp:72
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
s
XmlRpcServer s
rviz::ResourceIOStream::Write
size_t Write(const void *, size_t, size_t) override
Definition: mesh_loader.cpp:94
rviz::ResourceIOSystem::getOsSeparator
char getOsSeparator() const override
Definition: mesh_loader.cpp:177
resource_retriever::MemoryResource
rviz::loadMaterials
void loadMaterials(const std::string &resource_path, const aiScene *scene, std::vector< Ogre::MaterialPtr > &material_table_out)
Load all materials needed by the given scene.
Definition: mesh_loader.cpp:441
rviz::ResourceIOSystem
Definition: mesh_loader.cpp:146
rviz::ResourceIOStream::FileSize
size_t FileSize() const override
Definition: mesh_loader.cpp:132
get
def get(url)
resource_retriever::MemoryResource::data
boost::shared_array< uint8_t > data
rviz::ResourceIOStream::pos_
uint8_t * pos_
Definition: mesh_loader.cpp:143
rviz::ResourceIOStream
Definition: mesh_loader.cpp:69
rviz::ResourceIOStream::Seek
aiReturn Seek(size_t offset, aiOrigin origin) override
Definition: mesh_loader.cpp:100
ROS_DEBUG
#define ROS_DEBUG(...)
rviz::ResourceIOSystem::~ResourceIOSystem
~ResourceIOSystem() override
Definition: mesh_loader.cpp:153
rviz
Definition: add_display_dialog.cpp:54
resource_retriever::Retriever::get
MemoryResource get(const std::string &url)
mesh_loader.h
resource_retriever::Retriever
rviz::ResourceIOSystem::ResourceIOSystem
ResourceIOSystem()
Definition: mesh_loader.cpp:149
rviz::ResourceIOStream::Read
size_t Read(void *buffer, size_t size, size_t count) override
Definition: mesh_loader.cpp:80
rviz::ResourceIOSystem::retriever_
resource_retriever::Retriever retriever_
Definition: mesh_loader.cpp:206
rviz::loadTexture
void loadTexture(const std::string &resource_path)
Definition: mesh_loader.cpp:392
rviz::loadMeshFromResource
Ogre::MeshPtr loadMeshFromResource(const std::string &resource_path)
Definition: mesh_loader.cpp:605
rviz::ResourceIOSystem::Close
void Close(Assimp::IOStream *stream) override
Definition: mesh_loader.cpp:209
rviz::ResourceIOStream::res_
resource_retriever::MemoryResource res_
Definition: mesh_loader.cpp:142
rviz::meshFromAssimpScene
Ogre::MeshPtr meshFromAssimpScene(const std::string &name, const aiScene *scene)
Definition: mesh_loader.cpp:578
rviz::ResourceIOStream::~ResourceIOStream
~ResourceIOStream() override
Definition: mesh_loader.cpp:76
retriever.h
ROS_ERROR
#define ROS_ERROR(...)
rviz::ResourceIOStream::Flush
void Flush() override
Definition: mesh_loader.cpp:137
rviz::ResourceIOStream::Tell
size_t Tell() const override
Definition: mesh_loader.cpp:127
resource_retriever::Exception
assert.h
ROS_ASSERT
#define ROS_ASSERT(cond)
rviz::buildMesh
void buildMesh(const aiScene *scene, const aiNode *node, const Ogre::MeshPtr &mesh, Ogre::AxisAlignedBox &aabb, float &radius, std::vector< Ogre::MaterialPtr > &material_table, aiMatrix4x4 transform=aiMatrix4x4())
Recursive mesh-building function.
Definition: mesh_loader.cpp:220


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09