broadphase.cc
Go to the documentation of this file.
1 //
2 // Software License Agreement (BSD License)
3 //
4 // Copyright (c) 2022 INRIA
5 // Author: Justin Carpentier
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 <hpp/fcl/fwd.hh>
36 #include "../fcl.hh"
37 
45 
46 #ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC
47 #include "doxygen_autodoc/functions.h"
48 #include "doxygen_autodoc/hpp/fcl/broadphase/default_broadphase_callbacks.h"
49 // #include "doxygen_autodoc/hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h"
50 // #include
51 //"doxygen_autodoc/hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h"
52 // #include "doxygen_autodoc/hpp/fcl/broadphase/broadphase_bruteforce.h"
53 // #include "doxygen_autodoc/hpp/fcl/broadphase/broadphase_SaP.h"
54 // #include "doxygen_autodoc/hpp/fcl/broadphase/broadphase_SSaP.h"
55 // #include "doxygen_autodoc/hpp/fcl/broadphase/broadphase_interval_tree.h"
56 // #include "doxygen_autodoc/hpp/fcl/broadphase/broadphase_spatialhash.h"
57 #endif
58 
59 #include "broadphase_callbacks.hh"
61 
62 using namespace hpp::fcl;
63 
67 
68  // CollisionCallBackDefault
69  bp::class_<CollisionCallBackDefault, bp::bases<CollisionCallBackBase> >(
70  "CollisionCallBackDefault", bp::no_init)
71  .def(dv::init<CollisionCallBackDefault>())
73 
74  // DistanceCallBackDefault
75  bp::class_<DistanceCallBackDefault, bp::bases<DistanceCallBackBase> >(
76  "DistanceCallBackDefault", bp::no_init)
77  .def(dv::init<DistanceCallBackDefault>())
79 
80  // CollisionCallBackCollect
81  bp::class_<CollisionCallBackCollect, bp::bases<CollisionCallBackBase> >(
82  "CollisionCallBackCollect", bp::no_init)
83  .def(dv::init<CollisionCallBackCollect, const size_t>())
84  .DEF_CLASS_FUNC(CollisionCallBackCollect, numCollisionPairs)
85  .DEF_CLASS_FUNC2(CollisionCallBackCollect, getCollisionPairs,
86  bp::return_value_policy<bp::copy_const_reference>())
88 
89  bp::class_<CollisionData>("CollisionData", bp::no_init)
90  .def(dv::init<CollisionData>())
91  .DEF_RW_CLASS_ATTRIB(CollisionData, request)
92  .DEF_RW_CLASS_ATTRIB(CollisionData, result)
93  .DEF_RW_CLASS_ATTRIB(CollisionData, done)
94  .DEF_CLASS_FUNC(CollisionData, clear);
95 
96  bp::class_<DistanceData>("DistanceData", bp::no_init)
97  .def(dv::init<DistanceData>())
98  .DEF_RW_CLASS_ATTRIB(DistanceData, request)
99  .DEF_RW_CLASS_ATTRIB(DistanceData, result)
100  .DEF_RW_CLASS_ATTRIB(DistanceData, done)
101  .DEF_CLASS_FUNC(DistanceData, clear);
102 
104 
111  BroadPhaseCollisionManagerWrapper::exposeDerived<SSaPCollisionManager>();
112  BroadPhaseCollisionManagerWrapper::exposeDerived<SaPCollisionManager>();
113  BroadPhaseCollisionManagerWrapper::exposeDerived<NaiveCollisionManager>();
114 
115  // Specific case of SpatialHashingCollisionManager
116  {
119  HashTable;
121  bp::class_<Derived, bp::bases<BroadPhaseCollisionManager> >(
122  "SpatialHashingCollisionManager", bp::no_init)
123  .def(dv::init<Derived, FCL_REAL, const Vec3f &, const Vec3f &,
124  bp::optional<unsigned int> >());
125  }
126 }
broadphase_collision_manager.hh
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
hpp::fcl::BroadPhaseCollisionManagerWrapper::exposeDerived
static void exposeDerived()
Definition: broadphase_collision_manager.hh:217
hpp::fcl::SpatialHashingCollisionManager
spatial hashing collision mananger
Definition: broadphase_spatialhash.h:55
hpp::fcl::BroadPhaseCollisionManagerWrapper::expose
static void expose()
Definition: broadphase_collision_manager.hh:123
hpp::fcl::CollisionData
Collision data stores the collision request and the result given by collision algorithm.
Definition: default_broadphase_callbacks.h:56
data
data
doxygen::def
void def(const char *name, Func func)
Definition: doxygen-boost.hh:106
broadphase_spatialhash.h
DEF_RW_CLASS_ATTRIB
#define DEF_RW_CLASS_ATTRIB(CLASS, ATTRIB)
Definition: python/fwd.hh:29
hpp::fcl::DynamicAABBTreeCollisionManager
Definition: broadphase_dynamic_AABB_tree.h:54
hpp::fcl::detail::SpatialHash
Spatial hash function: hash an AABB to a set of integer values.
Definition: spatial_hash.h:50
hpp::fcl::FCL_REAL
double FCL_REAL
Definition: data_types.h:65
hpp::fcl::DistanceCallBackDefault
Default distance callback to check collision between collision objects.
Definition: default_broadphase_callbacks.h:211
DEF_CLASS_FUNC
#define DEF_CLASS_FUNC(CLASS, ATTRIB)
Definition: python/fwd.hh:35
hpp::fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: collision_object.h:215
hpp::fcl::CollisionCallBackBaseWrapper::expose
static void expose()
Definition: broadphase_callbacks.hh:65
broadphase_dynamic_AABB_tree_array.h
hpp::fcl::CollisionCallBackCollect
Collision callback to collect collision pairs potentially in contacts.
Definition: default_broadphase_callbacks.h:224
hpp::fcl::AABB
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: BV/AABB.h:54
broadphase_SaP.h
broadphase_interval_tree.h
hpp::fcl
Definition: broadphase_bruteforce.h:45
hpp::fcl::CollisionCallBackDefault
Default collision callback to check collision between collision objects.
Definition: default_broadphase_callbacks.h:197
exposeBroadPhase
void exposeBroadPhase()
Definition: broadphase.cc:64
broadphase_dynamic_AABB_tree.h
broadphase_SSaP.h
fwd.hh
hpp::fcl::DynamicAABBTreeArrayCollisionManager
Definition: broadphase_dynamic_AABB_tree_array.h:55
hpp::fcl::detail::SimpleHashTable
A simple hash table implemented as multiple buckets. HashFnc is any extended hash function: HashFnc(k...
Definition: simple_hash_table.h:53
broadphase_callbacks.hh
hpp::fcl::DistanceData
Distance data stores the distance request and the result given by distance algorithm.
Definition: default_broadphase_callbacks.h:77
broadphase_bruteforce.h
hpp::fcl::IntervalTreeCollisionManager
Collision manager based on interval tree.
Definition: broadphase_interval_tree.h:51
hpp::fcl::DistanceCallBackBaseWrapper::expose
static void expose()
Definition: broadphase_callbacks.hh:95


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