56 #ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC
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"
74 using boost::noncopyable;
80 typedef Eigen::Matrix<double, Eigen::Dynamic, 3, Eigen::RowMajor>
RowMatrixX3;
85 if (i >= bvh.
num_vertices)
throw std::out_of_range(
"index is out of range");
94 if (i >= bvh.
num_tris)
throw std::out_of_range(
"index is out of range");
99 template <
typename BV>
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&>())
109 .DEF_CLASS_FUNC(BVH, makeParentRelative)
112 return_value_policy<manage_new_object>())
116 template <
typename BV>
119 typedef typename Geometry::Base
Base;
120 typedef typename Geometry::Node Node;
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)
128 bp::optional<FCL_REAL> >())
132 .DEF_CLASS_FUNC(
Geometry, getMinHeight)
133 .DEF_CLASS_FUNC(
Geometry, getMaxHeight)
134 .DEF_CLASS_FUNC(
Geometry, getNodeType)
135 .DEF_CLASS_FUNC(
Geometry, updateHeights)
137 .def(
"clone", &Geometry::clone,
139 return_value_policy<manage_new_object>())
140 .
def(
"getXGrid", &Geometry::getXGrid,
142 bp::return_value_policy<bp::copy_const_reference>())
143 .
def(
"getYGrid", &Geometry::getYGrid,
145 bp::return_value_policy<bp::copy_const_reference>())
146 .
def(
"getHeights", &Geometry::getHeights,
148 bp::return_value_policy<bp::copy_const_reference>())
149 .
def(
"getBV", (Node & (
Geometry::*)(
unsigned int)) & Geometry::getBV,
152 bp::return_internal_reference<>())
157 typedef Eigen::Matrix<double, Eigen::Dynamic, 3, Eigen::RowMajor>
RowMatrixX3;
163 throw std::out_of_range(
"index is out of range");
173 throw std::out_of_range(
"index is out of range");
181 const char* qhullCommand) {
182 return ConvexBase::convexHull(points.data(), (
unsigned int)points.size(),
183 keepTri, qhullCommand);
187 template <
typename PolygonT>
193 throw std::out_of_range(
"index is out of range");
200 for (std::size_t i = 0; i < _points.size(); ++i) points[i] = _points[i];
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()));
209 template <
typename T>
211 doxygen::def(
"computeMemoryFootprint", &computeMemoryFootprint<T>);
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>();
225 defComputeMemoryFootprint<BVHModel<OBB> >();
226 defComputeMemoryFootprint<BVHModel<RSS> >();
227 defComputeMemoryFootprint<BVHModel<OBBRSS> >();
231 class_<ShapeBase, bases<CollisionGeometry>, shared_ptr<ShapeBase>,
232 noncopyable>(
"ShapeBase", doxygen::class_doc<ShapeBase>(), no_init)
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&>())
244 return_value_policy<manage_new_object>())
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&>())
253 .DEF_RW_CLASS_ATTRIB(
Capsule, halfLength)
255 return_value_policy<manage_new_object>())
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&>())
264 .DEF_RW_CLASS_ATTRIB(
Cone, halfLength)
266 return_value_policy<manage_new_object>())
269 class_<ConvexBase, bases<ShapeBase>, shared_ptr<ConvexBase>, noncopyable>(
270 "ConvexBase", doxygen::class_doc<ConvexBase>(), no_init)
274 "Retrieve the point given by its index.",
275 bp::return_internal_reference<>())
277 "Retrieve the point given by its index.",
279 bp::return_internal_reference<> >())
281 "Retrieve all the points.",
282 bp::with_custodian_and_ward_postcall<0, 1>())
289 return_value_policy<manage_new_object>())
290 .staticmethod(
"convexHull")
291 .def(
"clone", &ConvexBase::clone,
293 return_value_policy<manage_new_object>());
295 class_<Convex<Triangle>, bases<ConvexBase>, shared_ptr<Convex<Triangle> >,
296 noncopyable>(
"Convex", doxygen::class_doc<Convex<Triangle> >(),
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&>())
311 .DEF_RW_CLASS_ATTRIB(
Cylinder, halfLength)
312 .def(
"clone", &Cylinder::clone,
314 return_value_policy<manage_new_object>())
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>())
325 .def(
"clone", &Halfspace::clone,
327 return_value_policy<manage_new_object>())
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)
339 return_value_policy<manage_new_object>())
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>())
349 return_value_policy<manage_new_object>())
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,
361 return_value_policy<manage_new_object>())
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&>())
372 .def(
"clone", &TriangleP::clone,
374 return_value_policy<manage_new_object>())
381 return boost::python::make_tuple(
distance,
P, Q);
385 enum_<BVHModelType>(
"BVHModelType")
391 enum_<BVHBuildState>(
"BVHBuildState")
400 if (!eigenpy::register_symbolic_link_to_registered_type<OBJECT_TYPE>()) {
401 enum_<OBJECT_TYPE>(
"OBJECT_TYPE")
410 if (!eigenpy::register_symbolic_link_to_registered_type<NODE_TYPE>()) {
411 enum_<NODE_TYPE>(
"NODE_TYPE")
438 "A class describing the AABB collision structure, which is a "
439 "box in 3D space determined by two diagonal points",
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>(
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."))
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,
457 "Check whether the AABB contains another AABB.")
460 bp::args(
"self",
"other"),
"Check whether two AABB are overlap.")
462 bp::args(
"self",
"other",
"overlapping_part"),
463 "Check whether two AABB are overlaping and return the overloaping "
467 bp::args(
"self",
"other"),
"Distance between two AABBs.")
476 +[](
AABB&
self) ->
Vec3f& {
return self.min_; },
477 bp::return_internal_reference<>()),
479 +[](
AABB&
self,
const Vec3f& min_) ->
void {
self.min_ = min_; }),
480 "The min point in the AABB.")
484 +[](
AABB&
self) ->
Vec3f& {
return self.max_; },
485 bp::return_internal_reference<>()),
487 +[](
AABB&
self,
const Vec3f& max_) ->
void {
self.max_ = max_; }),
488 "The max point in the AABB.")
490 .def(bp::self == bp::self)
491 .def(bp::self != bp::self)
493 .def(bp::self + bp::self)
494 .def(bp::self += bp::self)
495 .def(bp::self +=
Vec3f())
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.")
510 bp::return_internal_reference<>())
517 bp::return_internal_reference<>())
523 bp::return_internal_reference<>())
527 bp::args(
"aabb",
"t"),
"Translate the center of AABB by t");
530 bp::args(
"aabb",
"R"),
"Rotate the AABB object by R");
534 class_<CollisionGeometry, CollisionGeometryPtr_t, noncopyable>(
535 "CollisionGeometry", no_init)
536 .def(
"getObjectType", &CollisionGeometry::getObjectType)
537 .def(
"getNodeType", &CollisionGeometry::getNodeType)
539 .def(
"computeLocalAABB", &CollisionGeometry::computeLocalAABB)
541 .def(
"computeCOM", &CollisionGeometry::computeCOM)
542 .def(
"computeMomentofInertia",
543 &CollisionGeometry::computeMomentofInertia)
544 .def(
"computeVolume", &CollisionGeometry::computeVolume)
545 .def(
"computeMomentofInertiaRelatedToCOM",
546 &CollisionGeometry::computeMomentofInertiaRelatedToCOM)
548 .def_readwrite(
"aabb_radius", &CollisionGeometry::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.")
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.")
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).")
577 class_<BVHModelBase, bases<CollisionGeometry>,
BVHModelPtr_t, noncopyable>(
578 "BVHModelBase", no_init)
580 "Retrieve the vertex given by its index.",
581 bp::return_internal_reference<>())
583 "Retrieve the vertex given by its index.",
585 bp::return_internal_reference<> >())
587 "Retrieve all the vertices.",
588 bp::with_custodian_and_ward_postcall<0, 1>())
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)
599 .def_readonly(
"convex", &BVHModelBase::convex)
601 .DEF_CLASS_FUNC(
BVHModelBase, buildConvexRepresentation)
612 &BVHModelBase::addSubModel))
614 "addSubModel", &BVHModelBase::addSubModel))
618 &BVHModelBase::beginReplaceModel))
624 exposeBVHModel<OBB>(
"OBB");
625 exposeBVHModel<OBBRSS>(
"OBBRSS");
626 exposeHeightField<OBBRSS>(
"OBBRSS");
627 exposeHeightField<AABB>(
"AABB");
634 if (!eigenpy::register_symbolic_link_to_registered_type<CollisionObject>()) {
635 class_<CollisionObject, CollisionObjectPtr_t>(
"CollisionObject", no_init)
637 bp::optional<bool> >())
648 &CollisionObject::getAABB),
649 bp::return_internal_reference<>()))
652 bp::return_value_policy<bp::copy_const_reference>())
655 bp::return_value_policy<bp::copy_const_reference>())
658 bp::return_value_policy<bp::copy_const_reference>())
662 &CollisionObject::setTransform)))
667 (bp::with_custodian_and_ward_postcall<1, 2>()))
672 &CollisionObject::collisionGeometry),
673 bp::return_value_policy<bp::copy_const_reference>()));