9 #include <boost/test/unit_test.hpp>
10 #include <boost/utility/binary.hpp>
12 #include "utils/macros.hpp"
16 BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE)
26 R.isApprox(Eigen::AngleAxis<double>(
v.angular().norm(),
v.angular().normalized()).matrix()));
29 BOOST_CHECK(R0.isIdentity());
35 BOOST_CHECK(R_nan != R_nan);
40 BOOST_CHECK(
R.isApprox(
M.rotation()));
42 Eigen::Matrix<double, 7, 1>
q0;
43 q0 << 0., 0., 0., 0., 0., 0., 1.;
45 Eigen::Quaterniond quat0(
q.tail<4>());
46 BOOST_CHECK(
R.isApprox(quat0.matrix()));
50 Motion::Vector6 vec6_nan(Motion::Vector6::Constant(NAN));
52 BOOST_CHECK(M_nan != M_nan);
55 R =
exp3(SE3::Vector3::Zero());
56 BOOST_CHECK(
R.isIdentity());
59 Eigen::Quaterniond
quat;
61 BOOST_CHECK(
quat.toRotationMatrix().isApprox(
M.rotation()));
64 BOOST_CHECK(
quat.toRotationMatrix().isIdentity());
65 BOOST_CHECK(
quat.vec().isZero() &&
quat.coeffs().tail<1>().isOnes());
69 Eigen::QuaternionMapd quat_map(vec4.data());
71 BOOST_CHECK(quat_map.toRotationMatrix().isApprox(
M.rotation()));
82 const size_t num_tries = 20;
84 for (
size_t i = 0;
i < num_tries;
i++)
89 R_normed = pinocchio::renormalize_rotation_matrix(R1);
90 BOOST_CHECK((R_normed.transpose() * R_normed).isApprox(Id));
93 tr = R_normed.trace();
94 vals = 2. * R_normed.diagonal().array() - tr + 1.;
102 v.linear().setZero();
105 BOOST_CHECK(omega.isZero());
111 BOOST_CHECK(omega_nan != omega_nan);
115 M.translation().setZero();
118 omega =
log3(
M.rotation());
119 BOOST_CHECK(omega.isApprox(
v.angular()));
124 Motion::Vector6 v_nan =
log6(mat4_nan);
125 BOOST_CHECK(v_nan != v_nan);
129 Eigen::Quaterniond
quat(SE3::Matrix3::Identity());
131 BOOST_CHECK(omega.isZero());
133 for (
int k = 0; k < 1e3; ++k)
140 BOOST_CHECK(
quat.toRotationMatrix().isApprox(rot));
143 const double PI_value = PI<double>();
144 BOOST_CHECK(omega.norm() <= PI_value);
148 BOOST_CHECK(omega.isApprox(omega_ref));
152 Eigen::Vector4d vec4;
153 Eigen::QuaternionMapd quat_map(vec4.data());
162 BOOST_CHECK(M_res.isApprox(
M.rotation()));
167 BOOST_CHECK(v_res.isApprox(
v));
173 Eigen::Quaterniond
quat;
175 Eigen::Quaterniond quat_res;
177 BOOST_CHECK(quat_res.isApprox(
quat) || quat_res.coeffs().isApprox(-
quat.coeffs()));
186 BOOST_CHECK(v_est.isApprox(
v));
192 BOOST_CHECK(v_est.isApprox(
v));
209 const double eps = 1e-8;
210 for (
int i = 0;
i < 3; ++
i)
215 Jfd.col(
i) = (
log3(R_dR_plus) -
log3(R_dR_minus)) / (2 *
eps);
218 BOOST_CHECK(Jfd.isApprox(Jlog, std::sqrt(
eps)));
232 Jexp3(Motion::Vector3::Zero(), Jexp);
233 BOOST_CHECK(Jexp.isIdentity());
240 const double eps = 1e-3;
241 for (
int i = 0;
i < 3; ++
i)
247 Jexp_fd.col(
i) =
log3(Rpn) / (2. *
eps);
250 BOOST_CHECK(Jexp_fd.isApprox(Jexp, std::sqrt(
eps)));
253 template<
typename QuaternionLike,
typename Matrix43Like>
255 const Eigen::QuaternionBase<QuaternionLike> & quat,
const Eigen::MatrixBase<Matrix43Like> & Jexp)
259 skew(0.5 *
quat.vec(), Jout.template topRows<3>());
260 Jout.template topRows<3>().diagonal().array() += 0.5 *
quat.w();
261 Jout.template bottomRows<1>() = -0.5 *
quat.vec().transpose();
272 typedef Eigen::Matrix<Scalar, 4, 3> Matrix43;
275 Matrix43
Jexp3, Jexp3_fd;
280 const double eps = 1e-8;
282 for (
int i = 0;
i < 3; ++
i)
287 Jexp3_fd.col(
i) = (quat_plus.coeffs() -
quat.coeffs()) /
eps;
290 BOOST_CHECK(
Jexp3.isApprox(Jexp3_fd, sqrt(
eps)));
297 Matrix43 Jexp_quat_local;
301 Matrix43 Jcompositon =
Jexp3 * Jlog;
302 BOOST_CHECK(Jcompositon.isApprox(Jexp_quat_local));
311 for (
int i = 0;
i < 3; ++
i)
316 Jexp3_fd.col(
i) = (quat_plus.coeffs() -
quat.coeffs()) /
eps;
319 BOOST_CHECK(
Jexp3.isApprox(Jexp3_fd, sqrt(
eps)));
328 const double eps = 1e-8;
330 typedef Eigen::Matrix<double, 7, 6> Matrix76;
331 Matrix76 Jexp6_fd, Jexp6_quat;
332 Jexp6_quat.setZero();
333 typedef Eigen::Matrix<double, 4, 3> Matrix43;
341 Jexp6_quat.middleRows<3>(Motion::LINEAR).middleCols<3>(Motion::LINEAR) =
M.rotation();
342 Jexp6_quat.middleRows<4>(Motion::ANGULAR).middleCols<3>(Motion::ANGULAR) =
344 for (
int i = 0;
i < 6; ++
i)
349 Jexp6_fd.middleRows<3>(Motion::LINEAR).col(
i) = (M_next.translation() -
M.translation()) /
eps;
350 Jexp6_fd.middleRows<4>(Motion::ANGULAR).col(
i) = (quat_next.coeffs() -
quat.coeffs()) /
eps;
351 dv.toVector()[
i] = 0.;
354 BOOST_CHECK(Jexp6_quat.isApprox(Jexp6_fd, sqrt(
eps)));
363 Eigen::Matrix3d
R(
exp3(
v.angular())), Jexp, Jlog;
368 BOOST_CHECK((Jlog * Jexp).isIdentity());
376 BOOST_CHECK((Jexp * Jlog).isIdentity());
395 BOOST_CHECK(
res.isApprox(res_ref));
402 BOOST_CHECK(M_res.isApprox(
M));
406 BOOST_CHECK(v_res.toVector().isApprox(
v.toVector()));
423 for (
int i = 0;
i < 6; ++
i)
425 dM.toVector()[
i] = step;
427 Jfd.col(
i) = (
log6(M_dM).toVector() -
log6(
M).toVector()) / step;
428 dM.toVector()[
i] = 0;
431 BOOST_CHECK(Jfd.isApprox(Jlog, sqrt(step)));
434 BOOST_CHECK(Jlog2.isApprox(Jlog));
439 for (
size_t i = 0;
i < 15;
i++)
450 SE3 dM(M0.actInv(M0));
456 BOOST_CHECK(J0.isApprox(J_val));
469 BOOST_CHECK(Jexp.isIdentity());
475 const double eps = 1e-8;
476 for (
int i = 0;
i < 6; ++
i)
480 Jexp_fd.col(
i) =
log6(
M.actInv(M_next)).toVector() /
eps;
483 BOOST_CHECK(Jexp_fd.isApprox(Jexp, std::sqrt(
eps)));
486 BOOST_CHECK(Jexp2.isApprox(Jexp));
499 Ja = -Jlog * (Ma.
inverse() * Mb).toActionMatrixInverse();
507 for (
int i = 0;
i < 6; ++
i)
509 dM.toVector()[
i] = step;
514 dM.toVector()[
i] = 0;
517 BOOST_CHECK(Jfda.isApprox(Ja, sqrt(step)));
518 BOOST_CHECK(Jfdb.isApprox(Jb, sqrt(step)));
527 Eigen::Matrix<double, 6, 6, Eigen::RowMajor> Jexp, Jlog;
531 BOOST_CHECK((Jlog * Jexp).isIdentity());
538 Eigen::Matrix<double, 6, 6> Jexp, Jlog;
542 BOOST_CHECK((Jexp * Jlog).isIdentity());
552 Matrix3
R(
q.matrix());
559 for (
int k = 0; k < 3; ++k)
567 Matrix3 R_dR =
R *
exp3(step * e_k);
568 Matrix3 Jlog_R, Jlog_R_dR;
570 Jlog3(R_dR, Jlog_R_dR);
572 Matrix3 Hlog_e_k_fd = (Jlog_R_dR - Jlog_R) / step;
574 BOOST_CHECK(Hlog_e_k.isApprox(Hlog_e_k_fd, sqrt(step)));
582 typedef Eigen::Matrix4d Matrix4;
583 typedef pinocchio::Motion::Vector6 Vector6;
590 BOOST_CHECK(
R.transpose().isApprox(
R.inverse(),
EPSILON));
591 BOOST_CHECK_SMALL(
R.determinant() - 1.0,
EPSILON);
593 BOOST_CHECK(v3.isApprox(v3FromLog,
EPSILON));
598 BOOST_CHECK(
m.rotation().transpose().isApprox(
m.rotation().inverse(),
EPSILON));
599 BOOST_CHECK_SMALL(
m.rotation().determinant() - 1.0,
EPSILON);
601 BOOST_CHECK(nu.linear().isApprox(nuFromLog.linear(),
EPSILON));
602 BOOST_CHECK(nu.angular().isApprox(nuFromLog.angular(),
EPSILON));
604 Vector6 v6(Vector6::Random());
608 Matrix4
M = m2.toHomogeneousMatrix();
610 Vector6 v6FromLog(nu2FromLog.toVector());
611 BOOST_CHECK(v6.isApprox(v6FromLog,
EPSILON));
620 BOOST_CHECK(A_bis.isApprox(
A));
622 BOOST_CHECK(B_bis.isApprox(
B));
625 BOOST_CHECK(A_bis.isApprox(
A));
628 BOOST_CHECK(B_bis.isApprox(
B));
632 BOOST_CHECK(
D.isApprox(
C));
637 const int num_tests = 1e1;
638 for (
int k = 0; k < num_tests; ++k)
643 BOOST_CHECK(
res.isIdentity());
647 BOOST_AUTO_TEST_SUITE_END()