18 bp::def(
"exp3",&exp3_proxy<Eigen::Vector3d>,
20 "Exp: so3 -> SO3. Return the integral of the input" 21 " angular velocity during time 1.");
23 bp::def(
"Jexp3",&Jexp3_proxy<Eigen::Vector3d>,
25 "Jacobian of exp(R) which maps from the tangent of SO(3) at exp(v) to" 26 " the tangent of SO(3) at Identity.");
28 bp::def(
"log3",&log3_proxy<Eigen::Matrix3d>,
30 "Log: SO3 -> so3. Pseudo-inverse of log from SO3" 31 " -> { v in so3, ||v|| < 2pi }.Exp: so3 -> SO3.");
33 bp::def(
"Jlog3",&Jlog3_proxy<Eigen::Matrix3d>,
35 "Jacobian of log(R) which maps from the tangent of SO(3) at R to" 36 " the tangent of SO(3) at Identity.");
38 bp::def(
"Hlog3",&Hlog3_proxy<Eigen::Matrix3d, Eigen::Vector3d>,
40 "Vector v to be multiplied to the hessian",
41 "v^T * H where H is the Hessian of log(R)");
43 bp::def(
"exp6",&exp6_proxy<double,0>,
45 "Exp: se3 -> SE3. Return the integral of the input" 46 " spatial velocity during time 1.");
48 bp::def(
"exp6",&exp6_proxy<Motion::Vector6>,
50 "Exp: se3 -> SE3. Return the integral of the input" 51 " spatial velocity during time 1.");
53 bp::def(
"Jexp6",&Jexp6_proxy<double,0>,
55 "Jacobian of exp(v) which maps from the tangent of SE(3) at exp(v) to" 56 " the tangent of SE(3) at Identity.");
58 bp::def(
"Jexp6",&Jexp6_proxy<Motion::Vector6>,
60 "Jacobian of exp(v) which maps from the tangent of SE(3) at exp(v) to" 61 " the tangent of SE(3) at Identity.");
63 bp::def(
"log6",(
Motion (*)(
const SE3 &))&log6<double,0>,
65 "Log: SE3 -> se3. Pseudo-inverse of exp from SE3" 66 " -> { v,w in se3, ||w|| < 2pi }.");
68 bp::def(
"log6",&log6_proxy<Eigen::Matrix4d>,
70 "Log: SE3 -> se3. Pseudo-inverse of exp from SE3" 71 " -> { v,w in se3, ||w|| < 2pi }.");
73 bp::def(
"Jlog6",&Jlog6_proxy<double,0>,
75 "Jacobian of log(M) which maps from the tangent of SE(3) at M to" 76 " the tangent of SE(3) at Identity.");
Main pinocchio namespace.