Commit 7a571738 authored by Joseph Mirabel's avatar Joseph Mirabel
Browse files

[Python] Add more documentation.

parent 02e26d16
......@@ -37,6 +37,12 @@ inline member_func_impl<function_type> member_func (const char* name, function_t
} // namespace visitor
template<typename Func>
void def(const char* name, Func func)
{
boost::python::def(name, func, member_func_doc(func));
}
} // namespace doxygen
#endif // DOXYGEN_BOOST_DOC_HH
......@@ -87,7 +87,7 @@ ADD_HEADER_GROUP(${LIBRARY_NAME}_HEADER)
ADD_SOURCE_GROUP(${LIBRARY_NAME}_SOURCES)
IF(ENABLE_DOXYGEN_AUTODOC)
ADD_DEPENDENCIES(${LIBRARY_NAME} generate_doxygen_cpp_doc)
TARGET_COMPILE_DEFINITIONS(${LIBRARY_NAME} PRIVATE -DHAS_DOXYGEN_AUTODOC)
TARGET_COMPILE_DEFINITIONS(${LIBRARY_NAME} PRIVATE -DHPP_FCL_HAS_DOXYGEN_AUTODOC)
ENDIF()
TARGET_LINK_BOOST_PYTHON(${LIBRARY_NAME} PUBLIC)
......
......@@ -43,13 +43,24 @@
#include <hpp/fcl/shape/convex.h>
#include <hpp/fcl/BVH/BVH_model.h>
#ifdef HAS_DOXYGEN_AUTODOC
#ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC
#include "doxygen_autodoc/hpp/fcl/BVH/BVH_model.h"
#include "doxygen_autodoc/hpp/fcl/shape/geometric_shapes.h"
#endif
#include "../doc/python/doxygen.hh"
#define DEF_RW_CLASS_ATTRIB(CLASS, ATTRIB) \
def_readwrite (#ATTRIB, &CLASS::ATTRIB, \
doxygen::class_attrib_doc<CLASS>(#ATTRIB))
#define DEF_RO_CLASS_ATTRIB(CLASS, ATTRIB) \
def_readonly (#ATTRIB, &CLASS::ATTRIB, \
doxygen::class_attrib_doc<CLASS>(#ATTRIB))
#define DEF_CLASS_FUNC(CLASS, ATTRIB) \
def (#ATTRIB, &CLASS::ATTRIB, doxygen::member_func_doc(&CLASS::ATTRIB))
#define DEF_CLASS_FUNC2(CLASS, ATTRIB,policy) \
def (#ATTRIB, &CLASS::ATTRIB, doxygen::member_func_doc(&CLASS::ATTRIB),policy)
using namespace boost::python;
using namespace hpp::fcl;
......@@ -125,67 +136,68 @@ void exposeShapes ()
.def (init<Vec3f>())
.add_property("halfSide",
make_getter(&Box::halfSide, return_value_policy<return_by_value>()),
make_setter(&Box::halfSide, return_value_policy<return_by_value>()));
make_setter(&Box::halfSide, return_value_policy<return_by_value>()),
doxygen::class_attrib_doc<Box>("halfSide"))
;
class_ <Capsule, bases<ShapeBase>, shared_ptr<Capsule> >
("Capsule", doxygen::class_doc<Capsule>(), init<FCL_REAL, FCL_REAL>())
.def_readwrite ("radius", &Capsule::radius)
.def_readwrite ("halfLength", &Capsule::halfLength)
.DEF_RW_CLASS_ATTRIB (Capsule, radius)
.DEF_RW_CLASS_ATTRIB (Capsule, halfLength)
;
class_ <Cone, bases<ShapeBase>, shared_ptr<Cone> >
("Cone", doxygen::class_doc<Cone>(), init<FCL_REAL, FCL_REAL>())
.def_readwrite ("radius", &Cone::radius)
.def_readwrite ("halfLength", &Cone::halfLength)
.DEF_RW_CLASS_ATTRIB (Cone, radius)
.DEF_RW_CLASS_ATTRIB (Cone, halfLength)
;
class_ <ConvexBase, bases<ShapeBase>, shared_ptr<ConvexBase >, noncopyable>
("ConvexBase", doxygen::class_doc<ConvexBase>(), no_init)
.def_readonly ("center", &ConvexBase::center)
.def_readonly ("num_points", &ConvexBase::num_points)
.DEF_RO_CLASS_ATTRIB (ConvexBase, center)
.DEF_RO_CLASS_ATTRIB (ConvexBase, num_points)
.def ("points", &ConvexBaseWrapper::points)
.def ("neighbors", &ConvexBaseWrapper::neighbors)
;
class_ <Convex<Triangle>, bases<ConvexBase>, shared_ptr<Convex<Triangle> >, noncopyable>
("Convex", doxygen::class_doc< Convex<Triangle> >(), no_init)
.def_readonly ("num_polygons", &Convex<Triangle>::num_polygons)
.DEF_RO_CLASS_ATTRIB (Convex<Triangle>, num_polygons)
.def ("polygons", &ConvexWrapper<Triangle>::polygons)
;
class_ <Cylinder, bases<ShapeBase>, shared_ptr<Cylinder> >
("Cylinder", doxygen::class_doc<Cylinder>(), init<FCL_REAL, FCL_REAL>())
.def_readwrite ("radius", &Cylinder::radius)
.def_readwrite ("halfLength", &Cylinder::halfLength)
.DEF_RW_CLASS_ATTRIB (Cylinder, radius)
.DEF_RW_CLASS_ATTRIB (Cylinder, halfLength)
;
class_ <Halfspace, bases<ShapeBase>, shared_ptr<Halfspace> >
("Halfspace", doxygen::class_doc<Halfspace>(), init<const Vec3f&, FCL_REAL>())
.def (init<FCL_REAL,FCL_REAL,FCL_REAL,FCL_REAL>())
.def (init<>())
.def_readwrite ("n", &Halfspace::n)
.def_readwrite ("d", &Halfspace::d)
.DEF_RW_CLASS_ATTRIB (Halfspace, n)
.DEF_RW_CLASS_ATTRIB (Halfspace, d)
;
class_ <Plane, bases<ShapeBase>, shared_ptr<Plane> >
("Plane", doxygen::class_doc<Plane>(), init<const Vec3f&, FCL_REAL>())
.def (init<FCL_REAL,FCL_REAL,FCL_REAL,FCL_REAL>())
.def (init<>())
.def_readwrite ("n", &Plane::n)
.def_readwrite ("d", &Plane::d)
.DEF_RW_CLASS_ATTRIB (Plane, n)
.DEF_RW_CLASS_ATTRIB (Plane, d)
;
class_ <Sphere, bases<ShapeBase>, shared_ptr<Sphere> >
("Sphere", doxygen::class_doc<Sphere>(), init<FCL_REAL>(doxygen::constructor_doc<Sphere>()))
.def_readwrite ("radius", &Sphere::radius, doxygen::class_attrib_doc<Sphere>("radius"))
.DEF_RW_CLASS_ATTRIB (Sphere, radius)
;
class_ <TriangleP, bases<ShapeBase>, shared_ptr<TriangleP> >
("TriangleP", doxygen::class_doc<TriangleP>(), init<const Vec3f&, const Vec3f&, const Vec3f&>())
.def_readwrite ("a", &TriangleP::a)
.def_readwrite ("b", &TriangleP::b)
.def_readwrite ("c", &TriangleP::c)
.DEF_RW_CLASS_ATTRIB (TriangleP, a)
.DEF_RW_CLASS_ATTRIB (TriangleP, b)
.DEF_RW_CLASS_ATTRIB (TriangleP, c)
;
}
......
......@@ -42,6 +42,25 @@
#include <hpp/fcl/fwd.hh>
#include <hpp/fcl/collision.h>
#ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC
#include "doxygen_autodoc/functions.h"
#include "doxygen_autodoc/hpp/fcl/collision_data.h"
#endif
#include "../doc/python/doxygen.hh"
#include "../doc/python/doxygen-boost.hh"
#define DEF_RW_CLASS_ATTRIB(CLASS, ATTRIB) \
def_readwrite (#ATTRIB, &CLASS::ATTRIB, \
doxygen::class_attrib_doc<CLASS>(#ATTRIB))
#define DEF_RO_CLASS_ATTRIB(CLASS, ATTRIB) \
def_readonly (#ATTRIB, &CLASS::ATTRIB, \
doxygen::class_attrib_doc<CLASS>(#ATTRIB))
#define DEF_CLASS_FUNC(CLASS, ATTRIB) \
def (#ATTRIB, &CLASS::ATTRIB, doxygen::member_func_doc(&CLASS::ATTRIB))
#define DEF_CLASS_FUNC2(CLASS, ATTRIB,policy) \
def (#ATTRIB, &CLASS::ATTRIB, doxygen::member_func_doc(&CLASS::ATTRIB),policy)
using namespace boost::python;
using namespace hpp::fcl;
......@@ -59,31 +78,33 @@ void exposeCollisionAPI ()
if(!eigenpy::register_symbolic_link_to_registered_type<CollisionRequest>())
{
class_ <CollisionRequest> ("CollisionRequest", init<>())
class_ <CollisionRequest> ("CollisionRequest",
doxygen::class_doc<CollisionRequest>(), init<>())
.def (init<CollisionRequestFlag, size_t>())
.def_readwrite ("num_max_contacts" , &CollisionRequest::num_max_contacts)
.def_readwrite ("enable_contact" , &CollisionRequest::enable_contact)
.def_readwrite ("enable_distance_lower_bound", &CollisionRequest::enable_distance_lower_bound)
.def_readwrite ("enable_cached_gjk_guess" , &CollisionRequest::enable_cached_gjk_guess)
.def_readwrite ("cached_gjk_guess" , &CollisionRequest::cached_gjk_guess)
.def_readwrite ("security_margin" , &CollisionRequest::security_margin)
.def_readwrite ("break_distance" , &CollisionRequest::break_distance)
.DEF_RW_CLASS_ATTRIB (CollisionRequest, num_max_contacts )
.DEF_RW_CLASS_ATTRIB (CollisionRequest, enable_contact )
.DEF_RW_CLASS_ATTRIB (CollisionRequest, enable_distance_lower_bound)
.DEF_RW_CLASS_ATTRIB (CollisionRequest, enable_cached_gjk_guess )
.DEF_RW_CLASS_ATTRIB (CollisionRequest, cached_gjk_guess )
.DEF_RW_CLASS_ATTRIB (CollisionRequest, security_margin )
.DEF_RW_CLASS_ATTRIB (CollisionRequest, break_distance )
;
}
if(!eigenpy::register_symbolic_link_to_registered_type<Contact>())
{
class_ <Contact> ("Contact", init<>())
class_ <Contact> ("Contact",
doxygen::class_doc<Contact>(), init<>())
//.def(init<CollisionGeometryPtr_t, CollisionGeometryPtr_t, int, int>())
//.def(init<CollisionGeometryPtr_t, CollisionGeometryPtr_t, int, int, Vec3f, Vec3f, FCL_REAL>())
.def_readonly ("o1", &Contact::o1)
.def_readonly ("o2", &Contact::o2)
.def_readwrite ("b1", &Contact::b1)
.def_readwrite ("b2", &Contact::b2)
.def_readwrite ("normal", &Contact::normal)
.def_readwrite ("pos", &Contact::pos)
.def_readwrite ("penetration_depth", &Contact::penetration_depth)
.DEF_RO_CLASS_ATTRIB (Contact, o1)
.DEF_RO_CLASS_ATTRIB (Contact, o2)
.DEF_RW_CLASS_ATTRIB (Contact, b1)
.DEF_RW_CLASS_ATTRIB (Contact, b2)
.DEF_RW_CLASS_ATTRIB (Contact, normal)
.DEF_RW_CLASS_ATTRIB (Contact, pos)
.DEF_RW_CLASS_ATTRIB (Contact, penetration_depth)
.def (self == self)
.def (self != self)
;
......@@ -96,15 +117,18 @@ void exposeCollisionAPI ()
;
}
if(!eigenpy::register_symbolic_link_to_registered_type< std::vector<CollisionResult> >())
if(!eigenpy::register_symbolic_link_to_registered_type< CollisionResult >())
{
class_ <CollisionResult> ("CollisionResult", init<>())
.def ("isCollision", &CollisionResult::isCollision)
.def ("numContacts", &CollisionResult::numContacts)
.def ("getContact" , &CollisionResult::getContact , return_value_policy<copy_const_reference>())
.def ("getContacts", &CollisionResult::getContacts, return_internal_reference<>())
.def ("addContact" , &CollisionResult::addContact )
.def ("clear", &CollisionResult::clear)
class_ <CollisionResult> ("CollisionResult",
doxygen::class_doc<CollisionResult>(), init<>())
.DEF_CLASS_FUNC (CollisionResult, isCollision)
.DEF_CLASS_FUNC (CollisionResult, numContacts)
.DEF_CLASS_FUNC (CollisionResult, addContact )
.DEF_CLASS_FUNC (CollisionResult, clear)
.DEF_CLASS_FUNC2 (CollisionResult, getContact , return_value_policy<copy_const_reference>())
.DEF_CLASS_FUNC2 (CollisionResult, getContacts, return_internal_reference<>())
.DEF_RW_CLASS_ATTRIB(CollisionResult, distance_lower_bound)
;
}
......@@ -115,9 +139,9 @@ void exposeCollisionAPI ()
;
}
def ("collide", static_cast< std::size_t (*)(const CollisionObject*, const CollisionObject*,
doxygen::def ("collide", static_cast< std::size_t (*)(const CollisionObject*, const CollisionObject*,
const CollisionRequest&, CollisionResult&) > (&collide));
def ("collide", static_cast< std::size_t (*)(
doxygen::def ("collide", static_cast< std::size_t (*)(
const CollisionGeometry*, const Transform3f&,
const CollisionGeometry*, const Transform3f&,
const CollisionRequest&, CollisionResult&) > (&collide));
......
......@@ -42,6 +42,25 @@
#include <hpp/fcl/fwd.hh>
#include <hpp/fcl/distance.h>
#ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC
#include "doxygen_autodoc/functions.h"
#include "doxygen_autodoc/hpp/fcl/collision_data.h"
#endif
#include "../doc/python/doxygen.hh"
#include "../doc/python/doxygen-boost.hh"
#define DEF_RW_CLASS_ATTRIB(CLASS, ATTRIB) \
def_readwrite (#ATTRIB, &CLASS::ATTRIB, \
doxygen::class_attrib_doc<CLASS>(#ATTRIB))
#define DEF_RO_CLASS_ATTRIB(CLASS, ATTRIB) \
def_readonly (#ATTRIB, &CLASS::ATTRIB, \
doxygen::class_attrib_doc<CLASS>(#ATTRIB))
#define DEF_CLASS_FUNC(CLASS, ATTRIB) \
def (#ATTRIB, &CLASS::ATTRIB, doxygen::member_func_doc(&CLASS::ATTRIB))
#define DEF_CLASS_FUNC2(CLASS, ATTRIB,policy) \
def (#ATTRIB, &CLASS::ATTRIB, doxygen::member_func_doc(&CLASS::ATTRIB),policy)
using namespace boost::python;
using namespace hpp::fcl;
......@@ -56,27 +75,33 @@ void exposeDistanceAPI ()
{
if(!eigenpy::register_symbolic_link_to_registered_type<DistanceRequest>())
{
class_ <DistanceRequest> ("DistanceRequest", init<optional<bool,FCL_REAL,FCL_REAL> >())
.def_readwrite ("enable_nearest_points", &DistanceRequest::enable_nearest_points)
.def_readwrite ("rel_err" , &DistanceRequest::rel_err)
.def_readwrite ("abs_err" , &DistanceRequest::abs_err)
class_ <DistanceRequest> ("DistanceRequest",
doxygen::class_doc<DistanceRequest>(),
init<optional<bool,FCL_REAL,FCL_REAL> >())
.DEF_RW_CLASS_ATTRIB (DistanceRequest, enable_nearest_points)
.DEF_RW_CLASS_ATTRIB (DistanceRequest, rel_err)
.DEF_RW_CLASS_ATTRIB (DistanceRequest, abs_err)
;
}
if(!eigenpy::register_symbolic_link_to_registered_type<DistanceResult>())
{
class_ <DistanceResult> ("DistanceResult", init<>())
.def_readwrite ("min_distance", &DistanceResult::min_distance)
.def_readwrite ("normal", &DistanceResult::normal)
class_ <DistanceResult> ("DistanceResult",
doxygen::class_doc<DistanceResult>(), init<>())
.DEF_RW_CLASS_ATTRIB (DistanceResult, min_distance)
.DEF_RW_CLASS_ATTRIB (DistanceResult, normal)
//.def_readwrite ("nearest_points", &DistanceResult::nearest_points)
.def("getNearestPoint1",&DistanceRequestWrapper::getNearestPoint1)
.def("getNearestPoint2",&DistanceRequestWrapper::getNearestPoint2)
.def_readonly ("o1", &DistanceResult::o1)
.def_readonly ("o2", &DistanceResult::o2)
.def_readwrite ("b1", &DistanceResult::b1)
.def_readwrite ("b2", &DistanceResult::b2)
.def("getNearestPoint1",&DistanceRequestWrapper::getNearestPoint1,
doxygen::class_attrib_doc<DistanceResult>("nearest_points"))
.def("getNearestPoint2",&DistanceRequestWrapper::getNearestPoint2,
doxygen::class_attrib_doc<DistanceResult>("nearest_points"))
.DEF_RO_CLASS_ATTRIB (DistanceResult, o1)
.DEF_RO_CLASS_ATTRIB (DistanceResult, o2)
.DEF_RW_CLASS_ATTRIB (DistanceResult, b1)
.DEF_RW_CLASS_ATTRIB (DistanceResult, b2)
.def ("clear", &DistanceResult::clear)
.def ("clear", &DistanceResult::clear,
doxygen::member_func_doc(&DistanceResult::clear))
;
}
......@@ -87,9 +112,9 @@ void exposeDistanceAPI ()
;
}
def ("distance", static_cast< FCL_REAL (*)(const CollisionObject*, const CollisionObject*,
doxygen::def ("distance", static_cast< FCL_REAL (*)(const CollisionObject*, const CollisionObject*,
const DistanceRequest&, DistanceResult&) > (&distance));
def ("distance", static_cast< FCL_REAL (*)(
doxygen::def ("distance", static_cast< FCL_REAL (*)(
const CollisionGeometry*, const Transform3f&,
const CollisionGeometry*, const Transform3f&,
const DistanceRequest&, DistanceResult&) > (&distance));
......
......@@ -46,8 +46,8 @@
#include <hpp/fcl/collision.h>
#ifdef HAS_DOXYGEN_AUTODOC
#include "doxygen_autodoc/hpp/fcl/math/transform.h"
#ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC
#include "doxygen_autodoc/hpp/fcl/mesh_loader/loader.h"
#endif
#include "../doc/python/doxygen.hh"
......
......@@ -42,7 +42,7 @@
#include "fcl.hh"
#ifdef HAS_DOXYGEN_AUTODOC
#ifdef HPP_FCL_HAS_DOXYGEN_AUTODOC
#include "doxygen_autodoc/hpp/fcl/math/transform.h"
#endif
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment