collision-geometries.cc
Go to the documentation of this file.
1 //
2 // Software License Agreement (BSD License)
3 //
4 // Copyright (c) 2019-2022 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>
37 
38 #include "fcl.hh"
39 #include "deprecation.hh"
40 
41 #include <hpp/fcl/fwd.hh>
43 #include <hpp/fcl/shape/convex.h>
44 #include <hpp/fcl/BVH/BVH_model.h>
45 #include <hpp/fcl/hfield.h>
46 
53 
54 #include "pickle.hh"
55 
56 #ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC
57 // FIXME for a reason I do not understand, doxygen fails to understand that
58 // BV_splitter is not defined in hpp/fcl/BVH/BVH_model.h
61 
62 #include "doxygen_autodoc/hpp/fcl/BVH/BVH_model.h"
63 #include "doxygen_autodoc/hpp/fcl/BV/AABB.h"
64 #include "doxygen_autodoc/hpp/fcl/hfield.h"
65 #include "doxygen_autodoc/hpp/fcl/shape/geometric_shapes.h"
66 #include "doxygen_autodoc/functions.h"
67 #endif
68 
69 using namespace boost::python;
70 using namespace hpp::fcl;
71 namespace dv = doxygen::visitor;
72 namespace bp = boost::python;
73 
74 using boost::noncopyable;
75 
76 typedef std::vector<Vec3f> Vec3fs;
77 typedef std::vector<Triangle> Triangles;
78 
80  typedef Eigen::Matrix<double, Eigen::Dynamic, 3, Eigen::RowMajor> RowMatrixX3;
81  typedef Eigen::Map<RowMatrixX3> MapRowMatrixX3;
82  typedef Eigen::Ref<RowMatrixX3> RefRowMatrixX3;
83 
84  static Vec3f& vertex(BVHModelBase& bvh, unsigned int i) {
85  if (i >= bvh.num_vertices) throw std::out_of_range("index is out of range");
86  return bvh.vertices[i];
87  }
88 
90  return MapRowMatrixX3(bvh.vertices[0].data(), bvh.num_vertices, 3);
91  }
92 
93  static Triangle tri_indices(const BVHModelBase& bvh, unsigned int i) {
94  if (i >= bvh.num_tris) throw std::out_of_range("index is out of range");
95  return bvh.tri_indices[i];
96  }
97 };
98 
99 template <typename BV>
100 void exposeBVHModel(const std::string& bvname) {
101  typedef BVHModel<BV> BVH;
102 
103  const std::string type_name = "BVHModel" + bvname;
104  class_<BVH, bases<BVHModelBase>, shared_ptr<BVH> >(
105  type_name.c_str(), doxygen::class_doc<BVH>(), no_init)
106  .def(dv::init<BVH>())
107  .def(dv::init<BVH, const BVH&>())
108  .DEF_CLASS_FUNC(BVH, getNumBVs)
109  .DEF_CLASS_FUNC(BVH, makeParentRelative)
110  .DEF_CLASS_FUNC(BVHModelBase, memUsage)
111  .def("clone", &BVH::clone, doxygen::member_func_doc(&BVH::clone),
112  return_value_policy<manage_new_object>())
113  .def_pickle(PickleObject<BVH>());
114 }
115 
116 template <typename BV>
117 void exposeHeightField(const std::string& bvname) {
118  typedef HeightField<BV> Geometry;
119  typedef typename Geometry::Base Base;
120  typedef typename Geometry::Node Node;
121 
122  const std::string type_name = "HeightField" + bvname;
123  class_<Geometry, bases<Base>, shared_ptr<Geometry> >(
124  type_name.c_str(), doxygen::class_doc<Geometry>(), no_init)
125  .def(dv::init<HeightField<BV> >())
126  .def(dv::init<HeightField<BV>, const HeightField<BV>&>())
127  .def(dv::init<HeightField<BV>, FCL_REAL, FCL_REAL, const MatrixXf&,
128  bp::optional<FCL_REAL> >())
129 
130  .DEF_CLASS_FUNC(Geometry, getXDim)
131  .DEF_CLASS_FUNC(Geometry, getYDim)
132  .DEF_CLASS_FUNC(Geometry, getMinHeight)
133  .DEF_CLASS_FUNC(Geometry, getMaxHeight)
134  .DEF_CLASS_FUNC(Geometry, getNodeType)
135  .DEF_CLASS_FUNC(Geometry, updateHeights)
136 
137  .def("clone", &Geometry::clone,
138  doxygen::member_func_doc(&Geometry::clone),
139  return_value_policy<manage_new_object>())
140  .def("getXGrid", &Geometry::getXGrid,
141  doxygen::member_func_doc(&Geometry::getXGrid),
142  bp::return_value_policy<bp::copy_const_reference>())
143  .def("getYGrid", &Geometry::getYGrid,
144  doxygen::member_func_doc(&Geometry::getYGrid),
145  bp::return_value_policy<bp::copy_const_reference>())
146  .def("getHeights", &Geometry::getHeights,
147  doxygen::member_func_doc(&Geometry::getHeights),
148  bp::return_value_policy<bp::copy_const_reference>())
149  .def("getBV", (Node & (Geometry::*)(unsigned int)) & Geometry::getBV,
150  doxygen::member_func_doc((Node & (Geometry::*)(unsigned int)) &
151  Geometry::getBV),
152  bp::return_internal_reference<>())
153  .def_pickle(PickleObject<Geometry>());
154 }
155 
157  typedef Eigen::Matrix<double, Eigen::Dynamic, 3, Eigen::RowMajor> RowMatrixX3;
158  typedef Eigen::Map<RowMatrixX3> MapRowMatrixX3;
159  typedef Eigen::Ref<RowMatrixX3> RefRowMatrixX3;
160 
161  static Vec3f& point(const ConvexBase& convex, unsigned int i) {
162  if (i >= convex.num_points)
163  throw std::out_of_range("index is out of range");
164  return convex.points[i];
165  }
166 
167  static RefRowMatrixX3 points(const ConvexBase& convex) {
168  return MapRowMatrixX3(convex.points[0].data(), convex.num_points, 3);
169  }
170 
171  static list neighbors(const ConvexBase& convex, unsigned int i) {
172  if (i >= convex.num_points)
173  throw std::out_of_range("index is out of range");
174  list n;
175  for (unsigned char j = 0; j < convex.neighbors[i].count(); ++j)
176  n.append(convex.neighbors[i][j]);
177  return n;
178  }
179 
180  static ConvexBase* convexHull(const Vec3fs& points, bool keepTri,
181  const char* qhullCommand) {
182  return ConvexBase::convexHull(points.data(), (unsigned int)points.size(),
183  keepTri, qhullCommand);
184  }
185 };
186 
187 template <typename PolygonT>
190 
191  static PolygonT polygons(const Convex_t& convex, unsigned int i) {
192  if (i >= convex.num_polygons)
193  throw std::out_of_range("index is out of range");
194  return convex.polygons[i];
195  }
196 
197  static shared_ptr<Convex_t> constructor(const Vec3fs& _points,
198  const Triangles& _tris) {
199  Vec3f* points = new Vec3f[_points.size()];
200  for (std::size_t i = 0; i < _points.size(); ++i) points[i] = _points[i];
201  Triangle* tris = new Triangle[_tris.size()];
202  for (std::size_t i = 0; i < _tris.size(); ++i) tris[i] = _tris[i];
203  return shared_ptr<Convex_t>(new Convex_t(true, points,
204  (unsigned int)_points.size(), tris,
205  (unsigned int)_tris.size()));
206  }
207 };
208 
209 template <typename T>
211  doxygen::def("computeMemoryFootprint", &computeMemoryFootprint<T>);
212 }
213 
215  defComputeMemoryFootprint<Sphere>();
216  defComputeMemoryFootprint<Ellipsoid>();
217  defComputeMemoryFootprint<Cone>();
218  defComputeMemoryFootprint<Capsule>();
219  defComputeMemoryFootprint<Cylinder>();
220  defComputeMemoryFootprint<Box>();
221  defComputeMemoryFootprint<Plane>();
222  defComputeMemoryFootprint<Halfspace>();
223  defComputeMemoryFootprint<TriangleP>();
224 
225  defComputeMemoryFootprint<BVHModel<OBB> >();
226  defComputeMemoryFootprint<BVHModel<RSS> >();
227  defComputeMemoryFootprint<BVHModel<OBBRSS> >();
228 }
229 
230 void exposeShapes() {
231  class_<ShapeBase, bases<CollisionGeometry>, shared_ptr<ShapeBase>,
232  noncopyable>("ShapeBase", doxygen::class_doc<ShapeBase>(), no_init)
233  //.def ("getObjectType", &CollisionGeometry::getObjectType)
234  ;
235 
236  class_<Box, bases<ShapeBase>, shared_ptr<Box> >(
237  "Box", doxygen::class_doc<ShapeBase>(), no_init)
238  .def(dv::init<Box>())
239  .def(dv::init<Box, const Box&>())
240  .def(dv::init<Box, FCL_REAL, FCL_REAL, FCL_REAL>())
241  .def(dv::init<Box, const Vec3f&>())
242  .DEF_RW_CLASS_ATTRIB(Box, halfSide)
243  .def("clone", &Box::clone, doxygen::member_func_doc(&Box::clone),
244  return_value_policy<manage_new_object>())
245  .def_pickle(PickleObject<Box>());
246 
247  class_<Capsule, bases<ShapeBase>, shared_ptr<Capsule> >(
248  "Capsule", doxygen::class_doc<Capsule>(), no_init)
249  .def(dv::init<Capsule>())
250  .def(dv::init<Capsule, FCL_REAL, FCL_REAL>())
251  .def(dv::init<Capsule, const Capsule&>())
252  .DEF_RW_CLASS_ATTRIB(Capsule, radius)
253  .DEF_RW_CLASS_ATTRIB(Capsule, halfLength)
254  .def("clone", &Capsule::clone, doxygen::member_func_doc(&Capsule::clone),
255  return_value_policy<manage_new_object>())
256  .def_pickle(PickleObject<Capsule>());
257 
258  class_<Cone, bases<ShapeBase>, shared_ptr<Cone> >(
259  "Cone", doxygen::class_doc<Cone>(), no_init)
260  .def(dv::init<Cone>())
261  .def(dv::init<Cone, FCL_REAL, FCL_REAL>())
262  .def(dv::init<Cone, const Cone&>())
263  .DEF_RW_CLASS_ATTRIB(Cone, radius)
264  .DEF_RW_CLASS_ATTRIB(Cone, halfLength)
265  .def("clone", &Cone::clone, doxygen::member_func_doc(&Cone::clone),
266  return_value_policy<manage_new_object>())
267  .def_pickle(PickleObject<Cone>());
268 
269  class_<ConvexBase, bases<ShapeBase>, shared_ptr<ConvexBase>, noncopyable>(
270  "ConvexBase", doxygen::class_doc<ConvexBase>(), no_init)
272  .DEF_RO_CLASS_ATTRIB(ConvexBase, num_points)
273  .def("point", &ConvexBaseWrapper::point, bp::args("self", "index"),
274  "Retrieve the point given by its index.",
275  bp::return_internal_reference<>())
276  .def("points", &ConvexBaseWrapper::point, bp::args("self", "index"),
277  "Retrieve the point given by its index.",
279  bp::return_internal_reference<> >())
280  .def("points", &ConvexBaseWrapper::points, bp::args("self"),
281  "Retrieve all the points.",
282  bp::with_custodian_and_ward_postcall<0, 1>())
283  // .add_property ("points",
284  // bp::make_function(&ConvexBaseWrapper::points,bp::with_custodian_and_ward_postcall<0,1>()),
285  // "Points of the convex.")
286  .def("neighbors", &ConvexBaseWrapper::neighbors)
287  .def("convexHull", &ConvexBaseWrapper::convexHull,
288  doxygen::member_func_doc(&ConvexBase::convexHull),
289  return_value_policy<manage_new_object>())
290  .staticmethod("convexHull")
291  .def("clone", &ConvexBase::clone,
292  doxygen::member_func_doc(&ConvexBase::clone),
293  return_value_policy<manage_new_object>());
294 
295  class_<Convex<Triangle>, bases<ConvexBase>, shared_ptr<Convex<Triangle> >,
296  noncopyable>("Convex", doxygen::class_doc<Convex<Triangle> >(),
297  no_init)
298  .def("__init__", make_constructor(&ConvexWrapper<Triangle>::constructor))
299  .def(dv::init<Convex<Triangle> >())
300  .def(dv::init<Convex<Triangle>, const Convex<Triangle>&>())
301  .DEF_RO_CLASS_ATTRIB(Convex<Triangle>, num_polygons)
302  .def("polygons", &ConvexWrapper<Triangle>::polygons)
303  .def_pickle(PickleObject<Convex<Triangle> >());
304 
305  class_<Cylinder, bases<ShapeBase>, shared_ptr<Cylinder> >(
306  "Cylinder", doxygen::class_doc<Cylinder>(), no_init)
307  .def(dv::init<Cylinder>())
308  .def(dv::init<Cylinder, FCL_REAL, FCL_REAL>())
309  .def(dv::init<Cylinder, const Cylinder&>())
310  .DEF_RW_CLASS_ATTRIB(Cylinder, radius)
311  .DEF_RW_CLASS_ATTRIB(Cylinder, halfLength)
312  .def("clone", &Cylinder::clone,
313  doxygen::member_func_doc(&Cylinder::clone),
314  return_value_policy<manage_new_object>())
315  .def_pickle(PickleObject<Cylinder>());
316 
317  class_<Halfspace, bases<ShapeBase>, shared_ptr<Halfspace> >(
318  "Halfspace", doxygen::class_doc<Halfspace>(), no_init)
319  .def(dv::init<Halfspace, const Vec3f&, FCL_REAL>())
320  .def(dv::init<Halfspace, const Halfspace&>())
321  .def(dv::init<Halfspace, FCL_REAL, FCL_REAL, FCL_REAL, FCL_REAL>())
322  .def(dv::init<Halfspace>())
324  .DEF_RW_CLASS_ATTRIB(Halfspace, d)
325  .def("clone", &Halfspace::clone,
326  doxygen::member_func_doc(&Halfspace::clone),
327  return_value_policy<manage_new_object>())
328  .def_pickle(PickleObject<Halfspace>());
329 
330  class_<Plane, bases<ShapeBase>, shared_ptr<Plane> >(
331  "Plane", doxygen::class_doc<Plane>(), no_init)
332  .def(dv::init<Plane, const Vec3f&, FCL_REAL>())
333  .def(dv::init<Plane, const Plane&>())
334  .def(dv::init<Plane, FCL_REAL, FCL_REAL, FCL_REAL, FCL_REAL>())
335  .def(dv::init<Plane>())
337  .DEF_RW_CLASS_ATTRIB(Plane, d)
338  .def("clone", &Plane::clone, doxygen::member_func_doc(&Plane::clone),
339  return_value_policy<manage_new_object>())
340  .def_pickle(PickleObject<Plane>());
341 
342  class_<Sphere, bases<ShapeBase>, shared_ptr<Sphere> >(
343  "Sphere", doxygen::class_doc<Sphere>(), no_init)
344  .def(dv::init<Sphere>())
345  .def(dv::init<Sphere, const Sphere&>())
346  .def(dv::init<Sphere, FCL_REAL>())
347  .DEF_RW_CLASS_ATTRIB(Sphere, radius)
348  .def("clone", &Sphere::clone, doxygen::member_func_doc(&Sphere::clone),
349  return_value_policy<manage_new_object>())
350  .def_pickle(PickleObject<Sphere>());
351 
352  class_<Ellipsoid, bases<ShapeBase>, shared_ptr<Ellipsoid> >(
353  "Ellipsoid", doxygen::class_doc<Ellipsoid>(), no_init)
354  .def(dv::init<Ellipsoid>())
355  .def(dv::init<Ellipsoid, FCL_REAL, FCL_REAL, FCL_REAL>())
356  .def(dv::init<Ellipsoid, Vec3f>())
357  .def(dv::init<Ellipsoid, const Ellipsoid&>())
359  .def("clone", &Ellipsoid::clone,
360  doxygen::member_func_doc(&Ellipsoid::clone),
361  return_value_policy<manage_new_object>())
362  .def_pickle(PickleObject<Ellipsoid>());
363 
364  class_<TriangleP, bases<ShapeBase>, shared_ptr<TriangleP> >(
365  "TriangleP", doxygen::class_doc<TriangleP>(), no_init)
366  .def(dv::init<TriangleP>())
367  .def(dv::init<TriangleP, const Vec3f&, const Vec3f&, const Vec3f&>())
368  .def(dv::init<TriangleP, const TriangleP&>())
370  .DEF_RW_CLASS_ATTRIB(TriangleP, b)
371  .DEF_RW_CLASS_ATTRIB(TriangleP, c)
372  .def("clone", &TriangleP::clone,
373  doxygen::member_func_doc(&TriangleP::clone),
374  return_value_policy<manage_new_object>())
375  .def_pickle(PickleObject<TriangleP>());
376 }
377 
378 boost::python::tuple AABB_distance_proxy(const AABB& self, const AABB& other) {
379  Vec3f P, Q;
380  FCL_REAL distance = self.distance(other, &P, &Q);
381  return boost::python::make_tuple(distance, P, Q);
382 }
383 
385  enum_<BVHModelType>("BVHModelType")
386  .value("BVH_MODEL_UNKNOWN", BVH_MODEL_UNKNOWN)
387  .value("BVH_MODEL_TRIANGLES", BVH_MODEL_TRIANGLES)
388  .value("BVH_MODEL_POINTCLOUD", BVH_MODEL_POINTCLOUD)
389  .export_values();
390 
391  enum_<BVHBuildState>("BVHBuildState")
392  .value("BVH_BUILD_STATE_EMPTY", BVH_BUILD_STATE_EMPTY)
393  .value("BVH_BUILD_STATE_BEGUN", BVH_BUILD_STATE_BEGUN)
394  .value("BVH_BUILD_STATE_PROCESSED", BVH_BUILD_STATE_PROCESSED)
395  .value("BVH_BUILD_STATE_UPDATE_BEGUN", BVH_BUILD_STATE_UPDATE_BEGUN)
396  .value("BVH_BUILD_STATE_UPDATED", BVH_BUILD_STATE_UPDATED)
397  .value("BVH_BUILD_STATE_REPLACE_BEGUN", BVH_BUILD_STATE_REPLACE_BEGUN)
398  .export_values();
399 
400  if (!eigenpy::register_symbolic_link_to_registered_type<OBJECT_TYPE>()) {
401  enum_<OBJECT_TYPE>("OBJECT_TYPE")
402  .value("OT_UNKNOWN", OT_UNKNOWN)
403  .value("OT_BVH", OT_BVH)
404  .value("OT_GEOM", OT_GEOM)
405  .value("OT_OCTREE", OT_OCTREE)
406  .value("OT_HFIELD", OT_HFIELD)
407  .export_values();
408  }
409 
410  if (!eigenpy::register_symbolic_link_to_registered_type<NODE_TYPE>()) {
411  enum_<NODE_TYPE>("NODE_TYPE")
412  .value("BV_UNKNOWN", BV_UNKNOWN)
413  .value("BV_AABB", BV_AABB)
414  .value("BV_OBB", BV_OBB)
415  .value("BV_RSS", BV_RSS)
416  .value("BV_kIOS", BV_kIOS)
417  .value("BV_OBBRSS", BV_OBBRSS)
418  .value("BV_KDOP16", BV_KDOP16)
419  .value("BV_KDOP18", BV_KDOP18)
420  .value("BV_KDOP24", BV_KDOP24)
421  .value("GEOM_BOX", GEOM_BOX)
422  .value("GEOM_SPHERE", GEOM_SPHERE)
423  .value("GEOM_ELLIPSOID", GEOM_ELLIPSOID)
424  .value("GEOM_CAPSULE", GEOM_CAPSULE)
425  .value("GEOM_CONE", GEOM_CONE)
426  .value("GEOM_CYLINDER", GEOM_CYLINDER)
427  .value("GEOM_CONVEX", GEOM_CONVEX)
428  .value("GEOM_PLANE", GEOM_PLANE)
429  .value("GEOM_HALFSPACE", GEOM_HALFSPACE)
430  .value("GEOM_TRIANGLE", GEOM_TRIANGLE)
431  .value("GEOM_OCTREE", GEOM_OCTREE)
432  .value("HF_AABB", HF_AABB)
433  .value("HF_OBBRSS", HF_OBBRSS)
434  .export_values();
435  }
436 
437  class_<AABB>("AABB",
438  "A class describing the AABB collision structure, which is a "
439  "box in 3D space determined by two diagonal points",
440  no_init)
441  .def(init<>(bp::arg("self"), "Default constructor"))
442  .def(init<AABB>(bp::args("self", "other"), "Copy constructor"))
443  .def(init<Vec3f>(bp::args("self", "v"),
444  "Creating an AABB at position v with zero size."))
445  .def(init<Vec3f, Vec3f>(bp::args("self", "a", "b"),
446  "Creating an AABB with two endpoints a and b."))
447  .def(init<AABB, Vec3f>(
448  bp::args("self", "core", "delta"),
449  "Creating an AABB centered as core and is of half-dimension delta."))
450  .def(init<Vec3f, Vec3f, Vec3f>(bp::args("self", "a", "b", "c"),
451  "Creating an AABB contains three points."))
452 
453  .def("contain", (bool(AABB::*)(const Vec3f&) const) & AABB::contain,
454  bp::args("self", "p"), "Check whether the AABB contains a point p.")
455  .def("contain", (bool(AABB::*)(const AABB&) const) & AABB::contain,
456  bp::args("self", "other"),
457  "Check whether the AABB contains another AABB.")
458 
459  .def("overlap", (bool(AABB::*)(const AABB&) const) & AABB::overlap,
460  bp::args("self", "other"), "Check whether two AABB are overlap.")
461  .def("overlap", (bool(AABB::*)(const AABB&, AABB&) const) & AABB::overlap,
462  bp::args("self", "other", "overlapping_part"),
463  "Check whether two AABB are overlaping and return the overloaping "
464  "part if true.")
465 
466  .def("distance", (FCL_REAL(AABB::*)(const AABB&) const) & AABB::distance,
467  bp::args("self", "other"), "Distance between two AABBs.")
468  // .def("distance",
469  // AABB_distance_proxy,
470  // bp::args("self","other"),
471  // "Distance between two AABBs.")
472 
473  .add_property(
474  "min_",
475  bp::make_function(
476  +[](AABB& self) -> Vec3f& { return self.min_; },
477  bp::return_internal_reference<>()),
478  bp::make_function(
479  +[](AABB& self, const Vec3f& min_) -> void { self.min_ = min_; }),
480  "The min point in the AABB.")
481  .add_property(
482  "max_",
483  bp::make_function(
484  +[](AABB& self) -> Vec3f& { return self.max_; },
485  bp::return_internal_reference<>()),
486  bp::make_function(
487  +[](AABB& self, const Vec3f& max_) -> void { self.max_ = max_; }),
488  "The max point in the AABB.")
489 
490  .def(bp::self == bp::self)
491  .def(bp::self != bp::self)
492 
493  .def(bp::self + bp::self)
494  .def(bp::self += bp::self)
495  .def(bp::self += Vec3f())
496 
497  .def("size", &AABB::volume, bp::arg("self"), "Size of the AABB.")
498  .def("center", &AABB::center, bp::arg("self"), "Center of the AABB.")
499  .def("width", &AABB::width, bp::arg("self"), "Width of the AABB.")
500  .def("height", &AABB::height, bp::arg("self"), "Height of the AABB.")
501  .def("depth", &AABB::depth, bp::arg("self"), "Depth of the AABB.")
502  .def("volume", &AABB::volume, bp::arg("self"), "Volume of the AABB.")
503 
504  .def("expand",
505  static_cast<AABB& (AABB::*)(const AABB&, FCL_REAL)>(&AABB::expand),
506  // doxygen::member_func_doc(static_cast<AABB& (AABB::*)(const
507  // AABB &, FCL_REAL)>(&AABB::expand)),
508  // doxygen::member_func_args(static_cast<AABB&
509  // (AABB::*)(const AABB &, FCL_REAL)>(&AABB::expand)),
510  bp::return_internal_reference<>())
511  .def("expand",
512  static_cast<AABB& (AABB::*)(const FCL_REAL)>(&AABB::expand),
513  // doxygen::member_func_doc(static_cast<AABB& (AABB::*)(const
514  // FCL_REAL)>(&AABB::expand)),
515  // doxygen::member_func_args(static_cast<AABB&
516  // (AABB::*)(const FCL_REAL)>(&AABB::expand)),
517  bp::return_internal_reference<>())
518  .def("expand", static_cast<AABB& (AABB::*)(const Vec3f&)>(&AABB::expand),
519  // doxygen::member_func_doc(static_cast<AABB& (AABB::*)(const
520  // Vec3f &)>(&AABB::expand)),
521  // doxygen::member_func_args(static_cast<AABB&
522  // (AABB::*)(const Vec3f &)>(&AABB::expand)),
523  bp::return_internal_reference<>())
524  .def_pickle(PickleObject<AABB>());
525 
526  def("translate", (AABB(*)(const AABB&, const Vec3f&)) & translate,
527  bp::args("aabb", "t"), "Translate the center of AABB by t");
528 
529  def("rotate", (AABB(*)(const AABB&, const Matrix3f&)) & rotate,
530  bp::args("aabb", "R"), "Rotate the AABB object by R");
531 
533  CollisionGeometry>()) {
534  class_<CollisionGeometry, CollisionGeometryPtr_t, noncopyable>(
535  "CollisionGeometry", no_init)
536  .def("getObjectType", &CollisionGeometry::getObjectType)
537  .def("getNodeType", &CollisionGeometry::getNodeType)
538 
539  .def("computeLocalAABB", &CollisionGeometry::computeLocalAABB)
540 
541  .def("computeCOM", &CollisionGeometry::computeCOM)
542  .def("computeMomentofInertia",
543  &CollisionGeometry::computeMomentofInertia)
544  .def("computeVolume", &CollisionGeometry::computeVolume)
545  .def("computeMomentofInertiaRelatedToCOM",
546  &CollisionGeometry::computeMomentofInertiaRelatedToCOM)
547 
548  .def_readwrite("aabb_radius", &CollisionGeometry::aabb_radius,
549  "AABB radius.")
550  .def_readwrite("aabb_center", &CollisionGeometry::aabb_center,
551  "AABB center in local coordinate.")
552  .def_readwrite("aabb_local", &CollisionGeometry::aabb_local,
553  "AABB in local coordinate, used for tight AABB when "
554  "only translation transform.")
555 
556  .def("isOccupied", &CollisionGeometry::isOccupied, bp::arg("self"),
557  "Whether the object is completely occupied.")
558  .def("isFree", &CollisionGeometry::isFree, bp::arg("self"),
559  "Whether the object is completely free.")
560  .def("isUncertain", &CollisionGeometry::isUncertain, bp::arg("self"),
561  "Whether the object has some uncertainty.")
562 
563  .def_readwrite("cost_density", &CollisionGeometry::cost_density,
564  "Collision cost for unit volume.")
565  .def_readwrite("threshold_occupied",
566  &CollisionGeometry::threshold_occupied,
567  "Threshold for occupied ( >= is occupied).")
568  .def_readwrite("threshold_free", &CollisionGeometry::threshold_free,
569  "Threshold for free (<= is free).")
570 
571  .def(self == self)
572  .def(self != self);
573  }
574 
575  exposeShapes();
576 
577  class_<BVHModelBase, bases<CollisionGeometry>, BVHModelPtr_t, noncopyable>(
578  "BVHModelBase", no_init)
579  .def("vertex", &BVHModelBaseWrapper::vertex, bp::args("self", "index"),
580  "Retrieve the vertex given by its index.",
581  bp::return_internal_reference<>())
582  .def("vertices", &BVHModelBaseWrapper::vertex, bp::args("self", "index"),
583  "Retrieve the vertex given by its index.",
585  bp::return_internal_reference<> >())
586  .def("vertices", &BVHModelBaseWrapper::vertices, bp::args("self"),
587  "Retrieve all the vertices.",
588  bp::with_custodian_and_ward_postcall<0, 1>())
589  // .add_property ("vertices",
590  // bp::make_function(&BVHModelBaseWrapper::vertices,bp::with_custodian_and_ward_postcall<0,1>()),
591  // "Vertices of the BVH.")
592  .def("tri_indices", &BVHModelBaseWrapper::tri_indices,
593  bp::args("self", "index"),
594  "Retrieve the triangle given by its index.")
595  .def_readonly("num_vertices", &BVHModelBase::num_vertices)
596  .def_readonly("num_tris", &BVHModelBase::num_tris)
597  .def_readonly("build_state", &BVHModelBase::build_state)
598 
599  .def_readonly("convex", &BVHModelBase::convex)
600 
601  .DEF_CLASS_FUNC(BVHModelBase, buildConvexRepresentation)
602  .DEF_CLASS_FUNC(BVHModelBase, buildConvexHull)
603 
604  // Expose function to build a BVH
605  .def(dv::member_func("beginModel", &BVHModelBase::beginModel))
606  .def(dv::member_func("addVertex", &BVHModelBase::addVertex))
607  .def(dv::member_func("addVertices", &BVHModelBase::addVertices))
608  .def(dv::member_func("addTriangle", &BVHModelBase::addTriangle))
609  .def(dv::member_func("addTriangles", &BVHModelBase::addTriangles))
610  .def(dv::member_func<int (BVHModelBase::*)(
611  const Vec3fs&, const Triangles&)>("addSubModel",
612  &BVHModelBase::addSubModel))
613  .def(dv::member_func<int (BVHModelBase::*)(const Vec3fs&)>(
614  "addSubModel", &BVHModelBase::addSubModel))
615  .def(dv::member_func("endModel", &BVHModelBase::endModel))
616  // Expose function to replace a BVH
617  .def(dv::member_func("beginReplaceModel",
618  &BVHModelBase::beginReplaceModel))
619  .def(dv::member_func("replaceVertex", &BVHModelBase::replaceVertex))
620  .def(dv::member_func("replaceTriangle", &BVHModelBase::replaceTriangle))
621  .def(dv::member_func("replaceSubModel", &BVHModelBase::replaceSubModel))
622  .def(dv::member_func("endReplaceModel", &BVHModelBase::endReplaceModel))
623  .def(dv::member_func("getModelType", &BVHModelBase::getModelType));
624  exposeBVHModel<OBB>("OBB");
625  exposeBVHModel<OBBRSS>("OBBRSS");
626  exposeHeightField<OBBRSS>("OBBRSS");
627  exposeHeightField<AABB>("AABB");
629 }
630 
632  namespace bp = boost::python;
633 
634  if (!eigenpy::register_symbolic_link_to_registered_type<CollisionObject>()) {
635  class_<CollisionObject, CollisionObjectPtr_t>("CollisionObject", no_init)
636  .def(dv::init<CollisionObject, const CollisionGeometryPtr_t&,
637  bp::optional<bool> >())
638  .def(dv::init<CollisionObject, const CollisionGeometryPtr_t&,
639  const Transform3f&, bp::optional<bool> >())
640  .def(dv::init<CollisionObject, const CollisionGeometryPtr_t&,
641  const Matrix3f&, const Vec3f&, bp::optional<bool> >())
642 
643  .DEF_CLASS_FUNC(CollisionObject, getObjectType)
644  .DEF_CLASS_FUNC(CollisionObject, getNodeType)
645  .DEF_CLASS_FUNC(CollisionObject, computeAABB)
646  .def(dv::member_func("getAABB",
647  static_cast<AABB& (CollisionObject::*)()>(
648  &CollisionObject::getAABB),
649  bp::return_internal_reference<>()))
650 
651  .DEF_CLASS_FUNC2(CollisionObject, getTranslation,
652  bp::return_value_policy<bp::copy_const_reference>())
653  .DEF_CLASS_FUNC(CollisionObject, setTranslation)
654  .DEF_CLASS_FUNC2(CollisionObject, getRotation,
655  bp::return_value_policy<bp::copy_const_reference>())
656  .DEF_CLASS_FUNC(CollisionObject, setRotation)
657  .DEF_CLASS_FUNC2(CollisionObject, getTransform,
658  bp::return_value_policy<bp::copy_const_reference>())
659  .def(dv::member_func(
660  "setTransform",
661  static_cast<void (CollisionObject::*)(const Transform3f&)>(
662  &CollisionObject::setTransform)))
663 
664  .DEF_CLASS_FUNC(CollisionObject, isIdentityTransform)
665  .DEF_CLASS_FUNC(CollisionObject, setIdentityTransform)
666  .DEF_CLASS_FUNC2(CollisionObject, setCollisionGeometry,
667  (bp::with_custodian_and_ward_postcall<1, 2>()))
668 
669  .def(dv::member_func(
670  "collisionGeometry",
671  static_cast<const CollisionGeometryPtr_t& (CollisionObject::*)()>(
672  &CollisionObject::collisionGeometry),
673  bp::return_value_policy<bp::copy_const_reference>()));
674  }
675 }
hpp::fcl::BVH_BUILD_STATE_UPDATE_BEGUN
@ BVH_BUILD_STATE_UPDATE_BEGUN
after tree has been build, ready for cd use
Definition: BVH_internal.h:55
hpp::fcl::HF_OBBRSS
@ HF_OBBRSS
Definition: collision_object.h:87
BVHModelBaseWrapper::MapRowMatrixX3
Eigen::Map< RowMatrixX3 > MapRowMatrixX3
Definition: collision-geometries.cc:81
hpp::fcl::GEOM_HALFSPACE
@ GEOM_HALFSPACE
Definition: collision_object.h:82
exposeComputeMemoryFootprint
void exposeComputeMemoryFootprint()
Definition: collision-geometries.cc:214
boost::python
hpp::fcl::GEOM_ELLIPSOID
@ GEOM_ELLIPSOID
Definition: collision_object.h:85
hpp::fcl::Vec3f
Eigen::Matrix< FCL_REAL, 3, 1 > Vec3f
Definition: data_types.h:66
hpp::fcl::ConvexBase::neighbors
Neighbors * neighbors
Definition: shape/geometric_shapes.h:655
hfield.h
hpp::fcl::ConvexBase::points
Vec3f * points
An array of the points of the polygon.
Definition: shape/geometric_shapes.h:623
hpp::fcl::GEOM_BOX
@ GEOM_BOX
Definition: collision_object.h:75
eigenpy.hpp
hpp::fcl::BV_KDOP24
@ BV_KDOP24
Definition: collision_object.h:74
hpp::fcl::MatrixXf
Eigen::Matrix< FCL_REAL, Eigen::Dynamic, Eigen::Dynamic > MatrixXf
Definition: data_types.h:71
ConvexWrapper::constructor
static shared_ptr< Convex_t > constructor(const Vec3fs &_points, const Triangles &_tris)
Definition: collision-geometries.cc:197
BVHModelBaseWrapper::vertex
static Vec3f & vertex(BVHModelBase &bvh, unsigned int i)
Definition: collision-geometries.cc:84
hpp::fcl::GEOM_PLANE
@ GEOM_PLANE
Definition: collision_object.h:81
hpp::fcl::ConvexBase::num_points
unsigned int num_points
Definition: shape/geometric_shapes.h:624
ConvexBaseWrapper::MapRowMatrixX3
Eigen::Map< RowMatrixX3 > MapRowMatrixX3
Definition: collision-geometries.cc:158
eigenpy::register_symbolic_link_to_registered_type
bool register_symbolic_link_to_registered_type()
hpp::fcl::Sphere
Center at zero point sphere.
Definition: shape/geometric_shapes.h:196
hpp::fcl::BV_RSS
@ BV_RSS
Definition: collision_object.h:69
hpp::fcl::BVH_BUILD_STATE_PROCESSED
@ BVH_BUILD_STATE_PROCESSED
Definition: BVH_internal.h:54
ConvexWrapper::polygons
static PolygonT polygons(const Convex_t &convex, unsigned int i)
Definition: collision-geometries.cc:191
hpp::fcl::HeightField
Data structure depicting a height field given by the base grid dimensions and the elevation along the...
Definition: hfield.h:182
ConvexBaseWrapper::RefRowMatrixX3
Eigen::Ref< RowMatrixX3 > RefRowMatrixX3
Definition: collision-geometries.cc:159
rotate
Vec3f rotate(Vec3f input, FCL_REAL w, Vec3f vec)
Definition: math.cpp:108
hpp::fcl::BVH_MODEL_UNKNOWN
@ BVH_MODEL_UNKNOWN
Definition: BVH_internal.h:81
hpp::fcl::OT_HFIELD
@ OT_HFIELD
Definition: collision_object.h:58
AABB_distance_proxy
boost::python::tuple AABB_distance_proxy(const AABB &self, const AABB &other)
Definition: collision-geometries.cc:378
distance
double distance(const std::vector< Transform3f > &tf, const BVHModel< BV > &m1, const BVHModel< BV > &m2, bool verbose)
Definition: benchmark.cpp:93
eigen-to-python.hpp
hpp::fcl::BVHModelBase::num_vertices
unsigned int num_vertices
Number of points.
Definition: BVH/BVH_model.h:78
doxygen::visitor
Definition: doxygen-boost.hh:12
hpp::fcl::GEOM_CONVEX
@ GEOM_CONVEX
Definition: collision_object.h:80
exposeHeightField
void exposeHeightField(const std::string &bvname)
Definition: collision-geometries.cc:117
hpp::fcl::BV_OBB
@ BV_OBB
Definition: collision_object.h:68
hpp::fcl::Convex::num_polygons
unsigned int num_polygons
Definition: shape/convex.h:77
hierarchy_tree.h
fcl.hh
hpp::fcl::CollisionGeometryPtr_t
shared_ptr< CollisionGeometry > CollisionGeometryPtr_t
Definition: include/hpp/fcl/fwd.hh:96
exposeCollisionGeometries
void exposeCollisionGeometries()
Definition: collision-geometries.cc:384
doxygen::def
void def(const char *name, Func func)
Definition: doxygen-boost.hh:106
hpp::fcl::CollisionGeometry
The geometry for the object for collision or distance computation.
Definition: collision_object.h:95
hpp::fcl::BVHModelBase::tri_indices
Triangle * tri_indices
Geometry triangle index data, will be NULL for point clouds.
Definition: BVH/BVH_model.h:69
hpp::fcl::Cylinder
Cylinder along Z axis. The cylinder is defined at its centroid.
Definition: shape/geometric_shapes.h:501
hpp::fcl::ConvexBase::Neighbors::count
unsigned char const & count() const
Definition: shape/geometric_shapes.h:630
ConvexBaseWrapper::RowMatrixX3
Eigen::Matrix< double, Eigen::Dynamic, 3, Eigen::RowMajor > RowMatrixX3
Definition: collision-geometries.cc:157
hpp::fcl::OT_BVH
@ OT_BVH
Definition: collision_object.h:55
DEF_RW_CLASS_ATTRIB
#define DEF_RW_CLASS_ATTRIB(CLASS, ATTRIB)
Definition: python/fwd.hh:29
hpp::fcl::BVH_BUILD_STATE_REPLACE_BEGUN
@ BVH_BUILD_STATE_REPLACE_BEGUN
Definition: BVH_internal.h:59
a
list a
hpp::fcl::Convex
Convex polytope.
Definition: shape/convex.h:50
hpp::fcl::Ellipsoid
Ellipsoid centered at point zero.
Definition: shape/geometric_shapes.h:258
doxygen_xml_parser.args
args
Definition: doxygen_xml_parser.py:884
ConvexWrapper
Definition: collision-geometries.cc:188
hpp::fcl::OT_GEOM
@ OT_GEOM
Definition: collision_object.h:56
hpp::fcl::BV_OBBRSS
@ BV_OBBRSS
Definition: collision_object.h:71
hpp::fcl::FCL_REAL
double FCL_REAL
Definition: data_types.h:65
hpp::fcl::BVH_BUILD_STATE_EMPTY
@ BVH_BUILD_STATE_EMPTY
Definition: BVH_internal.h:51
hpp::fcl::BV_AABB
@ BV_AABB
Definition: collision_object.h:67
ConvexBaseWrapper::neighbors
static list neighbors(const ConvexBase &convex, unsigned int i)
Definition: collision-geometries.cc:171
hpp::fcl::BVH_MODEL_TRIANGLES
@ BVH_MODEL_TRIANGLES
unknown model type
Definition: BVH_internal.h:82
Vec3fs
std::vector< Vec3f > Vec3fs
Definition: collision-geometries.cc:76
DEF_CLASS_FUNC
#define DEF_CLASS_FUNC(CLASS, ATTRIB)
Definition: python/fwd.hh:35
c
c
Triangles
std::vector< Triangle > Triangles
Definition: collision-geometries.cc:77
P
P
defComputeMemoryFootprint
void defComputeMemoryFootprint()
Definition: collision-geometries.cc:210
hpp::fcl::GEOM_SPHERE
@ GEOM_SPHERE
Definition: collision_object.h:76
hpp::fcl::CollisionObject
the object for collision or distance computation, contains the geometry and the transform information
Definition: collision_object.h:215
doxygen::visitor::member_func
member_func_impl< function_type > member_func(const char *name, const function_type &function)
Definition: doxygen-boost.hh:49
deprecation.hh
ConvexBaseWrapper::convexHull
static ConvexBase * convexHull(const Vec3fs &points, bool keepTri, const char *qhullCommand)
Definition: collision-geometries.cc:180
BVHModelBaseWrapper::RowMatrixX3
Eigen::Matrix< double, Eigen::Dynamic, 3, Eigen::RowMajor > RowMatrixX3
Definition: collision-geometries.cc:80
geometric_shapes.h
pickle.hh
hpp::fcl::OT_OCTREE
@ OT_OCTREE
Definition: collision_object.h:57
hpp::fcl::Triangle::size
static size_type size()
Definition: data_types.h:119
hpp::fcl::Cone
Cone The base of the cone is at and the top is at .
Definition: shape/geometric_shapes.h:414
hpp::fcl::Capsule
Capsule It is where is the distance between the point x and the capsule segment AB,...
Definition: shape/geometric_shapes.h:333
hpp::fcl::AABB
A class describing the AABB collision structure, which is a box in 3D space determined by two diagona...
Definition: BV/AABB.h:54
ConvexWrapper::Convex_t
Convex< PolygonT > Convex_t
Definition: collision-geometries.cc:189
hpp::fcl
Definition: broadphase_bruteforce.h:45
hpp::fcl::GEOM_OCTREE
@ GEOM_OCTREE
Definition: collision_object.h:84
AABB.h
exposeBVHModel
void exposeBVHModel(const std::string &bvname)
Definition: collision-geometries.cc:100
hpp::fcl::Matrix3f
Eigen::Matrix< FCL_REAL, 3, 3 > Matrix3f
Definition: data_types.h:68
BVH_model.h
convex.h
generate_distance_plot.b
float b
Definition: generate_distance_plot.py:7
PickleObject
Definition: pickle.hh:19
hpp::fcl::Transform3f
Simple transform class used locally by InterpMotion.
Definition: transform.h:54
hpp::fcl::ConvexBase
Base for convex polytope.
Definition: shape/geometric_shapes.h:581
ConvexBaseWrapper
Definition: collision-geometries.cc:156
hpp::fcl::Halfspace
Half Space: this is equivalent to the Plane in ODE. The separation plane is defined as n * x = d; Poi...
Definition: shape/geometric_shapes.h:729
hpp::fcl::BVHModel
A class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewed as ...
Definition: BVH/BVH_model.h:273
hpp::fcl::BVH_BUILD_STATE_BEGUN
@ BVH_BUILD_STATE_BEGUN
empty state, immediately after constructor
Definition: BVH_internal.h:52
hpp::fcl::GEOM_CYLINDER
@ GEOM_CYLINDER
Definition: collision_object.h:79
exposeCollisionObject
void exposeCollisionObject()
Definition: collision-geometries.cc:631
BVHModelBaseWrapper::vertices
static RefRowMatrixX3 vertices(BVHModelBase &bvh)
Definition: collision-geometries.cc:89
BV_splitter.h
hpp::fcl::Convex::polygons
PolygonT * polygons
An array of PolygonT object. PolygonT should contains a list of vertices for each polygon,...
Definition: shape/convex.h:76
Geometry
Definition: profiling.cpp:69
BVH_model.h
hpp::fcl::overlap
HPP_FCL_DLLAPI bool overlap(const Matrix3f &R0, const Vec3f &T0, const AABB &b1, const AABB &b2)
Check collision between two aabbs, b1 is in configuration (R0, T0) and b2 is in identity.
Definition: AABB.cpp:134
hpp::fcl::BV_KDOP18
@ BV_KDOP18
Definition: collision_object.h:73
BVHModelBaseWrapper::tri_indices
static Triangle tri_indices(const BVHModelBase &bvh, unsigned int i)
Definition: collision-geometries.cc:93
fwd.hh
hpp::fcl::GEOM_CONE
@ GEOM_CONE
Definition: collision_object.h:78
hpp::fcl::TriangleP
Triangle stores the points instead of only indices of points.
Definition: shape/geometric_shapes.h:71
ConvexBaseWrapper::points
static RefRowMatrixX3 points(const ConvexBase &convex)
Definition: collision-geometries.cc:167
geometric_shapes.h
hpp::fcl::OT_UNKNOWN
@ OT_UNKNOWN
Definition: collision_object.h:54
hpp::fcl::BVH_BUILD_STATE_UPDATED
@ BVH_BUILD_STATE_UPDATED
Definition: BVH_internal.h:57
convex.h
hpp::fcl::BVHModelBase
A base class describing the bounding hierarchy of a mesh model or a point cloud model (which is viewe...
Definition: BVH/BVH_model.h:63
hfield.h
Base
hpp::fcl::Triangle
Triangle with 3 indices for points.
Definition: data_types.h:96
hpp::fcl::BV_kIOS
@ BV_kIOS
Definition: collision_object.h:70
hpp::fcl::BV_KDOP16
@ BV_KDOP16
Definition: collision_object.h:72
hpp::fcl::GEOM_CAPSULE
@ GEOM_CAPSULE
Definition: collision_object.h:77
hpp::fcl::BVH_MODEL_POINTCLOUD
@ BVH_MODEL_POINTCLOUD
triangle model
Definition: BVH_internal.h:83
hpp::fcl::HF_AABB
@ HF_AABB
Definition: collision_object.h:86
hpp::fcl::BVHModelPtr_t
shared_ptr< BVHModelBase > BVHModelPtr_t
Definition: include/hpp/fcl/fwd.hh:103
hpp::fcl::GEOM_TRIANGLE
@ GEOM_TRIANGLE
Definition: collision_object.h:83
memory.h
ConvexBaseWrapper::point
static Vec3f & point(const ConvexBase &convex, unsigned int i)
Definition: collision-geometries.cc:161
hpp::fcl::translate
static AABB translate(const AABB &aabb, const Vec3f &t)
translate the center of AABB by t
Definition: BV/AABB.h:226
BVHModelBaseWrapper
Definition: collision-geometries.cc:79
hpp::fcl::BVHModelBase::vertices
Vec3f * vertices
Geometry point data.
Definition: BVH/BVH_model.h:66
hpp::fcl::BVHModelBase::num_tris
unsigned int num_tris
Number of triangles.
Definition: BVH/BVH_model.h:75
doxygen::member_func_doc
const char * member_func_doc(FuncPtr)
Definition: doxygen.hh:33
DEF_RO_CLASS_ATTRIB
#define DEF_RO_CLASS_ATTRIB(CLASS, ATTRIB)
Definition: python/fwd.hh:32
hpp::fcl::BV_UNKNOWN
@ BV_UNKNOWN
Definition: collision_object.h:66
hpp::fcl::python::deprecated_member
Definition: deprecation.hh:35
hpp::fcl::Box
Center at zero point, axis aligned box.
Definition: shape/geometric_shapes.h:125
BVHModelBaseWrapper::RefRowMatrixX3
Eigen::Ref< RowMatrixX3 > RefRowMatrixX3
Definition: collision-geometries.cc:82
hpp::fcl::Plane
Infinite plane.
Definition: shape/geometric_shapes.h:810
exposeShapes
void exposeShapes()
Definition: collision-geometries.cc:230


hpp-fcl
Author(s):
autogenerated on Fri Jan 26 2024 03:46:13