Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
Guilhem Saurel
hpp-fcl
Commits
ab128713
Unverified
Commit
ab128713
authored
Apr 20, 2020
by
Joseph Mirabel
Committed by
GitHub
Apr 20, 2020
Browse files
Merge pull request #155 from jmirabel/devel
Add MeshLoader::loadOctree
parents
670ffb66
c36547ff
Changes
3
Show whitespace changes
Inline
Side-by-side
include/hpp/fcl/mesh_loader/loader.h
View file @
ab128713
...
...
@@ -57,6 +57,10 @@ namespace fcl {
virtual
BVHModelPtr_t
load
(
const
std
::
string
&
filename
,
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
)
{}
private:
...
...
python/fcl.cc
View file @
ab128713
...
...
@@ -51,8 +51,10 @@
#endif
#include
"../doc/python/doxygen.hh"
#include
"../doc/python/doxygen-boost.hh"
using
namespace
hpp
::
fcl
;
namespace
dv
=
doxygen
::
visitor
;
BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS
(
load_overloads
,
MeshLoader
::
load
,
1
,
2
)
...
...
@@ -69,6 +71,7 @@ void exposeMeshLoader ()
.
def
(
"load"
,
&
MeshLoader
::
load
,
load_overloads
((
arg
(
"self"
),
arg
(
"filename"
),
arg
(
"scale"
)),
doxygen
::
member_func_doc
(
&
MeshLoader
::
load
)))
.
def
(
dv
::
member_func
(
"loadOctree"
,
&
MeshLoader
::
loadOctree
))
;
}
...
...
src/mesh_loader/loader.cpp
View file @
ab128713
...
...
@@ -37,6 +37,10 @@
#include
<hpp/fcl/mesh_loader/loader.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>
namespace
hpp
...
...
@@ -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
,
const
Vec3f
&
scale
)
{
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment