Directory: | ./ |
---|---|
File: | tests/explicit-relative-transformation.cc |
Date: | 2024-12-13 16:14:03 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 222 | 222 | 100.0% |
Branches: | 678 | 1342 | 50.5% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | // Copyright (c) 2017, Joseph Mirabel | ||
2 | // Authors: Joseph Mirabel (joseph.mirabel@laas.fr) | ||
3 | // | ||
4 | |||
5 | // Redistribution and use in source and binary forms, with or without | ||
6 | // modification, are permitted provided that the following conditions are | ||
7 | // met: | ||
8 | // | ||
9 | // 1. Redistributions of source code must retain the above copyright | ||
10 | // notice, this list of conditions and the following disclaimer. | ||
11 | // | ||
12 | // 2. Redistributions in binary form must reproduce the above copyright | ||
13 | // notice, this list of conditions and the following disclaimer in the | ||
14 | // documentation and/or other materials provided with the distribution. | ||
15 | // | ||
16 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS | ||
17 | // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT | ||
18 | // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR | ||
19 | // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT | ||
20 | // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, | ||
21 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT | ||
22 | // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, | ||
23 | // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY | ||
24 | // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT | ||
25 | // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE | ||
26 | // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH | ||
27 | // DAMAGE. | ||
28 | |||
29 | #define BOOST_TEST_MODULE ExplicitRelativeTransformationTest | ||
30 | #include <../tests/util.hh> | ||
31 | #include <boost/test/included/unit_test.hpp> | ||
32 | #include <pinocchio/fwd.hpp> | ||
33 | |||
34 | // Force benchmark output | ||
35 | #define HPP_ENABLE_BENCHMARK 1 | ||
36 | #include <hpp/constraints/differentiable-function.hh> | ||
37 | #include <hpp/constraints/explicit/relative-pose.hh> | ||
38 | #include <hpp/constraints/generic-transformation.hh> | ||
39 | #include <hpp/constraints/matrix-view.hh> | ||
40 | #include <hpp/core/configuration-shooter/uniform.hh> | ||
41 | #include <hpp/core/fwd.hh> | ||
42 | #include <hpp/pinocchio/configuration.hh> | ||
43 | #include <hpp/pinocchio/joint.hh> | ||
44 | #include <hpp/pinocchio/liegroup.hh> | ||
45 | #include <hpp/pinocchio/simple-device.hh> | ||
46 | #include <hpp/pinocchio/urdf/util.hh> | ||
47 | #include <hpp/util/timer.hh> | ||
48 | |||
49 | using namespace hpp::pinocchio; | ||
50 | using namespace hpp::constraints; | ||
51 | using namespace hpp::core; | ||
52 | |||
53 | #define NB_RANDOM_CONF 2 | ||
54 | |||
55 | const value_type test_precision = 1e-8; | ||
56 | |||
57 | 3 | DevicePtr_t createRobot() { | |
58 | // DevicePtr_t robot = unittest::makeDevice(unittest::HumanoidRomeo, "romeo"); | ||
59 |
2/4✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 3 times.
✗ Branch 6 not taken.
|
6 | DevicePtr_t robot(Device::create("2-objects")); |
60 |
6/12✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 3 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 3 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 3 times.
✗ Branch 14 not taken.
✓ Branch 17 taken 3 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 3 times.
✗ Branch 21 not taken.
|
3 | urdf::loadModel(robot, 0, "obj1/", "freeflyer", |
61 | "file://" DATA_DIR "/empty.urdf", ""); | ||
62 |
2/4✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 3 times.
✗ Branch 7 not taken.
|
3 | robot->rootJoint()->lowerBound(0, -10); |
63 |
2/4✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 3 times.
✗ Branch 7 not taken.
|
3 | robot->rootJoint()->lowerBound(1, -10); |
64 |
2/4✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 3 times.
✗ Branch 7 not taken.
|
3 | robot->rootJoint()->lowerBound(2, -10); |
65 |
2/4✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 3 times.
✗ Branch 7 not taken.
|
3 | robot->rootJoint()->upperBound(0, 10); |
66 |
2/4✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 3 times.
✗ Branch 7 not taken.
|
3 | robot->rootJoint()->upperBound(1, 10); |
67 |
2/4✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 3 times.
✗ Branch 7 not taken.
|
3 | robot->rootJoint()->upperBound(2, 10); |
68 | |||
69 | /// Add a freeflyer at the end. | ||
70 |
6/12✓ Branch 1 taken 3 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 3 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 3 times.
✗ Branch 10 not taken.
✓ Branch 13 taken 3 times.
✗ Branch 14 not taken.
✓ Branch 17 taken 3 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 3 times.
✗ Branch 21 not taken.
|
3 | urdf::loadModel(robot, 0, "obj2/", "freeflyer", |
71 | "file://" DATA_DIR "/empty.urdf", ""); | ||
72 |
2/4✓ Branch 3 taken 3 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 3 times.
✗ Branch 7 not taken.
|
6 | JointPtr_t rj = robot->getJointByName("obj2/root_joint"); |
73 |
1/2✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
|
3 | rj->lowerBound(0, -10); |
74 |
1/2✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
|
3 | rj->lowerBound(1, -10); |
75 |
1/2✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
|
3 | rj->lowerBound(2, -10); |
76 |
1/2✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
|
3 | rj->upperBound(0, 10); |
77 |
1/2✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
|
3 | rj->upperBound(1, 10); |
78 |
1/2✓ Branch 2 taken 3 times.
✗ Branch 3 not taken.
|
3 | rj->upperBound(2, 10); |
79 | |||
80 | 6 | return robot; | |
81 | 3 | } | |
82 | |||
83 | template <typename T> | ||
84 | inline typename T::template NRowsBlockXpr<3>::Type trans( | ||
85 | const Eigen::MatrixBase<T>& j) { | ||
86 | return const_cast<Eigen::MatrixBase<T>&>(j).derived().template topRows<3>(); | ||
87 | } | ||
88 | template <typename T> | ||
89 | inline typename T::template NRowsBlockXpr<3>::Type omega( | ||
90 | const Eigen::MatrixBase<T>& j) { | ||
91 | return const_cast<Eigen::MatrixBase<T>&>(j) | ||
92 | .derived() | ||
93 | .template bottomRows<3>(); | ||
94 | } | ||
95 | |||
96 |
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(two_freeflyers) { |
97 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | DevicePtr_t robot = createRobot(); |
98 |
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 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
|
2 | BOOST_REQUIRE(robot); |
99 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ConfigurationShooterPtr_t cs = configurationShooter::Uniform::create(robot); |
100 | |||
101 |
2/4✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
|
4 | JointPtr_t object2 = robot->getJointByName("obj2/root_joint"); |
102 |
2/4✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
|
4 | JointPtr_t object1 = robot->getJointByName("obj1/root_joint"); |
103 | |||
104 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Transform3s M2inO2(Transform3s::Identity()); |
105 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Transform3s M1inO1(Transform3s::Identity()); |
106 | |||
107 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
6 | ExplicitPtr_t enm(explicit_::RelativePose::create( |
108 | "explicit_relative_transformation", robot, object1, object2, M1inO1, | ||
109 | 6 | M2inO2, 6 * Equality)); | |
110 | 2 | DifferentiableFunctionPtr_t ert(enm->explicitFunction()); | |
111 | |||
112 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
|
2 | Configuration_t q = robot->currentConfiguration(), qrand = cs->shoot(), |
113 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | qout = qrand; |
114 | |||
115 | // Check the output value | ||
116 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | Eigen::RowBlockIndices outConf(enm->outputConf()); |
117 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | Eigen::RowBlockIndices inConf(enm->inputConf()); |
118 | |||
119 | // Compute position of object2 by solving explicit constraints | ||
120 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | LiegroupElement q_obj2(ert->outputSpace()); |
121 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | vector_t q_obj1(inConf.rview(qout).eval()); |
122 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | ert->value(q_obj2, q_obj1); |
123 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | outConf.lview(qout) = q_obj2.vector(); |
124 | |||
125 | // Test that at solution configuration, object2 and robot frames coincide. | ||
126 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | robot->currentConfiguration(qout); |
127 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | robot->computeForwardKinematics(JOINT_POSITION); |
128 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Transform3s diff = M1inO1.inverse() * |
129 |
3/6✓ 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.
|
6 | object1->currentTransformation().inverse() * |
130 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
|
4 | object2->currentTransformation() * M2inO2; |
131 | |||
132 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(diff.isIdentity()); |
133 | |||
134 | // Check Jacobian of implicit numerical constraints by finite difference | ||
135 | // | ||
136 | 2 | value_type dt(1e-5); | |
137 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Configuration_t q0(qout); |
138 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | vector_t v(robot->numberDof()); |
139 |
1/2✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | matrix_t J(6, enm->function().inputDerivativeSize()); |
140 |
1/2✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | LiegroupElement value0(enm->function().outputSpace()), |
141 |
1/2✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | value(enm->function().outputSpace()); |
142 |
3/6✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
|
2 | enm->function().value(value0, q0); |
143 |
3/6✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
|
2 | enm->function().jacobian(J, q0); |
144 |
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 | std::cout << "J=" << std::endl << J << std::endl; |
145 |
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 | std::cout << "q0=" << q0.transpose() << std::endl; |
146 | // First at solution configuration | ||
147 |
2/2✓ Branch 0 taken 12 times.
✓ Branch 1 taken 1 times.
|
26 | for (size_type i = 0; i < 12; ++i) { |
148 | // test canonical basis vectors | ||
149 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
24 | v.setZero(); |
150 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
24 | v[i] = 1; |
151 |
5/10✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 12 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 12 times.
✗ Branch 14 not taken.
|
24 | integrate(robot, q0, dt * v, q); |
152 |
3/6✓ Branch 3 taken 12 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 12 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 12 times.
✗ Branch 10 not taken.
|
24 | enm->function().value(value, q); |
153 |
3/6✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
|
24 | vector_t df((value - value0) / dt); |
154 |
2/4✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
|
24 | vector_t Jdq(J * v); |
155 |
4/8✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 12 times.
✗ Branch 11 not taken.
|
24 | std::cout << "v=" << v.transpose() << std::endl; |
156 |
4/8✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 12 times.
✗ Branch 11 not taken.
|
24 | std::cout << "q=" << q.transpose() << std::endl; |
157 |
4/8✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 12 times.
✗ Branch 11 not taken.
|
24 | std::cout << "df=" << df.transpose() << std::endl; |
158 |
4/8✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 12 times.
✗ Branch 11 not taken.
|
24 | std::cout << "Jdq=" << Jdq.transpose() << std::endl; |
159 |
5/10✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 12 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 12 times.
✗ Branch 14 not taken.
|
48 | std::cout << "||Jdq - df ||=" << (df - Jdq).norm() << std::endl |
160 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
24 | << std::endl; |
161 |
8/16✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 12 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 12 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 12 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 12 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 12 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 12 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 12 times.
|
24 | BOOST_CHECK((df - Jdq).norm() < 1e-4); |
162 | 24 | } | |
163 | // Second at random configurations | ||
164 |
2/2✓ Branch 0 taken 2 times.
✓ Branch 1 taken 1 times.
|
6 | for (size_type i = 0; i < NB_RANDOM_CONF; ++i) { |
165 |
1/2✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
|
4 | q0 = cs->shoot(); |
166 |
3/6✓ Branch 3 taken 2 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 2 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 2 times.
✗ Branch 10 not taken.
|
4 | enm->function().jacobian(J, q0); |
167 |
4/8✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 2 times.
✗ Branch 11 not taken.
|
4 | std::cout << "J=" << std::endl << J << std::endl; |
168 |
4/8✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 2 times.
✗ Branch 11 not taken.
|
4 | std::cout << "q0=" << q0.transpose() << std::endl; |
169 |
3/6✓ Branch 3 taken 2 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 2 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 2 times.
✗ Branch 10 not taken.
|
4 | enm->function().value(value0, q0); |
170 |
3/6✓ Branch 3 taken 2 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 2 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 2 times.
✗ Branch 10 not taken.
|
4 | enm->function().jacobian(J, q0); |
171 |
2/2✓ Branch 0 taken 24 times.
✓ Branch 1 taken 2 times.
|
52 | for (size_type j = 0; j < 12; ++j) { |
172 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
48 | v.setZero(); |
173 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
48 | v[j] = 1; |
174 |
4/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 24 times.
✗ Branch 11 not taken.
|
48 | std::cout << "v=" << v.transpose() << std::endl; |
175 |
5/10✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 24 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 24 times.
✗ Branch 14 not taken.
|
48 | integrate(robot, q0, dt * v, q); |
176 |
4/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 24 times.
✗ Branch 11 not taken.
|
48 | std::cout << "q=" << q.transpose() << std::endl; |
177 |
3/6✓ Branch 3 taken 24 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 24 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 24 times.
✗ Branch 10 not taken.
|
48 | enm->function().value(value, q); |
178 |
3/6✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
|
48 | vector_t df((value - value0) / dt); |
179 |
2/4✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
|
48 | vector_t Jdq(J * v); |
180 |
4/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 24 times.
✗ Branch 11 not taken.
|
48 | std::cout << "df=" << df.transpose() << std::endl; |
181 |
4/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 24 times.
✗ Branch 11 not taken.
|
48 | std::cout << "Jdq=" << Jdq.transpose() << std::endl; |
182 |
5/10✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 24 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 24 times.
✗ Branch 14 not taken.
|
96 | std::cout << "||Jdq - df ||=" << (df - Jdq).norm() << std::endl |
183 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
48 | << std::endl; |
184 |
8/16✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 24 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 24 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 24 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 24 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 24 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 24 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 24 times.
|
48 | BOOST_CHECK((df - Jdq).norm() < 1e-4); |
185 | 48 | } | |
186 |
1/2✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
|
4 | std::cout << std::endl; |
187 | } | ||
188 | 2 | } | |
189 | |||
190 |
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(two_frames_on_freeflyer) { |
191 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | DevicePtr_t robot = createRobot(); |
192 |
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 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
|
2 | BOOST_REQUIRE(robot); |
193 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ConfigurationShooterPtr_t cs = configurationShooter::Uniform::create(robot); |
194 | |||
195 |
2/4✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
|
4 | JointPtr_t object2 = robot->getJointByName("obj2/root_joint"); |
196 |
2/4✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
|
4 | JointPtr_t object1 = robot->getJointByName("obj1/root_joint"); |
197 | |||
198 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Transform3s M2inO2(Transform3s::Random()); |
199 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Transform3s M1inO1(Transform3s::Random()); |
200 | |||
201 |
3/6✓ 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.
|
2 | std::cout << "M2inO2=" << M2inO2 << std::endl; |
202 |
3/6✓ 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.
|
2 | std::cout << "M1inO1=" << M1inO1 << std::endl; |
203 | |||
204 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
6 | ExplicitPtr_t enm(explicit_::RelativePose::create( |
205 | "explicit_relative_transformation", robot, object1, object2, M1inO1, | ||
206 | 6 | M2inO2, 6 * Equality)); | |
207 | 2 | DifferentiableFunctionPtr_t ert(enm->explicitFunction()); | |
208 | |||
209 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
|
2 | Configuration_t q = robot->currentConfiguration(), qrand = cs->shoot(), |
210 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | qout = qrand; |
211 | |||
212 | // Check the output value | ||
213 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | Eigen::RowBlockIndices outConf(enm->outputConf()); |
214 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | Eigen::RowBlockIndices inConf(enm->inputConf()); |
215 | |||
216 | // Compute position of object2 by solving explicit constraints | ||
217 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | LiegroupElement q_obj2(ert->outputSpace()); |
218 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | vector_t q_obj1(inConf.rview(qout).eval()); |
219 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | ert->value(q_obj2, q_obj1); |
220 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | outConf.lview(qout) = q_obj2.vector(); |
221 | |||
222 | // Test that at solution configuration, object2 and robot frames coincide. | ||
223 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | robot->currentConfiguration(qout); |
224 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | robot->computeForwardKinematics(JOINT_POSITION); |
225 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Transform3s diff = M1inO1.inverse() * |
226 |
3/6✓ 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.
|
6 | object1->currentTransformation().inverse() * |
227 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
|
4 | object2->currentTransformation() * M2inO2; |
228 | |||
229 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(diff.isIdentity()); |
230 | |||
231 | // Check Jacobian of implicit numerical constraints by finite difference | ||
232 | // | ||
233 | 2 | value_type dt(1e-5); | |
234 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Configuration_t q0(qout); |
235 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | vector_t v(robot->numberDof()); |
236 |
1/2✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | matrix_t J(6, enm->function().inputDerivativeSize()); |
237 |
1/2✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | LiegroupElement value0(enm->function().outputSpace()), |
238 |
1/2✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | value(enm->function().outputSpace()); |
239 |
3/6✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
|
2 | enm->function().value(value0, q0); |
240 |
3/6✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
|
2 | enm->function().jacobian(J, q0); |
241 |
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 | std::cout << "J=" << std::endl << J << std::endl; |
242 |
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 | std::cout << "q0=" << q0.transpose() << std::endl; |
243 | // First at solution configuration | ||
244 |
2/2✓ Branch 0 taken 12 times.
✓ Branch 1 taken 1 times.
|
26 | for (size_type i = 0; i < 12; ++i) { |
245 | // test canonical basis vectors | ||
246 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
24 | v.setZero(); |
247 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
24 | v[i] = 1; |
248 |
5/10✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 12 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 12 times.
✗ Branch 14 not taken.
|
24 | integrate(robot, q0, dt * v, q); |
249 |
3/6✓ Branch 3 taken 12 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 12 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 12 times.
✗ Branch 10 not taken.
|
24 | enm->function().value(value, q); |
250 |
3/6✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
|
24 | vector_t df((value - value0) / dt); |
251 |
2/4✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
|
24 | vector_t Jdq(J * v); |
252 |
4/8✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 12 times.
✗ Branch 11 not taken.
|
24 | std::cout << "v=" << v.transpose() << std::endl; |
253 |
4/8✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 12 times.
✗ Branch 11 not taken.
|
24 | std::cout << "q=" << q.transpose() << std::endl; |
254 |
4/8✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 12 times.
✗ Branch 11 not taken.
|
24 | std::cout << "df=" << df.transpose() << std::endl; |
255 |
4/8✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 12 times.
✗ Branch 11 not taken.
|
24 | std::cout << "Jdq=" << Jdq.transpose() << std::endl; |
256 |
5/10✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 12 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 12 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 12 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 12 times.
✗ Branch 14 not taken.
|
48 | std::cout << "||Jdq - df ||=" << (df - Jdq).norm() << std::endl |
257 |
1/2✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
|
24 | << std::endl; |
258 |
8/16✓ Branch 1 taken 12 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 12 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 12 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 12 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 12 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 12 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 12 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 12 times.
|
24 | BOOST_CHECK((df - Jdq).norm() < 1e-4); |
259 | 24 | } | |
260 | // Second at random configurations | ||
261 |
2/2✓ Branch 0 taken 2 times.
✓ Branch 1 taken 1 times.
|
6 | for (size_type i = 0; i < NB_RANDOM_CONF; ++i) { |
262 |
1/2✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
|
4 | q0 = cs->shoot(); |
263 |
3/6✓ Branch 3 taken 2 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 2 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 2 times.
✗ Branch 10 not taken.
|
4 | enm->function().jacobian(J, q0); |
264 |
4/8✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 2 times.
✗ Branch 11 not taken.
|
4 | std::cout << "J=" << std::endl << J << std::endl; |
265 |
4/8✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 2 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 2 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 2 times.
✗ Branch 11 not taken.
|
4 | std::cout << "q0=" << q0.transpose() << std::endl; |
266 |
3/6✓ Branch 3 taken 2 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 2 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 2 times.
✗ Branch 10 not taken.
|
4 | enm->function().value(value0, q0); |
267 |
3/6✓ Branch 3 taken 2 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 2 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 2 times.
✗ Branch 10 not taken.
|
4 | enm->function().jacobian(J, q0); |
268 |
2/2✓ Branch 0 taken 24 times.
✓ Branch 1 taken 2 times.
|
52 | for (size_type j = 0; j < 12; ++j) { |
269 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
48 | v.setZero(); |
270 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
48 | v[j] = 1; |
271 |
4/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 24 times.
✗ Branch 11 not taken.
|
48 | std::cout << "v=" << v.transpose() << std::endl; |
272 |
5/10✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 24 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 24 times.
✗ Branch 14 not taken.
|
48 | integrate(robot, q0, dt * v, q); |
273 |
4/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 24 times.
✗ Branch 11 not taken.
|
48 | std::cout << "q=" << q.transpose() << std::endl; |
274 |
3/6✓ Branch 3 taken 24 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 24 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 24 times.
✗ Branch 10 not taken.
|
48 | enm->function().value(value, q); |
275 |
3/6✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
|
48 | vector_t df((value - value0) / dt); |
276 |
2/4✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
|
48 | vector_t Jdq(J * v); |
277 |
4/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 24 times.
✗ Branch 11 not taken.
|
48 | std::cout << "df=" << df.transpose() << std::endl; |
278 |
4/8✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 24 times.
✗ Branch 11 not taken.
|
48 | std::cout << "Jdq=" << Jdq.transpose() << std::endl; |
279 |
5/10✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 24 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 24 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 24 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 24 times.
✗ Branch 14 not taken.
|
96 | std::cout << "||Jdq - df ||=" << (df - Jdq).norm() << std::endl |
280 |
1/2✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
|
48 | << std::endl; |
281 |
8/16✓ Branch 1 taken 24 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 24 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 24 times.
✗ Branch 12 not taken.
✓ Branch 14 taken 24 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 24 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 24 times.
✗ Branch 21 not taken.
✓ Branch 23 taken 24 times.
✗ Branch 24 not taken.
✗ Branch 28 not taken.
✓ Branch 29 taken 24 times.
|
48 | BOOST_CHECK((df - Jdq).norm() < 1e-4); |
282 | 48 | } | |
283 |
1/2✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
|
4 | std::cout << std::endl; |
284 | } | ||
285 | 2 | } | |
286 | |||
287 |
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(compare_to_relative_transform) { |
288 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | DevicePtr_t robot = createRobot(); |
289 |
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 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 22 not taken.
✓ Branch 23 taken 1 times.
|
2 | BOOST_REQUIRE(robot); |
290 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | ConfigurationShooterPtr_t cs = configurationShooter::Uniform::create(robot); |
291 | |||
292 |
2/4✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
|
4 | JointPtr_t object2 = robot->getJointByName("obj2/root_joint"); |
293 |
2/4✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
|
4 | JointPtr_t object1 = robot->getJointByName("obj1/root_joint"); |
294 | |||
295 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Transform3s M2inO2(Transform3s::Random()); |
296 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Transform3s M1inO1(Transform3s::Random()); |
297 | |||
298 |
6/12✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
|
2 | BOOST_TEST_MESSAGE("M2inO2=" << M2inO2); |
299 |
6/12✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
|
2 | BOOST_TEST_MESSAGE("M1inO1=" << M1inO1); |
300 | |||
301 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
6 | ExplicitPtr_t enm(explicit_::RelativePose::create( |
302 | "explicit_relative_transformation", robot, object1, object2, M1inO1, | ||
303 | 6 | M2inO2, 6 * Equality)); | |
304 | 2 | DifferentiableFunctionPtr_t ert(enm->explicitFunction()); | |
305 | 2 | DifferentiableFunctionPtr_t irt = enm->functionPtr(); | |
306 | RelativeTransformationR3xSO3::Ptr_t rt(RelativeTransformationR3xSO3::create( | ||
307 | "relative_transformation_R3xSO3", robot, object1, object2, M1inO1, | ||
308 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
4 | M2inO2)); |
309 | |||
310 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
|
2 | Configuration_t q = robot->currentConfiguration(), qrand = cs->shoot(), |
311 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | qout = qrand; |
312 | |||
313 | // Check the output value | ||
314 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | Eigen::RowBlockIndices outConf(enm->outputConf()); |
315 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | Eigen::RowBlockIndices inConf(enm->inputConf()); |
316 | |||
317 | // Compute position of object2 by solving explicit constraints | ||
318 |
1/2✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
|
2 | LiegroupElement q_obj2(ert->outputSpace()); |
319 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | vector_t q_obj1(inConf.rview(qout).eval()); |
320 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | ert->value(q_obj2, q_obj1); |
321 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | outConf.lview(qout) = q_obj2.vector(); |
322 | |||
323 | // Test that at solution configuration, object2 and robot frames coincide. | ||
324 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
|
2 | robot->currentConfiguration(qout); |
325 |
1/2✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
|
2 | robot->computeForwardKinematics(JOINT_POSITION); |
326 |
2/4✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 1 times.
✗ Branch 5 not taken.
|
2 | Transform3s diff = M1inO1.inverse() * |
327 |
3/6✓ 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.
|
6 | object1->currentTransformation().inverse() * |
328 |
2/4✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
|
4 | object2->currentTransformation() * M2inO2; |
329 | |||
330 |
7/14✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
✓ Branch 15 taken 1 times.
✗ Branch 16 not taken.
✓ Branch 18 taken 1 times.
✗ Branch 19 not taken.
✓ Branch 21 taken 1 times.
✗ Branch 22 not taken.
✗ Branch 26 not taken.
✓ Branch 27 taken 1 times.
|
2 | BOOST_CHECK(diff.isIdentity()); |
331 | |||
332 | // Check that value and Jacobian of relative transform from | ||
333 | // GenericTransformation and from ExplicitRelativeTransformation are equal | ||
334 | |||
335 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 1 times.
|
2 | BOOST_CHECK_EQUAL(irt->inputSize(), rt->inputSize()); |
336 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 1 times.
|
2 | BOOST_CHECK_EQUAL(irt->inputDerivativeSize(), rt->inputDerivativeSize()); |
337 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 1 times.
|
2 | BOOST_CHECK_EQUAL(irt->outputSize(), rt->outputSize()); |
338 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 14 taken 1 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 1 times.
✗ Branch 18 not taken.
✗ Branch 21 not taken.
✓ Branch 22 taken 1 times.
|
2 | BOOST_CHECK_EQUAL(irt->outputDerivativeSize(), rt->outputDerivativeSize()); |
339 |
5/10✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 16 taken 1 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 1 times.
✗ Branch 20 not taken.
✗ Branch 25 not taken.
✓ Branch 26 taken 1 times.
|
2 | BOOST_CHECK_EQUAL(*irt->outputSpace(), *rt->outputSpace()); |
340 | |||
341 |
1/2✓ Branch 1 taken 1 times.
✗ Branch 2 not taken.
|
2 | Configuration_t q0(qout); |
342 |
4/8✓ Branch 3 taken 1 times.
✗ Branch 4 not taken.
✓ Branch 6 taken 1 times.
✗ Branch 7 not taken.
✓ Branch 9 taken 1 times.
✗ Branch 10 not taken.
✓ Branch 12 taken 1 times.
✗ Branch 13 not taken.
|
4 | LiegroupElement v0(rt->outputSpace()), v1(v0), q_out(q_obj2), q_in(q_obj2); |
343 |
2/4✓ Branch 7 taken 1 times.
✗ Branch 8 not taken.
✓ Branch 11 taken 1 times.
✗ Branch 12 not taken.
|
2 | matrix_t J0(rt->outputSpace()->nv(), rt->inputDerivativeSize()), J1(J0); |
344 | |||
345 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | irt->value(v0, q0); |
346 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | irt->jacobian(J0, q0); |
347 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | rt->value(v1, q0); |
348 |
3/6✓ Branch 2 taken 1 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 1 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 1 times.
✗ Branch 9 not taken.
|
2 | rt->jacobian(J1, q0); |
349 | |||
350 |
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 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(log(v0).isZero(test_precision)); |
351 |
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 29 not taken.
✓ Branch 30 taken 1 times.
|
2 | BOOST_CHECK(log(v1).isZero(test_precision)); |
352 |
11/22✓ 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 22 taken 1 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 1 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 1 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 1 times.
✗ Branch 32 not taken.
✗ Branch 40 not taken.
✓ Branch 41 taken 1 times.
|
2 | EIGEN_IS_APPROX(J0, J1, test_precision); |
353 | |||
354 | // Second at random configurations | ||
355 |
2/2✓ Branch 0 taken 2 times.
✓ Branch 1 taken 1 times.
|
6 | for (size_type i = 0; i < NB_RANDOM_CONF; ++i) { |
356 |
1/2✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
|
4 | q0 = cs->shoot(); |
357 | |||
358 |
3/6✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 2 times.
✗ Branch 9 not taken.
|
4 | irt->value(v0, q0); |
359 |
3/6✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 2 times.
✗ Branch 9 not taken.
|
4 | irt->jacobian(J0, q0); |
360 |
3/6✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 2 times.
✗ Branch 9 not taken.
|
4 | rt->value(v1, q0); |
361 |
3/6✓ Branch 2 taken 2 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
✓ Branch 8 taken 2 times.
✗ Branch 9 not taken.
|
4 | rt->jacobian(J1, q0); |
362 |
13/26✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 2 times.
✗ Branch 11 not taken.
✓ Branch 14 taken 2 times.
✗ Branch 15 not taken.
✓ Branch 17 taken 2 times.
✗ Branch 18 not taken.
✓ Branch 20 taken 2 times.
✗ Branch 21 not taken.
✓ Branch 24 taken 2 times.
✗ Branch 25 not taken.
✓ Branch 27 taken 2 times.
✗ Branch 28 not taken.
✓ Branch 30 taken 2 times.
✗ Branch 31 not taken.
✓ Branch 35 taken 2 times.
✗ Branch 36 not taken.
✓ Branch 38 taken 2 times.
✗ Branch 39 not taken.
✓ Branch 41 taken 2 times.
✗ Branch 42 not taken.
✗ Branch 50 not taken.
✓ Branch 51 taken 2 times.
|
4 | EIGEN_VECTOR_IS_APPROX(v0.vector(), v1.vector(), test_precision); |
363 |
11/22✓ Branch 1 taken 2 times.
✗ Branch 2 not taken.
✓ Branch 5 taken 2 times.
✗ Branch 6 not taken.
✓ Branch 10 taken 2 times.
✗ Branch 11 not taken.
✓ Branch 13 taken 2 times.
✗ Branch 14 not taken.
✓ Branch 16 taken 2 times.
✗ Branch 17 not taken.
✓ Branch 19 taken 2 times.
✗ Branch 20 not taken.
✓ Branch 22 taken 2 times.
✗ Branch 23 not taken.
✓ Branch 25 taken 2 times.
✗ Branch 26 not taken.
✓ Branch 28 taken 2 times.
✗ Branch 29 not taken.
✓ Branch 31 taken 2 times.
✗ Branch 32 not taken.
✗ Branch 40 not taken.
✓ Branch 41 taken 2 times.
|
4 | EIGEN_IS_APPROX(J0, J1, test_precision); |
364 | } | ||
365 | 2 | } | |
366 |