expose-broadphase.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2022 INRIA
3 //
4 
7 
9 
11 
19 
20 namespace pinocchio
21 {
22  namespace python
23  {
24  void exposeBroadphaseCallbacks(); // fwd
25 
26  template<typename BroadPhaseManager>
28  {
29 
30  typedef BroadPhaseManager Manager;
31  typedef BroadPhaseManagerBase<BroadPhaseManager> BaseManager;
32 
33  bp::def(
34  "computeCollisions", (bool (*)(BaseManager &, CollisionCallBackBase *)) & computeCollisions,
35  (bp::arg("manager"), bp::arg("callback")),
36  "Determine if all collision pairs are effectively in collision or not.\n"
37  "This function assumes that updateGeometryPlacements and broadphase_manager.update() "
38  "have been called first.");
39 
40  bp::def(
41  "computeCollisions", (bool (*)(BaseManager &, const bool)) & computeCollisions,
42  (bp::arg("manager"), bp::arg("stop_at_first_collision") = false),
43  "Determine if all collision pairs are effectively in collision or not.\n"
44  "This function assumes that updateGeometryPlacements and broadphase_manager.update() "
45  "have been called first.");
46 
47  bp::def(
48  "computeCollisions",
49  (bool (*)(
50  const Model &, Data &, BaseManager &, const Eigen::MatrixBase<Eigen::VectorXd> &,
51  const bool))
52  & computeCollisions<double, 0, JointCollectionDefaultTpl, Manager, Eigen::VectorXd>,
53  (bp::arg("model"), bp::arg("data"), bp::arg("broadphase_manager"), bp::arg("q"),
54  bp::arg("stop_at_first_collision") = false),
55  "Compute the forward kinematics, update the geometry placements and run the "
56  "collision detection using the broadphase manager.");
57 
58  bp::def(
59  "computeCollisions",
60  (bool (*)(
61  const Model &, Data &, BaseManager &, CollisionCallBackBase *,
62  const Eigen::MatrixBase<Eigen::VectorXd> &))
63  & computeCollisions<double, 0, JointCollectionDefaultTpl, Manager, Eigen::VectorXd>,
64  (bp::arg("model"), bp::arg("data"), bp::arg("broadphase_manager"), bp::arg("callback"),
65  bp::arg("q")),
66  "Compute the forward kinematics, update the geometry placements and run the "
67  "collision detection using the broadphase manager.");
68  }
69 
70  template<typename BroadPhaseManager>
72  {
74  _exposeBroadphaseAlgo<BroadPhaseManagerTpl<BroadPhaseManager>>();
75 
77  _exposeBroadphaseAlgo<TreeBroadPhaseManagerTpl<BroadPhaseManager>>();
78  }
79 
81  {
82  using namespace Eigen;
84 
85  typedef ::hpp::fcl::CollisionObject * CollisionObjectPointer;
87  "StdVec_FCL_CollisionObjectPointer");
88  StdVectorPythonVisitor<std::vector<CollisionObject>>::expose("StdVec_CollisionObject");
89 
90  exposeBroadphaseAlgo<hpp::fcl::DynamicAABBTreeCollisionManager>();
91  exposeBroadphaseAlgo<hpp::fcl::DynamicAABBTreeArrayCollisionManager>();
92  exposeBroadphaseAlgo<hpp::fcl::SSaPCollisionManager>();
93  exposeBroadphaseAlgo<hpp::fcl::SaPCollisionManager>();
94  exposeBroadphaseAlgo<hpp::fcl::NaiveCollisionManager>();
95  exposeBroadphaseAlgo<hpp::fcl::IntervalTreeCollisionManager>();
96  // exposeBroadphaseAlgo<hpp::fcl::SpatialHashingCollisionManager<> >();
97  }
98  } // namespace python
99 } // namespace pinocchio
broadphase_dynamic_AABB_tree.h
broadphase_dynamic_AABB_tree_array.h
Eigen
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::computeCollisions
bool computeCollisions(BroadPhaseManagerBase< BroadPhaseManagerDerived > &broadphase_manager, CollisionCallBackBase *callback)
Calls computeCollision for every active pairs of GeometryData. This function assumes that updateGeome...
Definition: broadphase.hpp:34
pinocchio::BroadPhaseManagerBase
Definition: collision/broadphase-manager-base.hpp:15
eigenpy::StdVectorPythonVisitor
broadphase_bruteforce.h
CollisionObject
CollisionObject(const shared_ptr< CollisionGeometry > &cgeom_, bool compute_local_aabb=true)
pinocchio::python::exposeBroadphaseCallbacks
void exposeBroadphaseCallbacks()
Definition: expose-broadphase-callbacks.cpp:70
pinocchio::python::exposeBroadphaseAlgo
void exposeBroadphaseAlgo()
Definition: expose-broadphase.cpp:71
broadphase-manager.hpp
pinocchio::python::_exposeBroadphaseAlgo
void _exposeBroadphaseAlgo()
Definition: expose-broadphase.cpp:27
pinocchio::CollisionCallBackBase
Interface for Pinocchio collision callback functors.
Definition: broadphase-callbacks.hpp:19
broadphase.hpp
broadphase_SSaP.h
python
pinocchio::python::TreeBroadPhaseManagerPythonVisitor::expose
static void expose()
Definition: bindings/python/collision/tree-broadphase-manager.hpp:49
tree-broadphase-manager.hpp
broadphase_SaP.h
pinocchio::python::BroadPhaseManagerPythonVisitor::expose
static void expose()
Definition: bindings/python/collision/broadphase-manager.hpp:62
std-vector.hpp
pinocchio::ModelTpl
Definition: context/generic.hpp:20
broadphase_interval_tree.h
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::python::exposeBroadphase
void exposeBroadphase()
Definition: expose-broadphase.cpp:80
broadphase_spatialhash.h


pinocchio
Author(s):
autogenerated on Wed Jun 19 2024 02:41:13