GCC Code Coverage Report


Directory: ./
File: python/collision-geometries.cc
Date: 2025-04-01 09:23:31
Exec Total Coverage
Lines: 390 459 85.0%
Branches: 384 826 46.5%

Line Branch Exec Source
1 //
2 // Software License Agreement (BSD License)
3 //
4 // Copyright (c) 2019-2024 CNRS-LAAS INRIA
5 // Author: Joseph Mirabel
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 <eigenpy/eigenpy.hpp>
36 #include <eigenpy/eigen-to-python.hpp>
37
38 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
39 #include <eigenpy/id.hpp>
40 #endif
41 #include "coal.hh"
42
43 #include "deprecation.hh"
44
45 #include "coal/fwd.hh"
46 #include "coal/shape/geometric_shapes.h"
47 #include "coal/shape/convex.h"
48 #include "coal/BVH/BVH_model.h"
49 #include "coal/hfield.h"
50
51 #include "coal/serialization/memory.h"
52 #include "coal/serialization/AABB.h"
53 #include "coal/serialization/BVH_model.h"
54 #include "coal/serialization/hfield.h"
55 #include "coal/serialization/geometric_shapes.h"
56 #include "coal/serialization/convex.h"
57
58 #include "pickle.hh"
59 #include "serializable.hh"
60
61 #ifdef COAL_HAS_DOXYGEN_AUTODOC
62 // FIXME for a reason I do not understand, doxygen fails to understand that
63 // BV_splitter is not defined in coal/BVH/BVH_model.h
64 #include "coal/internal/BV_splitter.h"
65 #include "coal/broadphase/detail/hierarchy_tree.h"
66
67 #include "doxygen_autodoc/coal/BVH/BVH_model.h"
68 #include "doxygen_autodoc/coal/BV/AABB.h"
69 #include "doxygen_autodoc/coal/hfield.h"
70 #include "doxygen_autodoc/coal/shape/geometric_shapes.h"
71 #include "doxygen_autodoc/functions.h"
72 #endif
73
74 using namespace boost::python;
75 using namespace coal;
76 using namespace coal::python;
77 namespace dv = doxygen::visitor;
78 namespace bp = boost::python;
79
80 using boost::noncopyable;
81
82 typedef std::vector<Vec3s> Vec3ss;
83 typedef std::vector<Triangle> Triangles;
84
85 struct BVHModelBaseWrapper {
86 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 3, Eigen::RowMajor> RowMatrixX3;
87 typedef Eigen::Map<RowMatrixX3> MapRowMatrixX3;
88 typedef Eigen::Ref<RowMatrixX3> RefRowMatrixX3;
89
90 static Vec3s& vertex(BVHModelBase& bvh, unsigned int i) {
91 if (i >= bvh.num_vertices) throw std::out_of_range("index is out of range");
92 return (*(bvh.vertices))[i];
93 }
94
95 1 static RefRowMatrixX3 vertices(BVHModelBase& bvh) {
96
1/2
✗ Branch 0 not taken.
✓ Branch 1 taken 1 times.
1 if (bvh.num_vertices > 0)
97 return MapRowMatrixX3(bvh.vertices->data()->data(), bvh.num_vertices, 3);
98 else
99
2/4
✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
2 return MapRowMatrixX3(NULL, bvh.num_vertices, 3);
100 }
101
102 static Triangle tri_indices(const BVHModelBase& bvh, unsigned int i) {
103 if (i >= bvh.num_tris) throw std::out_of_range("index is out of range");
104 return (*bvh.tri_indices)[i];
105 }
106 };
107
108 template <typename BV>
109 20 void exposeBVHModel(const std::string& bvname) {
110 typedef BVHModel<BV> BVH;
111
112
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 const std::string type_name = "BVHModel" + bvname;
113
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 10 times.
✗ Branch 6 not taken.
20 class_<BVH, bases<BVHModelBase>, shared_ptr<BVH>>(
114 type_name.c_str(), doxygen::class_doc<BVH>(), no_init)
115
1/2
✓ Branch 2 taken 10 times.
✗ Branch 3 not taken.
20 .def(dv::init<BVH>())
116
1/2
✓ Branch 2 taken 10 times.
✗ Branch 3 not taken.
20 .def(dv::init<BVH, const BVH&>())
117
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
20 .DEF_CLASS_FUNC(BVH, getNumBVs)
118
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
20 .DEF_CLASS_FUNC(BVH, makeParentRelative)
119
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
20 .DEF_CLASS_FUNC(BVHModelBase, memUsage)
120 20 .def("clone", &BVH::clone, doxygen::member_func_doc(&BVH::clone),
121 return_value_policy<manage_new_object>())
122
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
20 .def_pickle(PickleObject<BVH>())
123
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 .def(SerializableVisitor<BVH>())
124 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
125
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 .def(eigenpy::IdVisitor<BVH>())
126 #endif
127 ;
128 20 }
129
130 template <typename BV>
131 20 void exposeHeightField(const std::string& bvname) {
132 typedef HeightField<BV> Geometry;
133 typedef typename Geometry::Base Base;
134 typedef typename Geometry::Node Node;
135
136
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 const std::string type_name = "HeightField" + bvname;
137
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 10 times.
✗ Branch 6 not taken.
20 class_<Geometry, bases<Base>, shared_ptr<Geometry>>(
138 type_name.c_str(), doxygen::class_doc<Geometry>(), no_init)
139
1/2
✓ Branch 2 taken 10 times.
✗ Branch 3 not taken.
20 .def(dv::init<HeightField<BV>>())
140
1/2
✓ Branch 2 taken 10 times.
✗ Branch 3 not taken.
20 .def(dv::init<HeightField<BV>, const HeightField<BV>&>())
141
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 .def(dv::init<HeightField<BV>, Scalar, Scalar, const MatrixXs&,
142 20 bp::optional<Scalar>>())
143
144
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
20 .DEF_CLASS_FUNC(Geometry, getXDim)
145
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
20 .DEF_CLASS_FUNC(Geometry, getYDim)
146
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
20 .DEF_CLASS_FUNC(Geometry, getMinHeight)
147
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
20 .DEF_CLASS_FUNC(Geometry, getMaxHeight)
148
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
20 .DEF_CLASS_FUNC(Geometry, getNodeType)
149
2/4
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
20 .DEF_CLASS_FUNC(Geometry, updateHeights)
150
151 40 .def("clone", &Geometry::clone,
152 20 doxygen::member_func_doc(&Geometry::clone),
153 return_value_policy<manage_new_object>())
154
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 .def("getXGrid", &Geometry::getXGrid,
155 20 doxygen::member_func_doc(&Geometry::getXGrid),
156 bp::return_value_policy<bp::copy_const_reference>())
157
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 .def("getYGrid", &Geometry::getYGrid,
158 20 doxygen::member_func_doc(&Geometry::getYGrid),
159 bp::return_value_policy<bp::copy_const_reference>())
160
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 .def("getHeights", &Geometry::getHeights,
161 20 doxygen::member_func_doc(&Geometry::getHeights),
162 bp::return_value_policy<bp::copy_const_reference>())
163
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 .def("getBV", (Node & (Geometry::*)(unsigned int)) & Geometry::getBV,
164
1/2
✓ Branch 2 taken 10 times.
✗ Branch 3 not taken.
20 doxygen::member_func_doc((Node & (Geometry::*)(unsigned int)) &
165 Geometry::getBV),
166 bp::return_internal_reference<>())
167
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 .def_pickle(PickleObject<Geometry>())
168
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 .def(SerializableVisitor<Geometry>())
169 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
170
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 .def(eigenpy::IdVisitor<Geometry>())
171 #endif
172 ;
173 20 }
174
175 struct ConvexBaseWrapper {
176 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, 3, Eigen::RowMajor> RowMatrixX3;
177 typedef Eigen::Map<RowMatrixX3> MapRowMatrixX3;
178 typedef Eigen::Ref<RowMatrixX3> RefRowMatrixX3;
179 typedef Eigen::Map<VecXs> MapVecXs;
180 typedef Eigen::Ref<VecXs> RefVecXs;
181
182 static Vec3s& point(const ConvexBase& convex, unsigned int i) {
183 if (i >= convex.num_points)
184 throw std::out_of_range("index is out of range");
185 return (*(convex.points))[i];
186 }
187
188 static RefRowMatrixX3 points(const ConvexBase& convex) {
189 return MapRowMatrixX3((*(convex.points))[0].data(), convex.num_points, 3);
190 }
191
192 static Vec3s& normal(const ConvexBase& convex, unsigned int i) {
193 if (i >= convex.num_normals_and_offsets)
194 throw std::out_of_range("index is out of range");
195 return (*(convex.normals))[i];
196 }
197
198 static RefRowMatrixX3 normals(const ConvexBase& convex) {
199 return MapRowMatrixX3((*(convex.normals))[0].data(),
200 convex.num_normals_and_offsets, 3);
201 }
202
203 static Scalar offset(const ConvexBase& convex, unsigned int i) {
204 if (i >= convex.num_normals_and_offsets)
205 throw std::out_of_range("index is out of range");
206 return (*(convex.offsets))[i];
207 }
208
209 static RefVecXs offsets(const ConvexBase& convex) {
210 return MapVecXs(convex.offsets->data(), convex.num_normals_and_offsets, 1);
211 }
212
213 static list neighbors(const ConvexBase& convex, unsigned int i) {
214 if (i >= convex.num_points)
215 throw std::out_of_range("index is out of range");
216 list n;
217 const std::vector<ConvexBase::Neighbors>& neighbors_ = *(convex.neighbors);
218 for (unsigned char j = 0; j < neighbors_[i].count(); ++j)
219 n.append(neighbors_[i][j]);
220 return n;
221 }
222
223 1 static ConvexBase* convexHull(const Vec3ss& points, bool keepTri,
224 const char* qhullCommand) {
225 1 return ConvexBase::convexHull(points.data(), (unsigned int)points.size(),
226 keepTri, qhullCommand);
227 }
228 };
229
230 template <typename PolygonT>
231 struct ConvexWrapper {
232 typedef Convex<PolygonT> Convex_t;
233
234 static PolygonT polygons(const Convex_t& convex, unsigned int i) {
235 if (i >= convex.num_polygons)
236 throw std::out_of_range("index is out of range");
237 return (*convex.polygons)[i];
238 }
239
240 3 static shared_ptr<Convex_t> constructor(const Vec3ss& _points,
241 const Triangles& _tris) {
242
1/2
✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
6 std::shared_ptr<std::vector<Vec3s>> points(
243
2/4
✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 3 times.
✗ Branch 6 not taken.
6 new std::vector<Vec3s>(_points.size()));
244 3 std::vector<Vec3s>& points_ = *points;
245
3/4
✓ Branch 3 taken 11 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 11 times.
✓ Branch 7 taken 3 times.
14 for (std::size_t i = 0; i < _points.size(); ++i) points_[i] = _points[i];
246
247
1/2
✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
6 std::shared_ptr<std::vector<Triangle>> tris(
248
2/4
✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 3 times.
✗ Branch 6 not taken.
6 new std::vector<Triangle>(_tris.size()));
249 3 std::vector<Triangle>& tris_ = *tris;
250
2/2
✓ Branch 3 taken 9 times.
✓ Branch 4 taken 3 times.
12 for (std::size_t i = 0; i < _tris.size(); ++i) tris_[i] = _tris[i];
251
1/2
✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
3 return shared_ptr<Convex_t>(new Convex_t(points,
252 6 (unsigned int)_points.size(), tris,
253
2/4
✓ Branch 5 taken 3 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 3 times.
✗ Branch 9 not taken.
9 (unsigned int)_tris.size()));
254 3 }
255 };
256
257 template <typename T>
258 120 void defComputeMemoryFootprint() {
259 120 doxygen::def("computeMemoryFootprint", &computeMemoryFootprint<T>);
260 120 }
261
262 5 void exposeComputeMemoryFootprint() {
263 5 defComputeMemoryFootprint<Sphere>();
264 5 defComputeMemoryFootprint<Ellipsoid>();
265 5 defComputeMemoryFootprint<Cone>();
266 5 defComputeMemoryFootprint<Capsule>();
267 5 defComputeMemoryFootprint<Cylinder>();
268 5 defComputeMemoryFootprint<Box>();
269 5 defComputeMemoryFootprint<Plane>();
270 5 defComputeMemoryFootprint<Halfspace>();
271 5 defComputeMemoryFootprint<TriangleP>();
272
273 5 defComputeMemoryFootprint<BVHModel<OBB>>();
274 5 defComputeMemoryFootprint<BVHModel<RSS>>();
275 5 defComputeMemoryFootprint<BVHModel<OBBRSS>>();
276 5 }
277
278 5 void exposeShapes() {
279 5 class_<ShapeBase, bases<CollisionGeometry>, shared_ptr<ShapeBase>,
280 noncopyable>("ShapeBase", doxygen::class_doc<ShapeBase>(), no_init)
281 //.def ("getObjectType", &CollisionGeometry::getObjectType)
282
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(dv::member_func("setSweptSphereRadius",
283
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 &ShapeBase::setSweptSphereRadius))
284
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(dv::member_func("getSweptSphereRadius",
285
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
10 &ShapeBase::getSweptSphereRadius));
286
287 5 class_<Box, bases<ShapeBase>, shared_ptr<Box>>(
288 "Box", doxygen::class_doc<ShapeBase>(), no_init)
289
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Box>())
290
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Box, const Box&>())
291
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Box, Scalar, Scalar, Scalar>())
292
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Box, const Vec3s&>())
293
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(Box, halfSide)
294
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def("clone", &Box::clone, doxygen::member_func_doc(&Box::clone),
295 return_value_policy<manage_new_object>())
296
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_pickle(PickleObject<Box>())
297
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(SerializableVisitor<Box>())
298 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
299
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(eigenpy::IdVisitor<Box>())
300 #endif
301 ;
302
303 5 class_<Capsule, bases<ShapeBase>, shared_ptr<Capsule>>(
304 "Capsule", doxygen::class_doc<Capsule>(), no_init)
305
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Capsule>())
306
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Capsule, Scalar, Scalar>())
307
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Capsule, const Capsule&>())
308
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(Capsule, radius)
309
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(Capsule, halfLength)
310
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def("clone", &Capsule::clone, doxygen::member_func_doc(&Capsule::clone),
311 return_value_policy<manage_new_object>())
312
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_pickle(PickleObject<Capsule>())
313
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(SerializableVisitor<Capsule>())
314 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
315
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(eigenpy::IdVisitor<Capsule>())
316 #endif
317 ;
318
319 5 class_<Cone, bases<ShapeBase>, shared_ptr<Cone>>(
320 "Cone", doxygen::class_doc<Cone>(), no_init)
321
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Cone>())
322
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Cone, Scalar, Scalar>())
323
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Cone, const Cone&>())
324
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(Cone, radius)
325
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(Cone, halfLength)
326
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def("clone", &Cone::clone, doxygen::member_func_doc(&Cone::clone),
327 return_value_policy<manage_new_object>())
328
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_pickle(PickleObject<Cone>())
329
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(SerializableVisitor<Cone>())
330 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
331
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(eigenpy::IdVisitor<Cone>())
332 #endif
333 ;
334
335 5 class_<ConvexBase, bases<ShapeBase>, shared_ptr<ConvexBase>, noncopyable>(
336 "ConvexBase", doxygen::class_doc<ConvexBase>(), no_init)
337
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RO_CLASS_ATTRIB(ConvexBase, center)
338
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RO_CLASS_ATTRIB(ConvexBase, num_points)
339
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RO_CLASS_ATTRIB(ConvexBase, num_normals_and_offsets)
340
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def("point", &ConvexBaseWrapper::point, bp::args("self", "index"),
341 "Retrieve the point given by its index.",
342 5 bp::return_internal_reference<>())
343
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def("points", &ConvexBaseWrapper::point, bp::args("self", "index"),
344 "Retrieve the point given by its index.",
345
2/4
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 5 times.
✗ Branch 6 not taken.
10 ::coal::python::deprecated_member<bp::return_internal_reference<>>())
346
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def("points", &ConvexBaseWrapper::points, bp::args("self"),
347 "Retrieve all the points.",
348 5 bp::with_custodian_and_ward_postcall<0, 1>())
349 // .add_property ("points",
350 // bp::make_function(&ConvexBaseWrapper::points,bp::with_custodian_and_ward_postcall<0,1>()),
351 // "Points of the convex.")
352
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def("normal", &ConvexBaseWrapper::normal, bp::args("self", "index"),
353 "Retrieve the normal given by its index.",
354 5 bp::return_internal_reference<>())
355
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def("normals", &ConvexBaseWrapper::normals, bp::args("self"),
356 "Retrieve all the normals.",
357 5 bp::with_custodian_and_ward_postcall<0, 1>())
358
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
10 .def("offset", &ConvexBaseWrapper::offset, bp::args("self", "index"),
359 "Retrieve the offset given by its index.")
360
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def("offsets", &ConvexBaseWrapper::offsets, bp::args("self"),
361 "Retrieve all the offsets.",
362 5 bp::with_custodian_and_ward_postcall<0, 1>())
363
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("neighbors", &ConvexBaseWrapper::neighbors)
364
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("convexHull", &ConvexBaseWrapper::convexHull,
365 // doxygen::member_func_doc(&ConvexBase::convexHull),
366 return_value_policy<manage_new_object>())
367
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .staticmethod("convexHull")
368 5 .def("clone", &ConvexBase::clone,
369
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 doxygen::member_func_doc(&ConvexBase::clone),
370 5 return_value_policy<manage_new_object>());
371
372 5 class_<Convex<Triangle>, bases<ConvexBase>, shared_ptr<Convex<Triangle>>,
373 noncopyable>("Convex", doxygen::class_doc<Convex<Triangle>>(), no_init)
374
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
10 .def("__init__", make_constructor(&ConvexWrapper<Triangle>::constructor))
375
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Convex<Triangle>>())
376
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Convex<Triangle>, const Convex<Triangle>&>())
377
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .DEF_RO_CLASS_ATTRIB(Convex<Triangle>, num_polygons)
378
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("polygons", &ConvexWrapper<Triangle>::polygons)
379
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_pickle(PickleObject<Convex<Triangle>>())
380
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(SerializableVisitor<Convex<Triangle>>())
381 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
382
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(eigenpy::IdVisitor<Convex<Triangle>>())
383 #endif
384 ;
385
386 5 class_<Cylinder, bases<ShapeBase>, shared_ptr<Cylinder>>(
387 "Cylinder", doxygen::class_doc<Cylinder>(), no_init)
388
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Cylinder>())
389
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Cylinder, Scalar, Scalar>())
390
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Cylinder, const Cylinder&>())
391
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(Cylinder, radius)
392
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(Cylinder, halfLength)
393 10 .def("clone", &Cylinder::clone,
394
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 doxygen::member_func_doc(&Cylinder::clone),
395 return_value_policy<manage_new_object>())
396
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_pickle(PickleObject<Cylinder>())
397
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(SerializableVisitor<Cylinder>())
398 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
399
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(eigenpy::IdVisitor<Cylinder>())
400 #endif
401 ;
402
403 5 class_<Halfspace, bases<ShapeBase>, shared_ptr<Halfspace>>(
404 "Halfspace", doxygen::class_doc<Halfspace>(), no_init)
405
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Halfspace, const Vec3s&, Scalar>())
406
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Halfspace, const Halfspace&>())
407
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Halfspace, Scalar, Scalar, Scalar, Scalar>())
408
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Halfspace>())
409
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(Halfspace, n)
410
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(Halfspace, d)
411 10 .def("clone", &Halfspace::clone,
412
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 doxygen::member_func_doc(&Halfspace::clone),
413 return_value_policy<manage_new_object>())
414
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_pickle(PickleObject<Halfspace>())
415
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(SerializableVisitor<Halfspace>())
416 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
417
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(eigenpy::IdVisitor<Halfspace>())
418 #endif
419 ;
420
421 5 class_<Plane, bases<ShapeBase>, shared_ptr<Plane>>(
422 "Plane", doxygen::class_doc<Plane>(), no_init)
423
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Plane, const Vec3s&, Scalar>())
424
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Plane, const Plane&>())
425
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Plane, Scalar, Scalar, Scalar, Scalar>())
426
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Plane>())
427
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(Plane, n)
428
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(Plane, d)
429
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def("clone", &Plane::clone, doxygen::member_func_doc(&Plane::clone),
430 return_value_policy<manage_new_object>())
431
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_pickle(PickleObject<Plane>())
432
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(SerializableVisitor<Plane>())
433 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
434
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(eigenpy::IdVisitor<Plane>())
435 #endif
436 ;
437
438 5 class_<Sphere, bases<ShapeBase>, shared_ptr<Sphere>>(
439 "Sphere", doxygen::class_doc<Sphere>(), no_init)
440
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Sphere>())
441
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Sphere, const Sphere&>())
442
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Sphere, Scalar>())
443
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(Sphere, radius)
444
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def("clone", &Sphere::clone, doxygen::member_func_doc(&Sphere::clone),
445 return_value_policy<manage_new_object>())
446
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_pickle(PickleObject<Sphere>())
447
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(SerializableVisitor<Sphere>())
448 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
449
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(eigenpy::IdVisitor<Sphere>())
450 #endif
451 ;
452
453 5 class_<Ellipsoid, bases<ShapeBase>, shared_ptr<Ellipsoid>>(
454 "Ellipsoid", doxygen::class_doc<Ellipsoid>(), no_init)
455
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Ellipsoid>())
456
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Ellipsoid, Scalar, Scalar, Scalar>())
457
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Ellipsoid, Vec3s>())
458
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<Ellipsoid, const Ellipsoid&>())
459
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(Ellipsoid, radii)
460 10 .def("clone", &Ellipsoid::clone,
461
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 doxygen::member_func_doc(&Ellipsoid::clone),
462 return_value_policy<manage_new_object>())
463
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_pickle(PickleObject<Ellipsoid>())
464
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(SerializableVisitor<Ellipsoid>())
465 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
466
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(eigenpy::IdVisitor<Ellipsoid>())
467 #endif
468 ;
469
470 5 class_<TriangleP, bases<ShapeBase>, shared_ptr<TriangleP>>(
471 "TriangleP", doxygen::class_doc<TriangleP>(), no_init)
472
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<TriangleP>())
473
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<TriangleP, const Vec3s&, const Vec3s&, const Vec3s&>())
474
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(dv::init<TriangleP, const TriangleP&>())
475
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(TriangleP, a)
476
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(TriangleP, b)
477
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_RW_CLASS_ATTRIB(TriangleP, c)
478 10 .def("clone", &TriangleP::clone,
479
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 doxygen::member_func_doc(&TriangleP::clone),
480 return_value_policy<manage_new_object>())
481
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_pickle(PickleObject<TriangleP>())
482
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(SerializableVisitor<TriangleP>())
483 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
484
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(eigenpy::IdVisitor<TriangleP>())
485 #endif
486 ;
487 5 }
488
489 boost::python::tuple AABB_distance_proxy(const AABB& self, const AABB& other) {
490 Vec3s P, Q;
491 Scalar distance = self.distance(other, &P, &Q);
492 return boost::python::make_tuple(distance, P, Q);
493 }
494
495 5 void exposeCollisionGeometries() {
496 10 enum_<BVHModelType>("BVHModelType")
497
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BVH_MODEL_UNKNOWN", BVH_MODEL_UNKNOWN)
498
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BVH_MODEL_TRIANGLES", BVH_MODEL_TRIANGLES)
499
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BVH_MODEL_POINTCLOUD", BVH_MODEL_POINTCLOUD)
500
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .export_values();
501
502 10 enum_<BVHBuildState>("BVHBuildState")
503
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BVH_BUILD_STATE_EMPTY", BVH_BUILD_STATE_EMPTY)
504
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BVH_BUILD_STATE_BEGUN", BVH_BUILD_STATE_BEGUN)
505
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BVH_BUILD_STATE_PROCESSED", BVH_BUILD_STATE_PROCESSED)
506
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BVH_BUILD_STATE_UPDATE_BEGUN", BVH_BUILD_STATE_UPDATE_BEGUN)
507
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BVH_BUILD_STATE_UPDATED", BVH_BUILD_STATE_UPDATED)
508
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BVH_BUILD_STATE_REPLACE_BEGUN", BVH_BUILD_STATE_REPLACE_BEGUN)
509
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .export_values();
510
511
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 if (!eigenpy::register_symbolic_link_to_registered_type<OBJECT_TYPE>()) {
512 10 enum_<OBJECT_TYPE>("OBJECT_TYPE")
513
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("OT_UNKNOWN", OT_UNKNOWN)
514
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("OT_BVH", OT_BVH)
515
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("OT_GEOM", OT_GEOM)
516
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("OT_OCTREE", OT_OCTREE)
517
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("OT_HFIELD", OT_HFIELD)
518
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .export_values();
519 }
520
521
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 if (!eigenpy::register_symbolic_link_to_registered_type<NODE_TYPE>()) {
522 10 enum_<NODE_TYPE>("NODE_TYPE")
523
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BV_UNKNOWN", BV_UNKNOWN)
524
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BV_AABB", BV_AABB)
525
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BV_OBB", BV_OBB)
526
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BV_RSS", BV_RSS)
527
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BV_kIOS", BV_kIOS)
528
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BV_OBBRSS", BV_OBBRSS)
529
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BV_KDOP16", BV_KDOP16)
530
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BV_KDOP18", BV_KDOP18)
531
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("BV_KDOP24", BV_KDOP24)
532
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("GEOM_BOX", GEOM_BOX)
533
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("GEOM_SPHERE", GEOM_SPHERE)
534
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("GEOM_ELLIPSOID", GEOM_ELLIPSOID)
535
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("GEOM_CAPSULE", GEOM_CAPSULE)
536
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("GEOM_CONE", GEOM_CONE)
537
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("GEOM_CYLINDER", GEOM_CYLINDER)
538
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("GEOM_CONVEX", GEOM_CONVEX)
539
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("GEOM_PLANE", GEOM_PLANE)
540
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("GEOM_HALFSPACE", GEOM_HALFSPACE)
541
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("GEOM_TRIANGLE", GEOM_TRIANGLE)
542
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("GEOM_OCTREE", GEOM_OCTREE)
543
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("HF_AABB", HF_AABB)
544
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .value("HF_OBBRSS", HF_OBBRSS)
545
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .export_values();
546 }
547
548 5 class_<AABB>("AABB",
549 "A class describing the AABB collision structure, which is a "
550 "box in 3D space determined by two diagonal points",
551 no_init)
552
3/6
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 5 times.
✗ Branch 8 not taken.
10 .def(init<>(bp::arg("self"), "Default constructor"))
553
3/6
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 5 times.
✗ Branch 8 not taken.
10 .def(init<AABB>(bp::args("self", "other"), "Copy constructor"))
554
3/6
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 5 times.
✗ Branch 8 not taken.
10 .def(init<Vec3s>(bp::args("self", "v"),
555 "Creating an AABB at position v with zero size."))
556
3/6
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 5 times.
✗ Branch 8 not taken.
10 .def(init<Vec3s, Vec3s>(bp::args("self", "a", "b"),
557 "Creating an AABB with two endpoints a and b."))
558
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def(init<AABB, Vec3s>(
559
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
10 bp::args("self", "core", "delta"),
560 "Creating an AABB centered as core and is of half-dimension delta."))
561
3/6
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 5 times.
✗ Branch 8 not taken.
10 .def(init<Vec3s, Vec3s, Vec3s>(bp::args("self", "a", "b", "c"),
562 "Creating an AABB contains three points."))
563
564 10 .def("contain", (bool(AABB::*)(const Vec3s&) const) & AABB::contain,
565
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
10 bp::args("self", "p"), "Check whether the AABB contains a point p.")
566
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("contain", (bool(AABB::*)(const AABB&) const) & AABB::contain,
567
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
10 bp::args("self", "other"),
568 "Check whether the AABB contains another AABB.")
569
570
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("overlap", (bool(AABB::*)(const AABB&) const) & AABB::overlap,
571
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
10 bp::args("self", "other"), "Check whether two AABB are overlap.")
572
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("overlap", (bool(AABB::*)(const AABB&, AABB&) const) & AABB::overlap,
573
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
10 bp::args("self", "other", "overlapping_part"),
574 "Check whether two AABB are overlaping and return the overloaping "
575 "part if true.")
576
577
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("distance", (Scalar(AABB::*)(const AABB&) const)&AABB::distance,
578
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
10 bp::args("self", "other"), "Distance between two AABBs.")
579 // .def("distance",
580 // AABB_distance_proxy,
581 // bp::args("self","other"),
582 // "Distance between two AABBs.")
583
584
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
10 .add_property(
585 "min_",
586
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 bp::make_function(
587 +[](AABB& self) -> Vec3s& { return self.min_; },
588 bp::return_internal_reference<>()),
589
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
10 bp::make_function(
590 +[](AABB& self, const Vec3s& min_) -> void { self.min_ = min_; }),
591 "The min point in the AABB.")
592
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .add_property(
593 "max_",
594
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 bp::make_function(
595 +[](AABB& self) -> Vec3s& { return self.max_; },
596 bp::return_internal_reference<>()),
597
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
10 bp::make_function(
598 +[](AABB& self, const Vec3s& max_) -> void { self.max_ = max_; }),
599 "The max point in the AABB.")
600
601
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(bp::self == bp::self)
602
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(bp::self != bp::self)
603
604
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(bp::self + bp::self)
605
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(bp::self += bp::self)
606
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 5 times.
✗ Branch 6 not taken.
5 .def(bp::self += Vec3s())
607
608
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
10 .def("size", &AABB::volume, bp::arg("self"), "Size of the AABB.")
609
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
10 .def("center", &AABB::center, bp::arg("self"), "Center of the AABB.")
610
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
10 .def("width", &AABB::width, bp::arg("self"), "Width of the AABB.")
611
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
10 .def("height", &AABB::height, bp::arg("self"), "Height of the AABB.")
612
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
10 .def("depth", &AABB::depth, bp::arg("self"), "Depth of the AABB.")
613
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
10 .def("volume", &AABB::volume, bp::arg("self"), "Volume of the AABB.")
614
615 10 .def("expand",
616 static_cast<AABB& (AABB::*)(const AABB&, Scalar)>(&AABB::expand),
617 // doxygen::member_func_doc(static_cast<AABB& (AABB::*)(const
618 // AABB &, Scalar)>(&AABB::expand)),
619 // doxygen::member_func_args(static_cast<AABB&
620 // (AABB::*)(const AABB &, Scalar)>(&AABB::expand)),
621 bp::return_internal_reference<>())
622
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("expand", static_cast<AABB& (AABB::*)(const Scalar)>(&AABB::expand),
623 // doxygen::member_func_doc(static_cast<AABB& (AABB::*)(const
624 // Scalar)>(&AABB::expand)),
625 // doxygen::member_func_args(static_cast<AABB&
626 // (AABB::*)(const Scalar)>(&AABB::expand)),
627 bp::return_internal_reference<>())
628
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("expand", static_cast<AABB& (AABB::*)(const Vec3s&)>(&AABB::expand),
629 // doxygen::member_func_doc(static_cast<AABB& (AABB::*)(const
630 // Vec3s &)>(&AABB::expand)),
631 // doxygen::member_func_args(static_cast<AABB&
632 // (AABB::*)(const Vec3s &)>(&AABB::expand)),
633 bp::return_internal_reference<>())
634
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def_pickle(PickleObject<AABB>())
635
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(SerializableVisitor<AABB>())
636 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
637
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(eigenpy::IdVisitor<AABB>())
638 #endif
639 ;
640
641
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 def("translate", (AABB(*)(const AABB&, const Vec3s&))&translate,
642 10 bp::args("aabb", "t"), "Translate the center of AABB by t");
643
644
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 def("rotate", (AABB(*)(const AABB&, const Matrix3s&))&rotate,
645 10 bp::args("aabb", "R"), "Rotate the AABB object by R");
646
647 5 if (!eigenpy::register_symbolic_link_to_registered_type<
648
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 CollisionGeometry>()) {
649 10 class_<CollisionGeometry, CollisionGeometryPtr_t, noncopyable>(
650 "CollisionGeometry", no_init)
651
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("getObjectType", &CollisionGeometry::getObjectType)
652
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("getNodeType", &CollisionGeometry::getNodeType)
653
654
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("computeLocalAABB", &CollisionGeometry::computeLocalAABB)
655
656
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("computeCOM", &CollisionGeometry::computeCOM)
657
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("computeMomentofInertia",
658 &CollisionGeometry::computeMomentofInertia)
659
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("computeVolume", &CollisionGeometry::computeVolume)
660
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("computeMomentofInertiaRelatedToCOM",
661 &CollisionGeometry::computeMomentofInertiaRelatedToCOM)
662
663
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_readwrite("aabb_radius", &CollisionGeometry::aabb_radius,
664 "AABB radius.")
665
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_readwrite("aabb_center", &CollisionGeometry::aabb_center,
666 "AABB center in local coordinate.")
667
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_readwrite("aabb_local", &CollisionGeometry::aabb_local,
668 "AABB in local coordinate, used for tight AABB when "
669 "only translation transform.")
670
671
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
10 .def("isOccupied", &CollisionGeometry::isOccupied, bp::arg("self"),
672 "Whether the object is completely occupied.")
673
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
10 .def("isFree", &CollisionGeometry::isFree, bp::arg("self"),
674 "Whether the object is completely free.")
675
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
10 .def("isUncertain", &CollisionGeometry::isUncertain, bp::arg("self"),
676 "Whether the object has some uncertainty.")
677
678
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_readwrite("cost_density", &CollisionGeometry::cost_density,
679 "Collision cost for unit volume.")
680 10 .def_readwrite("threshold_occupied",
681
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 &CollisionGeometry::threshold_occupied,
682 "Threshold for occupied ( >= is occupied).")
683
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_readwrite("threshold_free", &CollisionGeometry::threshold_free,
684 "Threshold for free (<= is free).")
685
686
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(self == self)
687
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .def(self != self);
688 }
689
690 5 exposeShapes();
691
692 5 class_<BVHModelBase, bases<CollisionGeometry>, BVHModelPtr_t, noncopyable>(
693 "BVHModelBase", no_init)
694
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def("vertex", &BVHModelBaseWrapper::vertex, bp::args("self", "index"),
695 "Retrieve the vertex given by its index.",
696 5 bp::return_internal_reference<>())
697
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def("vertices", &BVHModelBaseWrapper::vertex, bp::args("self", "index"),
698 "Retrieve the vertex given by its index.",
699
2/4
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 5 times.
✗ Branch 6 not taken.
10 ::coal::python::deprecated_member<bp::return_internal_reference<>>())
700
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def("vertices", &BVHModelBaseWrapper::vertices, bp::args("self"),
701 "Retrieve all the vertices.",
702 5 bp::with_custodian_and_ward_postcall<0, 1>())
703 // .add_property ("vertices",
704 // bp::make_function(&BVHModelBaseWrapper::vertices,bp::with_custodian_and_ward_postcall<0,1>()),
705 // "Vertices of the BVH.")
706
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def("tri_indices", &BVHModelBaseWrapper::tri_indices,
707
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
10 bp::args("self", "index"),
708 "Retrieve the triangle given by its index.")
709
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_readonly("num_vertices", &BVHModelBase::num_vertices)
710
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_readonly("num_tris", &BVHModelBase::num_tris)
711
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_readonly("build_state", &BVHModelBase::build_state)
712
713
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def_readonly("convex", &BVHModelBase::convex)
714
715
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .DEF_CLASS_FUNC(BVHModelBase, buildConvexRepresentation)
716
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .DEF_CLASS_FUNC(BVHModelBase, buildConvexHull)
717
718 // Expose function to build a BVH
719
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def(dv::member_func("beginModel", &BVHModelBase::beginModel))
720
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def(dv::member_func("addVertex", &BVHModelBase::addVertex))
721
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def(dv::member_func("addVertices", &BVHModelBase::addVertices))
722
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def(dv::member_func("addTriangle", &BVHModelBase::addTriangle))
723
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def(dv::member_func("addTriangles", &BVHModelBase::addTriangles))
724
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(dv::member_func<int (BVHModelBase::*)(
725
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 const Vec3ss&, const Triangles&)>("addSubModel",
726 &BVHModelBase::addSubModel))
727
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def(dv::member_func<int (BVHModelBase::*)(const Vec3ss&)>(
728 "addSubModel", &BVHModelBase::addSubModel))
729
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def(dv::member_func("endModel", &BVHModelBase::endModel))
730 // Expose function to replace a BVH
731
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(dv::member_func("beginReplaceModel",
732
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 &BVHModelBase::beginReplaceModel))
733
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def(dv::member_func("replaceVertex", &BVHModelBase::replaceVertex))
734
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def(dv::member_func("replaceTriangle", &BVHModelBase::replaceTriangle))
735
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def(dv::member_func("replaceSubModel", &BVHModelBase::replaceSubModel))
736
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def(dv::member_func("endReplaceModel", &BVHModelBase::endReplaceModel))
737
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .def(dv::member_func("getModelType", &BVHModelBase::getModelType));
738
2/4
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 5 times.
✗ Branch 6 not taken.
5 exposeBVHModel<OBB>("OBB");
739
2/4
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 5 times.
✗ Branch 6 not taken.
5 exposeBVHModel<OBBRSS>("OBBRSS");
740
2/4
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 5 times.
✗ Branch 6 not taken.
5 exposeHeightField<OBBRSS>("OBBRSS");
741
2/4
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 5 times.
✗ Branch 6 not taken.
5 exposeHeightField<AABB>("AABB");
742 5 exposeComputeMemoryFootprint();
743 5 }
744
745 5 void exposeCollisionObject() {
746 namespace bp = boost::python;
747
748
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 if (!eigenpy::register_symbolic_link_to_registered_type<CollisionObject>()) {
749 10 class_<CollisionObject, CollisionObjectPtr_t>("CollisionObject", no_init)
750
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(dv::init<CollisionObject, const CollisionGeometryPtr_t&,
751 5 bp::optional<bool>>())
752
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(dv::init<CollisionObject, const CollisionGeometryPtr_t&,
753 5 const Transform3s&, bp::optional<bool>>())
754
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(dv::init<CollisionObject, const CollisionGeometryPtr_t&,
755 5 const Matrix3s&, const Vec3s&, bp::optional<bool>>())
756
757
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .DEF_CLASS_FUNC(CollisionObject, getObjectType)
758
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .DEF_CLASS_FUNC(CollisionObject, getNodeType)
759
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .DEF_CLASS_FUNC(CollisionObject, computeAABB)
760
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(dv::member_func("getAABB",
761
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 static_cast<AABB& (CollisionObject::*)()>(
762 &CollisionObject::getAABB),
763 bp::return_internal_reference<>()))
764
765
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_CLASS_FUNC2(CollisionObject, getTranslation,
766 bp::return_value_policy<bp::copy_const_reference>())
767
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .DEF_CLASS_FUNC(CollisionObject, setTranslation)
768
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_CLASS_FUNC2(CollisionObject, getRotation,
769 bp::return_value_policy<bp::copy_const_reference>())
770
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .DEF_CLASS_FUNC(CollisionObject, setRotation)
771
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_CLASS_FUNC2(CollisionObject, getTransform,
772 bp::return_value_policy<bp::copy_const_reference>())
773
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(dv::member_func(
774 "setTransform",
775
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 static_cast<void (CollisionObject::*)(const Transform3s&)>(
776 &CollisionObject::setTransform)))
777
778
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .DEF_CLASS_FUNC(CollisionObject, isIdentityTransform)
779
2/4
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 5 times.
✗ Branch 5 not taken.
5 .DEF_CLASS_FUNC(CollisionObject, setIdentityTransform)
780
1/2
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
5 .DEF_CLASS_FUNC2(CollisionObject, setCollisionGeometry,
781 (bp::with_custodian_and_ward_postcall<1, 2>()))
782
783
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 .def(dv::member_func(
784 "collisionGeometry",
785
1/2
✓ Branch 1 taken 5 times.
✗ Branch 2 not taken.
5 static_cast<const CollisionGeometryPtr_t& (CollisionObject::*)()>(
786 &CollisionObject::collisionGeometry),
787 5 bp::return_value_policy<bp::copy_const_reference>()));
788 }
789 5 }
790