fcl.cc
Go to the documentation of this file.
1 //
2 // Software License Agreement (BSD License)
3 //
4 // Copyright (c) 2019-2022 CNRS-LAAS INRIA
5 // Author: Joseph Mirabel
6 // All rights reserved.
7 //
8 // Redistribution and use in source and binary forms, with or without
9 // modification, are permitted provided that the following conditions
10 // are met:
11 //
12 // * Redistributions of source code must retain the above copyright
13 // notice, this list of conditions and the following disclaimer.
14 // * Redistributions in binary form must reproduce the above
15 // copyright notice, this list of conditions and the following
16 // disclaimer in the documentation and/or other materials provided
17 // with the distribution.
18 // * Neither the name of CNRS-LAAS. nor the names of its
19 // contributors may be used to endorse or promote products derived
20 // from this software without specific prior written permission.
21 //
22 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 // POSSIBILITY OF SUCH DAMAGE.
34 
35 #include <eigenpy/eigenpy.hpp>
36 
37 #include "fcl.hh"
38 
39 #include <hpp/fcl/fwd.hh>
41 #include <hpp/fcl/BVH/BVH_model.h>
42 
44 
45 #include <hpp/fcl/collision.h>
46 
47 #ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC
48 #include "doxygen_autodoc/hpp/fcl/mesh_loader/loader.h"
49 #endif
50 
51 #include "../doc/python/doxygen.hh"
52 #include "../doc/python/doxygen-boost.hh"
53 
54 using namespace hpp::fcl;
55 namespace dv = doxygen::visitor;
56 
57 #pragma GCC diagnostic push
58 #pragma GCC diagnostic ignored "-Wconversion"
59 BOOST_PYTHON_MEMBER_FUNCTION_OVERLOADS(load_overloads, MeshLoader::load, 1, 2)
60 #pragma GCC diagnostic pop
61 
63  using namespace boost::python;
64 
65  if (!eigenpy::register_symbolic_link_to_registered_type<MeshLoader>()) {
66  class_<MeshLoader, shared_ptr<MeshLoader> >(
67  "MeshLoader", doxygen::class_doc<MeshLoader>(),
68  init<optional<NODE_TYPE> >(
69  (arg("self"), arg("node_type")),
70  doxygen::constructor_doc<MeshLoader, const NODE_TYPE&>()))
71  .def("load", &MeshLoader::load,
72  load_overloads((arg("self"), arg("filename"), arg("scale")),
74  .def(dv::member_func("loadOctree", &MeshLoader::loadOctree));
75  }
76 
77  if (!eigenpy::register_symbolic_link_to_registered_type<CachedMeshLoader>()) {
78  class_<CachedMeshLoader, bases<MeshLoader>, shared_ptr<CachedMeshLoader> >(
79  "CachedMeshLoader", doxygen::class_doc<MeshLoader>(),
80  init<optional<NODE_TYPE> >(
81  (arg("self"), arg("node_type")),
82  doxygen::constructor_doc<CachedMeshLoader, const NODE_TYPE&>()));
83  }
84 }
85 
87  namespace bp = boost::python;
88 
89  PyImport_ImportModule("warnings");
91 
92  exposeVersion();
93  exposeMaths();
99  exposeGJK();
100 #ifdef HPP_FCL_HAS_OCTOMAP
101  exposeOctree();
102 #endif
104 }
boost::python
eigenpy.hpp
eigenpy::enableEigenPy
void EIGENPY_DLLAPI enableEigenPy()
exposeOctree
void exposeOctree()
Definition: octree.cc:11
exposeDistanceAPI
void exposeDistanceAPI()
Definition: distance.cc:61
doxygen::visitor
Definition: doxygen-boost.hh:12
fcl.hh
exposeCollisionGeometries
void exposeCollisionGeometries()
Definition: collision-geometries.cc:384
BOOST_PYTHON_MODULE
BOOST_PYTHON_MODULE(hppfcl)
Definition: fcl.cc:86
exposeVersion
void exposeVersion()
Definition: version.cc:19
exposeCollisionAPI
void exposeCollisionAPI()
Definition: collision.cc:62
exposeMeshLoader
void exposeMeshLoader()
Definition: fcl.cc:62
doxygen::visitor::member_func
member_func_impl< function_type > member_func(const char *name, const function_type &function)
Definition: doxygen-boost.hh:49
hpp::fcl
Definition: broadphase_bruteforce.h:45
exposeGJK
void exposeGJK()
Definition: gjk.cc:53
exposeMaths
void exposeMaths()
Definition: math.cc:65
exposeBroadPhase
void exposeBroadPhase()
Definition: broadphase.cc:64
exposeCollisionObject
void exposeCollisionObject()
Definition: collision-geometries.cc:631
BVH_model.h
hppfcl
Definition: __init__.py:1
fwd.hh
loader.h
hpp::fcl::MeshLoader::load
virtual BVHModelPtr_t load(const std::string &filename, const Vec3f &scale=Vec3f::Ones())
Definition: loader.cpp:68
geometric_shapes.h
hpp::fcl::MeshLoader::loadOctree
virtual CollisionGeometryPtr_t loadOctree(const std::string &filename)
Definition: loader.cpp:92
doxygen::member_func_doc
const char * member_func_doc(FuncPtr)
Definition: doxygen.hh:33
collision.h


hpp-fcl
Author(s):
autogenerated on Fri Jan 26 2024 03:46:13