expose-explog.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2019 CNRS INRIA
3 // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
7 #include <boost/python.hpp>
8 
9 namespace pinocchio
10 {
11  namespace python
12  {
13  namespace bp = boost::python;
14 
15  void exposeExplog()
16  {
17 
18  bp::def("exp3",&exp3_proxy<Eigen::Vector3d>,
19  bp::arg("Angular velocity (vector of size 3)"),
20  "Exp: so3 -> SO3. Return the integral of the input"
21  " angular velocity during time 1.");
22 
23  bp::def("Jexp3",&Jexp3_proxy<Eigen::Vector3d>,
24  bp::arg("v: Angular velocity (vector of size 3)"),
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.");
27 
28  bp::def("log3",&log3_proxy<Eigen::Matrix3d>,
29  bp::arg("Rotation matrix (matrix of size 3x3))"),
30  "Log: SO3 -> so3. Pseudo-inverse of log from SO3"
31  " -> { v in so3, ||v|| < 2pi }.Exp: so3 -> SO3.");
32 
33  bp::def("Jlog3",&Jlog3_proxy<Eigen::Matrix3d>,
34  bp::arg("Rotation matrix R (matrix of size 3x3)"),
35  "Jacobian of log(R) which maps from the tangent of SO(3) at R to"
36  " the tangent of SO(3) at Identity.");
37 
38  bp::def("Hlog3",&Hlog3_proxy<Eigen::Matrix3d, Eigen::Vector3d>,
39  bp::args("R","v"),
40  "Vector v to be multiplied to the hessian",
41  "v^T * H where H is the Hessian of log(R)");
42 
43  bp::def("exp6",&exp6_proxy<double,0>,
44  bp::arg("Spatial velocity (Motion)"),
45  "Exp: se3 -> SE3. Return the integral of the input"
46  " spatial velocity during time 1.");
47 
48  bp::def("exp6",&exp6_proxy<Motion::Vector6>,
49  bp::arg("Spatial velocity (vector 6x1)"),
50  "Exp: se3 -> SE3. Return the integral of the input"
51  " spatial velocity during time 1.");
52 
53  bp::def("Jexp6",&Jexp6_proxy<double,0>,
54  bp::arg("v: Spatial velocity (Motion)"),
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.");
57 
58  bp::def("Jexp6",&Jexp6_proxy<Motion::Vector6>,
59  bp::arg("v: Spatial velocity (vector 6x1)"),
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.");
62 
63  bp::def("log6",(Motion (*)(const SE3 &))&log6<double,0>,
64  bp::arg("Spatial transform (SE3)"),
65  "Log: SE3 -> se3. Pseudo-inverse of exp from SE3"
66  " -> { v,w in se3, ||w|| < 2pi }.");
67 
68  bp::def("log6",&log6_proxy<Eigen::Matrix4d>,
69  bp::arg("Homegenious matrix (matrix 4x4)"),
70  "Log: SE3 -> se3. Pseudo-inverse of exp from SE3"
71  " -> { v,w in se3, ||w|| < 2pi }.");
72 
73  bp::def("Jlog6",&Jlog6_proxy<double,0>,
74  bp::arg("Spatial transform M (SE3)"),
75  "Jacobian of log(M) which maps from the tangent of SE(3) at M to"
76  " the tangent of SE(3) at Identity.");
77 
78  }
79 
80  } // namespace python
81 } // namespace pinocchio
Main pinocchio namespace.
Definition: timings.cpp:30


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:02