GCC Code Coverage Report


Directory: ./
File: bindings/python/spatial/expose-explog.cpp
Date: 2025-02-12 21:03:38
Exec Total Coverage
Lines: 44 44 100.0%
Branches: 21 42 50.0%

Line Branch Exec Source
1 //
2 // Copyright (c) 2015-2021 CNRS INRIA
3 // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5
6 #include <boost/python.hpp>
7
8 #include "pinocchio/bindings/python/context.hpp"
9 #include "pinocchio/bindings/python/spatial/explog.hpp"
10
11 namespace pinocchio
12 {
13 namespace python
14 {
15 namespace bp = boost::python;
16
17 69 void exposeExplog()
18 {
19
20
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
21 138 "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.");
24
25
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
26 138 "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.");
29
30
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
31 138 "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.");
34
35
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
36 138 "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 }.");
39
40
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
41 138 "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.");
45
46
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
47 138 "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.");
51
52
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
53 138 "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 "
55 "so3 to the unit"
56 " quaternions. It maps from S^3 -> { v in so3, ||v|| < 2pi }.");
57
58
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
59 138 "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 "
61 "so3 to the unit"
62 " quaternions. It maps from S^3 -> { v in so3, ||v|| < 2pi }.");
63
64
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
65 "log3", &log3_proxy_quatvec<context::Vector4s, context::Matrix1s>,
66 138 bp::args("quat", "theta"),
67 "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from "
68 "so3 to the unit"
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.");
71
72
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
73 "log3", &log3_proxy_quatvec_fix<context::Vector4s, context::Scalar>,
74 138 bp::args("quat", "theta"),
75 "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from "
76 "so3 to the unit"
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.");
79
80
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
81 138 "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.");
84
85
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
86 138 "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)");
88
89
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
90 138 "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.");
93
94
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
95 138 "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.");
98
99
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
100 138 "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.");
104
105
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
106 138 "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.");
109
110
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
111 138 "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.");
114
115
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
116 "log6", (context::Motion(*)(const context::SE3 &))&log6<context::Scalar, context::Options>,
117 138 bp::arg("M"),
118 "Log: SE3 -> se3. Pseudo-inverse of exp from SE3"
119 " -> { v,w in se3, ||w|| < 2pi }.");
120
121
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
122 138 "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 }.");
125
126
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
127 138 "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.");
130
131
1/2
✓ Branch 1 taken 69 times.
✗ Branch 2 not taken.
69 bp::def(
132 138 "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.");
135 69 }
136
137 } // namespace python
138 } // namespace pinocchio
139