Directory: | ./ |
---|---|
File: | unittest/casadi/spatial.cpp |
Date: | 2025-02-12 21:03:38 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 69 | 69 | 100.0% |
Branches: | 302 | 600 | 50.3% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // | ||
2 | // Copyright (c) 2019 INRIA | ||
3 | // | ||
4 | |||
5 | #include <pinocchio/autodiff/casadi.hpp> | ||
6 | |||
7 | #include <pinocchio/math/quaternion.hpp> | ||
8 | #include <pinocchio/spatial/se3.hpp> | ||
9 | #include <pinocchio/spatial/motion.hpp> | ||
10 | #include "pinocchio/spatial/explog.hpp" | ||
11 | |||
12 | #include <pinocchio/spatial/explog.hpp> | ||
13 | |||
14 | #include <boost/variant.hpp> // to avoid C99 warnings | ||
15 | |||
16 | #include <iostream> | ||
17 | #include <boost/test/unit_test.hpp> | ||
18 | #include <boost/utility/binary.hpp> | ||
19 | |||
20 | BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) | ||
21 | |||
22 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_se3) |
23 | { | ||
24 | typedef pinocchio::SE3Tpl<casadi::SX> SE3; | ||
25 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 M1 = SE3::Identity(); |
26 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 M2 = SE3::Random(); |
27 | |||
28 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 M3 = M2 * M1; |
29 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3 M1inv = M1.inverse(); |
30 | |||
31 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ::casadi::SX trans; |
32 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | pinocchio::casadi::copy(M1.translation(), trans); |
33 | |||
34 | 2 | const Eigen::DenseIndex col = 0; | |
35 |
2/2✓ Branch 0 taken 3 times.
✓ Branch 1 taken 1 times.
|
8 | for (Eigen::DenseIndex k = 0; k < 3; ++k) |
36 | { | ||
37 |
10/20✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 3 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 3 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 3 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 3 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 3 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 3 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 3 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 3 times.
✗ Branch 30 not taken.
✗ Branch 35 not taken.
✓ Branch 36 taken 3 times.
|
6 | BOOST_CHECK(casadi::SX::is_equal(trans(k, col), M1.translation()[k])); |
38 | } | ||
39 | 2 | } | |
40 | |||
41 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_motion) |
42 | { | ||
43 | typedef pinocchio::MotionTpl<casadi::SX> Motion; | ||
44 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v1 = Motion::Zero(); |
45 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v2 = Motion::Random(); |
46 | |||
47 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Motion v3 = v1 + v2; |
48 | 2 | } | |
49 | |||
50 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_quaternion) |
51 | { | ||
52 | typedef pinocchio::SE3Tpl<casadi::SX> SE3AD; | ||
53 | typedef pinocchio::SE3 SE3; | ||
54 | |||
55 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3AD ad_M; |
56 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3AD::Matrix3 & ad_rot = ad_M.rotation(); |
57 | |||
58 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
4 | casadi::SX cs_rot = casadi::SX::sym("rot", 3, 3); |
59 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::casadi::copy(cs_rot, ad_rot); |
60 | |||
61 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3AD::Quaternion ad_quat; |
62 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::quaternion::assignQuaternion(ad_quat, ad_rot); |
63 | |||
64 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | casadi::SX cs_quat(4, 1); |
65 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | pinocchio::casadi::copy(ad_quat.coeffs(), cs_quat); |
66 | |||
67 |
6/12✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
|
12 | casadi::Function eval_quat("eval_quat", casadi::SXVector{cs_rot}, casadi::SXVector{cs_quat}); |
68 | |||
69 |
2/2✓ Branch 0 taken 10000 times.
✓ Branch 1 taken 1 times.
|
20002 | for (int k = 0; k < 1e4; ++k) |
70 | { | ||
71 |
1/2✓ Branch 1 taken 10000 times.
✗ Branch 2 not taken.
|
20000 | SE3 M(SE3::Random()); |
72 |
2/4✓ Branch 1 taken 10000 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10000 times.
✗ Branch 5 not taken.
|
20000 | SE3::Quaternion quat_ref(M.rotation()); |
73 | |||
74 |
1/2✓ Branch 1 taken 10000 times.
✗ Branch 2 not taken.
|
20000 | casadi::DM vec_rot(3, 3); |
75 |
2/4✓ Branch 1 taken 10000 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10000 times.
✗ Branch 5 not taken.
|
20000 | pinocchio::casadi::copy(M.rotation(), vec_rot); |
76 | |||
77 |
4/8✓ Branch 1 taken 10000 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 10000 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 10000 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 10000 times.
✗ Branch 13 not taken.
|
60000 | casadi::DM quat_res = eval_quat(casadi::DMVector{vec_rot})[0]; |
78 |
1/2✓ Branch 1 taken 10000 times.
✗ Branch 2 not taken.
|
20000 | SE3::Quaternion quat_value; |
79 | |||
80 | 20000 | quat_value.coeffs() = | |
81 |
4/8✓ Branch 1 taken 10000 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10000 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 10000 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 10000 times.
✗ Branch 12 not taken.
|
40000 | Eigen::Map<Eigen::Vector4d>(static_cast<std::vector<double>>(quat_res).data()); |
82 |
7/14✓ Branch 1 taken 10000 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 10000 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 10000 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 10000 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 10000 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 10000 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 10000 times.
|
20000 | BOOST_CHECK(pinocchio::quaternion::defineSameRotation(quat_value, quat_ref)); |
83 | // if(! quat_value.coeffs().isApprox(quat_ref.coeffs())) | ||
84 | // { | ||
85 | // std::cout << "quat_value: " << quat_value.coeffs().transpose() << std::endl; | ||
86 | // std::cout << "quat_ref: " << quat_ref.coeffs().transpose() << std::endl; | ||
87 | // } | ||
88 | 20000 | } | |
89 | 2 | } | |
90 | |||
91 |
33/66✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✓ Branch 27 taken 1 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 1 times.
✗ Branch 31 not taken.
✓ Branch 33 taken 1 times.
✗ Branch 34 not taken.
✓ Branch 36 taken 1 times.
✗ Branch 37 not taken.
✓ Branch 41 taken 1 times.
✗ Branch 42 not taken.
✓ Branch 45 taken 1 times.
✗ Branch 46 not taken.
✓ Branch 48 taken 1 times.
✗ Branch 49 not taken.
✓ Branch 52 taken 1 times.
✗ Branch 53 not taken.
✓ Branch 55 taken 1 times.
✗ Branch 56 not taken.
✓ Branch 58 taken 1 times.
✗ Branch 59 not taken.
✓ Branch 61 taken 1 times.
✗ Branch 62 not taken.
✓ Branch 66 taken 1 times.
✗ Branch 67 not taken.
✓ Branch 70 taken 1 times.
✗ Branch 71 not taken.
✓ Branch 73 taken 1 times.
✗ Branch 74 not taken.
✓ Branch 77 taken 1 times.
✗ Branch 78 not taken.
✓ Branch 80 taken 1 times.
✗ Branch 81 not taken.
✓ Branch 83 taken 1 times.
✗ Branch 84 not taken.
✓ Branch 86 taken 1 times.
✗ Branch 87 not taken.
✓ Branch 91 taken 1 times.
✗ Branch 92 not taken.
✓ Branch 95 taken 1 times.
✗ Branch 96 not taken.
✓ Branch 98 taken 1 times.
✗ Branch 99 not taken.
✓ Branch 102 taken 1 times.
✗ Branch 103 not taken.
✓ Branch 105 taken 1 times.
✗ Branch 106 not taken.
✓ Branch 108 taken 1 times.
✗ Branch 109 not taken.
✓ Branch 111 taken 1 times.
✗ Branch 112 not taken.
✓ Branch 116 taken 1 times.
✗ Branch 117 not taken.
|
4 | BOOST_AUTO_TEST_CASE(test_log3_firstorder_derivatives) |
92 | { | ||
93 | typedef double Scalar; | ||
94 | typedef casadi::SX ADScalar; | ||
95 | |||
96 | typedef pinocchio::SE3 SE3; | ||
97 | typedef SE3::Vector3 Vector3; | ||
98 | typedef SE3::Matrix3 Matrix3; | ||
99 | |||
100 | typedef pinocchio::SE3Tpl<ADScalar> SE3AD; | ||
101 | typedef SE3AD::Vector3 Vector3AD; | ||
102 | typedef SE3AD::Matrix3 Matrix3AD; | ||
103 | |||
104 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3::Matrix3 RTarget; |
105 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | pinocchio::toRotationMatrix(Vector3(SE3::Vector3::UnitX()), pinocchio::PI<Scalar>() / 4, RTarget); |
106 | |||
107 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SE3::Quaternion quat0(0.707107, 0.707107, 0, 0); |
108 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Matrix3 R0 = quat0.toRotationMatrix(); |
109 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Vector3 nu0 = pinocchio::log3(R0); |
110 | |||
111 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
4 | casadi::SX cs_nu = casadi::SX::sym("nu", 3); |
112 | |||
113 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
2 | Vector3AD nu_ad = Eigen::Map<Vector3AD>(static_cast<std::vector<ADScalar>>(cs_nu).data()); |
114 | auto log3_casadi_exp = | ||
115 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
|
2 | pinocchio::log3(pinocchio::exp3(nu_ad).transpose() * RTarget.cast<ADScalar>()); |
116 | |||
117 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
4 | casadi::SX cs_res = casadi::SX::sym("res", 3); |
118 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | pinocchio::casadi::copy(log3_casadi_exp, cs_res); |
119 | |||
120 |
6/12✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
|
12 | casadi::Function log3_casadi("log3_casadi", casadi::SXVector{cs_nu}, casadi::SXVector{cs_res}); |
121 | |||
122 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | std::vector<double> log3_casadi_input(3); |
123 |
3/6✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | Eigen::Map<Vector3>(log3_casadi_input.data()) = nu0; |
124 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
|
6 | casadi::DM log3_casadi_res = log3_casadi(casadi::DMVector{log3_casadi_input})[0]; |
125 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
2 | Vector3 res0 = Eigen::Map<Vector3>(static_cast<std::vector<double>>(log3_casadi_res).data()); |
126 | |||
127 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
|
2 | Vector3 res0_ref = pinocchio::log3(pinocchio::exp3(nu0).transpose() * RTarget); |
128 | |||
129 | // Check first that the value matches | ||
130 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(res0 == res0); |
131 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(res0_ref == res0_ref); |
132 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(res0.isApprox(res0_ref)); |
133 | |||
134 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | ADScalar log3_casadi_jacobian_exp = jacobian(cs_res, cs_nu); |
135 | casadi::Function log3_casadi_jacobian( | ||
136 |
6/12✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
|
12 | "log3_casadi_jacobian", casadi::SXVector{cs_nu}, casadi::SXVector{log3_casadi_jacobian_exp}); |
137 | |||
138 | casadi::DM log3_casadi_jacobian_res = | ||
139 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
|
6 | log3_casadi_jacobian(casadi::DMVector{log3_casadi_input})[0]; |
140 | Matrix3 jac0 = | ||
141 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
2 | Eigen::Map<Matrix3>(static_cast<std::vector<double>>(log3_casadi_jacobian_res).data()); |
142 | |||
143 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(jac0 == jac0); |
144 | |||
145 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | ADScalar log3_casadi_gradient_exp = gradient(log3_casadi_exp[0], cs_nu); |
146 | |||
147 | casadi::Function log3_casadi_gradient( | ||
148 |
6/12✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
|
12 | "log3_casadi_jacobian", casadi::SXVector{cs_nu}, casadi::SXVector{log3_casadi_gradient_exp}); |
149 | |||
150 | casadi::DM log3_casadi_gradient_res = | ||
151 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
|
6 | log3_casadi_gradient(casadi::DMVector{log3_casadi_input})[0]; |
152 | Vector3 grad0 = | ||
153 |
4/8✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
2 | Eigen::Map<Vector3>(static_cast<std::vector<double>>(log3_casadi_gradient_res).data()); |
154 | |||
155 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 1 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK(grad0 == grad0); |
156 | 2 | } | |
157 | |||
158 | BOOST_AUTO_TEST_SUITE_END() | ||
159 |