| Directory: | ./ |
|---|---|
| File: | bindings/python/collision/expose-broadphase.cpp |
| Date: | 2025-02-12 21:03:38 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 29 | 29 | 100.0% |
| Branches: | 32 | 64 | 50.0% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // | ||
| 2 | // Copyright (c) 2022 INRIA | ||
| 3 | // | ||
| 4 | |||
| 5 | #include "pinocchio/bindings/python/collision/broadphase-manager.hpp" | ||
| 6 | #include "pinocchio/bindings/python/collision/tree-broadphase-manager.hpp" | ||
| 7 | |||
| 8 | #include "pinocchio/bindings/python/utils/std-vector.hpp" | ||
| 9 | |||
| 10 | #include "pinocchio/collision/broadphase.hpp" | ||
| 11 | |||
| 12 | #include <hpp/fcl/broadphase/broadphase_dynamic_AABB_tree.h> | ||
| 13 | #include <hpp/fcl/broadphase/broadphase_dynamic_AABB_tree_array.h> | ||
| 14 | #include <hpp/fcl/broadphase/broadphase_SSaP.h> | ||
| 15 | #include <hpp/fcl/broadphase/broadphase_SaP.h> | ||
| 16 | #include <hpp/fcl/broadphase/broadphase_bruteforce.h> | ||
| 17 | #include <hpp/fcl/broadphase/broadphase_interval_tree.h> | ||
| 18 | #include <hpp/fcl/broadphase/broadphase_spatialhash.h> | ||
| 19 | |||
| 20 | namespace pinocchio | ||
| 21 | { | ||
| 22 | namespace python | ||
| 23 | { | ||
| 24 | void exposeBroadphaseCallbacks(); // fwd | ||
| 25 | |||
| 26 | template<typename BroadPhaseManager> | ||
| 27 | 1560 | void _exposeBroadphaseAlgo() | |
| 28 | { | ||
| 29 | |||
| 30 | typedef BroadPhaseManager Manager; | ||
| 31 | typedef BroadPhaseManagerBase<BroadPhaseManager> BaseManager; | ||
| 32 | |||
| 33 |
2/4✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 780 times.
✗ Branch 5 not taken.
|
1560 | bp::def( |
| 34 | "computeCollisions", (bool (*)(BaseManager &, CollisionCallBackBase *))&computeCollisions, | ||
| 35 |
1/2✓ Branch 2 taken 780 times.
✗ Branch 3 not taken.
|
3120 | (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 |
1/2✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
|
1560 | bp::def( |
| 41 | "computeCollisions", (bool (*)(BaseManager &, const bool))&computeCollisions, | ||
| 42 |
3/6✓ Branch 2 taken 780 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 780 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 780 times.
✗ Branch 9 not taken.
|
3120 | (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 |
4/8✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 780 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 780 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 780 times.
✗ Branch 11 not taken.
|
6240 | bp::def( |
| 48 | "computeCollisions", | ||
| 49 | (bool (*)( | ||
| 50 | const Model &, Data &, BaseManager &, const Eigen::MatrixBase<Eigen::VectorXd> &, | ||
| 51 | const bool))&computeCollisions<double, 0, JointCollectionDefaultTpl, Manager, Eigen::VectorXd>, | ||
| 52 |
3/6✓ Branch 2 taken 780 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 780 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 780 times.
✗ Branch 9 not taken.
|
6240 | (bp::arg("model"), bp::arg("data"), bp::arg("broadphase_manager"), bp::arg("q"), |
| 53 |
3/6✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 780 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 780 times.
✗ Branch 8 not taken.
|
3120 | bp::arg("stop_at_first_collision") = false), |
| 54 | "Compute the forward kinematics, update the geometry placements and run the " | ||
| 55 | "collision detection using the broadphase manager."); | ||
| 56 | |||
| 57 |
5/10✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 780 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 780 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 780 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 780 times.
✗ Branch 14 not taken.
|
6240 | bp::def( |
| 58 | "computeCollisions", | ||
| 59 | (bool (*)( | ||
| 60 | const Model &, Data &, BaseManager &, CollisionCallBackBase *, | ||
| 61 | const Eigen::MatrixBase< | ||
| 62 | Eigen:: | ||
| 63 | VectorXd> &))&computeCollisions<double, 0, JointCollectionDefaultTpl, Manager, Eigen::VectorXd>, | ||
| 64 |
3/6✓ Branch 2 taken 780 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 780 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 780 times.
✗ Branch 9 not taken.
|
6240 | (bp::arg("model"), bp::arg("data"), bp::arg("broadphase_manager"), bp::arg("callback"), |
| 65 |
1/2✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
|
3120 | bp::arg("q")), |
| 66 | "Compute the forward kinematics, update the geometry placements and run the " | ||
| 67 | "collision detection using the broadphase manager."); | ||
| 68 | 1560 | } | |
| 69 | |||
| 70 | template<typename BroadPhaseManager> | ||
| 71 | 780 | void exposeBroadphaseAlgo() | |
| 72 | { | ||
| 73 | 780 | BroadPhaseManagerPythonVisitor<BroadPhaseManager>::expose(); | |
| 74 | 780 | _exposeBroadphaseAlgo<BroadPhaseManagerTpl<BroadPhaseManager>>(); | |
| 75 | |||
| 76 | 780 | TreeBroadPhaseManagerPythonVisitor<BroadPhaseManager>::expose(); | |
| 77 | 780 | _exposeBroadphaseAlgo<TreeBroadPhaseManagerTpl<BroadPhaseManager>>(); | |
| 78 | 780 | } | |
| 79 | |||
| 80 | 65 | void exposeBroadphase() | |
| 81 | { | ||
| 82 | using namespace Eigen; | ||
| 83 | 65 | exposeBroadphaseCallbacks(); | |
| 84 | |||
| 85 | typedef ::hpp::fcl::CollisionObject * CollisionObjectPointer; | ||
| 86 |
3/6✓ Branch 2 taken 65 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 65 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 65 times.
✗ Branch 10 not taken.
|
65 | StdVectorPythonVisitor<std::vector<CollisionObjectPointer>>::expose( |
| 87 | "StdVec_FCL_CollisionObjectPointer"); | ||
| 88 |
3/6✓ Branch 2 taken 65 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 65 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 65 times.
✗ Branch 10 not taken.
|
65 | StdVectorPythonVisitor<std::vector<CollisionObject>>::expose("StdVec_CollisionObject"); |
| 89 | |||
| 90 | 65 | exposeBroadphaseAlgo<hpp::fcl::DynamicAABBTreeCollisionManager>(); | |
| 91 | 65 | exposeBroadphaseAlgo<hpp::fcl::DynamicAABBTreeArrayCollisionManager>(); | |
| 92 | 65 | exposeBroadphaseAlgo<hpp::fcl::SSaPCollisionManager>(); | |
| 93 | 65 | exposeBroadphaseAlgo<hpp::fcl::SaPCollisionManager>(); | |
| 94 | 65 | exposeBroadphaseAlgo<hpp::fcl::NaiveCollisionManager>(); | |
| 95 | 65 | exposeBroadphaseAlgo<hpp::fcl::IntervalTreeCollisionManager>(); | |
| 96 | // exposeBroadphaseAlgo<hpp::fcl::SpatialHashingCollisionManager<> >(); | ||
| 97 | 65 | } | |
| 98 | } // namespace python | ||
| 99 | } // namespace pinocchio | ||
| 100 |