Skip to content
Snippets Groups Projects
Unverified Commit e3087e90 authored by Justin Carpentier's avatar Justin Carpentier Committed by GitHub
Browse files

Merge pull request #135 from jcarpent/topic/devel

Fix Python documentation
parents a5268cc2 16b36852
No related branches found
No related tags found
No related merge requests found
...@@ -8,7 +8,6 @@ ...@@ -8,7 +8,6 @@
#include "eigenpy/fwd.hpp" #include "eigenpy/fwd.hpp"
#include <boost/python.hpp>
#include <Eigen/Core> #include <Eigen/Core>
#include <Eigen/Geometry> #include <Eigen/Geometry>
...@@ -54,15 +53,15 @@ namespace eigenpy ...@@ -54,15 +53,15 @@ namespace eigenpy
void visit(PyClass& cl) const void visit(PyClass& cl) const
{ {
cl cl
.def(bp::init<>("Default constructor")) .def(bp::init<>(bp::arg("self"),"Default constructor"))
.def(bp::init<Scalar,Vector3> .def(bp::init<Scalar,Vector3>
((bp::arg("angle"),bp::arg("axis")), ((bp::arg("self"),bp::arg("angle"),bp::arg("axis")),
"Initialize from angle and axis.")) "Initialize from angle and axis."))
.def(bp::init<Matrix3> .def(bp::init<Matrix3>
((bp::arg("rotationMatrix")), ((bp::arg("self"),bp::arg("rotation matrix")),
"Initialize from a rotation matrix")) "Initialize from a rotation matrix"))
.def(bp::init<Quaternion>(bp::arg("quaternion"),"Initialize from a quaternion.")) .def(bp::init<Quaternion>((bp::arg("self"),bp::arg("quaternion")),"Initialize from a quaternion."))
.def(bp::init<AngleAxis>(bp::arg("copy"),"Copy constructor.")) .def(bp::init<AngleAxis>((bp::arg("self"),bp::arg("copy")),"Copy constructor."))
/* --- Properties --- */ /* --- Properties --- */
.add_property("axis", .add_property("axis",
...@@ -74,15 +73,24 @@ namespace eigenpy ...@@ -74,15 +73,24 @@ namespace eigenpy
&AngleAxisVisitor::setAngle,"The rotation angle.") &AngleAxisVisitor::setAngle,"The rotation angle.")
/* --- Methods --- */ /* --- Methods --- */
.def("inverse",&AngleAxis::inverse,"Return the inverse rotation.") .def("inverse",&AngleAxis::inverse,
bp::arg("self"),
"Return the inverse rotation.")
.def("fromRotationMatrix",&AngleAxis::template fromRotationMatrix<Matrix3>, .def("fromRotationMatrix",&AngleAxis::template fromRotationMatrix<Matrix3>,
bp::arg("Sets *this from a 3x3 rotation matrix."),bp::return_self<>()) (bp::arg("self"),bp::arg("rotation matrix")),
.def("toRotationMatrix",&AngleAxis::toRotationMatrix,"Constructs and returns an equivalent 3x3 rotation matrix.") "Sets *this from a 3x3 rotation matrix",
.def("matrix",&AngleAxis::matrix,"Returns an equivalent rotation matrix.") bp::return_self<>())
.def("toRotationMatrix",
// bp::arg("self"),
&AngleAxis::toRotationMatrix,
"Constructs and returns an equivalent 3x3 rotation matrix.")
.def("matrix",&AngleAxis::matrix,
bp::arg("self"),
"Returns an equivalent rotation matrix.")
.def("isApprox", .def("isApprox",
&call<AngleAxis>::isApprox, &call<AngleAxis>::isApprox,
isApproxAngleAxis_overload(bp::args("other","prec"), isApproxAngleAxis_overload(bp::args("self","other","prec"),
"Returns true if *this is approximately equal to other, within the precision determined by prec.")) "Returns true if *this is approximately equal to other, within the precision determined by prec."))
/* --- Operators --- */ /* --- Operators --- */
...@@ -125,7 +133,7 @@ namespace eigenpy ...@@ -125,7 +133,7 @@ namespace eigenpy
static void expose() static void expose()
{ {
bp::class_<AngleAxis>("AngleAxis", bp::class_<AngleAxis>("AngleAxis",
"AngleAxis representation of rotations.\n\n", "AngleAxis representation of a rotation.\n\n",
bp::no_init) bp::no_init)
.def(AngleAxisVisitor<AngleAxis>()); .def(AngleAxisVisitor<AngleAxis>());
} }
......
...@@ -12,7 +12,6 @@ ...@@ -12,7 +12,6 @@
#include <Eigen/Geometry> #include <Eigen/Geometry>
#include "eigenpy/exception.hpp" #include "eigenpy/exception.hpp"
#include "eigenpy/registration.hpp"
namespace eigenpy namespace eigenpy
{ {
...@@ -69,17 +68,17 @@ namespace eigenpy ...@@ -69,17 +68,17 @@ namespace eigenpy
void visit(PyClass& cl) const void visit(PyClass& cl) const
{ {
cl cl
.def(bp::init<>("Default constructor")) .def(bp::init<>(bp::arg("self"),"Default constructor"))
.def(bp::init<Vector4>((bp::arg("vec4")), .def(bp::init<Vector4>((bp::arg("self"),bp::arg("vec4")),
"Initialize from a vector 4D.\n" "Initialize from a vector 4D.\n"
"\tvec4 : a 4D vector representing quaternion coefficients in the order xyzw.")) "\tvec4 : a 4D vector representing quaternion coefficients in the order xyzw."))
.def(bp::init<Matrix3>((bp::arg("R")), .def(bp::init<Matrix3>((bp::arg("self"),bp::arg("R")),
"Initialize from rotation matrix.\n" "Initialize from rotation matrix.\n"
"\tR : a rotation matrix 3x3.")) "\tR : a rotation matrix 3x3."))
.def(bp::init<AngleAxis>((bp::arg("aa")), .def(bp::init<AngleAxis>((bp::arg("self"),bp::arg("aa")),
"Initialize from an angle axis.\n" "Initialize from an angle axis.\n"
"\taa: angle axis object.")) "\taa: angle axis object."))
.def(bp::init<Quaternion>((bp::arg("quat")), .def(bp::init<Quaternion>((bp::arg("self"),bp::arg("quat")),
"Copy constructor.\n" "Copy constructor.\n"
"\tquat: a quaternion.")) "\tquat: a quaternion."))
.def("__init__",bp::make_constructor(&QuaternionVisitor::FromTwoVectors, .def("__init__",bp::make_constructor(&QuaternionVisitor::FromTwoVectors,
...@@ -87,7 +86,7 @@ namespace eigenpy ...@@ -87,7 +86,7 @@ namespace eigenpy
(bp::arg("u: a 3D vector"),bp::arg("v: a 3D vector"))), (bp::arg("u: a 3D vector"),bp::arg("v: a 3D vector"))),
"Initialize from two vectors u and v") "Initialize from two vectors u and v")
.def(bp::init<Scalar,Scalar,Scalar,Scalar> .def(bp::init<Scalar,Scalar,Scalar,Scalar>
((bp::arg("w"),bp::arg("x"),bp::arg("y"),bp::arg("z")), ((bp::arg("self"),bp::arg("w"),bp::arg("x"),bp::arg("y"),bp::arg("z")),
"Initialize from coefficients.\n\n" "Initialize from coefficients.\n\n"
"... note:: The order of coefficients is *w*, *x*, *y*, *z*. " "... note:: The order of coefficients is *w*, *x*, *y*, *z*. "
"The [] operator numbers them differently, 0...4 for *x* *y* *z* *w*!")) "The [] operator numbers them differently, 0...4 for *x* *y* *z* *w*!"))
...@@ -107,30 +106,61 @@ namespace eigenpy ...@@ -107,30 +106,61 @@ namespace eigenpy
.def("isApprox", .def("isApprox",
&call<Quaternion>::isApprox, &call<Quaternion>::isApprox,
isApproxQuaternion_overload(bp::args("other","prec"), isApproxQuaternion_overload(bp::args("self","other","prec"),
"Returns true if *this is approximately equal to other, within the precision determined by prec.")) "Returns true if *this is approximately equal to other, within the precision determined by prec."))
/* --- Methods --- */ /* --- Methods --- */
.def("coeffs",(const Vector4 & (Quaternion::*)()const)&Quaternion::coeffs, .def("coeffs",(const Vector4 & (Quaternion::*)()const)&Quaternion::coeffs,
bp::arg("self"),
"Returns a vector of the coefficients (x,y,z,w)",
bp::return_value_policy<bp::copy_const_reference>()) bp::return_value_policy<bp::copy_const_reference>())
.def("matrix",&Quaternion::matrix,"Returns an equivalent 3x3 rotation matrix. Similar to toRotationMatrix.") .def("matrix",&Quaternion::matrix,
.def("toRotationMatrix",&Quaternion::toRotationMatrix,"Returns an equivalent 3x3 rotation matrix.") bp::arg("self"),
"Returns an equivalent 3x3 rotation matrix. Similar to toRotationMatrix.")
.def("toRotationMatrix",&Quaternion::toRotationMatrix,
// bp::arg("self"), // Bug in Boost.Python
"Returns an equivalent 3x3 rotation matrix.")
.def("setFromTwoVectors",&setFromTwoVectors,((bp::arg("a"),bp::arg("b"))),"Set *this to be the quaternion which transforms a into b through a rotation." .def("setFromTwoVectors",&setFromTwoVectors,((bp::arg("self"),bp::arg("a"),bp::arg("b"))),
"Set *this to be the quaternion which transforms a into b through a rotation."
,bp::return_self<>()) ,bp::return_self<>())
.def("conjugate",&Quaternion::conjugate,"Returns the conjugated quaternion. The conjugate of a quaternion represents the opposite rotation.") .def("conjugate",&Quaternion::conjugate,
.def("inverse",&Quaternion::inverse,"Returns the quaternion describing the inverse rotation.") bp::arg("self"),
.def("setIdentity",&Quaternion::setIdentity,bp::return_self<>(),"Set *this to the idendity rotation.") "Returns the conjugated quaternion.\n"
.def("norm",&Quaternion::norm,"Returns the norm of the quaternion's coefficients.") "The conjugate of a quaternion represents the opposite rotation.")
.def("normalize",&Quaternion::normalize,"Normalizes the quaternion *this.") .def("inverse",&Quaternion::inverse,
.def("normalized",&Quaternion::normalized,"Returns a normalized copy of *this.") bp::arg("self"),
.def("squaredNorm",&Quaternion::squaredNorm,"Returns the squared norm of the quaternion's coefficients.") "Returns the quaternion describing the inverse rotation.")
.def("dot",&Quaternion::template dot<Quaternion>,bp::arg("other"),"Returns the dot product of *this with other" .def("setIdentity",&Quaternion::setIdentity,
bp::arg("self"),
"Set *this to the idendity rotation.",bp::return_self<>())
.def("norm",&Quaternion::norm,
bp::arg("self"),
"Returns the norm of the quaternion's coefficients.")
.def("normalize",&Quaternion::normalize,
bp::arg("self"),
"Normalizes the quaternion *this.")
.def("normalized",&Quaternion::normalized,
bp::arg("self"),
"Returns a normalized copy of *this.")
.def("squaredNorm",&Quaternion::squaredNorm,
bp::arg("self"),
"Returns the squared norm of the quaternion's coefficients.")
.def("dot",&Quaternion::template dot<Quaternion>,
(bp::arg("self"),bp::arg("other")),
"Returns the dot product of *this with an other Quaternion.\n"
"Geometrically speaking, the dot product of two unit quaternions corresponds to the cosine of half the angle between the two rotations.") "Geometrically speaking, the dot product of two unit quaternions corresponds to the cosine of half the angle between the two rotations.")
.def("_transformVector",&Quaternion::_transformVector,bp::arg("vector"),"Rotation of a vector by a quaternion.") .def("_transformVector",&Quaternion::_transformVector,
.def("vec",&vec,"Returns a vector expression of the imaginary part (x,y,z).") (bp::arg("self"),bp::arg("vector")),
.def("angularDistance",&Quaternion::template angularDistance<Quaternion>,"Returns the angle (in radian) between two rotations.") "Rotation of a vector by a quaternion.")
.def("slerp",&slerp,bp::args("t","other"), .def("vec",&vec,
bp::arg("self"),
"Returns a vector expression of the imaginary part (x,y,z).")
.def("angularDistance",
// (bp::arg("self"),bp::arg("other")), // Bug in Boost.Python
&Quaternion::template angularDistance<Quaternion>,
"Returns the angle (in radian) between two rotations.")
.def("slerp",&slerp,bp::args("self","t","other"),
"Returns the spherical linear interpolation between the two quaternions *this and other at the parameter t in [0;1].") "Returns the spherical linear interpolation between the two quaternions *this and other at the parameter t in [0;1].")
/* --- Operators --- */ /* --- Operators --- */
...@@ -144,9 +174,9 @@ namespace eigenpy ...@@ -144,9 +174,9 @@ namespace eigenpy
.def("__setitem__",&QuaternionVisitor::__setitem__) .def("__setitem__",&QuaternionVisitor::__setitem__)
.def("__getitem__",&QuaternionVisitor::__getitem__) .def("__getitem__",&QuaternionVisitor::__getitem__)
.def("assign",&assign<Quaternion>, .def("assign",&assign<Quaternion>,
bp::arg("quat"),"Set *this from an quaternion quat and returns a reference to *this.",bp::return_self<>()) bp::args("self","quat"),"Set *this from an quaternion quat and returns a reference to *this.",bp::return_self<>())
.def("assign",(Quaternion & (Quaternion::*)(const AngleAxis &))&Quaternion::operator=, .def("assign",(Quaternion & (Quaternion::*)(const AngleAxis &))&Quaternion::operator=,
bp::arg("aa"),"Set *this from an angle-axis aa and returns a reference to *this.",bp::return_self<>()) bp::args("self","aa"),"Set *this from an angle-axis aa and returns a reference to *this.",bp::return_self<>())
.def("__str__",&print) .def("__str__",&print)
.def("__repr__",&print) .def("__repr__",&print)
...@@ -158,7 +188,8 @@ namespace eigenpy ...@@ -158,7 +188,8 @@ namespace eigenpy
"Returns the quaternion which transforms a into b through a rotation.", "Returns the quaternion which transforms a into b through a rotation.",
bp::return_value_policy<bp::manage_new_object>()) bp::return_value_policy<bp::manage_new_object>())
.staticmethod("FromTwoVectors") .staticmethod("FromTwoVectors")
.def("Identity",&Quaternion::Identity,"Returns a quaternion representing an identity rotation.") .def("Identity",&Quaternion::Identity,
"Returns a quaternion representing an identity rotation.")
.staticmethod("Identity") .staticmethod("Identity")
; ;
} }
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment