GCC Code Coverage Report


Directory: ./
File: bindings/python/collision/expose-broadphase-callbacks.cpp
Date: 2025-02-12 21:03:38
Exec Total Coverage
Lines: 29 31 93.5%
Branches: 17 34 50.0%

Line Branch Exec Source
1 //
2 // Copyright (c) 2022 INRIA
3 //
4
5 #include <eigenpy/eigenpy.hpp>
6
7 #include "pinocchio/collision/broadphase-callbacks.hpp"
8
9 namespace bp = boost::python;
10
11 namespace pinocchio
12 {
13 namespace python
14 {
15
16 struct CollisionCallBackBaseWrapper
17 : CollisionCallBackBase
18 , bp::wrapper<CollisionCallBackBase>
19 {
20 typedef CollisionCallBackBase Base;
21
22 bool stop() const
23 {
24 return this->get_override("stop")();
25 }
26 void done()
27 {
28 if (bp::override done = this->get_override("done"))
29 done();
30 Base::done();
31 }
32
33 void done_default()
34 {
35 return this->Base::done();
36 }
37
38 65 static void expose()
39 {
40 65 bp::class_<
41 CollisionCallBackBaseWrapper, bp::bases<hpp::fcl::CollisionCallBackBase>,
42 boost::noncopyable>("CollisionCallBackBase", bp::no_init)
43
1/2
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
65 .def(
44
1/2
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
65 "getGeometryModel", &CollisionCallBackDefault::getGeometryModel, bp::arg("self"),
45 65 bp::return_value_policy<bp::copy_const_reference>())
46 130 .def(
47 "getGeometryData",
48 (GeometryData & (CollisionCallBackDefault::*)())
49 & CollisionCallBackDefault::getGeometryData,
50
1/2
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
130 bp::arg("self"), bp::return_internal_reference<>())
51
52
1/2
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
65 .def_readonly(
53
1/2
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
65 "collision", &CollisionCallBackDefault::collision,
54 "Whether there is a collision or not.")
55 130 .def_readonly(
56
1/2
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
65 "accumulate", &CollisionCallBackDefault::accumulate,
57 "Whether the callback is used in an accumulate mode where several collide "
58 "methods are called successively.")
59
60
2/4
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 65 times.
✗ Branch 5 not taken.
65 .def(
61
1/2
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
130 "stop", bp::pure_virtual(&Base::stop), bp::arg("self"),
62 "If true, the stopping criteria related to the collision callback has been met and "
63 "one can stop.")
64 65 .def(
65
1/2
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
65 "done", &Base::done, &CollisionCallBackBaseWrapper::done_default,
66 "Callback method called after the termination of a collisition detection algorithm.");
67 65 }
68 };
69
70 65 void exposeBroadphaseCallbacks()
71 {
72 65 CollisionCallBackBaseWrapper::expose();
73
74 65 bp::class_<CollisionCallBackDefault, bp::bases<CollisionCallBackBase>>(
75 "CollisionCallBackDefault", bp::no_init)
76
2/4
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 65 times.
✗ Branch 5 not taken.
130 .def(bp::init<const GeometryModel &, GeometryData &, bp::optional<bool>>(
77
1/2
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
130 bp::args("self", "geometry_model", "geometry_data", "stopAtFirstCollision"),
78 "Default constructor from a given GeometryModel and a GeometryData")
79
1/2
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
65 [bp::with_custodian_and_ward<1, 2>(), bp::with_custodian_and_ward<1, 3>()])
80
81 130 .def_readwrite(
82
1/2
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
65 "stopAtFirstCollision", &CollisionCallBackDefault::stopAtFirstCollision,
83 "Whether to stop or not when localizing a first collision")
84 130 .def_readonly(
85
1/2
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
65 "collisionPairIndex", &CollisionCallBackDefault::collisionPairIndex,
86 "The collision index of the first pair in collision")
87 65 .def_readonly(
88
1/2
✓ Branch 1 taken 65 times.
✗ Branch 2 not taken.
65 "count", &CollisionCallBackDefault::count, "Number of visits of the collide method");
89 65 }
90
91 } // namespace python
92 } // namespace pinocchio
93