38 #if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
61 #ifdef COAL_HAS_DOXYGEN_AUTODOC
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"
80 using boost::noncopyable;
86 typedef Eigen::Matrix<double, Eigen::Dynamic, 3, Eigen::RowMajor>
RowMatrixX3;
91 if (i >= bvh.
num_vertices)
throw std::out_of_range(
"index is out of range");
103 if (i >= bvh.
num_tris)
throw std::out_of_range(
"index is out of range");
108 template <
typename BV>
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&>())
118 .DEF_CLASS_FUNC(BVH, makeParentRelative)
121 return_value_policy<manage_new_object>())
124 #
if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
130 template <
typename BV>
133 typedef typename Geometry::Base
Base;
134 typedef typename Geometry::Node Node;
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)
142 bp::optional<CoalScalar>>())
146 .DEF_CLASS_FUNC(
Geometry, getMinHeight)
147 .DEF_CLASS_FUNC(
Geometry, getMaxHeight)
148 .DEF_CLASS_FUNC(
Geometry, getNodeType)
149 .DEF_CLASS_FUNC(
Geometry, updateHeights)
151 .def(
"clone", &Geometry::clone,
153 return_value_policy<manage_new_object>())
154 .
def(
"getXGrid", &Geometry::getXGrid,
156 bp::return_value_policy<bp::copy_const_reference>())
157 .
def(
"getYGrid", &Geometry::getYGrid,
159 bp::return_value_policy<bp::copy_const_reference>())
160 .
def(
"getHeights", &Geometry::getHeights,
162 bp::return_value_policy<bp::copy_const_reference>())
163 .
def(
"getBV", (Node & (
Geometry::*)(
unsigned int)) & Geometry::getBV,
166 bp::return_internal_reference<>())
169 #
if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
176 typedef Eigen::Matrix<double, Eigen::Dynamic, 3, Eigen::RowMajor>
RowMatrixX3;
185 throw std::out_of_range(
"index is out of range");
186 return (*(convex.
points))[i];
195 throw std::out_of_range(
"index is out of range");
206 throw std::out_of_range(
"index is out of range");
217 throw std::out_of_range(
"index is out of range");
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]);
226 const char* qhullCommand) {
227 return ConvexBase::convexHull(points.data(), (
unsigned int)points.size(),
228 keepTri, qhullCommand);
232 template <
typename PolygonT>
238 throw std::out_of_range(
"index is out of range");
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];
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()));
259 template <
typename T>
261 doxygen::def(
"computeMemoryFootprint", &computeMemoryFootprint<T>);
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>();
275 defComputeMemoryFootprint<BVHModel<OBB>>();
276 defComputeMemoryFootprint<BVHModel<RSS>>();
277 defComputeMemoryFootprint<BVHModel<OBBRSS>>();
281 class_<ShapeBase, bases<CollisionGeometry>, shared_ptr<ShapeBase>,
282 noncopyable>(
"ShapeBase", doxygen::class_doc<ShapeBase>(), no_init)
285 &ShapeBase::setSweptSphereRadius))
287 &ShapeBase::getSweptSphereRadius));
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&>())
297 return_value_policy<manage_new_object>())
300 #
if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
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&>())
311 .DEF_RW_CLASS_ATTRIB(
Capsule, halfLength)
313 return_value_policy<manage_new_object>())
316 #
if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
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&>())
327 .DEF_RW_CLASS_ATTRIB(
Cone, halfLength)
329 return_value_policy<manage_new_object>())
332 #
if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
337 class_<ConvexBase, bases<ShapeBase>, shared_ptr<ConvexBase>, noncopyable>(
338 "ConvexBase", doxygen::class_doc<ConvexBase>(), no_init)
341 .DEF_RO_CLASS_ATTRIB(
ConvexBase, num_normals_and_offsets)
343 "Retrieve the point given by its index.",
344 bp::return_internal_reference<>())
346 "Retrieve the point given by its index.",
349 "Retrieve all the points.",
350 bp::with_custodian_and_ward_postcall<0, 1>())
355 "Retrieve the normal given by its index.",
356 bp::return_internal_reference<>())
358 "Retrieve all the normals.",
359 bp::with_custodian_and_ward_postcall<0, 1>())
361 "Retrieve the offset given by its index.")
363 "Retrieve all the offsets.",
364 bp::with_custodian_and_ward_postcall<0, 1>())
368 return_value_policy<manage_new_object>())
369 .staticmethod(
"convexHull")
370 .def(
"clone", &ConvexBase::clone,
372 return_value_policy<manage_new_object>());
374 class_<Convex<Triangle>, bases<ConvexBase>, shared_ptr<Convex<Triangle>>,
375 noncopyable>(
"Convex", doxygen::class_doc<Convex<Triangle>>(), no_init)
383 #
if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
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&>())
394 .DEF_RW_CLASS_ATTRIB(
Cylinder, halfLength)
395 .def(
"clone", &Cylinder::clone,
397 return_value_policy<manage_new_object>())
400 #
if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
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&>())
410 dv::init<Halfspace, CoalScalar, CoalScalar, CoalScalar, CoalScalar>())
411 .
def(dv::init<Halfspace>())
414 .def(
"clone", &Halfspace::clone,
416 return_value_policy<manage_new_object>())
419 #
if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
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)
433 return_value_policy<manage_new_object>())
436 #
if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
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>())
448 return_value_policy<manage_new_object>())
451 #
if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
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,
465 return_value_policy<manage_new_object>())
468 #
if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
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&>())
481 .def(
"clone", &TriangleP::clone,
483 return_value_policy<manage_new_object>())
486 #
if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
495 return boost::python::make_tuple(
distance,
P, Q);
499 enum_<BVHModelType>(
"BVHModelType")
505 enum_<BVHBuildState>(
"BVHBuildState")
514 if (!eigenpy::register_symbolic_link_to_registered_type<OBJECT_TYPE>()) {
515 enum_<OBJECT_TYPE>(
"OBJECT_TYPE")
524 if (!eigenpy::register_symbolic_link_to_registered_type<NODE_TYPE>()) {
525 enum_<NODE_TYPE>(
"NODE_TYPE")
552 "A class describing the AABB collision structure, which is a "
553 "box in 3D space determined by two diagonal points",
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>(
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."))
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,
571 "Check whether the AABB contains another AABB.")
574 bp::args(
"self",
"other"),
"Check whether two AABB are overlap.")
576 bp::args(
"self",
"other",
"overlapping_part"),
577 "Check whether two AABB are overlaping and return the overloaping "
581 bp::args(
"self",
"other"),
"Distance between two AABBs.")
590 +[](
AABB&
self) ->
Vec3s& {
return self.min_; },
591 bp::return_internal_reference<>()),
593 +[](
AABB&
self,
const Vec3s& min_) ->
void {
self.min_ = min_; }),
594 "The min point in the AABB.")
598 +[](
AABB&
self) ->
Vec3s& {
return self.max_; },
599 bp::return_internal_reference<>()),
601 +[](
AABB&
self,
const Vec3s& max_) ->
void {
self.max_ = max_; }),
602 "The max point in the AABB.")
604 .def(bp::self == bp::self)
605 .def(bp::self != bp::self)
607 .def(bp::self + bp::self)
608 .def(bp::self += bp::self)
609 .def(bp::self +=
Vec3s())
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.")
624 bp::return_internal_reference<>())
631 bp::return_internal_reference<>())
637 bp::return_internal_reference<>())
640 #
if EIGENPY_VERSION_AT_LEAST(3, 8, 0)
646 bp::args(
"aabb",
"t"),
"Translate the center of AABB by t");
649 bp::args(
"aabb",
"R"),
"Rotate the AABB object by R");
653 class_<CollisionGeometry, CollisionGeometryPtr_t, noncopyable>(
654 "CollisionGeometry", no_init)
655 .def(
"getObjectType", &CollisionGeometry::getObjectType)
656 .def(
"getNodeType", &CollisionGeometry::getNodeType)
658 .def(
"computeLocalAABB", &CollisionGeometry::computeLocalAABB)
660 .def(
"computeCOM", &CollisionGeometry::computeCOM)
661 .def(
"computeMomentofInertia",
662 &CollisionGeometry::computeMomentofInertia)
663 .def(
"computeVolume", &CollisionGeometry::computeVolume)
664 .def(
"computeMomentofInertiaRelatedToCOM",
665 &CollisionGeometry::computeMomentofInertiaRelatedToCOM)
667 .def_readwrite(
"aabb_radius", &CollisionGeometry::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.")
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.")
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).")
696 class_<BVHModelBase, bases<CollisionGeometry>,
BVHModelPtr_t, noncopyable>(
697 "BVHModelBase", no_init)
699 "Retrieve the vertex given by its index.",
700 bp::return_internal_reference<>())
702 "Retrieve the vertex given by its index.",
705 "Retrieve all the vertices.",
706 bp::with_custodian_and_ward_postcall<0, 1>())
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)
717 .def_readonly(
"convex", &BVHModelBase::convex)
719 .DEF_CLASS_FUNC(
BVHModelBase, buildConvexRepresentation)
730 &BVHModelBase::addSubModel))
732 "addSubModel", &BVHModelBase::addSubModel))
736 &BVHModelBase::beginReplaceModel))
742 exposeBVHModel<OBB>(
"OBB");
743 exposeBVHModel<OBBRSS>(
"OBBRSS");
744 exposeHeightField<OBBRSS>(
"OBBRSS");
745 exposeHeightField<AABB>(
"AABB");
752 if (!eigenpy::register_symbolic_link_to_registered_type<CollisionObject>()) {
753 class_<CollisionObject, CollisionObjectPtr_t>(
"CollisionObject", no_init)
755 bp::optional<bool>>())
766 &CollisionObject::getAABB),
767 bp::return_internal_reference<>()))
770 bp::return_value_policy<bp::copy_const_reference>())
773 bp::return_value_policy<bp::copy_const_reference>())
776 bp::return_value_policy<bp::copy_const_reference>())
780 &CollisionObject::setTransform)))
785 (bp::with_custodian_and_ward_postcall<1, 2>()))
790 &CollisionObject::collisionGeometry),
791 bp::return_value_policy<bp::copy_const_reference>()));