#include <loader.h>
Public Member Functions | |
virtual BVHModelPtr_t | load (const std::string &filename, const Vec3f &scale=Vec3f::Ones()) |
virtual CollisionGeometryPtr_t | loadOctree (const std::string &filename) |
MeshLoader (const NODE_TYPE &bvType=BV_OBBRSS) | |
virtual | ~MeshLoader () |
Private Attributes | |
const NODE_TYPE | bvType_ |
Base class for building polyhedron from files. This class builds a new object for each file.
|
virtual |
Reimplemented in hpp::fcl::CachedMeshLoader.
Definition at line 68 of file loader.cpp.
|
virtual |
Create an OcTree from a file in binary octomap format.
Definition at line 92 of file loader.cpp.