Unverified Commit ab128713 authored by Joseph Mirabel's avatar Joseph Mirabel Committed by GitHub
Browse files

Merge pull request #155 from jmirabel/devel

Add MeshLoader::loadOctree
parents 670ffb66 c36547ff
...@@ -57,6 +57,10 @@ namespace fcl { ...@@ -57,6 +57,10 @@ namespace fcl {
virtual BVHModelPtr_t load (const std::string& filename, virtual BVHModelPtr_t load (const std::string& filename,
const Vec3f& scale = Vec3f::Ones()); const Vec3f& scale = Vec3f::Ones());
/// Create an OcTree from a file in binary octomap format.
/// \todo add OctreePtr_t
virtual CollisionGeometryPtr_t loadOctree (const std::string& filename);
MeshLoader (const NODE_TYPE& bvType = BV_OBBRSS) : bvType_ (bvType) {} MeshLoader (const NODE_TYPE& bvType = BV_OBBRSS) : bvType_ (bvType) {}
private: private:
......
...@@ -51,8 +51,10 @@ ...@@ -51,8 +51,10 @@
#endif #endif
#include "../doc/python/doxygen.hh" #include "../doc/python/doxygen.hh"
#include "../doc/python/doxygen-boost.hh"
using namespace hpp::fcl; using namespace hpp::fcl;
namespace dv = doxygen::visitor;
BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(load_overloads,MeshLoader::load,1,2) BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(load_overloads,MeshLoader::load,1,2)
...@@ -69,6 +71,7 @@ void exposeMeshLoader () ...@@ -69,6 +71,7 @@ void exposeMeshLoader ()
.def ("load",&MeshLoader::load, .def ("load",&MeshLoader::load,
load_overloads((arg("self"),arg("filename"),arg("scale")), load_overloads((arg("self"),arg("filename"),arg("scale")),
doxygen::member_func_doc(&MeshLoader::load))) doxygen::member_func_doc(&MeshLoader::load)))
.def (dv::member_func("loadOctree",&MeshLoader::loadOctree))
; ;
} }
......
...@@ -37,6 +37,10 @@ ...@@ -37,6 +37,10 @@
#include <hpp/fcl/mesh_loader/loader.h> #include <hpp/fcl/mesh_loader/loader.h>
#include <hpp/fcl/mesh_loader/assimp.h> #include <hpp/fcl/mesh_loader/assimp.h>
#ifdef HPP_FCL_HAVE_OCTOMAP
# include <hpp/fcl/octree.h>
#endif
#include <hpp/fcl/BV/BV.h> #include <hpp/fcl/BV/BV.h>
namespace hpp namespace hpp
...@@ -77,6 +81,16 @@ namespace fcl { ...@@ -77,6 +81,16 @@ namespace fcl {
} }
} }
CollisionGeometryPtr_t MeshLoader::loadOctree (const std::string& filename)
{
#ifdef HPP_FCL_HAVE_OCTOMAP
boost::shared_ptr<octomap::OcTree> octree (new octomap::OcTree (filename));
return CollisionGeometryPtr_t (new hpp::fcl::OcTree (octree));
#else
throw std::logic_error("hpp-fcl compiled without OctoMap. Cannot create OcTrees.");
#endif
}
BVHModelPtr_t CachedMeshLoader::load (const std::string& filename, BVHModelPtr_t CachedMeshLoader::load (const std::string& filename,
const Vec3f& scale) const Vec3f& scale)
{ {
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment