GCC Code Coverage Report | |||||||||||||||||||||
|
|||||||||||||||||||||
Line | Branch | Exec | Source |
1 |
// |
||
2 |
// Copyright (c) 2016-2019 CNRS INRIA |
||
3 |
// Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France. |
||
4 |
// |
||
5 |
|||
6 |
#include "pinocchio/spatial/explog.hpp" |
||
7 |
|||
8 |
#include <boost/test/unit_test.hpp> |
||
9 |
#include <boost/utility/binary.hpp> |
||
10 |
|||
11 |
#include "utils/macros.hpp" |
||
12 |
|||
13 |
using namespace pinocchio; |
||
14 |
|||
15 |
BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE ) |
||
16 |
|||
17 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(exp) |
18 |
{ |
||
19 |
✓✗ | 2 |
SE3 M(SE3::Random()); |
20 |
✓✗✓✗ ✓✗ |
2 |
Motion v(Motion::Random()); v.linear().setZero(); |
21 |
|||
22 |
✓✗✓✗ |
2 |
SE3::Matrix3 R = exp3(v.angular()); |
23 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(R.isApprox(Eigen::AngleAxis<double>(v.angular().norm(), v.angular().normalized()).matrix())); |
24 |
|||
25 |
✓✗✓✗ |
2 |
SE3::Matrix3 R0 = exp3(SE3::Vector3::Zero()); |
26 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(R0.isIdentity()); |
27 |
|||
28 |
// check the NAN case |
||
29 |
#ifdef NDEBUG |
||
30 |
Motion::Vector3 vec3_nan(Motion::Vector3::Constant(NAN)); |
||
31 |
SE3::Matrix3 R_nan = exp3(vec3_nan); |
||
32 |
BOOST_CHECK(R_nan != R_nan); |
||
33 |
#endif |
||
34 |
|||
35 |
✓✗ | 2 |
M = exp6(v); |
36 |
|||
37 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✗✓ |
2 |
BOOST_CHECK(R.isApprox(M.rotation())); |
38 |
|||
39 |
// check the NAN case |
||
40 |
#ifdef NDEBUG |
||
41 |
Motion::Vector6 vec6_nan(Motion::Vector6::Constant(NAN)); |
||
42 |
SE3 M_nan = exp6(vec6_nan); |
||
43 |
BOOST_CHECK(M_nan != M_nan); |
||
44 |
#endif |
||
45 |
|||
46 |
✓✗✓✗ |
2 |
R = exp3(SE3::Vector3::Zero()); |
47 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(R.isIdentity()); |
48 |
|||
49 |
// Quaternion |
||
50 |
✓✗ | 2 |
Eigen::Quaterniond quat; |
51 |
✓✗✓✗ |
2 |
quaternion::exp3(v.angular(),quat); |
52 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(quat.toRotationMatrix().isApprox(M.rotation())); |
53 |
|||
54 |
✓✗✓✗ |
2 |
quaternion::exp3(SE3::Vector3::Zero(),quat); |
55 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✗✓ |
2 |
BOOST_CHECK(quat.toRotationMatrix().isIdentity()); |
56 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✗✓ |
2 |
BOOST_CHECK(quat.vec().isZero() && quat.coeffs().tail<1>().isOnes()); |
57 |
|||
58 |
// Check QuaternionMap |
||
59 |
✓✗ | 2 |
Eigen::Vector4d vec4; |
60 |
✓✗✓✗ |
2 |
Eigen::QuaternionMapd quat_map(vec4.data()); |
61 |
✓✗✓✗ |
2 |
quaternion::exp3(v.angular(),quat_map); |
62 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(quat_map.toRotationMatrix().isApprox(M.rotation())); |
63 |
2 |
} |
|
64 |
|||
65 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(log) |
66 |
{ |
||
67 |
✓✗ | 2 |
SE3 M(SE3::Identity()); |
68 |
✓✗✓✗ ✓✗ |
2 |
Motion v(Motion::Random()); v.linear().setZero(); |
69 |
|||
70 |
✓✗✓✗ |
2 |
SE3::Vector3 omega = log3(M.rotation()); |
71 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(omega.isZero()); |
72 |
|||
73 |
// check the NAN case |
||
74 |
#ifdef NDEBUG |
||
75 |
SE3::Matrix3 mat3_nan(SE3::Matrix3::Constant(NAN)); |
||
76 |
SE3::Vector3 omega_nan = log3(mat3_nan); |
||
77 |
BOOST_CHECK(omega_nan != omega_nan); |
||
78 |
#endif |
||
79 |
|||
80 |
✓✗ | 2 |
M.setRandom(); |
81 |
✓✗✓✗ |
2 |
M.translation().setZero(); |
82 |
|||
83 |
✓✗ | 2 |
v = log6(M); |
84 |
✓✗✓✗ |
2 |
omega = log3(M.rotation()); |
85 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✗✓ |
2 |
BOOST_CHECK(omega.isApprox(v.angular())); |
86 |
|||
87 |
// check the NAN case |
||
88 |
#ifdef NDEBUG |
||
89 |
SE3::Matrix4 mat4_nan(SE3::Matrix4::Constant(NAN)); |
||
90 |
Motion::Vector6 v_nan = log6(mat4_nan); |
||
91 |
BOOST_CHECK(v_nan != v_nan); |
||
92 |
#endif |
||
93 |
|||
94 |
// Quaternion |
||
95 |
✓✗✓✗ |
2 |
Eigen::Quaterniond quat(SE3::Matrix3::Identity()); |
96 |
✓✗ | 2 |
omega = quaternion::log3(quat); |
97 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(omega.isZero()); |
98 |
|||
99 |
✓✓ | 2002 |
for(int k = 0; k < 1e3; ++k) |
100 |
{ |
||
101 |
✓✗✓✗ |
2000 |
SE3::Vector3 w; w.setRandom(); |
102 |
✓✗ | 2000 |
quaternion::exp3(w,quat); |
103 |
✓✗ | 2000 |
SE3::Matrix3 rot = exp3(w); |
104 |
|||
105 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✗✓ |
2000 |
BOOST_CHECK(quat.toRotationMatrix().isApprox(rot)); |
106 |
double theta; |
||
107 |
✓✗ | 2000 |
omega = quaternion::log3(quat,theta); |
108 |
2000 |
const double PI_value = PI<double>(); |
|
109 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2000 |
BOOST_CHECK(omega.norm() <= PI_value); |
110 |
double theta_ref; |
||
111 |
✓✗✓✗ |
2000 |
SE3::Vector3 omega_ref = log3(quat.toRotationMatrix(),theta_ref); |
112 |
|||
113 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2000 |
BOOST_CHECK(omega.isApprox(omega_ref)); |
114 |
} |
||
115 |
|||
116 |
|||
117 |
// Check QuaternionMap |
||
118 |
✓✗ | 2 |
Eigen::Vector4d vec4; |
119 |
✓✗✓✗ |
2 |
Eigen::QuaternionMapd quat_map(vec4.data()); |
120 |
✓✗✓✗ ✓✗ |
2 |
quat_map = SE3::Random().rotation(); |
121 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✗✓ |
2 |
BOOST_CHECK(quaternion::log3(quat_map).isApprox(log3(quat_map.toRotationMatrix()))); |
122 |
2 |
} |
|
123 |
|||
124 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(explog3) |
125 |
{ |
||
126 |
✓✗ | 2 |
SE3 M(SE3::Random()); |
127 |
✓✗✓✗ ✓✗ |
2 |
SE3::Matrix3 M_res = exp3(log3(M.rotation())); |
128 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✗✓ |
2 |
BOOST_CHECK(M_res.isApprox(M.rotation())); |
129 |
|||
130 |
✓✗✓✗ |
2 |
Motion::Vector3 v; v.setRandom(); |
131 |
✓✗✓✗ |
2 |
Motion::Vector3 v_res = log3(exp3(v)); |
132 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(v_res.isApprox(v)); |
133 |
2 |
} |
|
134 |
|||
135 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(explog3_quaternion) |
136 |
{ |
||
137 |
✓✗ | 2 |
SE3 M(SE3::Random()); |
138 |
✓✗ | 2 |
Eigen::Quaterniond quat; |
139 |
✓✗✓✗ |
2 |
quat = M.rotation(); |
140 |
✓✗ | 2 |
Eigen::Quaterniond quat_res; |
141 |
✓✗✓✗ |
2 |
quaternion::exp3(quaternion::log3(quat),quat_res); |
142 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(quat_res.isApprox(quat) || quat_res.coeffs().isApprox(-quat.coeffs())); |
143 |
|||
144 |
✓✗✓✗ |
2 |
Motion::Vector3 v; v.setRandom(); |
145 |
✓✗ | 2 |
quaternion::exp3(v,quat); |
146 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✗✓ |
2 |
BOOST_CHECK(quaternion::log3(quat).isApprox(v)); |
147 |
|||
148 |
✓✗✓✗ ✓✗✓✗ |
2 |
SE3::Matrix3 R_next = M.rotation() * exp3(v); |
149 |
✓✗✓✗ ✓✗✓✗ |
2 |
Motion::Vector3 v_est = log3(M.rotation().transpose() * R_next); |
150 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(v_est.isApprox(v)); |
151 |
|||
152 |
✓✗ | 2 |
SE3::Quaternion quat_v; |
153 |
✓✗ | 2 |
quaternion::exp3(v,quat_v); |
154 |
✓✗ | 2 |
SE3::Quaternion quat_next = quat * quat_v; |
155 |
✓✗✓✗ ✓✗ |
2 |
v_est = quaternion::log3(quat.conjugate() * quat_next); |
156 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(v_est.isApprox(v)); |
157 |
2 |
} |
|
158 |
|||
159 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(Jlog3_fd) |
160 |
{ |
||
161 |
✓✗ | 2 |
SE3 M(SE3::Random()); |
162 |
✓✗✓✗ |
2 |
SE3::Matrix3 R (M.rotation()); |
163 |
|||
164 |
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH |
||
165 |
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED |
||
166 |
✓✗✓✗ |
2 |
SE3::Matrix3 Jfd, Jlog; |
167 |
✓✗ | 2 |
Jlog3 (R, Jlog); |
168 |
PINOCCHIO_COMPILER_DIAGNOSTIC_POP |
||
169 |
✓✗ | 2 |
Jfd.setZero(); |
170 |
|||
171 |
✓✗✓✗ |
2 |
Motion::Vector3 dR; dR.setZero(); |
172 |
2 |
const double eps = 1e-8; |
|
173 |
✓✓ | 8 |
for (int i = 0; i < 3; ++i) |
174 |
{ |
||
175 |
✓✗ | 6 |
dR[i] = eps; |
176 |
✓✗✓✗ ✓✗ |
6 |
SE3::Matrix3 R_dR = R * exp3(dR); |
177 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ |
6 |
Jfd.col(i) = (log3(R_dR) - log3(R)) / eps; |
178 |
✓✗ | 6 |
dR[i] = 0; |
179 |
} |
||
180 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(Jfd.isApprox(Jlog, std::sqrt(eps))); |
181 |
2 |
} |
|
182 |
|||
183 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(Jexp3_fd) |
184 |
{ |
||
185 |
✓✗ | 2 |
SE3 M(SE3::Random()); |
186 |
✓✗✓✗ |
2 |
SE3::Matrix3 R (M.rotation()); |
187 |
|||
188 |
✓✗ | 2 |
Motion::Vector3 v = log3(R); |
189 |
|||
190 |
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH |
||
191 |
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED |
||
192 |
✓✗✓✗ |
2 |
SE3::Matrix3 Jexp_fd, Jexp; |
193 |
|||
194 |
✓✗✓✗ |
2 |
Jexp3(Motion::Vector3::Zero(), Jexp); |
195 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(Jexp.isIdentity()); |
196 |
|||
197 |
✓✗ | 2 |
Jexp3(v, Jexp); |
198 |
PINOCCHIO_COMPILER_DIAGNOSTIC_POP |
||
199 |
|||
200 |
✓✗✓✗ |
2 |
Motion::Vector3 dv; dv.setZero(); |
201 |
2 |
const double eps = 1e-8; |
|
202 |
✓✓ | 8 |
for (int i = 0; i < 3; ++i) |
203 |
{ |
||
204 |
✓✗ | 6 |
dv[i] = eps; |
205 |
✓✗✓✗ |
6 |
SE3::Matrix3 R_next = exp3(v+dv); |
206 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ |
6 |
Jexp_fd.col(i) = log3(R.transpose()*R_next) / eps; |
207 |
✓✗ | 6 |
dv[i] = 0; |
208 |
} |
||
209 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(Jexp_fd.isApprox(Jexp, std::sqrt(eps))); |
210 |
2 |
} |
|
211 |
|||
212 |
template<typename QuaternionLike, typename Matrix43Like> |
||
213 |
2 |
void Jexp3QuatLocal(const Eigen::QuaternionBase<QuaternionLike> & quat, |
|
214 |
const Eigen::MatrixBase<Matrix43Like> & Jexp) |
||
215 |
{ |
||
216 |
2 |
Matrix43Like & Jout = PINOCCHIO_EIGEN_CONST_CAST(Matrix43Like,Jexp); |
|
217 |
|||
218 |
✓✗✓✗ ✓✗ |
2 |
skew(0.5 * quat.vec(),Jout.template topRows<3>()); |
219 |
✓✗✓✗ ✓✗✓✗ |
2 |
Jout.template topRows<3>().diagonal().array() += 0.5 * quat.w(); |
220 |
✓✗✓✗ ✓✗✓✗ |
2 |
Jout.template bottomRows<1>() = -0.5 * quat.vec().transpose(); |
221 |
2 |
} |
|
222 |
|||
223 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(Jexp3_quat_fd) |
224 |
{ |
||
225 |
typedef double Scalar; |
||
226 |
✓✗✓✗ |
2 |
SE3::Vector3 w; w.setRandom(); |
227 |
✓✗✓✗ |
2 |
SE3::Quaternion quat; quaternion::exp3(w,quat); |
228 |
|||
229 |
typedef Eigen::Matrix<Scalar,4,3> Matrix43; |
||
230 |
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH |
||
231 |
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED |
||
232 |
✓✗✓✗ |
2 |
Matrix43 Jexp3, Jexp3_fd; |
233 |
✓✗ | 2 |
quaternion::Jexp3CoeffWise(w,Jexp3); |
234 |
PINOCCHIO_COMPILER_DIAGNOSTIC_POP |
||
235 |
✓✗✓✗ |
2 |
SE3::Vector3 dw; dw.setZero(); |
236 |
2 |
const double eps = 1e-8; |
|
237 |
|||
238 |
✓✓ | 8 |
for(int i = 0; i < 3; ++i) |
239 |
{ |
||
240 |
✓✗ | 6 |
dw[i] = eps; |
241 |
✓✗✓✗ ✓✗ |
6 |
SE3::Quaternion quat_plus; quaternion::exp3(w + dw,quat_plus); |
242 |
✓✗✓✗ ✓✗✓✗ |
6 |
Jexp3_fd.col(i) = (quat_plus.coeffs() - quat.coeffs()) / eps; |
243 |
✓✗ | 6 |
dw[i] = 0; |
244 |
} |
||
245 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(Jexp3.isApprox(Jexp3_fd,sqrt(eps))); |
246 |
|||
247 |
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH |
||
248 |
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED |
||
249 |
✓✗ | 2 |
SE3::Matrix3 Jlog; |
250 |
✓✗✓✗ |
2 |
pinocchio::Jlog3(quat.toRotationMatrix(),Jlog); |
251 |
|||
252 |
✓✗ | 2 |
Matrix43 Jexp_quat_local; |
253 |
✓✗ | 2 |
Jexp3QuatLocal(quat,Jexp_quat_local); |
254 |
PINOCCHIO_COMPILER_DIAGNOSTIC_POP |
||
255 |
|||
256 |
|||
257 |
✓✗✓✗ |
2 |
Matrix43 Jcompositon = Jexp3 * Jlog; |
258 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(Jcompositon.isApprox(Jexp_quat_local)); |
259 |
// std::cout << "Jcompositon\n" << Jcompositon << std::endl; |
||
260 |
// std::cout << "Jexp_quat_local\n" << Jexp_quat_local << std::endl; |
||
261 |
|||
262 |
// Arount zero |
||
263 |
✓✗ | 2 |
w.setZero(); |
264 |
✓✗ | 2 |
w.fill(1e-6); |
265 |
✓✗ | 2 |
quaternion::exp3(w,quat); |
266 |
✓✗ | 2 |
quaternion::Jexp3CoeffWise(w,Jexp3); |
267 |
✓✓ | 8 |
for(int i = 0; i < 3; ++i) |
268 |
{ |
||
269 |
✓✗ | 6 |
dw[i] = eps; |
270 |
✓✗✓✗ ✓✗ |
6 |
SE3::Quaternion quat_plus; quaternion::exp3(w + dw,quat_plus); |
271 |
✓✗✓✗ ✓✗✓✗ |
6 |
Jexp3_fd.col(i) = (quat_plus.coeffs() - quat.coeffs()) / eps; |
272 |
✓✗ | 6 |
dw[i] = 0; |
273 |
} |
||
274 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(Jexp3.isApprox(Jexp3_fd,sqrt(eps))); |
275 |
|||
276 |
2 |
} |
|
277 |
|||
278 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(Jexp3_quat) |
279 |
{ |
||
280 |
✓✗ | 2 |
SE3 M(SE3::Random()); |
281 |
✓✗✓✗ |
2 |
SE3::Quaternion quat(M.rotation()); |
282 |
|||
283 |
✓✗ | 2 |
Motion dv(Motion::Zero()); |
284 |
2 |
const double eps = 1e-8; |
|
285 |
|||
286 |
typedef Eigen::Matrix<double,7,6> Matrix76; |
||
287 |
✓✗✓✗ ✓✗ |
2 |
Matrix76 Jexp6_fd, Jexp6_quat; Jexp6_quat.setZero(); |
288 |
typedef Eigen::Matrix<double,4,3> Matrix43; |
||
289 |
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH |
||
290 |
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED |
||
291 |
✓✗✓✗ |
2 |
Matrix43 Jexp3_quat; Jexp3QuatLocal(quat,Jexp3_quat); |
292 |
PINOCCHIO_COMPILER_DIAGNOSTIC_POP |
||
293 |
✓✗ | 2 |
SE3 M_next; |
294 |
|||
295 |
✓✗✓✗ ✓✗✓✗ |
2 |
Jexp6_quat.middleRows<3>(Motion::LINEAR).middleCols<3>(Motion::LINEAR) = M.rotation(); |
296 |
✓✗✓✗ ✓✗ |
2 |
Jexp6_quat.middleRows<4>(Motion::ANGULAR).middleCols<3>(Motion::ANGULAR) = Jexp3_quat;// * Jlog6_SE3.middleRows<3>(Motion::ANGULAR); |
297 |
✓✓ | 14 |
for(int i = 0; i < 6; ++i) |
298 |
{ |
||
299 |
✓✗✓✗ |
12 |
dv.toVector()[i] = eps; |
300 |
✓✗✓✗ |
12 |
M_next = M * exp6(dv); |
301 |
✓✗✓✗ |
12 |
const SE3::Quaternion quat_next(M_next.rotation()); |
302 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
12 |
Jexp6_fd.middleRows<3>(Motion::LINEAR).col(i) = (M_next.translation() - M.translation())/eps; |
303 |
✓✗✓✗ ✓✗✓✗ ✓✗ |
12 |
Jexp6_fd.middleRows<4>(Motion::ANGULAR).col(i) = (quat_next.coeffs() - quat.coeffs())/eps; |
304 |
✓✗✓✗ |
12 |
dv.toVector()[i] = 0.; |
305 |
} |
||
306 |
|||
307 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(Jexp6_quat.isApprox(Jexp6_fd,sqrt(eps))); |
308 |
2 |
} |
|
309 |
|||
310 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(Jexplog3) |
311 |
{ |
||
312 |
✓✗ | 2 |
Motion v(Motion::Random()); |
313 |
|||
314 |
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH |
||
315 |
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED |
||
316 |
✓✗✓✗ |
2 |
Eigen::Matrix3d R (exp3(v.angular())), |
317 |
✓✗✓✗ |
2 |
Jexp, Jlog; |
318 |
✓✗✓✗ |
2 |
Jexp3 (v.angular(), Jexp); |
319 |
✓✗ | 2 |
Jlog3 (R , Jlog); |
320 |
PINOCCHIO_COMPILER_DIAGNOSTIC_POP |
||
321 |
|||
322 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✗✓ |
2 |
BOOST_CHECK((Jlog * Jexp).isIdentity()); |
323 |
|||
324 |
✓✗ | 2 |
SE3 M(SE3::Random()); |
325 |
✓✗✓✗ |
2 |
R = M.rotation(); |
326 |
✓✗✓✗ ✓✗ |
2 |
v.angular() = log3(R); |
327 |
✓✗ | 2 |
Jlog3 (R , Jlog); |
328 |
✓✗✓✗ |
2 |
Jexp3 (v.angular(), Jexp); |
329 |
|||
330 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✗✓ |
2 |
BOOST_CHECK((Jexp * Jlog).isIdentity()); |
331 |
2 |
} |
|
332 |
|||
333 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(Jlog3_quat) |
334 |
{ |
||
335 |
✓✗✓✗ |
2 |
SE3::Vector3 w; w.setRandom(); |
336 |
✓✗✓✗ |
2 |
SE3::Quaternion quat; quaternion::exp3(w,quat); |
337 |
|||
338 |
✓✗ | 2 |
SE3::Matrix3 R(quat.toRotationMatrix()); |
339 |
|||
340 |
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH |
||
341 |
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED |
||
342 |
✓✗✓✗ |
2 |
SE3::Matrix3 res, res_ref; |
343 |
✓✗ | 2 |
quaternion::Jlog3(quat,res); |
344 |
✓✗ | 2 |
Jlog3(R,res_ref); |
345 |
PINOCCHIO_COMPILER_DIAGNOSTIC_POP |
||
346 |
|||
347 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(res.isApprox(res_ref)); |
348 |
2 |
} |
|
349 |
|||
350 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(explog6) |
351 |
{ |
||
352 |
✓✗ | 2 |
SE3 M(SE3::Random()); |
353 |
✓✗✓✗ |
2 |
SE3 M_res = exp6(log6(M)); |
354 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(M_res.isApprox(M)); |
355 |
|||
356 |
✓✗ | 2 |
Motion v(Motion::Random()); |
357 |
✓✗✓✗ |
2 |
Motion v_res = log6(exp6(v)); |
358 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(v_res.toVector().isApprox(v.toVector())); |
359 |
2 |
} |
|
360 |
|||
361 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(Jlog6_fd) |
362 |
{ |
||
363 |
✓✗ | 2 |
SE3 M(SE3::Random()); |
364 |
|||
365 |
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH |
||
366 |
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED |
||
367 |
✓✗✓✗ |
2 |
SE3::Matrix6 Jfd, Jlog; |
368 |
✓✗ | 2 |
Jlog6 (M, Jlog); |
369 |
PINOCCHIO_COMPILER_DIAGNOSTIC_POP |
||
370 |
✓✗ | 2 |
Jfd.setZero(); |
371 |
|||
372 |
✓✗✓✗ |
2 |
Motion dM; dM.setZero(); |
373 |
2 |
double step = 1e-8; |
|
374 |
✓✓ | 14 |
for (int i = 0; i < 6; ++i) |
375 |
{ |
||
376 |
✓✗✓✗ |
12 |
dM.toVector()[i] = step; |
377 |
✓✗✓✗ |
12 |
SE3 M_dM = M * exp6(dM); |
378 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ |
12 |
Jfd.col(i) = (log6(M_dM).toVector() - log6(M).toVector()) / step; |
379 |
✓✗✓✗ |
12 |
dM.toVector()[i] = 0; |
380 |
} |
||
381 |
|||
382 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(Jfd.isApprox(Jlog, sqrt(step))); |
383 |
2 |
} |
|
384 |
|||
385 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(Jlog6_of_product_fd) |
386 |
{ |
||
387 |
✓✗ | 2 |
SE3 Ma(SE3::Random()); |
388 |
✓✗ | 2 |
SE3 Mb(SE3::Random()); |
389 |
|||
390 |
PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH |
||
391 |
PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED |
||
392 |
✓✗✓✗ ✓✗✓✗ ✓✗ |
2 |
SE3::Matrix6 Jlog, Ja, Jb, Jfda, Jfdb; |
393 |
✓✗✓✗ ✓✗ |
2 |
Jlog6 (Ma.inverse() * Mb, Jlog); |
394 |
PINOCCHIO_COMPILER_DIAGNOSTIC_POP |
||
395 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ |
2 |
Ja = - Jlog * (Ma.inverse() * Mb).toActionMatrixInverse(); |
396 |
✓✗ | 2 |
Jb = Jlog; |
397 |
✓✗ | 2 |
Jfda.setZero(); |
398 |
✓✗ | 2 |
Jfdb.setZero(); |
399 |
|||
400 |
✓✗✓✗ |
2 |
Motion dM; dM.setZero(); |
401 |
2 |
double step = 1e-8; |
|
402 |
✓✓ | 14 |
for (int i = 0; i < 6; ++i) |
403 |
{ |
||
404 |
✓✗✓✗ |
12 |
dM.toVector()[i] = step; |
405 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ |
12 |
Jfda.col(i) = (log6((Ma*exp6(dM)).inverse()*Mb).toVector() - log6(Ma.inverse()*Mb).toVector()) / step; |
406 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ |
12 |
Jfdb.col(i) = (log6(Ma.inverse()*Mb*exp6(dM)).toVector() - log6(Ma.inverse()*Mb).toVector()) / step; |
407 |
✓✗✓✗ |
12 |
dM.toVector()[i] = 0; |
408 |
} |
||
409 |
|||
410 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(Jfda.isApprox(Ja, sqrt(step))); |
411 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(Jfdb.isApprox(Jb, sqrt(step))); |
412 |
2 |
} |
|
413 |
|||
414 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(Jexplog6) |
415 |
{ |
||
416 |
✓✗ | 2 |
Motion v(Motion::Random()); |
417 |
|||
418 |
✓✗ | 2 |
SE3 M (exp6(v)); |
419 |
{ |
||
420 |
✓✗✓✗ |
2 |
Eigen::Matrix<double, 6, 6, Eigen::RowMajor> Jexp, Jlog; |
421 |
✓✗ | 2 |
Jexp6 (v, Jexp); |
422 |
✓✗ | 2 |
Jlog6 (M, Jlog); |
423 |
|||
424 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✗✓ |
2 |
BOOST_CHECK((Jlog * Jexp).isIdentity()); |
425 |
} |
||
426 |
|||
427 |
✓✗ | 2 |
M.setRandom(); |
428 |
|||
429 |
✓✗ | 2 |
v = log6(M); |
430 |
{ |
||
431 |
✓✗✓✗ |
2 |
Eigen::Matrix<double, 6, 6> Jexp, Jlog; |
432 |
✓✗ | 2 |
Jlog6 (M, Jlog); |
433 |
✓✗ | 2 |
Jexp6 (v, Jexp); |
434 |
|||
435 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✗✓ |
2 |
BOOST_CHECK((Jexp * Jlog).isIdentity()); |
436 |
} |
||
437 |
2 |
} |
|
438 |
|||
439 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(Hlog3_fd) |
440 |
{ |
||
441 |
typedef SE3::Vector3 Vector3; |
||
442 |
typedef SE3::Matrix3 Matrix3; |
||
443 |
✓✗✓✗ |
2 |
SE3::Quaternion q; quaternion::uniformRandom(q); |
444 |
✓✗ | 2 |
Matrix3 R (q.matrix()); |
445 |
|||
446 |
// Hlog3(R, v) returns the matrix H * v |
||
447 |
// We check that H * e_k matches the finite difference of Hlog3(R, e_k) |
||
448 |
✓✗✓✗ |
2 |
Vector3 dR; dR.setZero(); |
449 |
2 |
double step = 1e-8; |
|
450 |
✓✓ | 8 |
for (int k = 0; k < 3; ++k) |
451 |
{ |
||
452 |
✓✗✓✗ |
6 |
Vector3 e_k (Vector3::Zero()); |
453 |
✓✗ | 6 |
e_k[k] = 1.; |
454 |
|||
455 |
✓✗ | 6 |
Matrix3 Hlog_e_k; |
456 |
✓✗ | 6 |
Hlog3(R, e_k, Hlog_e_k); |
457 |
|||
458 |
✓✗✓✗ ✓✗✓✗ |
6 |
Matrix3 R_dR = R * exp3(step * e_k); |
459 |
✓✗✓✗ |
6 |
Matrix3 Jlog_R, Jlog_R_dR; |
460 |
✓✗ | 6 |
Jlog3(R, Jlog_R); |
461 |
✓✗ | 6 |
Jlog3(R_dR, Jlog_R_dR); |
462 |
|||
463 |
✓✗✓✗ ✓✗ |
6 |
Matrix3 Hlog_e_k_fd = (Jlog_R_dR - Jlog_R ) / step; |
464 |
|||
465 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
6 |
BOOST_CHECK(Hlog_e_k.isApprox(Hlog_e_k_fd, sqrt(step))); |
466 |
} |
||
467 |
2 |
} |
|
468 |
|||
469 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE (test_basic) |
470 |
{ |
||
471 |
typedef pinocchio::SE3::Vector3 Vector3; |
||
472 |
typedef pinocchio::SE3::Matrix3 Matrix3; |
||
473 |
typedef Eigen::Matrix4d Matrix4; |
||
474 |
typedef pinocchio::Motion::Vector6 Vector6; |
||
475 |
|||
476 |
2 |
const double EPSILON = 1e-12; |
|
477 |
|||
478 |
// exp3 and log3. |
||
479 |
✓✗✓✗ |
2 |
Vector3 v3(Vector3::Random()); |
480 |
✓✗ | 2 |
Matrix3 R(pinocchio::exp3(v3)); |
481 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(R.transpose().isApprox(R.inverse(), EPSILON)); |
482 |
✓✗✓✗ ✓✗✓✗ ✓✗✗✓ |
2 |
BOOST_CHECK_SMALL(R.determinant() - 1.0, EPSILON); |
483 |
✓✗ | 2 |
Vector3 v3FromLog(pinocchio::log3(R)); |
484 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(v3.isApprox(v3FromLog, EPSILON)); |
485 |
|||
486 |
// exp6 and log6. |
||
487 |
✓✗ | 2 |
pinocchio::Motion nu = pinocchio::Motion::Random(); |
488 |
✓✗ | 2 |
pinocchio::SE3 m = pinocchio::exp6(nu); |
489 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(m.rotation().transpose().isApprox(m.rotation().inverse(), |
490 |
EPSILON)); |
||
491 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK_SMALL(m.rotation().determinant() - 1.0, EPSILON); |
492 |
✓✗ | 2 |
pinocchio::Motion nuFromLog(pinocchio::log6(m)); |
493 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(nu.linear().isApprox(nuFromLog.linear(), EPSILON)); |
494 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(nu.angular().isApprox(nuFromLog.angular(), EPSILON)); |
495 |
|||
496 |
✓✗✓✗ |
2 |
Vector6 v6(Vector6::Random()); |
497 |
✓✗ | 2 |
pinocchio::SE3 m2(pinocchio::exp6(v6)); |
498 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(m2.rotation().transpose().isApprox(m2.rotation().inverse(), |
499 |
EPSILON)); |
||
500 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK_SMALL(m2.rotation().determinant() - 1.0, EPSILON); |
501 |
✓✗ | 2 |
Matrix4 M = m2.toHomogeneousMatrix(); |
502 |
✓✗ | 2 |
pinocchio::Motion nu2FromLog(pinocchio::log6(M)); |
503 |
✓✗✓✗ |
2 |
Vector6 v6FromLog(nu2FromLog.toVector()); |
504 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(v6.isApprox(v6FromLog, EPSILON)); |
505 |
2 |
} |
|
506 |
|||
507 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✓✗ |
4 |
BOOST_AUTO_TEST_CASE(test_SE3_interpolate) |
508 |
{ |
||
509 |
✓✗ | 2 |
SE3 A = SE3::Random(); |
510 |
✓✗ | 2 |
SE3 B = SE3::Random(); |
511 |
|||
512 |
✓✗ | 2 |
SE3 A_bis = SE3::Interpolate(A,B,0.); |
513 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(A_bis.isApprox(A)); |
514 |
✓✗ | 2 |
SE3 B_bis = SE3::Interpolate(A,B,1.); |
515 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(B_bis.isApprox(B)); |
516 |
|||
517 |
✓✗ | 2 |
A_bis = SE3::Interpolate(A,A,1.); |
518 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(A_bis.isApprox(A)); |
519 |
|||
520 |
✓✗ | 2 |
B_bis = SE3::Interpolate(B,B,1.); |
521 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(B_bis.isApprox(B)); |
522 |
|||
523 |
✓✗ | 2 |
SE3 C = SE3::Interpolate(A,B,0.5); |
524 |
✓✗ | 2 |
SE3 D = SE3::Interpolate(B,A,0.5); |
525 |
✓✗✓✗ ✓✗✓✗ ✓✗✓✗ ✗✓ |
2 |
BOOST_CHECK(D.isApprox(C)); |
526 |
2 |
} |
|
527 |
|||
528 |
BOOST_AUTO_TEST_SUITE_END() |
Generated by: GCOVR (Version 4.2) |