Commit f1063e87 authored by Joseph Mirabel's avatar Joseph Mirabel
Browse files

[Python] Remove MeshLoader (provided by hppfcl)

parent 87e8e27f
......@@ -83,7 +83,6 @@ IF(NOT BUILD_WITH_HPP_FCL_SUPPORT)
multibody/fcl/collision-result.hpp
multibody/fcl/distance-result.hpp
multibody/fcl/collision-geometry.hpp
multibody/fcl/mesh-loader.hpp
multibody/fcl/transform.hpp
)
......
......@@ -7,7 +7,6 @@
#include "pinocchio/bindings/python/multibody/fcl/collision-result.hpp"
#include "pinocchio/bindings/python/multibody/fcl/distance-result.hpp"
#include "pinocchio/bindings/python/multibody/fcl/collision-geometry.hpp"
#include "pinocchio/bindings/python/multibody/fcl/mesh-loader.hpp"
#include "pinocchio/bindings/python/multibody/fcl/transform.hpp"
#include "pinocchio/bindings/python/utils/std-vector.hpp"
......@@ -90,17 +89,6 @@ namespace pinocchio
CollisionGeometryPythonVisitor::expose();
}
typedef ::hpp::fcl::MeshLoader MeshLoader;
typedef ::hpp::fcl::CachedMeshLoader CachedMeshLoader;
if(!eigenpy::register_symbolic_link_to_registered_type<MeshLoader>())
MeshLoaderPythonVisitor<MeshLoader>::
expose("Class to create CollisionGeometry from mesh files.");
if(!eigenpy::register_symbolic_link_to_registered_type<CachedMeshLoader>())
MeshLoaderPythonVisitor<CachedMeshLoader>::
expose("Class to create CollisionGeometry from mesh files with cache mechanism.");
typedef ::hpp::fcl::Transform3f Transform3f;
// Register implicit conversion SE3 <=> ::hpp::fcl::Transform3f
......
//
// Copyright (c) 2017-2020 CNRS INRIA
//
#ifndef __pinocchio_python_fcl_mesh_loader_hpp__
#define __pinocchio_python_fcl_mesh_loader_hpp__
#include "pinocchio/spatial/fcl-pinocchio-conversions.hpp"
#include <hpp/fcl/mesh_loader/loader.h>
#include <boost/python.hpp>
#include <boost/python/type_id.hpp>
namespace pinocchio
{
namespace python
{
namespace fcl
{
namespace bp = boost::python;
template<typename MeshLoader>
struct MeshLoaderPythonVisitor
: public bp::def_visitor< MeshLoaderPythonVisitor<MeshLoader> >
{
typedef boost::shared_ptr<MeshLoader> MeshLoaderPtr_t;
template <typename T>
static boost::shared_ptr<T> create()
{
return boost::shared_ptr<T>(new T);
}
template<class PyClass>
void visit(PyClass& cl) const
{
cl
.def(bp::init<>(bp::arg("self"),"Default constructor"))
.def("create",&MeshLoaderPythonVisitor::create<MeshLoader>,"Create a new object.")
.staticmethod("create")
;
}
static void expose(const std::string & doc = "")
{
static const bp::type_info info = bp::type_id<MeshLoader>();
static const std::string class_name = info.name();
static const std::string class_name_without_namespace = class_name.substr(class_name.find_last_of(':')+1);
bp::class_<MeshLoader, MeshLoaderPtr_t>
(class_name_without_namespace.c_str(),
doc.c_str(),
bp::no_init)
.def(MeshLoaderPythonVisitor())
;
}
};
} // namespace fcl
} // namespace python
} // namespace pinocchio
#endif // namespace __pinocchio_python_fcl_mesh_loader_hpp__
Supports Markdown
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