Verified Commit e9431c9d authored by Justin Carpentier's avatar Justin Carpentier
Browse files

python/doc: add missing 'self"

parent b5f8b5dd
......@@ -92,8 +92,13 @@ void exposeBVHModel (const std::string& bvname)
std::string type = "BVHModel" + bvname;
class_ <BVHModel_t, bases<BVHModelBase>, shared_ptr<BVHModel_t> >
<<<<<<< HEAD
(type.c_str(), doxygen::class_doc<BVHModel_t>(), no_init)
.def (dv::init<BVHModel_t>())
=======
(type.c_str(), doxygen::class_doc<BVHModel_t>(),
init<>(boost::python::arg("self"),doxygen::constructor_doc<BVHModel_t>()))
>>>>>>> python/doc: add missing 'self"
;
}
......@@ -181,9 +186,9 @@ void exposeShapes ()
class_ <Halfspace, bases<ShapeBase>, shared_ptr<Halfspace> >
("Halfspace", doxygen::class_doc<Halfspace>(), no_init)
.def (dv::init<Halfspace, const Vec3f&, FCL_REAL>())
.def (dv::init<Halfspace, FCL_REAL,FCL_REAL,FCL_REAL,FCL_REAL>())
.def (dv::init<Halfspace>())
.def (dv::init<Halfspace, const Vec3f&, FCL_REAL>(args("self","normal","offset")))
.def (dv::init<Halfspace, FCL_REAL,FCL_REAL,FCL_REAL,FCL_REAL>(args("self","x","y","z","offset")))
.def (dv::init<Halfspace>(arg("self")))
.DEF_RW_CLASS_ATTRIB (Halfspace, n)
.DEF_RW_CLASS_ATTRIB (Halfspace, d)
;
......@@ -263,11 +268,11 @@ void exposeCollisionGeometries ()
class_<AABB>("AABB",
"A class describing the AABB collision structure, which is a box in 3D space determined by two diagonal points",
no_init)
.def(init<>("Default constructor"))
.def(init<Vec3f>(bp::arg("v"),"Creating an AABB at position v with zero size."))
.def(init<Vec3f,Vec3f>(bp::args("a","b"),"Creating an AABB with two endpoints a and b."))
.def(init<AABB,Vec3f>(bp::args("core","delta"),"Creating an AABB centered as core and is of half-dimension delta."))
.def(init<Vec3f,Vec3f,Vec3f>(bp::args("a","b","c"),"Creating an AABB contains three points."))
.def(init<>(bp::arg("self"), "Default constructor"))
.def(init<Vec3f>(bp::args("self","v"),"Creating an AABB at position v with zero size."))
.def(init<Vec3f,Vec3f>(bp::args("self","a","b"),"Creating an AABB with two endpoints a and b."))
.def(init<AABB,Vec3f>(bp::args("self","core","delta"),"Creating an AABB centered as core and is of half-dimension delta."))
.def(init<Vec3f,Vec3f,Vec3f>(bp::args("self","a","b","c"),"Creating an AABB contains three points."))
.def("contain",
(bool (AABB::*)(const Vec3f &) const)&AABB::contain,
......
......@@ -82,9 +82,8 @@ void exposeCollisionAPI ()
{
class_ <CollisionRequest> ("CollisionRequest",
doxygen::class_doc<CollisionRequest>(), no_init)
.def (dv::init<CollisionRequest>())
.def (dv::init<CollisionRequest, const CollisionRequestFlag, size_t>())
.def (dv::init<CollisionRequest>(::boost::python::arg("self")))
.def (dv::init<CollisionRequest, const CollisionRequestFlag, size_t>(::boost::python::args("self","flag","num_max_contacts")))
.DEF_RW_CLASS_ATTRIB (CollisionRequest, num_max_contacts )
.DEF_RW_CLASS_ATTRIB (CollisionRequest, enable_contact )
.DEF_RW_CLASS_ATTRIB (CollisionRequest, enable_distance_lower_bound)
......@@ -98,7 +97,7 @@ void exposeCollisionAPI ()
if(!eigenpy::register_symbolic_link_to_registered_type<Contact>())
{
class_ <Contact> ("Contact",
doxygen::class_doc<Contact>(), init<>())
doxygen::class_doc<Contact>(), init<>(arg("self"),"Default constructor"))
//.def(init<CollisionGeometryPtr_t, CollisionGeometryPtr_t, int, int>())
//.def(init<CollisionGeometryPtr_t, CollisionGeometryPtr_t, int, int, Vec3f, Vec3f, FCL_REAL>())
.DEF_RO_CLASS_ATTRIB (Contact, o1)
......@@ -130,7 +129,7 @@ void exposeCollisionAPI ()
{
class_ <CollisionResult> ("CollisionResult",
doxygen::class_doc<CollisionResult>(), no_init)
.def (dv::init<CollisionResult>())
.def (dv::init<CollisionResult>(arg("self")))
.DEF_CLASS_FUNC (CollisionResult, isCollision)
.DEF_CLASS_FUNC (CollisionResult, numContacts)
.DEF_CLASS_FUNC (CollisionResult, addContact)
......
......@@ -78,7 +78,10 @@ void exposeDistanceAPI ()
{
class_ <DistanceRequest> ("DistanceRequest",
doxygen::class_doc<DistanceRequest>(),
init<optional<bool,FCL_REAL,FCL_REAL> >())
init<optional<bool,FCL_REAL,FCL_REAL> >((arg("self"),
arg("enable_nearest_points"),
arg("rel_err"),
arg("abs_err")),"Constructor"))
.DEF_RW_CLASS_ATTRIB (DistanceRequest, enable_nearest_points)
.DEF_RW_CLASS_ATTRIB (DistanceRequest, rel_err)
.DEF_RW_CLASS_ATTRIB (DistanceRequest, abs_err)
......@@ -88,7 +91,8 @@ void exposeDistanceAPI ()
if(!eigenpy::register_symbolic_link_to_registered_type<DistanceResult>())
{
class_ <DistanceResult> ("DistanceResult",
doxygen::class_doc<DistanceResult>(), init<>())
doxygen::class_doc<DistanceResult>(),
init<>(arg("self"),"Default constructor"))
.DEF_RW_CLASS_ATTRIB (DistanceResult, min_distance)
.DEF_RW_CLASS_ATTRIB(DistanceResult, normal)
//.def_readwrite ("nearest_points", &DistanceResult::nearest_points)
......
......@@ -64,10 +64,10 @@ void exposeMeshLoader ()
{
class_ <MeshLoader, boost::shared_ptr<MeshLoader> > ("MeshLoader",
doxygen::class_doc<MeshLoader>(),
init< optional< NODE_TYPE> >(arg("node_type"),
init< optional< NODE_TYPE> >((arg("self"),arg("node_type")),
doxygen::constructor_doc<MeshLoader, const NODE_TYPE&>()))
.def ("load",&MeshLoader::load,
load_overloads(args("filename","scale"),
load_overloads((arg("self"),arg("filename"),arg("scale")),
doxygen::member_func_doc(&MeshLoader::load)))
;
}
......@@ -77,7 +77,7 @@ void exposeMeshLoader ()
class_ <CachedMeshLoader, bases<MeshLoader>, boost::shared_ptr<CachedMeshLoader> > (
"CachedMeshLoader",
doxygen::class_doc<MeshLoader>(),
init< optional< NODE_TYPE> >(arg("node_type"),
init< optional< NODE_TYPE> >((arg("self"),arg("node_type")),
doxygen::constructor_doc<CachedMeshLoader, const NODE_TYPE&>()))
;
}
......
......@@ -80,7 +80,7 @@ void exposeMaths ()
eigenpy::enableEigenPySpecific<Matrix3f>();
eigenpy::enableEigenPySpecific<Vec3f >();
class_ <Transform3f> ("Transform3f", doxygen::class_doc<Transform3f>(), init<>(doxygen::constructor_doc<Transform3f>()))
class_ <Transform3f> ("Transform3f", doxygen::class_doc<Transform3f>(), init<>(arg("self"),doxygen::constructor_doc<Transform3f>()))
.def (init<Matrix3f, Vec3f> (doxygen::constructor_doc<Transform3f, const Matrix3f::MatrixBase&, const Vec3f::MatrixBase&>()))
.def (init<Quaternion3f, Vec3f>(doxygen::constructor_doc<Transform3f, const Quaternion3f& , const Vec3f::MatrixBase&>()))
.def (init<Matrix3f> (doxygen::constructor_doc<Transform3f, const Matrix3f& >()))
......
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