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

Document more functions.

parent 21fbed01
...@@ -42,6 +42,7 @@ INCLUDE_DIRECTORIES("${Boost_INCLUDE_DIRS}" ${PYTHON_INCLUDE_DIRS}) ...@@ -42,6 +42,7 @@ INCLUDE_DIRECTORIES("${Boost_INCLUDE_DIRS}" ${PYTHON_INCLUDE_DIRS})
# To be run manually: # To be run manually:
# make doc # make doc
# ./cmake/doxygen/doxygen_xml_parser.py build-rel/doc/doxygen-xml/index.xml > build-rel/python/doxygen_autodoc.hh # ./cmake/doxygen/doxygen_xml_parser.py build-rel/doc/doxygen-xml/index.xml > build-rel/python/doxygen_autodoc.hh
INCLUDE_DIRECTORIES("${CMAKE_SOURCE_DIR}/src")
INCLUDE_DIRECTORIES("${CMAKE_CURRENT_BINARY_DIR}") INCLUDE_DIRECTORIES("${CMAKE_CURRENT_BINARY_DIR}")
SET(${LIBRARY_NAME}_HEADERS SET(${LIBRARY_NAME}_HEADERS
......
...@@ -43,6 +43,9 @@ ...@@ -43,6 +43,9 @@
#include <hpp/fcl/shape/convex.h> #include <hpp/fcl/shape/convex.h>
#include <hpp/fcl/BVH/BVH_model.h> #include <hpp/fcl/BVH/BVH_model.h>
#include "doxygen_autodoc/hpp/fcl/BVH/BVH_model.h"
#include "doxygen_autodoc/hpp/fcl/shape/geometric_shapes.h"
using namespace boost::python; using namespace boost::python;
using namespace hpp::fcl; using namespace hpp::fcl;
...@@ -71,7 +74,7 @@ void exposeBVHModel (const std::string& bvname) ...@@ -71,7 +74,7 @@ void exposeBVHModel (const std::string& bvname)
std::string type = "BVHModel" + bvname; std::string type = "BVHModel" + bvname;
class_ <BVHModel_t, bases<BVHModelBase>, shared_ptr<BVHModel_t> > class_ <BVHModel_t, bases<BVHModelBase>, shared_ptr<BVHModel_t> >
(type.c_str(), init<>()) (type.c_str(), doxygen::class_doc<BVHModel_t>(), init<>(doxygen::constructor_doc<BVHModel_t>()))
; ;
} }
...@@ -108,12 +111,12 @@ struct ConvexWrapper ...@@ -108,12 +111,12 @@ struct ConvexWrapper
void exposeShapes () void exposeShapes ()
{ {
class_ <ShapeBase, bases<CollisionGeometry>, shared_ptr<ShapeBase>, noncopyable> class_ <ShapeBase, bases<CollisionGeometry>, shared_ptr<ShapeBase>, noncopyable>
("ShapeBase", no_init) ("ShapeBase", doxygen::class_doc<ShapeBase>(), no_init)
//.def ("getObjectType", &CollisionGeometry::getObjectType) //.def ("getObjectType", &CollisionGeometry::getObjectType)
; ;
class_ <Box, bases<ShapeBase>, shared_ptr<Box> > class_ <Box, bases<ShapeBase>, shared_ptr<Box> >
("Box", init<>()) ("Box", doxygen::class_doc<ShapeBase>(), init<>())
.def (init<FCL_REAL,FCL_REAL,FCL_REAL>()) .def (init<FCL_REAL,FCL_REAL,FCL_REAL>())
.def (init<Vec3f>()) .def (init<Vec3f>())
.add_property("halfSide", .add_property("halfSide",
...@@ -122,19 +125,19 @@ void exposeShapes () ...@@ -122,19 +125,19 @@ void exposeShapes ()
; ;
class_ <Capsule, bases<ShapeBase>, shared_ptr<Capsule> > class_ <Capsule, bases<ShapeBase>, shared_ptr<Capsule> >
("Capsule", init<FCL_REAL, FCL_REAL>()) ("Capsule", doxygen::class_doc<Capsule>(), init<FCL_REAL, FCL_REAL>())
.def_readwrite ("radius", &Capsule::radius) .def_readwrite ("radius", &Capsule::radius)
.def_readwrite ("halfLength", &Capsule::halfLength) .def_readwrite ("halfLength", &Capsule::halfLength)
; ;
class_ <Cone, bases<ShapeBase>, shared_ptr<Cone> > class_ <Cone, bases<ShapeBase>, shared_ptr<Cone> >
("Cone", init<FCL_REAL, FCL_REAL>()) ("Cone", doxygen::class_doc<Cone>(), init<FCL_REAL, FCL_REAL>())
.def_readwrite ("radius", &Cone::radius) .def_readwrite ("radius", &Cone::radius)
.def_readwrite ("halfLength", &Cone::halfLength) .def_readwrite ("halfLength", &Cone::halfLength)
; ;
class_ <ConvexBase, bases<ShapeBase>, shared_ptr<ConvexBase >, noncopyable> class_ <ConvexBase, bases<ShapeBase>, shared_ptr<ConvexBase >, noncopyable>
("ConvexBase", no_init) ("ConvexBase", doxygen::class_doc<ConvexBase>(), no_init)
.def_readonly ("center", &ConvexBase::center) .def_readonly ("center", &ConvexBase::center)
.def_readonly ("num_points", &ConvexBase::num_points) .def_readonly ("num_points", &ConvexBase::num_points)
.def ("points", &ConvexBaseWrapper::points) .def ("points", &ConvexBaseWrapper::points)
...@@ -142,19 +145,19 @@ void exposeShapes () ...@@ -142,19 +145,19 @@ void exposeShapes ()
; ;
class_ <Convex<Triangle>, bases<ConvexBase>, shared_ptr<Convex<Triangle> >, noncopyable> class_ <Convex<Triangle>, bases<ConvexBase>, shared_ptr<Convex<Triangle> >, noncopyable>
("Convex", no_init) ("Convex", doxygen::class_doc< Convex<Triangle> >(), no_init)
.def_readonly ("num_polygons", &Convex<Triangle>::num_polygons) .def_readonly ("num_polygons", &Convex<Triangle>::num_polygons)
.def ("polygons", &ConvexWrapper<Triangle>::polygons) .def ("polygons", &ConvexWrapper<Triangle>::polygons)
; ;
class_ <Cylinder, bases<ShapeBase>, shared_ptr<Cylinder> > class_ <Cylinder, bases<ShapeBase>, shared_ptr<Cylinder> >
("Cylinder", init<FCL_REAL, FCL_REAL>()) ("Cylinder", doxygen::class_doc<Cylinder>(), init<FCL_REAL, FCL_REAL>())
.def_readwrite ("radius", &Cylinder::radius) .def_readwrite ("radius", &Cylinder::radius)
.def_readwrite ("halfLength", &Cylinder::halfLength) .def_readwrite ("halfLength", &Cylinder::halfLength)
; ;
class_ <Halfspace, bases<ShapeBase>, shared_ptr<Halfspace> > class_ <Halfspace, bases<ShapeBase>, shared_ptr<Halfspace> >
("Halfspace", "The half-space is defined by {x | n * x < d}.", init<const Vec3f&, FCL_REAL>()) ("Halfspace", doxygen::class_doc<Halfspace>(), init<const Vec3f&, FCL_REAL>())
.def (init<FCL_REAL,FCL_REAL,FCL_REAL,FCL_REAL>()) .def (init<FCL_REAL,FCL_REAL,FCL_REAL,FCL_REAL>())
.def (init<>()) .def (init<>())
.def_readwrite ("n", &Halfspace::n) .def_readwrite ("n", &Halfspace::n)
...@@ -162,7 +165,7 @@ void exposeShapes () ...@@ -162,7 +165,7 @@ void exposeShapes ()
; ;
class_ <Plane, bases<ShapeBase>, shared_ptr<Plane> > class_ <Plane, bases<ShapeBase>, shared_ptr<Plane> >
("Plane", "The plane is defined by {x | n * x = d}.", init<const Vec3f&, FCL_REAL>()) ("Plane", doxygen::class_doc<Plane>(), init<const Vec3f&, FCL_REAL>())
.def (init<FCL_REAL,FCL_REAL,FCL_REAL,FCL_REAL>()) .def (init<FCL_REAL,FCL_REAL,FCL_REAL,FCL_REAL>())
.def (init<>()) .def (init<>())
.def_readwrite ("n", &Plane::n) .def_readwrite ("n", &Plane::n)
...@@ -170,12 +173,12 @@ void exposeShapes () ...@@ -170,12 +173,12 @@ void exposeShapes ()
; ;
class_ <Sphere, bases<ShapeBase>, shared_ptr<Sphere> > class_ <Sphere, bases<ShapeBase>, shared_ptr<Sphere> >
("Sphere", init<FCL_REAL>()) ("Sphere", doxygen::class_doc<Sphere>(), init<FCL_REAL>())
.def_readwrite ("radius", &Sphere::radius) .def_readwrite ("radius", &Sphere::radius)
; ;
class_ <TriangleP, bases<ShapeBase>, shared_ptr<TriangleP> > class_ <TriangleP, bases<ShapeBase>, shared_ptr<TriangleP> >
("TriangleP", init<const Vec3f&, const Vec3f&, const Vec3f&>()) ("TriangleP", doxygen::class_doc<TriangleP>(), init<const Vec3f&, const Vec3f&, const Vec3f&>())
.def_readwrite ("a", &TriangleP::a) .def_readwrite ("a", &TriangleP::a)
.def_readwrite ("b", &TriangleP::b) .def_readwrite ("b", &TriangleP::b)
.def_readwrite ("c", &TriangleP::c) .def_readwrite ("c", &TriangleP::c)
......
...@@ -41,21 +41,10 @@ ...@@ -41,21 +41,10 @@
#include <hpp/fcl/math/transform.h> #include <hpp/fcl/math/transform.h>
#include "fcl.hh" #include "fcl.hh"
#include <hpp/fcl/collision.h>
#include <hpp/fcl/traversal/traversal_node_bvh_shape.h>
#include <hpp/fcl/traversal/traversal_node_bvhs.h>
#include <hpp/fcl/traversal/traversal_node_octree.h>
#include <hpp/fcl/traversal/traversal_node_shapes.h>
#include <hpp/fcl/mesh_loader/loader.h>
#include <hpp/fcl/narrowphase/gjk.h>
#include <hpp/fcl/BVH/BVH_model.h>
#include <hpp/fcl/octree.h>
#include <hpp/fcl/profile.h>
#include "doxygen_autodoc.hh"
using namespace boost::python; #include "doxygen_autodoc/hpp/fcl/math/transform.h"
using namespace boost::python;
using namespace hpp::fcl; using namespace hpp::fcl;
struct TriangleWrapper struct TriangleWrapper
...@@ -81,13 +70,15 @@ void exposeMaths () ...@@ -81,13 +70,15 @@ void exposeMaths ()
if(!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>()) if(!eigenpy::register_symbolic_link_to_registered_type<Eigen::AngleAxisd>())
eigenpy::exposeAngleAxis(); eigenpy::exposeAngleAxis();
class_ <Transform3f> ("Transform3f", init<>("Default constructor.")) eigenpy::enableEigenPySpecific<Matrix3f>();
.def (init<Matrix3f, Vec3f>()) eigenpy::enableEigenPySpecific<Vec3f >();
.def (init<Quaternion3f, Vec3f>())
.def (init<Matrix3f>()) class_ <Transform3f> ("Transform3f", doxygen::class_doc<Transform3f>(), init<>(doxygen::constructor_doc<Transform3f>()))
.def (init<Quaternion3f>()) .def (init<Matrix3f, Vec3f> (doxygen::constructor_doc<Transform3f, const Matrix3f::MatrixBase&, const Vec3f::MatrixBase&>()))
.def (init<Vec3f>()) .def (init<Quaternion3f, Vec3f>(doxygen::constructor_doc<Transform3f, const Quaternion3f& , const Vec3f::MatrixBase&>()))
.def (init<Transform3f>(args("self","other"),"Copy constructor.")) .def (init<Matrix3f> (doxygen::constructor_doc<Transform3f, const Matrix3f& >()))
.def (init<Quaternion3f> (doxygen::constructor_doc<Transform3f, const Quaternion3f& >()))
.def (init<Vec3f> (doxygen::constructor_doc<Transform3f, const Vec3f& >()))
.def ("getQuatRotation", &Transform3f::getQuatRotation, doxygen::member_func_doc(&Transform3f::getQuatRotation)) .def ("getQuatRotation", &Transform3f::getQuatRotation, doxygen::member_func_doc(&Transform3f::getQuatRotation))
.def ("getTranslation", &Transform3f::getTranslation, doxygen::member_func_doc(&Transform3f::getTranslation), return_value_policy<copy_const_reference>()) .def ("getTranslation", &Transform3f::getTranslation, doxygen::member_func_doc(&Transform3f::getTranslation), return_value_policy<copy_const_reference>())
......
Supports Markdown
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