| Directory: | ./ |
|---|---|
| File: | include/pinocchio/bindings/python/collision/broadphase-manager-base.hpp |
| Date: | 2025-02-12 21:03:38 |
| Exec | Total | Coverage | |
|---|---|---|---|
| Lines: | 22 | 26 | 84.6% |
| Branches: | 25 | 50 | 50.0% |
| Line | Branch | Exec | Source |
|---|---|---|---|
| 1 | // | ||
| 2 | // Copyright (c) 2022 INRIA | ||
| 3 | // | ||
| 4 | |||
| 5 | #ifndef __pinocchio_python_collision_broadphase_manager_base_hpp__ | ||
| 6 | #define __pinocchio_python_collision_broadphase_manager_base_hpp__ | ||
| 7 | |||
| 8 | #include "pinocchio/collision/broadphase-manager-base.hpp" | ||
| 9 | |||
| 10 | #include <eigenpy/eigen-to-python.hpp> | ||
| 11 | |||
| 12 | namespace pinocchio | ||
| 13 | { | ||
| 14 | namespace python | ||
| 15 | { | ||
| 16 | namespace bp = boost::python; | ||
| 17 | |||
| 18 | template<typename Derived> | ||
| 19 | struct BroadPhaseManagerBasePythonVisitor | ||
| 20 | : public bp::def_visitor<BroadPhaseManagerBasePythonVisitor<Derived>> | ||
| 21 | { | ||
| 22 | typedef Derived Self; | ||
| 23 | |||
| 24 | typedef typename Derived::GeometryModel GeometryModel; | ||
| 25 | typedef typename Derived::Model Model; | ||
| 26 | |||
| 27 | ✗ | static Model & getModel(const Self & self) | |
| 28 | { | ||
| 29 | ✗ | return const_cast<Model &>(self.getModel()); | |
| 30 | } | ||
| 31 | |||
| 32 | ✗ | static GeometryModel & getGeometryModel(const Self & self) | |
| 33 | { | ||
| 34 | ✗ | return const_cast<GeometryModel &>(self.getGeometryModel()); | |
| 35 | } | ||
| 36 | |||
| 37 | /* --- Exposing C++ API to python through the handler ----------------- */ | ||
| 38 | template<class PyClass> | ||
| 39 | 1560 | void visit(PyClass & cl) const | |
| 40 | { | ||
| 41 | |||
| 42 |
1/2✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
|
1560 | cl.def( |
| 43 |
1/2✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
|
1560 | "getModel", getModel, bp::arg("self"), "Returns the related model.", |
| 44 | 1560 | bp::return_internal_reference<>()) | |
| 45 |
1/2✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
|
1560 | .def( |
| 46 |
1/2✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
|
1560 | "getGeometryModel", getGeometryModel, bp::arg("self"), |
| 47 | 1560 | "Returns the related geometry model.", bp::return_internal_reference<>()) | |
| 48 | 3120 | .def( | |
| 49 | "getGeometryData", (GeometryData & (Self::*)()) & Self::getGeometryData, | ||
| 50 |
1/2✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
|
1560 | bp::arg("self"), "Returns the related geometry data.", |
| 51 | 1560 | bp::return_internal_reference<>()) | |
| 52 | |||
| 53 |
2/4✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 780 times.
✗ Branch 5 not taken.
|
3120 | .def( |
| 54 |
1/2✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
|
3120 | "check", (bool(Self::*)() const) & Self::check, bp::arg("self"), |
| 55 | "Check whether the base broad phase manager is aligned with the current " | ||
| 56 | "collision_objects.") | ||
| 57 |
2/4✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 780 times.
✗ Branch 5 not taken.
|
3120 | .def( |
| 58 | "check", (bool(Self::*)(CollisionCallBackBase *) const) & Self::check, | ||
| 59 | bp::args("self", "callback"), "Check whether the callback is inline with *this.") | ||
| 60 | |||
| 61 |
1/2✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
|
1560 | .def( |
| 62 | "update", (void(Self::*)(const bool)) & Self::update, | ||
| 63 |
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.
|
3120 | (bp::arg("self"), bp::arg("compute_local_aabb") = false), |
| 64 | "Update the manager from the current geometry positions and update the underlying " | ||
| 65 | "FCL broad phase manager.") | ||
| 66 |
2/4✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 780 times.
✗ Branch 5 not taken.
|
1560 | .def( |
| 67 | "update", (void(Self::*)(GeometryData * geom_data_new)) & Self::update, | ||
| 68 |
2/4✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 780 times.
✗ Branch 5 not taken.
|
3120 | (bp::arg("self"), bp::arg("geom_data_new")), |
| 69 | 1560 | "Update the manager with a new geometry data.", bp::with_custodian_and_ward<1, 2>()) | |
| 70 | |||
| 71 |
2/4✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 780 times.
✗ Branch 5 not taken.
|
3120 | .def( |
| 72 | "collide", | ||
| 73 | (bool(Self::*)(CollisionObject &, CollisionCallBackBase *) const) & Self::collide, | ||
| 74 | bp::args("self", "collision_object", "callback"), | ||
| 75 | "Performs collision test between one object and all the objects belonging to the " | ||
| 76 | "manager.") | ||
| 77 |
2/4✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 780 times.
✗ Branch 5 not taken.
|
3120 | .def( |
| 78 | "collide", (bool(Self::*)(CollisionCallBackBase *) const) & Self::collide, | ||
| 79 | bp::args("self", "callback"), | ||
| 80 | "Performs collision test for the objects belonging to the manager.") | ||
| 81 |
2/4✓ Branch 1 taken 780 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 780 times.
✗ Branch 5 not taken.
|
1560 | .def( |
| 82 | "collide", (bool(Self::*)(Self &, CollisionCallBackBase *) const) & Self::collide, | ||
| 83 | bp::args("self", "other_manager", "callback"), | ||
| 84 | "Performs collision test with objects belonging to another manager."); | ||
| 85 | 1560 | } | |
| 86 | }; | ||
| 87 | |||
| 88 | } // namespace python | ||
| 89 | } // namespace pinocchio | ||
| 90 | |||
| 91 | #endif // ifndef __pinocchio_python_collision_broadphase_manager_base_hpp__ | ||
| 92 |