Directory: | ./ |
---|---|
File: | unittest/liegroups.cpp |
Date: | 2025-02-12 21:03:38 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 424 | 426 | 99.5% |
Branches: | 1543 | 3025 | 51.0% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // Copyright (c) 2017-2020, CNRS INRIA | ||
2 | // Authors: Joseph Mirabel (joseph.mirabel@laas.fr) | ||
3 | // | ||
4 | |||
5 | #include <iostream> | ||
6 | #include <iomanip> | ||
7 | |||
8 | #include "pinocchio/multibody/liegroup/liegroup.hpp" | ||
9 | #include "pinocchio/multibody/liegroup/liegroup-collection.hpp" | ||
10 | #include "pinocchio/multibody/liegroup/liegroup-generic.hpp" | ||
11 | #include "pinocchio/multibody/liegroup/cartesian-product-variant.hpp" | ||
12 | |||
13 | #include "pinocchio/multibody/joint/joint-generic.hpp" | ||
14 | |||
15 | #include <boost/test/unit_test.hpp> | ||
16 | #include <boost/utility/binary.hpp> | ||
17 | #include <boost/algorithm/string.hpp> | ||
18 | #include <boost/mpl/vector.hpp> | ||
19 | |||
20 | #define EIGEN_VECTOR_IS_APPROX(Va, Vb, precision) \ | ||
21 | BOOST_CHECK_MESSAGE( \ | ||
22 | (Va).isApprox(Vb, precision), "check " #Va ".isApprox(" #Vb ") failed " \ | ||
23 | "[\n" \ | ||
24 | << (Va).transpose() << "\n!=\n" \ | ||
25 | << (Vb).transpose() << "\n]") | ||
26 | #define EIGEN_MATRIX_IS_APPROX(Va, Vb, precision) \ | ||
27 | BOOST_CHECK_MESSAGE( \ | ||
28 | (Va).isApprox(Vb, precision), "check " #Va ".isApprox(" #Vb ") failed " \ | ||
29 | "[\n" \ | ||
30 | << (Va) << "\n!=\n" \ | ||
31 | << (Vb) << "\n]") | ||
32 | |||
33 | using namespace pinocchio; | ||
34 | |||
35 | #define VERBOSE false | ||
36 | #define IFVERBOSE if (VERBOSE) | ||
37 | |||
38 | namespace pinocchio | ||
39 | { | ||
40 | template<typename Derived> | ||
41 | std::ostream & operator<<(std::ostream & os, const LieGroupBase<Derived> & lg) | ||
42 | { | ||
43 | return os << lg.name(); | ||
44 | } | ||
45 | template<typename LieGroupCollection> | ||
46 | ✗ | std::ostream & operator<<(std::ostream & os, const LieGroupGenericTpl<LieGroupCollection> & lg) | |
47 | { | ||
48 | ✗ | return os << lg.name(); | |
49 | } | ||
50 | } // namespace pinocchio | ||
51 | |||
52 | template<typename T> | ||
53 | 32640 | void test_lie_group_methods(T & jmodel, typename T::JointDataDerived &) | |
54 | { | ||
55 | typedef typename LieGroup<T>::type LieGroupType; | ||
56 | typedef double Scalar; | ||
57 | |||
58 | 32640 | const Scalar prec = Eigen::NumTraits<Scalar>::dummy_precision(); | |
59 |
7/14✓ Branch 2 taken 16320 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 16320 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 16320 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 16320 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 16320 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 16320 times.
✗ Branch 22 not taken.
|
32640 | BOOST_TEST_MESSAGE("Testing Joint over " << jmodel.shortname()); |
60 | typedef typename T::ConfigVector_t ConfigVector_t; | ||
61 | typedef typename T::TangentVector_t TangentVector_t; | ||
62 | |||
63 |
3/6✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 16320 times.
✗ Branch 8 not taken.
|
32640 | ConfigVector_t q1(ConfigVector_t::Random(jmodel.nq())); |
64 |
3/6✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 16320 times.
✗ Branch 8 not taken.
|
32640 | TangentVector_t q1_dot(TangentVector_t::Random(jmodel.nv())); |
65 |
3/6✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 16320 times.
✗ Branch 8 not taken.
|
32640 | ConfigVector_t q2(ConfigVector_t::Random(jmodel.nq())); |
66 | |||
67 |
6/12✓ Branch 0 taken 16 times.
✓ Branch 1 taken 16304 times.
✓ Branch 3 taken 16 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 16 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 16 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 16 times.
✗ Branch 13 not taken.
✗ Branch 15 not taken.
✗ Branch 16 not taken.
|
32640 | static ConfigVector_t Ones(ConfigVector_t::Ones(jmodel.nq())); |
68 | 32640 | const Scalar u = 0.3; | |
69 | // pinocchio::Inertia::Matrix6 Ia(pinocchio::Inertia::Random().matrix()); | ||
70 | // bool update_I = false; | ||
71 | |||
72 |
3/6✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 16320 times.
✗ Branch 8 not taken.
|
32640 | q1 = LieGroupType().randomConfiguration(-Ones, Ones); |
73 |
8/16✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 16320 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 16320 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 16320 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 16320 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 16320 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 16320 times.
|
32640 | BOOST_CHECK(LieGroupType().isNormalized(q1)); |
74 | |||
75 |
1/2✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
|
32640 | typename T::JointDataDerived jdata = jmodel.createData(); |
76 | |||
77 | // Check integrate | ||
78 |
1/2✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
|
32640 | jmodel.calc(jdata, q1, q1_dot); |
79 |
1/2✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
|
32640 | SE3 M1 = jdata.M; |
80 |
1/2✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
|
32640 | Motion v1(jdata.v); |
81 | |||
82 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
|
32640 | q2 = LieGroupType().integrate(q1, q1_dot); |
83 |
8/16✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 16320 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 16320 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 16320 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 16320 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 16320 times.
✗ Branch 25 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 16320 times.
|
32640 | BOOST_CHECK(LieGroupType().isNormalized(q2)); |
84 |
1/2✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
|
32640 | jmodel.calc(jdata, q2); |
85 |
1/2✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
|
32640 | SE3 M2 = jdata.M; |
86 | |||
87 | 32640 | double tol_test = 1e2; | |
88 |
3/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1020 times.
✓ Branch 6 taken 15300 times.
|
32640 | if (jmodel.shortname() == "JointModelPlanar") |
89 | 2040 | tol_test = 5e4; | |
90 | |||
91 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
|
32640 | const SE3 M2_exp = M1 * exp6(v1); |
92 | |||
93 |
3/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 15300 times.
✓ Branch 6 taken 1020 times.
|
32640 | if (jmodel.shortname() != "JointModelSphericalZYX") |
94 | { | ||
95 |
9/18✓ Branch 1 taken 15300 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 15300 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 15300 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 15300 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 15300 times.
✗ Branch 17 not taken.
✓ Branch 20 taken 15300 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 15300 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 15300 times.
✗ Branch 27 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 15300 times.
|
30600 | BOOST_CHECK_MESSAGE( |
96 | M2.isApprox(M2_exp), std::string("Error when integrating1 " + jmodel.shortname())); | ||
97 | } | ||
98 | |||
99 | // Check integrate when the same vector is passed as input and output | ||
100 |
3/6✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 16320 times.
✗ Branch 8 not taken.
|
32640 | ConfigVector_t qTest(ConfigVector_t::Random(jmodel.nq())); |
101 |
3/6✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 16320 times.
✗ Branch 8 not taken.
|
32640 | TangentVector_t qTest_dot(TangentVector_t::Random(jmodel.nv())); |
102 |
3/6✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 16320 times.
✗ Branch 8 not taken.
|
32640 | ConfigVector_t qResult(ConfigVector_t::Random(jmodel.nq())); |
103 |
3/6✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 16320 times.
✗ Branch 8 not taken.
|
32640 | qTest = LieGroupType().randomConfiguration(-Ones, Ones); |
104 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
|
32640 | qResult = LieGroupType().integrate(qTest, qTest_dot); |
105 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
|
32640 | LieGroupType().integrate(qTest, qTest_dot, qTest); |
106 |
10/20✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 16320 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 16320 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 16320 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 16320 times.
✗ Branch 20 not taken.
✓ Branch 23 taken 16320 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 16320 times.
✗ Branch 27 not taken.
✓ Branch 29 taken 16320 times.
✗ Branch 30 not taken.
✗ Branch 36 not taken.
✓ Branch 37 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE( |
107 | LieGroupType().isNormalized(qTest), | ||
108 | std::string( | ||
109 | "Normalization error when integrating with same input and output " + jmodel.shortname())); | ||
110 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
|
32640 | SE3 MTest, MResult; |
111 | { | ||
112 |
1/2✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
|
32640 | typename T::JointDataDerived jdata = jmodel.createData(); |
113 |
1/2✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
|
32640 | jmodel.calc(jdata, qTest); |
114 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 11220 times.
✗ Branch 5 not taken.
|
32640 | MTest = jdata.M; |
115 | } | ||
116 | { | ||
117 |
1/2✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
|
32640 | typename T::JointDataDerived jdata = jmodel.createData(); |
118 |
1/2✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
|
32640 | jmodel.calc(jdata, qResult); |
119 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 11220 times.
✗ Branch 5 not taken.
|
32640 | MResult = jdata.M; |
120 | } | ||
121 |
9/18✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 16320 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 16320 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 16320 times.
✗ Branch 17 not taken.
✓ Branch 20 taken 16320 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 16320 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 16320 times.
✗ Branch 27 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE( |
122 | MTest.isApprox(MResult), | ||
123 | std::string( | ||
124 | "Inconsistent value when integrating with same input and output " + jmodel.shortname())); | ||
125 | |||
126 |
9/18✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 16320 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 16320 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 16320 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 16320 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 16320 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 16320 times.
✗ Branch 26 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE( |
127 | qTest.isApprox(qResult, prec), | ||
128 | std::string( | ||
129 | "Inconsistent value when integrating with same input and output " + jmodel.shortname())); | ||
130 | |||
131 | // Check the reversability of integrate | ||
132 |
3/6✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 16320 times.
✗ Branch 8 not taken.
|
32640 | ConfigVector_t q3 = LieGroupType().integrate(q2, -q1_dot); |
133 |
1/2✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
|
32640 | jmodel.calc(jdata, q3); |
134 |
1/2✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
|
32640 | SE3 M3 = jdata.M; |
135 | |||
136 |
9/18✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 16320 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 16320 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 16320 times.
✗ Branch 17 not taken.
✓ Branch 20 taken 16320 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 16320 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 16320 times.
✗ Branch 27 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE( |
137 | M3.isApprox(M1), std::string("Error when integrating back " + jmodel.shortname())); | ||
138 | |||
139 | // Check interpolate | ||
140 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
|
32640 | ConfigVector_t q_interpolate = LieGroupType().interpolate(q1, q2, 0.); |
141 |
9/18✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 16320 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 16320 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 16320 times.
✗ Branch 17 not taken.
✓ Branch 20 taken 16320 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 16320 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 16320 times.
✗ Branch 27 not taken.
✗ Branch 33 not taken.
✓ Branch 34 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE( |
142 | q_interpolate.isApprox(q1), std::string("Error when interpolating " + jmodel.shortname())); | ||
143 | |||
144 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
|
32640 | q_interpolate = LieGroupType().interpolate(q1, q2, 1.); |
145 |
3/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1020 times.
✓ Branch 6 taken 15300 times.
|
32640 | if (jmodel.shortname() == "JointModelPlanar") // TODO(jcarpent) fix precision loss for |
146 | // JointModelPlanar log operations | ||
147 |
9/18✓ Branch 1 taken 1020 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1020 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 1020 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1020 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1020 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1020 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1020 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 1020 times.
✗ Branch 26 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1020 times.
|
2040 | BOOST_CHECK_MESSAGE( |
148 | q_interpolate.isApprox(q2, 1e-8), | ||
149 | std::string("Error when interpolating " + jmodel.shortname())); | ||
150 | else | ||
151 |
9/18✓ Branch 1 taken 15300 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 15300 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 15300 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 15300 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 15300 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 15300 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 15300 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 15300 times.
✗ Branch 26 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 15300 times.
|
30600 | BOOST_CHECK_MESSAGE( |
152 | q_interpolate.isApprox(q2, 1e0 * prec), | ||
153 | std::string("Error when interpolating " + jmodel.shortname())); | ||
154 | |||
155 |
3/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 15300 times.
✓ Branch 6 taken 1020 times.
|
32640 | if (jmodel.shortname() != "JointModelSphericalZYX") |
156 | { | ||
157 |
2/4✓ Branch 1 taken 15300 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 15300 times.
✗ Branch 5 not taken.
|
30600 | q_interpolate = LieGroupType().interpolate(q1, q2, u); |
158 |
1/2✓ Branch 1 taken 15300 times.
✗ Branch 2 not taken.
|
30600 | jmodel.calc(jdata, q_interpolate); |
159 |
1/2✓ Branch 1 taken 15300 times.
✗ Branch 2 not taken.
|
30600 | SE3 M_interpolate = jdata.M; |
160 | |||
161 |
3/6✓ Branch 1 taken 15300 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 15300 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 15300 times.
✗ Branch 8 not taken.
|
30600 | SE3 M_interpolate_expected = M1 * exp6(u * v1); |
162 |
9/18✓ Branch 1 taken 15300 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 15300 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 15300 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 15300 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 15300 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 15300 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 15300 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 15300 times.
✗ Branch 26 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 15300 times.
|
30600 | BOOST_CHECK_MESSAGE( |
163 | M_interpolate_expected.isApprox(M_interpolate, 1e4 * prec), | ||
164 | std::string("Error when interpolating " + jmodel.shortname())); | ||
165 | } | ||
166 | |||
167 | // Check that difference between two equal configuration is exactly 0 | ||
168 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
|
32640 | TangentVector_t zero = LieGroupType().difference(q1, q1); |
169 |
8/16✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 16320 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 16320 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 16320 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 16320 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 16320 times.
✗ Branch 25 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE( |
170 | zero.isZero(), std::string("Error: difference between two equal configurations is not 0.")); | ||
171 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
|
32640 | zero = LieGroupType().difference(q2, q2); |
172 |
8/16✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 16320 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 16320 times.
✗ Branch 15 not taken.
✓ Branch 18 taken 16320 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 16320 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 16320 times.
✗ Branch 25 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE( |
173 | zero.isZero(), std::string("Error: difference between two equal configurations is not 0.")); | ||
174 | |||
175 | // Check difference | ||
176 | // TODO(jcarpent): check the increase of tolerance. | ||
177 | |||
178 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
|
32640 | TangentVector_t vdiff = LieGroupType().difference(q1, q2); |
179 |
9/18✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 16320 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 16320 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 16320 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 16320 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 16320 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 16320 times.
✗ Branch 26 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE( |
180 | vdiff.isApprox(q1_dot, tol_test * prec), | ||
181 | std::string("Error when differentiating " + jmodel.shortname())); | ||
182 | |||
183 | // Check distance | ||
184 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
|
32640 | Scalar dist = LieGroupType().distance(q1, q2); |
185 |
6/12✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 16320 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 16320 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 16320 times.
✗ Branch 17 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE(dist > 0., "distance - wrong results"); |
186 |
6/12✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 16320 times.
✗ Branch 9 not taken.
✓ Branch 14 taken 16320 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 16320 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 16320 times.
|
32640 | BOOST_CHECK_SMALL(math::fabs(dist - q1_dot.norm()), tol_test * prec); |
187 | |||
188 |
1/2✓ Branch 2 taken 16320 times.
✗ Branch 3 not taken.
|
32640 | std::string error_prefix("LieGroup"); |
189 |
3/6✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 16320 times.
✗ Branch 8 not taken.
|
32640 | error_prefix += " on joint " + jmodel.shortname(); |
190 | |||
191 |
8/16✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 16320 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 16320 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 16320 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 16320 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 16320 times.
✗ Branch 23 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE(jmodel.nq() == LieGroupType::NQ, std::string(error_prefix + " - nq ")); |
192 |
8/16✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 16320 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 16320 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 16320 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 16320 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 16320 times.
✗ Branch 23 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE(jmodel.nv() == LieGroupType::NV, std::string(error_prefix + " - nv ")); |
193 | |||
194 |
11/22✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 16320 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 16320 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 16320 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 16320 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 16320 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 16320 times.
✗ Branch 26 not taken.
✓ Branch 29 taken 16320 times.
✗ Branch 30 not taken.
✓ Branch 32 taken 16320 times.
✗ Branch 33 not taken.
✗ Branch 38 not taken.
✓ Branch 39 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE( |
195 | jmodel.nq() == LieGroupType().randomConfiguration(-1 * Ones, Ones).size(), | ||
196 | std::string(error_prefix + " - RandomConfiguration dimensions ")); | ||
197 | |||
198 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
|
32640 | ConfigVector_t q_normalize(ConfigVector_t::Random()); |
199 |
1/2✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
|
32640 | Eigen::VectorXd q_normalize_ref(q_normalize); |
200 |
3/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1020 times.
✓ Branch 6 taken 15300 times.
|
32640 | if (jmodel.shortname() == "JointModelSpherical") |
201 | { | ||
202 |
9/18✓ Branch 1 taken 1020 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1020 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 1020 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1020 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1020 times.
✗ Branch 17 not taken.
✓ Branch 20 taken 1020 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1020 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1020 times.
✗ Branch 27 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1020 times.
|
2040 | BOOST_CHECK_MESSAGE( |
203 | !LieGroupType().isNormalized(q_normalize_ref), | ||
204 | std::string(error_prefix + " - !isNormalized ")); | ||
205 |
2/4✓ Branch 1 taken 1020 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1020 times.
✗ Branch 5 not taken.
|
2040 | q_normalize_ref /= q_normalize_ref.norm(); |
206 | } | ||
207 |
3/4✓ Branch 1 taken 15300 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1020 times.
✓ Branch 6 taken 14280 times.
|
30600 | else if (jmodel.shortname() == "JointModelFreeFlyer") |
208 | { | ||
209 |
9/18✓ Branch 1 taken 1020 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1020 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 1020 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1020 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1020 times.
✗ Branch 17 not taken.
✓ Branch 20 taken 1020 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1020 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1020 times.
✗ Branch 27 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1020 times.
|
2040 | BOOST_CHECK_MESSAGE( |
210 | !LieGroupType().isNormalized(q_normalize_ref), | ||
211 | std::string(error_prefix + " - !isNormalized ")); | ||
212 |
4/8✓ Branch 1 taken 1020 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1020 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1020 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1020 times.
✗ Branch 11 not taken.
|
2040 | q_normalize_ref.template tail<4>() /= q_normalize_ref.template tail<4>().norm(); |
213 | } | ||
214 |
4/6✓ Branch 2 taken 14280 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 14280 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 3060 times.
✓ Branch 10 taken 11220 times.
|
28560 | else if (boost::algorithm::istarts_with(jmodel.shortname(), "JointModelRUB")) |
215 | { | ||
216 |
9/18✓ Branch 1 taken 3060 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 3060 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 3060 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 3060 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 3060 times.
✗ Branch 17 not taken.
✓ Branch 20 taken 3060 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 3060 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 3060 times.
✗ Branch 27 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 3060 times.
|
6120 | BOOST_CHECK_MESSAGE( |
217 | !LieGroupType().isNormalized(q_normalize_ref), | ||
218 | std::string(error_prefix + " - !isNormalized ")); | ||
219 |
2/4✓ Branch 1 taken 3060 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 3060 times.
✗ Branch 5 not taken.
|
6120 | q_normalize_ref /= q_normalize_ref.norm(); |
220 | } | ||
221 |
3/4✓ Branch 1 taken 11220 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1020 times.
✓ Branch 6 taken 10200 times.
|
22440 | else if (jmodel.shortname() == "JointModelPlanar") |
222 | { | ||
223 |
9/18✓ Branch 1 taken 1020 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1020 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 1020 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1020 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1020 times.
✗ Branch 17 not taken.
✓ Branch 20 taken 1020 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 1020 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 1020 times.
✗ Branch 27 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 1020 times.
|
2040 | BOOST_CHECK_MESSAGE( |
224 | !LieGroupType().isNormalized(q_normalize_ref), | ||
225 | std::string(error_prefix + " - !isNormalized ")); | ||
226 |
4/8✓ Branch 1 taken 1020 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1020 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1020 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 1020 times.
✗ Branch 11 not taken.
|
2040 | q_normalize_ref.template tail<2>() /= q_normalize_ref.template tail<2>().norm(); |
227 | } | ||
228 |
9/18✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 16320 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 16320 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 16320 times.
✗ Branch 17 not taken.
✓ Branch 20 taken 16320 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 16320 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 16320 times.
✗ Branch 27 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE( |
229 | LieGroupType().isNormalized(q_normalize_ref), std::string(error_prefix + " - isNormalized ")); | ||
230 |
2/4✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 16320 times.
✗ Branch 5 not taken.
|
32640 | LieGroupType().normalize(q_normalize); |
231 |
8/16✓ Branch 1 taken 16320 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 16320 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 16320 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 16320 times.
✗ Branch 14 not taken.
✓ Branch 17 taken 16320 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 16320 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 16320 times.
✗ Branch 24 not taken.
✗ Branch 29 not taken.
✓ Branch 30 taken 16320 times.
|
32640 | BOOST_CHECK_MESSAGE( |
232 | q_normalize.isApprox(q_normalize_ref), std::string(error_prefix + " - normalize ")); | ||
233 | 32640 | } | |
234 | |||
235 | struct TestJoint | ||
236 | { | ||
237 | |||
238 | template<typename JointModel, typename JointData> | ||
239 | 640 | static void run_tests(JointModel & jmodel, JointData & jdata) | |
240 | { | ||
241 |
2/2✓ Branch 0 taken 16320 times.
✓ Branch 1 taken 320 times.
|
33280 | for (int i = 0; i <= 50; ++i) |
242 | { | ||
243 | 32640 | test_lie_group_methods(jmodel, jdata); | |
244 | } | ||
245 | 640 | } | |
246 | |||
247 | template<typename T> | ||
248 | 560 | void operator()(const T) const | |
249 | { | ||
250 |
1/2✓ Branch 1 taken 280 times.
✗ Branch 2 not taken.
|
560 | T jmodel; |
251 |
1/2✓ Branch 1 taken 280 times.
✗ Branch 2 not taken.
|
560 | jmodel.setIndexes(0, 0, 0); |
252 |
1/2✓ Branch 1 taken 280 times.
✗ Branch 2 not taken.
|
560 | typename T::JointDataDerived jdata = jmodel.createData(); |
253 | |||
254 |
1/2✓ Branch 1 taken 280 times.
✗ Branch 2 not taken.
|
560 | run_tests(jmodel, jdata); |
255 | 560 | } | |
256 | |||
257 | 20 | void operator()(const pinocchio::JointModelRevoluteUnaligned &) const | |
258 | { | ||
259 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | pinocchio::JointModelRevoluteUnaligned jmodel(1.5, 1., 0.); |
260 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | jmodel.setIndexes(0, 0, 0); |
261 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | pinocchio::JointModelRevoluteUnaligned::JointDataDerived jdata = jmodel.createData(); |
262 | |||
263 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | run_tests(jmodel, jdata); |
264 | 20 | } | |
265 | |||
266 | 20 | void operator()(const pinocchio::JointModelPrismaticUnaligned &) const | |
267 | { | ||
268 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | pinocchio::JointModelPrismaticUnaligned jmodel(1.5, 1., 0.); |
269 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | jmodel.setIndexes(0, 0, 0); |
270 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | pinocchio::JointModelPrismaticUnaligned::JointDataDerived jdata = jmodel.createData(); |
271 | |||
272 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | run_tests(jmodel, jdata); |
273 | 20 | } | |
274 | }; | ||
275 | |||
276 | struct LieGroup_Jdifference | ||
277 | { | ||
278 | template<typename T> | ||
279 | 320 | void operator()(const T) const | |
280 | { | ||
281 | typedef typename T::ConfigVector_t ConfigVector_t; | ||
282 | typedef typename T::TangentVector_t TangentVector_t; | ||
283 | typedef typename T::JacobianMatrix_t JacobianMatrix_t; | ||
284 | typedef typename T::Scalar Scalar; | ||
285 | |||
286 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | T lg; |
287 |
6/12✓ Branch 2 taken 160 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 160 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 160 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 160 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 160 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 160 times.
✗ Branch 19 not taken.
|
320 | BOOST_TEST_MESSAGE(lg.name()); |
288 |
6/8✓ Branch 1 taken 320 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 320 times.
✓ Branch 4 taken 160 times.
✓ Branch 6 taken 320 times.
✗ Branch 7 not taken.
✓ Branch 8 taken 320 times.
✓ Branch 9 taken 160 times.
|
1600 | ConfigVector_t q[2], q_dv[2]; |
289 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | q[0] = lg.random(); |
290 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | q[1] = lg.random(); |
291 | PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH | ||
292 | PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED | ||
293 |
3/6✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 160 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 160 times.
✗ Branch 8 not taken.
|
320 | TangentVector_t va, vb, dv; |
294 |
3/4✓ Branch 1 taken 320 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 320 times.
✓ Branch 4 taken 160 times.
|
960 | JacobianMatrix_t J[2]; |
295 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | dv.setZero(); |
296 | |||
297 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | lg.difference(q[0], q[1], va); |
298 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | lg.template dDifference<ARG0>(q[0], q[1], J[0]); |
299 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | lg.template dDifference<ARG1>(q[0], q[1], J[1]); |
300 | |||
301 | 320 | const Scalar eps = 1e-6; | |
302 |
2/2✓ Branch 0 taken 320 times.
✓ Branch 1 taken 160 times.
|
960 | for (int k = 0; k < 2; ++k) |
303 | { | ||
304 |
8/16✓ Branch 2 taken 320 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 320 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 320 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 320 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 320 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 320 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 320 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 320 times.
✗ Branch 25 not taken.
|
640 | BOOST_TEST_MESSAGE("Checking J" << k << '\n' << J[k]); |
305 |
1/2✓ Branch 1 taken 320 times.
✗ Branch 2 not taken.
|
640 | q_dv[0] = q[0]; |
306 |
1/2✓ Branch 1 taken 320 times.
✗ Branch 2 not taken.
|
640 | q_dv[1] = q[1]; |
307 | // Check J[k] | ||
308 |
2/2✓ Branch 1 taken 1000 times.
✓ Branch 2 taken 320 times.
|
2640 | for (int i = 0; i < dv.size(); ++i) |
309 | { | ||
310 |
1/2✓ Branch 1 taken 1000 times.
✗ Branch 2 not taken.
|
2000 | dv[i] = eps; |
311 |
1/2✓ Branch 1 taken 1000 times.
✗ Branch 2 not taken.
|
2000 | lg.integrate(q[k], dv, q_dv[k]); |
312 |
1/2✓ Branch 1 taken 1000 times.
✗ Branch 2 not taken.
|
2000 | lg.difference(q_dv[0], q_dv[1], vb); |
313 | |||
314 | // vb - va ~ J[k] * dv | ||
315 |
2/4✓ Branch 1 taken 1000 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1000 times.
✗ Branch 5 not taken.
|
2000 | TangentVector_t J_dv = J[k].col(i); |
316 |
3/6✓ Branch 1 taken 1000 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1000 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 1000 times.
✗ Branch 8 not taken.
|
2000 | TangentVector_t vb_va = (vb - va) / eps; |
317 |
13/26✓ Branch 1 taken 1000 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1000 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 1000 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1000 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1000 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1000 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 1000 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 1000 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1000 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 1000 times.
✗ Branch 32 not taken.
✓ Branch 34 taken 1000 times.
✗ Branch 35 not taken.
✓ Branch 37 taken 1000 times.
✗ Branch 38 not taken.
✗ Branch 46 not taken.
✓ Branch 47 taken 1000 times.
|
2000 | EIGEN_VECTOR_IS_APPROX(vb_va, J_dv, 1e-2); |
318 |
1/2✓ Branch 1 taken 1000 times.
✗ Branch 2 not taken.
|
2000 | dv[i] = 0; |
319 | } | ||
320 | PINOCCHIO_COMPILER_DIAGNOSTIC_POP | ||
321 | } | ||
322 | |||
323 |
2/4✓ Branch 1 taken 120 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 40 times.
✗ Branch 5 not taken.
|
320 | specificTests(lg); |
324 | 320 | } | |
325 | |||
326 | template<typename T> | ||
327 | 240 | void specificTests(const T) const | |
328 | { | ||
329 | 240 | } | |
330 | |||
331 | template<typename Scalar, int Options> | ||
332 | 20 | void specificTests(const SpecialEuclideanOperationTpl<3, Scalar, Options>) const | |
333 | { | ||
334 | |||
335 | 20 | const Scalar prec = Eigen::NumTraits<Scalar>::dummy_precision(); | |
336 | typedef SE3Tpl<Scalar> SE3; | ||
337 | typedef SpecialEuclideanOperationTpl<3, Scalar, Options> LG_t; | ||
338 | typedef typename LG_t::ConfigVector_t ConfigVector_t; | ||
339 | typedef typename LG_t::JacobianMatrix_t JacobianMatrix_t; | ||
340 | typedef typename LG_t::ConstQuaternionMap_t ConstQuaternionMap_t; | ||
341 | |||
342 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | LG_t lg; |
343 | |||
344 |
3/4✓ Branch 1 taken 40 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 40 times.
✓ Branch 4 taken 20 times.
|
60 | ConfigVector_t q[2]; |
345 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | q[0] = lg.random(); |
346 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | q[1] = lg.random(); |
347 | |||
348 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
|
20 | ConstQuaternionMap_t quat0(q[0].template tail<4>().data()), |
349 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
|
20 | quat1(q[1].template tail<4>().data()); |
350 |
3/4✓ Branch 1 taken 40 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 40 times.
✓ Branch 4 taken 20 times.
|
60 | JacobianMatrix_t J[2]; |
351 | |||
352 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | lg.template dDifference<ARG0>(q[0], q[1], J[0]); |
353 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | lg.template dDifference<ARG1>(q[0], q[1], J[1]); |
354 | |||
355 |
5/10✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 20 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 20 times.
✗ Branch 14 not taken.
|
20 | SE3 om0(typename SE3::Quaternion(q[0].template tail<4>()).matrix(), q[0].template head<3>()), |
356 |
5/10✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 20 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 20 times.
✗ Branch 14 not taken.
|
20 | om1(typename SE3::Quaternion(q[1].template tail<4>()).matrix(), q[1].template head<3>()), |
357 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | _1m2(om1.actInv(om0)); |
358 |
17/34✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 20 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 20 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 20 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 20 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 20 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 20 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 20 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 20 times.
✗ Branch 32 not taken.
✓ Branch 34 taken 20 times.
✗ Branch 35 not taken.
✓ Branch 37 taken 20 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 20 times.
✗ Branch 41 not taken.
✓ Branch 43 taken 20 times.
✗ Branch 44 not taken.
✓ Branch 46 taken 20 times.
✗ Branch 47 not taken.
✓ Branch 49 taken 20 times.
✗ Branch 50 not taken.
✗ Branch 58 not taken.
✓ Branch 59 taken 20 times.
|
20 | EIGEN_MATRIX_IS_APPROX(J[1] * _1m2.toActionMatrix(), -J[0], 1e-8); |
359 | |||
360 | // Test against SE3::Interpolate | ||
361 | 20 | const Scalar u = 0.3; | |
362 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | ConfigVector_t q_interp = lg.interpolate(q[0], q[1], u); |
363 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
|
20 | ConstQuaternionMap_t quat_interp(q_interp.template tail<4>().data()); |
364 | |||
365 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
20 | SE3 M0(quat0, q[0].template head<3>()); |
366 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
20 | SE3 M1(quat1, q[1].template head<3>()); |
367 | |||
368 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | SE3 M_u = SE3::Interpolate(M0, M1, u); |
369 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
20 | SE3 M_interp(quat_interp, q_interp.template head<3>()); |
370 |
7/14✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 20 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 20 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 20 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 20 times.
✗ Branch 21 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 20 times.
|
20 | BOOST_CHECK(M_u.isApprox(M_interp, prec)); |
371 | 20 | } | |
372 | |||
373 | template<typename Scalar, int Options> | ||
374 | 20 | void specificTests(const CartesianProductOperation< | |
375 | VectorSpaceOperationTpl<3, Scalar, Options>, | ||
376 | SpecialOrthogonalOperationTpl<3, Scalar, Options>>) const | ||
377 | { | ||
378 | typedef SE3Tpl<Scalar> SE3; | ||
379 | typedef CartesianProductOperation< | ||
380 | VectorSpaceOperationTpl<3, Scalar, Options>, | ||
381 | SpecialOrthogonalOperationTpl<3, Scalar, Options>> | ||
382 | LG_t; | ||
383 | typedef typename LG_t::ConfigVector_t ConfigVector_t; | ||
384 | typedef typename LG_t::JacobianMatrix_t JacobianMatrix_t; | ||
385 | |||
386 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | LG_t lg; |
387 | |||
388 |
3/4✓ Branch 1 taken 40 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 40 times.
✓ Branch 4 taken 20 times.
|
60 | ConfigVector_t q[2]; |
389 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | q[0] = lg.random(); |
390 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | q[1] = lg.random(); |
391 |
3/4✓ Branch 1 taken 40 times.
✗ Branch 2 not taken.
✓ Branch 3 taken 40 times.
✓ Branch 4 taken 20 times.
|
60 | JacobianMatrix_t J[2]; |
392 | |||
393 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | lg.template dDifference<ARG0>(q[0], q[1], J[0]); |
394 |
1/2✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
|
20 | lg.template dDifference<ARG1>(q[0], q[1], J[1]); |
395 | |||
396 |
3/6✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
|
20 | typename SE3::Matrix3 oR0(typename SE3::Quaternion(q[0].template tail<4>()).matrix()), |
397 |
3/6✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
|
20 | oR1(typename SE3::Quaternion(q[1].template tail<4>()).matrix()); |
398 |
2/4✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
|
20 | JacobianMatrix_t X(JacobianMatrix_t::Identity()); |
399 |
4/8✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 20 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 20 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 20 times.
✗ Branch 11 not taken.
|
20 | X.template bottomRightCorner<3, 3>() = oR1.transpose() * oR0; |
400 |
15/30✓ Branch 1 taken 20 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 20 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 20 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 20 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 20 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 20 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 20 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 20 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 20 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 20 times.
✗ Branch 32 not taken.
✓ Branch 34 taken 20 times.
✗ Branch 35 not taken.
✓ Branch 37 taken 20 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 20 times.
✗ Branch 41 not taken.
✓ Branch 43 taken 20 times.
✗ Branch 44 not taken.
✗ Branch 52 not taken.
✓ Branch 53 taken 20 times.
|
20 | EIGEN_MATRIX_IS_APPROX(J[1] * X, -J[0], 1e-8); |
401 | 20 | } | |
402 | }; | ||
403 | |||
404 | template<bool around_identity> | ||
405 | struct LieGroup_Jintegrate | ||
406 | { | ||
407 | template<typename T> | ||
408 | 336 | void operator()(const T) const | |
409 | { | ||
410 | typedef typename T::ConfigVector_t ConfigVector_t; | ||
411 | typedef typename T::TangentVector_t TangentVector_t; | ||
412 | typedef typename T::JacobianMatrix_t JacobianMatrix_t; | ||
413 | typedef typename T::Scalar Scalar; | ||
414 | |||
415 |
1/2✓ Branch 1 taken 168 times.
✗ Branch 2 not taken.
|
336 | T lg; |
416 |
1/2✓ Branch 1 taken 168 times.
✗ Branch 2 not taken.
|
336 | ConfigVector_t q = lg.random(); |
417 |
3/6✓ Branch 1 taken 168 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 168 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 168 times.
✗ Branch 8 not taken.
|
336 | TangentVector_t v, dq, dv; |
418 | if (around_identity) | ||
419 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | v.setZero(); |
420 | else | ||
421 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | v.setRandom(); |
422 | |||
423 |
1/2✓ Branch 1 taken 168 times.
✗ Branch 2 not taken.
|
336 | dq.setZero(); |
424 |
1/2✓ Branch 1 taken 168 times.
✗ Branch 2 not taken.
|
336 | dv.setZero(); |
425 | |||
426 |
1/2✓ Branch 1 taken 168 times.
✗ Branch 2 not taken.
|
336 | ConfigVector_t q_v = lg.integrate(q, v); |
427 | |||
428 | PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH | ||
429 | PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED | ||
430 |
2/4✓ Branch 1 taken 168 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 168 times.
✗ Branch 5 not taken.
|
336 | JacobianMatrix_t Jq, Jv; |
431 |
1/2✓ Branch 1 taken 168 times.
✗ Branch 2 not taken.
|
336 | lg.dIntegrate_dq(q, v, Jq); |
432 |
1/2✓ Branch 1 taken 168 times.
✗ Branch 2 not taken.
|
336 | lg.dIntegrate_dv(q, v, Jv); |
433 | PINOCCHIO_COMPILER_DIAGNOSTIC_POP | ||
434 | |||
435 | 336 | const Scalar eps = 1e-6; | |
436 |
2/2✓ Branch 1 taken 525 times.
✓ Branch 2 taken 168 times.
|
1386 | for (int i = 0; i < v.size(); ++i) |
437 | { | ||
438 |
2/4✓ Branch 1 taken 525 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 525 times.
✗ Branch 5 not taken.
|
1050 | dq[i] = dv[i] = eps; |
439 |
1/2✓ Branch 1 taken 525 times.
✗ Branch 2 not taken.
|
1050 | ConfigVector_t q_dq = lg.integrate(q, dq); |
440 | |||
441 |
1/2✓ Branch 1 taken 525 times.
✗ Branch 2 not taken.
|
1050 | ConfigVector_t q_dq_v = lg.integrate(q_dq, v); |
442 |
2/4✓ Branch 1 taken 525 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 525 times.
✗ Branch 5 not taken.
|
1050 | TangentVector_t Jq_dq = Jq.col(i); |
443 | // q_dv_v - q_v ~ Jq dv | ||
444 |
3/6✓ Branch 1 taken 525 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 525 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 525 times.
✗ Branch 8 not taken.
|
1050 | TangentVector_t dI_dq = lg.difference(q_v, q_dq_v) / eps; |
445 |
13/26✓ Branch 1 taken 525 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 525 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 525 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 525 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 525 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 525 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 525 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 525 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 525 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 525 times.
✗ Branch 32 not taken.
✓ Branch 34 taken 525 times.
✗ Branch 35 not taken.
✓ Branch 37 taken 525 times.
✗ Branch 38 not taken.
✗ Branch 46 not taken.
✓ Branch 47 taken 525 times.
|
1050 | EIGEN_VECTOR_IS_APPROX(dI_dq, Jq_dq, 1e-2); |
446 | |||
447 |
3/6✓ Branch 1 taken 525 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 525 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 525 times.
✗ Branch 8 not taken.
|
1050 | ConfigVector_t q_v_dv = lg.integrate(q, (v + dv).eval()); |
448 |
2/4✓ Branch 1 taken 525 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 525 times.
✗ Branch 5 not taken.
|
1050 | TangentVector_t Jv_dv = Jv.col(i); |
449 | // q_v_dv - q_v ~ Jv dv | ||
450 |
3/6✓ Branch 1 taken 525 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 525 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 525 times.
✗ Branch 8 not taken.
|
1050 | TangentVector_t dI_dv = lg.difference(q_v, q_v_dv) / eps; |
451 |
13/26✓ Branch 1 taken 525 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 525 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 525 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 525 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 525 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 525 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 525 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 525 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 525 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 525 times.
✗ Branch 32 not taken.
✓ Branch 34 taken 525 times.
✗ Branch 35 not taken.
✓ Branch 37 taken 525 times.
✗ Branch 38 not taken.
✗ Branch 46 not taken.
✓ Branch 47 taken 525 times.
|
1050 | EIGEN_VECTOR_IS_APPROX(dI_dv, Jv_dv, 1e-2); |
452 | |||
453 |
2/4✓ Branch 1 taken 525 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 525 times.
✗ Branch 5 not taken.
|
1050 | dq[i] = dv[i] = 0; |
454 | } | ||
455 | 336 | } | |
456 | }; | ||
457 | |||
458 | struct LieGroup_JintegrateJdifference | ||
459 | { | ||
460 | template<typename T> | ||
461 | 320 | void operator()(const T) const | |
462 | { | ||
463 | typedef typename T::ConfigVector_t ConfigVector_t; | ||
464 | typedef typename T::TangentVector_t TangentVector_t; | ||
465 | typedef typename T::JacobianMatrix_t JacobianMatrix_t; | ||
466 | |||
467 | PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH | ||
468 | PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED | ||
469 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | T lg; |
470 |
6/12✓ Branch 2 taken 160 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 160 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 160 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 160 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 160 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 160 times.
✗ Branch 19 not taken.
|
320 | BOOST_TEST_MESSAGE(lg.name()); |
471 |
2/4✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 160 times.
✗ Branch 6 not taken.
|
320 | ConfigVector_t qa, qb(lg.nq()); |
472 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | qa = lg.random(); |
473 |
1/2✓ Branch 2 taken 160 times.
✗ Branch 3 not taken.
|
320 | TangentVector_t v(lg.nv()); |
474 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | v.setRandom(); |
475 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | lg.integrate(qa, v, qb); |
476 | |||
477 |
2/4✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 160 times.
✗ Branch 5 not taken.
|
320 | JacobianMatrix_t Jd_qb, Ji_v; |
478 | |||
479 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | lg.template dDifference<ARG1>(qa, qb, Jd_qb); |
480 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | lg.template dIntegrate<ARG1>(qa, v, Ji_v); |
481 | PINOCCHIO_COMPILER_DIAGNOSTIC_POP | ||
482 | |||
483 |
17/34✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 160 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 160 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 160 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 160 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 160 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 160 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 160 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 160 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 160 times.
✗ Branch 32 not taken.
✓ Branch 34 taken 160 times.
✗ Branch 35 not taken.
✓ Branch 37 taken 160 times.
✗ Branch 38 not taken.
✓ Branch 40 taken 160 times.
✗ Branch 41 not taken.
✓ Branch 44 taken 160 times.
✗ Branch 45 not taken.
✓ Branch 47 taken 160 times.
✗ Branch 48 not taken.
✓ Branch 50 taken 160 times.
✗ Branch 51 not taken.
✗ Branch 63 not taken.
✓ Branch 64 taken 160 times.
|
320 | BOOST_CHECK_MESSAGE( |
484 | (Jd_qb * Ji_v).isIdentity(), "Jd_qb\n" | ||
485 | << Jd_qb << '\n' | ||
486 | << "* Ji_v\n" | ||
487 | << Ji_v << '\n' | ||
488 | << "!= Identity\n" | ||
489 | << Jd_qb * Ji_v << '\n'); | ||
490 | 320 | } | |
491 | }; | ||
492 | |||
493 | struct LieGroup_dIntegrateTransport | ||
494 | { | ||
495 | template<typename T> | ||
496 | 320 | void operator()(const T) const | |
497 | { | ||
498 | typedef typename T::ConfigVector_t ConfigVector_t; | ||
499 | typedef typename T::TangentVector_t TangentVector_t; | ||
500 | typedef typename T::JacobianMatrix_t JacobianMatrix_t; | ||
501 | |||
502 | PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH | ||
503 | PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED | ||
504 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | T lg; |
505 |
6/12✓ Branch 2 taken 160 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 160 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 160 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 160 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 160 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 160 times.
✗ Branch 19 not taken.
|
320 | BOOST_TEST_MESSAGE(lg.name()); |
506 |
2/4✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 160 times.
✗ Branch 6 not taken.
|
320 | ConfigVector_t qa, qb(lg.nq()); |
507 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | qa = lg.random(); |
508 |
4/8✓ Branch 2 taken 160 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 160 times.
✗ Branch 7 not taken.
✓ Branch 10 taken 160 times.
✗ Branch 11 not taken.
✓ Branch 14 taken 160 times.
✗ Branch 15 not taken.
|
320 | TangentVector_t v(lg.nv()), tvec_at_qb(lg.nv()), tvec_at_qa(lg.nv()), tvec_at_qa_r(lg.nv()); |
509 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | v.setRandom(); |
510 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | lg.integrate(qa, v, qb); |
511 | |||
512 | // transport random tangent vector from q1 to q0 | ||
513 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | tvec_at_qb.setRandom(); |
514 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | lg.dIntegrateTransport(qa, v, tvec_at_qb, tvec_at_qa, ARG0); |
515 | |||
516 | // test reverse direction | ||
517 |
2/4✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 160 times.
✗ Branch 5 not taken.
|
320 | TangentVector_t v_r = -v; // reverse path |
518 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | ConfigVector_t qa_r = lg.integrate(qb, v_r); |
519 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | lg.dIntegrateTransport(qa_r, v_r, tvec_at_qa, tvec_at_qa_r, ARG0); |
520 | |||
521 |
7/14✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 160 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 160 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 160 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 160 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 160 times.
✗ Branch 20 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 160 times.
|
320 | BOOST_CHECK_SMALL((qa - qa_r).norm(), 1e-6); // recover init point on manifold |
522 |
7/14✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 160 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 160 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 160 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 160 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 160 times.
✗ Branch 20 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 160 times.
|
320 | BOOST_CHECK_SMALL((tvec_at_qb - tvec_at_qa_r).norm(), 1e-6); |
523 | |||
524 | // same test for matrix | ||
525 |
1/2✓ Branch 3 taken 160 times.
✗ Branch 4 not taken.
|
320 | JacobianMatrix_t J_at_qa(lg.nv(), lg.nv()); |
526 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | J_at_qa.setRandom(); |
527 |
1/2✓ Branch 3 taken 160 times.
✗ Branch 4 not taken.
|
320 | JacobianMatrix_t J_at_qb(lg.nv(), lg.nv()); |
528 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | lg.dIntegrateTransport(qa, v, J_at_qa, J_at_qb, ARG0); |
529 |
1/2✓ Branch 3 taken 160 times.
✗ Branch 4 not taken.
|
320 | JacobianMatrix_t J_at_qa_r(lg.nv(), lg.nv()); |
530 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | lg.dIntegrateTransport(qa_r, v_r, J_at_qb, J_at_qa_r, ARG0); |
531 | |||
532 |
7/14✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 160 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 160 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 160 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 160 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 160 times.
✗ Branch 20 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 160 times.
|
320 | BOOST_CHECK_SMALL((J_at_qa - J_at_qa_r).norm(), 1e-6); |
533 | 320 | } | |
534 | }; | ||
535 | |||
536 | struct LieGroup_JintegrateCoeffWise | ||
537 | { | ||
538 | template<typename T> | ||
539 | 320 | void operator()(const T) const | |
540 | { | ||
541 | typedef typename T::ConfigVector_t ConfigVector_t; | ||
542 | typedef typename T::TangentVector_t TangentVector_t; | ||
543 | typedef typename T::Scalar Scalar; | ||
544 | |||
545 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | T lg; |
546 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | ConfigVector_t q = lg.random(); |
547 |
2/4✓ Branch 2 taken 160 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 160 times.
✗ Branch 6 not taken.
|
320 | TangentVector_t dv(TangentVector_t::Zero(lg.nv())); |
548 | |||
549 |
6/12✓ Branch 2 taken 160 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 160 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 160 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 160 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 160 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 160 times.
✗ Branch 19 not taken.
|
320 | BOOST_TEST_MESSAGE(lg.name()); |
550 | typedef Eigen::Matrix<Scalar, T::NQ, T::NV> JacobianCoeffs; | ||
551 |
2/4✓ Branch 3 taken 160 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 160 times.
✗ Branch 7 not taken.
|
320 | JacobianCoeffs Jintegrate(JacobianCoeffs::Zero(lg.nq(), lg.nv())); |
552 |
1/2✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
|
320 | lg.integrateCoeffWiseJacobian(q, Jintegrate); |
553 |
2/4✓ Branch 3 taken 160 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 160 times.
✗ Branch 7 not taken.
|
320 | JacobianCoeffs Jintegrate_fd(JacobianCoeffs::Zero(lg.nq(), lg.nv())); |
554 | |||
555 | 320 | const Scalar eps = 1e-8; | |
556 |
2/2✓ Branch 1 taken 500 times.
✓ Branch 2 taken 160 times.
|
1320 | for (int i = 0; i < lg.nv(); ++i) |
557 | { | ||
558 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | dv[i] = eps; |
559 |
2/4✓ Branch 2 taken 500 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 500 times.
✗ Branch 6 not taken.
|
1000 | ConfigVector_t q_next(ConfigVector_t::Zero(lg.nq())); |
560 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | lg.integrate(q, dv, q_next); |
561 |
4/8✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 500 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 500 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 500 times.
✗ Branch 11 not taken.
|
1000 | Jintegrate_fd.col(i) = (q_next - q) / eps; |
562 | |||
563 |
1/2✓ Branch 1 taken 500 times.
✗ Branch 2 not taken.
|
1000 | dv[i] = 0; |
564 | } | ||
565 | |||
566 |
11/22✓ Branch 1 taken 160 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 160 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 160 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 160 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 160 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 160 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 160 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 160 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 160 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 160 times.
✗ Branch 32 not taken.
✗ Branch 40 not taken.
✓ Branch 41 taken 160 times.
|
320 | EIGEN_MATRIX_IS_APPROX(Jintegrate, Jintegrate_fd, sqrt(eps)); |
567 | 320 | } | |
568 | }; | ||
569 | |||
570 | BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) | ||
571 | |||
572 |
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_all) |
573 | { | ||
574 | typedef boost::variant< | ||
575 | JointModelRX, JointModelRY, JointModelRZ, JointModelRevoluteUnaligned, JointModelSpherical, | ||
576 | JointModelSphericalZYX, JointModelPX, JointModelPY, JointModelPZ, JointModelPrismaticUnaligned, | ||
577 | JointModelFreeFlyer, JointModelPlanar, JointModelTranslation, JointModelRUBX, JointModelRUBY, | ||
578 | JointModelRUBZ> | ||
579 | Variant; | ||
580 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int i = 0; i < 20; ++i) |
581 | 40 | boost::mpl::for_each<Variant::types>(TestJoint()); | |
582 | |||
583 | // FIXME JointModelComposite does not work. | ||
584 | // boost::mpl::for_each<JointModelVariant::types>(TestJoint()); | ||
585 | 2 | } | |
586 | |||
587 |
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(Jdifference) |
588 | { | ||
589 | typedef double Scalar; | ||
590 | enum | ||
591 | { | ||
592 | Options = 0 | ||
593 | }; | ||
594 | |||
595 | typedef boost::mpl::vector< | ||
596 | VectorSpaceOperationTpl<1, Scalar, Options>, VectorSpaceOperationTpl<2, Scalar, Options>, | ||
597 | SpecialOrthogonalOperationTpl<2, Scalar, Options>, | ||
598 | SpecialOrthogonalOperationTpl<3, Scalar, Options>, | ||
599 | SpecialEuclideanOperationTpl<2, Scalar, Options>, | ||
600 | SpecialEuclideanOperationTpl<3, Scalar, Options>, | ||
601 | CartesianProductOperation< | ||
602 | VectorSpaceOperationTpl<2, Scalar, Options>, | ||
603 | SpecialOrthogonalOperationTpl<2, Scalar, Options>>, | ||
604 | CartesianProductOperation< | ||
605 | VectorSpaceOperationTpl<3, Scalar, Options>, | ||
606 | SpecialOrthogonalOperationTpl<3, Scalar, Options>>> | ||
607 | Types; | ||
608 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int i = 0; i < 20; ++i) |
609 | 40 | boost::mpl::for_each<Types>(LieGroup_Jdifference()); | |
610 | 2 | } | |
611 | |||
612 |
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(dIntegrateTransport) |
613 | { | ||
614 | typedef double Scalar; | ||
615 | enum | ||
616 | { | ||
617 | Options = 0 | ||
618 | }; | ||
619 | |||
620 | typedef boost::mpl::vector< | ||
621 | VectorSpaceOperationTpl<1, Scalar, Options>, VectorSpaceOperationTpl<2, Scalar, Options>, | ||
622 | SpecialOrthogonalOperationTpl<2, Scalar, Options>, | ||
623 | SpecialOrthogonalOperationTpl<3, Scalar, Options>, | ||
624 | SpecialEuclideanOperationTpl<2, Scalar, Options>, | ||
625 | SpecialEuclideanOperationTpl<3, Scalar, Options>, | ||
626 | CartesianProductOperation< | ||
627 | VectorSpaceOperationTpl<2, Scalar, Options>, | ||
628 | SpecialOrthogonalOperationTpl<2, Scalar, Options>>, | ||
629 | CartesianProductOperation< | ||
630 | VectorSpaceOperationTpl<3, Scalar, Options>, | ||
631 | SpecialOrthogonalOperationTpl<3, Scalar, Options>>> | ||
632 | Types; | ||
633 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int i = 0; i < 20; ++i) |
634 | 40 | boost::mpl::for_each<Types>(LieGroup_dIntegrateTransport()); | |
635 | 2 | } | |
636 | |||
637 |
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(Jintegrate) |
638 | { | ||
639 | typedef double Scalar; | ||
640 | enum | ||
641 | { | ||
642 | Options = 0 | ||
643 | }; | ||
644 | |||
645 | typedef boost::mpl::vector< | ||
646 | VectorSpaceOperationTpl<1, Scalar, Options>, VectorSpaceOperationTpl<2, Scalar, Options>, | ||
647 | SpecialOrthogonalOperationTpl<2, Scalar, Options>, | ||
648 | SpecialOrthogonalOperationTpl<3, Scalar, Options>, | ||
649 | SpecialEuclideanOperationTpl<2, Scalar, Options>, | ||
650 | SpecialEuclideanOperationTpl<3, Scalar, Options>, | ||
651 | CartesianProductOperation< | ||
652 | VectorSpaceOperationTpl<2, Scalar, Options>, | ||
653 | SpecialOrthogonalOperationTpl<2, Scalar, Options>>, | ||
654 | CartesianProductOperation< | ||
655 | VectorSpaceOperationTpl<3, Scalar, Options>, | ||
656 | SpecialOrthogonalOperationTpl<3, Scalar, Options>>> | ||
657 | Types; | ||
658 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int i = 0; i < 20; ++i) |
659 | 40 | boost::mpl::for_each<Types>(LieGroup_Jintegrate<false>()); | |
660 | |||
661 | // Around identity | ||
662 | 2 | boost::mpl::for_each<Types>(LieGroup_Jintegrate<true>()); | |
663 | 2 | } | |
664 | |||
665 |
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(Jintegrate_Jdifference) |
666 | { | ||
667 | typedef double Scalar; | ||
668 | enum | ||
669 | { | ||
670 | Options = 0 | ||
671 | }; | ||
672 | |||
673 | typedef boost::mpl::vector< | ||
674 | VectorSpaceOperationTpl<1, Scalar, Options>, VectorSpaceOperationTpl<2, Scalar, Options>, | ||
675 | SpecialOrthogonalOperationTpl<2, Scalar, Options>, | ||
676 | SpecialOrthogonalOperationTpl<3, Scalar, Options>, | ||
677 | SpecialEuclideanOperationTpl<2, Scalar, Options>, | ||
678 | SpecialEuclideanOperationTpl<3, Scalar, Options>, | ||
679 | CartesianProductOperation< | ||
680 | VectorSpaceOperationTpl<2, Scalar, Options>, | ||
681 | SpecialOrthogonalOperationTpl<2, Scalar, Options>>, | ||
682 | CartesianProductOperation< | ||
683 | VectorSpaceOperationTpl<3, Scalar, Options>, | ||
684 | SpecialOrthogonalOperationTpl<3, Scalar, Options>>> | ||
685 | Types; | ||
686 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int i = 0; i < 20; ++i) |
687 | 40 | boost::mpl::for_each<Types>(LieGroup_JintegrateJdifference()); | |
688 | 2 | } | |
689 | |||
690 |
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(JintegrateCoeffWise) |
691 | { | ||
692 | typedef double Scalar; | ||
693 | enum | ||
694 | { | ||
695 | Options = 0 | ||
696 | }; | ||
697 | |||
698 | typedef boost::mpl::vector< | ||
699 | VectorSpaceOperationTpl<1, Scalar, Options>, VectorSpaceOperationTpl<2, Scalar, Options>, | ||
700 | SpecialOrthogonalOperationTpl<2, Scalar, Options>, | ||
701 | SpecialOrthogonalOperationTpl<3, Scalar, Options>, | ||
702 | SpecialEuclideanOperationTpl<2, Scalar, Options>, | ||
703 | SpecialEuclideanOperationTpl<3, Scalar, Options>, | ||
704 | CartesianProductOperation< | ||
705 | VectorSpaceOperationTpl<2, Scalar, Options>, | ||
706 | SpecialOrthogonalOperationTpl<2, Scalar, Options>>, | ||
707 | CartesianProductOperation< | ||
708 | VectorSpaceOperationTpl<3, Scalar, Options>, | ||
709 | SpecialOrthogonalOperationTpl<3, Scalar, Options>>> | ||
710 | Types; | ||
711 |
2/2✓ Branch 0 taken 20 times.
✓ Branch 1 taken 1 times.
|
42 | for (int i = 0; i < 20; ++i) |
712 | 40 | boost::mpl::for_each<Types>(LieGroup_JintegrateCoeffWise()); | |
713 | |||
714 | { | ||
715 | typedef SpecialEuclideanOperationTpl<3, Scalar, Options> LieGroup; | ||
716 | typedef LieGroup::ConfigVector_t ConfigVector_t; | ||
717 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | LieGroup lg; |
718 | |||
719 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ConfigVector_t q = lg.random(); |
720 | // TangentVector_t dv(TangentVector_t::Zero(lg.nv())); | ||
721 | |||
722 | typedef Eigen::Matrix<Scalar, LieGroup::NQ, LieGroup::NV> JacobianCoeffs; | ||
723 |
2/4✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
|
2 | JacobianCoeffs Jintegrate(JacobianCoeffs::Zero(lg.nq(), lg.nv())); |
724 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | lg.integrateCoeffWiseJacobian(q, Jintegrate); |
725 | } | ||
726 | 2 | } | |
727 | |||
728 |
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_vector_space) |
729 | { | ||
730 | typedef VectorSpaceOperationTpl<3, double> VSO_t; | ||
731 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | VSO_t::ConfigVector_t q, |
732 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | lo(VSO_t::ConfigVector_t::Constant(-std::numeric_limits<double>::infinity())), |
733 | // lo(VSO_t::ConfigVector_t::Constant( 0)), | ||
734 | // up(VSO_t::ConfigVector_t::Constant( std::numeric_limits<double>::infinity())); | ||
735 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | up(VSO_t::ConfigVector_t::Constant(0)); |
736 | |||
737 | 2 | bool error = false; | |
738 | try | ||
739 | { | ||
740 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✗ Branch 4 not taken.
✓ Branch 5 taken 1 times.
|
2 | VSO_t().randomConfiguration(lo, up, q); |
741 | } | ||
742 |
1/2✗ Branch 0 not taken.
✓ Branch 1 taken 1 times.
|
2 | catch (const std::runtime_error &) |
743 | { | ||
744 | 2 | error = true; | |
745 | 2 | } | |
746 |
6/12✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 1 times.
|
2 | BOOST_CHECK_MESSAGE(error, "Random configuration between infinite bounds should return an error"); |
747 | 2 | } | |
748 | |||
749 |
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_size) |
750 | { | ||
751 | // R^1: neutral = [0] | ||
752 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | VectorSpaceOperationTpl<1, double> vs1; |
753 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Eigen::VectorXd neutral; |
754 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.resize(1); |
755 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.setZero(); |
756 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(vs1.nq() == 1); |
757 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(vs1.nv() == 1); |
758 |
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(vs1.name() == "R^1"); |
759 |
8/16✓ 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 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(vs1.neutral() == neutral); |
760 | // R^2: neutral = [0, 0] | ||
761 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | VectorSpaceOperationTpl<2, double> vs2; |
762 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.resize(2); |
763 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.setZero(); |
764 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(vs2.nq() == 2); |
765 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(vs2.nv() == 2); |
766 |
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(vs2.name() == "R^2"); |
767 |
8/16✓ 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 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(vs2.neutral() == neutral); |
768 | // R^3: neutral = [0, 0, 0] | ||
769 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | VectorSpaceOperationTpl<3, double> vs3; |
770 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.resize(3); |
771 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.setZero(); |
772 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(vs3.nq() == 3); |
773 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(vs3.nv() == 3); |
774 |
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(vs3.name() == "R^3"); |
775 |
8/16✓ 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 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(vs3.neutral() == neutral); |
776 | // SO(2): neutral = [1, 0] | ||
777 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SpecialOrthogonalOperationTpl<2, double> so2; |
778 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.resize(2); |
779 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral[0] = 1; |
780 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral[1] = 0; |
781 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(so2.nq() == 2); |
782 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(so2.nv() == 1); |
783 |
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(so2.name() == "SO(2)"); |
784 |
8/16✓ 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 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(so2.neutral() == neutral); |
785 | // SO(3): neutral = [0, 0, 0, 1] | ||
786 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SpecialOrthogonalOperationTpl<3, double> so3; |
787 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.resize(4); |
788 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.setZero(); |
789 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral[3] = 1; |
790 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(so3.nq() == 4); |
791 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(so3.nv() == 3); |
792 |
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(so3.name() == "SO(3)"); |
793 |
8/16✓ 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 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(so3.neutral() == neutral); |
794 | // SE(2): neutral = [0, 0, 1, 0] | ||
795 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SpecialEuclideanOperationTpl<2, double> se2; |
796 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.resize(4); |
797 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.setZero(); |
798 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral[2] = 1; |
799 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(se2.nq() == 4); |
800 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(se2.nv() == 3); |
801 |
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(se2.name() == "SE(2)"); |
802 |
8/16✓ 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 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(se2.neutral() == neutral); |
803 | // SE(3): neutral = [0, 0, 0, 0, 0, 0, 1] | ||
804 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SpecialEuclideanOperationTpl<3, double> se3; |
805 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.resize(7); |
806 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.setZero(); |
807 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral[6] = 1; |
808 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(se3.nq() == 7); |
809 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(se3.nv() == 6); |
810 |
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(se3.name() == "SE(3)"); |
811 |
8/16✓ 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 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(se3.neutral() == neutral); |
812 | // R^2 x SO(2): neutral = [0, 0, 1, 0] | ||
813 | CartesianProductOperation< | ||
814 | VectorSpaceOperationTpl<2, double>, SpecialOrthogonalOperationTpl<2, double>> | ||
815 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | r2xso2; |
816 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.resize(4); |
817 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.setZero(); |
818 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral[2] = 1; |
819 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(r2xso2.nq() == 4); |
820 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(r2xso2.nv() == 3); |
821 |
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(r2xso2.name() == "R^2*SO(2)"); |
822 |
8/16✓ 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 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(r2xso2.neutral() == neutral); |
823 | // R^3 x SO(3): neutral = [0, 0, 0, 0, 0, 0, 1] | ||
824 | CartesianProductOperation< | ||
825 | VectorSpaceOperationTpl<3, double>, SpecialOrthogonalOperationTpl<3, double>> | ||
826 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | r3xso3; |
827 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.resize(7); |
828 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral.setZero(); |
829 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | neutral[6] = 1; |
830 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(r3xso3.nq() == 7); |
831 |
6/12✓ 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 23 not taken.
✓ Branch 24 taken 1 times.
|
2 | BOOST_CHECK(r3xso3.nv() == 6); |
832 |
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 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 27 not taken.
✓ Branch 28 taken 1 times.
|
2 | BOOST_CHECK(r3xso3.name() == "R^3*SO(3)"); |
833 |
8/16✓ 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 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
2 | BOOST_CHECK(r3xso3.neutral() == neutral); |
834 | 2 | } | |
835 | |||
836 |
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_dim_computation) |
837 | { | ||
838 | 2 | int dim = eval_set_dim<1, 1>::value; | |
839 |
5/10✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✗ Branch 20 not taken.
✓ Branch 21 taken 1 times.
|
2 | BOOST_CHECK(dim == 2); |
840 | 2 | dim = eval_set_dim<Eigen::Dynamic, 1>::value; | |
841 |
5/10✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✗ Branch 20 not taken.
✓ Branch 21 taken 1 times.
|
2 | BOOST_CHECK(dim == Eigen::Dynamic); |
842 | 2 | dim = eval_set_dim<1, Eigen::Dynamic>::value; | |
843 |
5/10✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✗ Branch 20 not taken.
✓ Branch 21 taken 1 times.
|
2 | BOOST_CHECK(dim == Eigen::Dynamic); |
844 | 2 | } | |
845 | |||
846 |
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(small_distance_test) |
847 | { | ||
848 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | SpecialOrthogonalOperationTpl<3, double> so3; |
849 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | Eigen::VectorXd q1(so3.nq()); |
850 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | Eigen::VectorXd q2(so3.nq()); |
851 |
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 | q1 << 0, 0, -0.1953711450011105244, 0.9807293794421349169; |
852 |
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 | q2 << 0, 0, -0.19537114500111049664, 0.98072937944213492244; |
853 | |||
854 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 1 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✗ Branch 24 not taken.
✓ Branch 25 taken 1 times.
|
2 | BOOST_CHECK_MESSAGE(so3.distance(q1, q2) > 0., "SO3 small distance - wrong results"); |
855 | 2 | } | |
856 | |||
857 | template<typename LieGroupCollection> | ||
858 | struct TestLieGroupVariantVisitor | ||
859 | { | ||
860 | |||
861 | typedef LieGroupGenericTpl<LieGroupCollection> LieGroupGeneric; | ||
862 | typedef typename LieGroupGeneric::ConfigVector_t ConfigVector_t; | ||
863 | typedef typename LieGroupGeneric::TangentVector_t TangentVector_t; | ||
864 | |||
865 | template<typename Derived> | ||
866 | 16 | void operator()(const LieGroupBase<Derived> & lg) const | |
867 | { | ||
868 |
1/2✓ Branch 2 taken 8 times.
✗ Branch 3 not taken.
|
16 | LieGroupGenericTpl<LieGroupCollection> lg_generic(lg.derived()); |
869 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | test(lg, lg_generic); |
870 | 16 | } | |
871 | |||
872 | template<typename Derived> | ||
873 | static void | ||
874 | 16 | test(const LieGroupBase<Derived> & lg, const LieGroupGenericTpl<LieGroupCollection> & lg_generic) | |
875 | { | ||
876 |
12/21✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 8 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 3 times.
✓ Branch 15 taken 5 times.
✗ Branch 16 not taken.
✓ Branch 17 taken 3 times.
✓ Branch 18 taken 5 times.
✗ Branch 19 not taken.
✓ Branch 20 taken 3 times.
✓ Branch 21 taken 5 times.
✗ Branch 22 not taken.
✓ Branch 23 taken 3 times.
✗ Branch 24 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 5 times.
✗ Branch 28 not taken.
✓ Branch 29 taken 3 times.
|
16 | BOOST_CHECK(lg.nq() == nq(lg_generic)); |
877 |
12/21✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 8 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 1 times.
✓ Branch 15 taken 7 times.
✗ Branch 16 not taken.
✓ Branch 17 taken 1 times.
✓ Branch 18 taken 7 times.
✗ Branch 19 not taken.
✓ Branch 20 taken 1 times.
✓ Branch 21 taken 7 times.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
✗ Branch 24 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 7 times.
✗ Branch 28 not taken.
✓ Branch 29 taken 1 times.
|
16 | BOOST_CHECK(lg.nv() == nv(lg_generic)); |
878 | |||
879 |
8/16✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 8 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 8 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 8 times.
✗ Branch 18 not taken.
✓ Branch 21 taken 8 times.
✗ Branch 22 not taken.
✓ Branch 24 taken 8 times.
✗ Branch 25 not taken.
✗ Branch 31 not taken.
✓ Branch 32 taken 8 times.
|
16 | BOOST_CHECK(lg.name() == name(lg_generic)); |
880 | |||
881 |
10/19✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 8 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 8 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 8 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 8 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 8 times.
✗ Branch 24 not taken.
✓ Branch 26 taken 8 times.
✗ Branch 27 not taken.
✗ Branch 32 not taken.
✓ Branch 33 taken 7 times.
✓ Branch 34 taken 1 times.
|
16 | BOOST_CHECK(lg.neutral() == neutral(lg_generic)); |
882 | |||
883 | typedef typename LieGroupGeneric::ConfigVector_t ConfigVectorGeneric; | ||
884 | typedef typename LieGroupGeneric::TangentVector_t TangentVectorGeneric; | ||
885 | |||
886 |
2/4✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 7 times.
✗ Branch 5 not taken.
|
16 | ConfigVector_t q0 = lg.random(); |
887 |
5/8✓ Branch 1 taken 1 times.
✓ Branch 2 taken 7 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 1 times.
✓ Branch 5 taken 7 times.
✗ Branch 6 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
|
16 | TangentVector_t v = TangentVector_t::Random(lg.nv()); |
888 |
3/5✓ Branch 1 taken 3 times.
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
16 | ConfigVector_t qout_ref(lg.nq()); |
889 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | lg.integrate(q0, v, qout_ref); |
890 | |||
891 |
3/5✓ Branch 1 taken 3 times.
✓ Branch 2 taken 5 times.
✗ Branch 3 not taken.
✓ Branch 4 taken 3 times.
✗ Branch 5 not taken.
|
16 | ConfigVectorGeneric qout(lg.nq()); |
892 |
3/6✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 8 times.
✗ Branch 8 not taken.
|
16 | integrate(lg_generic, ConfigVectorGeneric(q0), TangentVectorGeneric(v), qout); |
893 |
7/14✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 8 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 8 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 8 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 8 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 8 times.
|
16 | BOOST_CHECK(qout.isApprox(qout_ref)); |
894 | |||
895 |
2/4✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8 times.
✗ Branch 5 not taken.
|
16 | ConfigVector_t q1(nq(lg_generic)); |
896 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | random(lg_generic, q1); |
897 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | difference(lg_generic, q0, q1, v); |
898 |
7/14✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 8 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 8 times.
✗ Branch 12 not taken.
✓ Branch 16 taken 8 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 8 times.
✗ Branch 20 not taken.
✗ Branch 23 not taken.
✓ Branch 24 taken 8 times.
|
16 | BOOST_CHECK_EQUAL(lg.distance(q0, q1), distance(lg_generic, q0, q1)); |
899 | |||
900 |
2/4✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8 times.
✗ Branch 5 not taken.
|
16 | ConfigVector_t q2(nq(lg_generic)); |
901 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | random(lg_generic, q2); |
902 |
1/2✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
|
16 | normalize(lg_generic, q2); |
903 |
7/14✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 8 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 8 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 8 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 8 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 8 times.
|
16 | BOOST_CHECK(isNormalized(lg_generic, q2)); |
904 | 16 | } | |
905 | }; | ||
906 | |||
907 |
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_liegroup_variant) |
908 | { | ||
909 | 2 | boost::mpl::for_each<LieGroupCollectionDefault::LieGroupVariant::types>( | |
910 | TestLieGroupVariantVisitor<LieGroupCollectionDefault>()); | ||
911 | 2 | } | |
912 | |||
913 | template<typename Lg1, typename Lg2> | ||
914 | 1 | void test_liegroup_variant_equal(Lg1 lg1, Lg2 lg2) | |
915 | { | ||
916 | typedef LieGroupGenericTpl<LieGroupCollectionDefault> LieGroupGeneric; | ||
917 |
5/10✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 1 times.
|
1 | BOOST_CHECK_EQUAL(LieGroupGeneric(lg1), LieGroupGeneric(lg2)); |
918 | 1 | } | |
919 | |||
920 | template<typename Lg1, typename Lg2> | ||
921 | 1 | void test_liegroup_variant_not_equal(Lg1 lg1, Lg2 lg2) | |
922 | { | ||
923 | typedef LieGroupGenericTpl<LieGroupCollectionDefault> LieGroupGeneric; | ||
924 |
5/10✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 13 taken 1 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
|
1 | BOOST_CHECK_PREDICATE( |
925 | std::not_equal_to<LieGroupGeneric>(), (LieGroupGeneric(lg1))(LieGroupGeneric(lg2))); | ||
926 | 1 | } | |
927 | |||
928 |
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_liegroup_variant_comparison) |
929 | { | ||
930 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | test_liegroup_variant_equal( |
931 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | VectorSpaceOperationTpl<1, double>(), VectorSpaceOperationTpl<Eigen::Dynamic, double>(1)); |
932 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | test_liegroup_variant_not_equal( |
933 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | VectorSpaceOperationTpl<1, double>(), VectorSpaceOperationTpl<Eigen::Dynamic, double>(2)); |
934 | 2 | } | |
935 | |||
936 | BOOST_AUTO_TEST_SUITE_END() | ||
937 |