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


hpp-fcl
Author(s):
autogenerated on Sat Nov 23 2024 03:44:57