6 #include <boost/python.hpp>
21 "exp3", &exp3_proxy<context::Vector3s>, bp::arg(
"w"),
22 "Exp: so3 -> SO3. Return the integral of the input"
23 " vector w during time 1. This is also known as the Rodrigues formula.");
26 "exp3_quat", &exp3_proxy_quat<context::Vector3s>, bp::arg(
"w"),
27 "Exp: so3 -> S3. Returns the integral of the input vector w during time 1, represented "
28 "as a unit Quaternion.");
31 "Jexp3", &Jexp3_proxy<context::Vector3s>, bp::arg(
"w"),
32 "Jacobian of exp(v) which maps from the tangent of SO(3) at R = exp(v) to"
33 " the tangent of SO(3) at Identity.");
36 "log3", &log3_proxy<context::Matrix3s>, bp::arg(
"R"),
37 "Log: SO3 -> so3 is the pseudo-inverse of Exp: so3 -> SO3. Log maps from SO3"
38 " -> { v in so3, ||v|| < 2pi }.");
41 "log3", &log3_proxy<context::Matrix3s, context::Matrix1s>, bp::args(
"R",
"theta"),
42 "Log: SO3 -> so3 is the pseudo-inverse of Exp: so3 -> SO3. Log maps from SO3"
43 " -> { v in so3, ||v|| < 2pi }.\n"
44 "It also returns the angle of rotation theta around the rotation axis.");
47 "log3", &log3_proxy_fix<context::Matrix3s, context::Scalar>, bp::args(
"R",
"theta"),
48 "Log: SO3 -> so3 is the pseudo-inverse of Exp: so3 -> SO3. Log maps from SO3"
49 " -> { v in so3, ||v|| < 2pi }.\n"
50 "It also returns the angle of rotation theta around the rotation axis.");
53 "log3", &log3_proxy<context::Quaternion>, bp::args(
"quat"),
54 "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from "
56 " quaternions. It maps from S^3 -> { v in so3, ||v|| < 2pi }.");
59 "log3", &log3_proxy_quatvec<context::Vector4s>, bp::args(
"quat"),
60 "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from "
62 " quaternions. It maps from S^3 -> { v in so3, ||v|| < 2pi }.");
65 "log3", &log3_proxy_quatvec<context::Vector4s, context::Matrix1s>,
66 bp::args(
"quat",
"theta"),
67 "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from "
69 " quaternions. It maps from S^3 -> { v in so3, ||v|| < 2pi }.\n"
70 "It also returns the angle of rotation theta around the rotation axis.");
73 "log3", &log3_proxy_quatvec_fix<context::Vector4s, context::Scalar>,
74 bp::args(
"quat",
"theta"),
75 "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from "
77 " quaternions. It maps from S^3 -> { v in so3, ||v|| < 2pi }.\n"
78 "It also returns the angle of rotation theta around the rotation axis.");
81 "Jlog3", &Jlog3_proxy<context::Matrix3s>, bp::arg(
"R"),
82 "Jacobian of log(R) which maps from the tangent of SO(3) at R to"
83 " the tangent of SO(3) at Identity.");
86 "Hlog3", &Hlog3_proxy<Eigen::Matrix3d, Eigen::Vector3d>, bp::args(
"R",
"v"),
87 "Vector v to be multiplied to the hessian",
"v^T * H where H is the Hessian of log(R)");
90 "exp6", &exp6_proxy<context::Scalar, context::Options>, bp::arg(
"motion"),
91 "Exp: se3 -> SE3. Return the integral of the input"
92 " spatial velocity during time 1.");
95 "exp6", &exp6_proxy<context::Motion::Vector6>, bp::arg(
"v"),
96 "Exp: se3 -> SE3. Return the integral of the input"
97 " spatial velocity during time 1.");
100 "exp6_quat", &exp6_proxy_quatvec<context::Motion::Vector6>, bp::arg(
"v"),
101 "Exp: se3 -> R3 * S3. Return the integral of the input 6D spatial velocity over unit time,"
102 " using quaternion to represent rotation as in the standard configuration layout"
103 " for the Lie group SE3.");
106 "Jexp6", &Jexp6_proxy<context::Scalar, context::Options>, bp::arg(
"motion"),
107 "Jacobian of exp(v) which maps from the tangent of SE(3) at exp(v) to"
108 " the tangent of SE(3) at Identity.");
111 "Jexp6", &Jexp6_proxy<context::Motion::Vector6>, bp::arg(
"v"),
112 "Jacobian of exp(v) which maps from the tangent of SE(3) at exp(v) to"
113 " the tangent of SE(3) at Identity.");
118 "Log: SE3 -> se3. Pseudo-inverse of exp from SE3"
119 " -> { v,w in se3, ||w|| < 2pi }.");
122 "log6", &log6_proxy<context::Matrix4s>, bp::arg(
"homegeneous_matrix"),
123 "Log: SE3 -> se3. Pseudo-inverse of Exp: so3 -> SO3. Log maps from SE3"
124 " -> { v,w in se3, ||w|| < 2pi }.");
127 "log6_quat", &log6_proxy_quatvec<context::Vector7s>, bp::arg(
"q"),
128 "Log: R^3 * S^3 -> se3. Pseudo-inverse of Exp: se3 -> R^3 * S^3,",
129 " the variant of the SE3 Exp using quaternions for the rotations.");
132 "Jlog6", &Jlog6_proxy<context::Scalar, context::Options>, bp::arg(
"M"),
133 "Jacobian of log(M) which maps from the tangent of SE(3) at M to"
134 " the tangent of SE(3) at Identity.");