6 #include "pinocchio/spatial/explog.hpp" 8 #include <boost/test/unit_test.hpp> 9 #include <boost/utility/binary.hpp> 15 BOOST_AUTO_TEST_SUITE ( BOOST_TEST_MODULE )
23 BOOST_CHECK(R.isApprox(Eigen::AngleAxis<double>(v.
angular().norm(), v.
angular().normalized()).
matrix()));
26 BOOST_CHECK(R0.isIdentity());
30 Motion::Vector3 vec3_nan(Motion::Vector3::Constant(NAN));
32 BOOST_CHECK(R_nan != R_nan);
37 BOOST_CHECK(R.isApprox(M.
rotation()));
41 Motion::Vector6 vec6_nan(Motion::Vector6::Constant(NAN));
43 BOOST_CHECK(M_nan != M_nan);
46 R =
exp3(SE3::Vector3::Zero());
47 BOOST_CHECK(R.isIdentity());
50 Eigen::Quaterniond
quat;
52 BOOST_CHECK(quat.toRotationMatrix().isApprox(M.
rotation()));
55 BOOST_CHECK(quat.toRotationMatrix().isIdentity());
56 BOOST_CHECK(quat.vec().isZero() && quat.coeffs().tail<1>().isOnes());
60 Eigen::QuaternionMapd quat_map(vec4.data());
62 BOOST_CHECK(quat_map.toRotationMatrix().isApprox(M.
rotation()));
71 BOOST_CHECK(omega.isZero());
77 BOOST_CHECK(omega_nan != omega_nan);
85 BOOST_CHECK(omega.isApprox(v.
angular()));
90 Motion::Vector6 v_nan =
log6(mat4_nan);
91 BOOST_CHECK(v_nan != v_nan);
95 Eigen::Quaterniond
quat(SE3::Matrix3::Identity());
97 BOOST_CHECK(omega.isZero());
99 for(
int k = 0; k < 1e3; ++k)
105 BOOST_CHECK(quat.toRotationMatrix().isApprox(rot));
108 const double PI_value = PI<double>();
109 BOOST_CHECK(omega.norm() <= PI_value);
113 BOOST_CHECK(omega.isApprox(omega_ref));
118 Eigen::Vector4d vec4;
119 Eigen::QuaternionMapd quat_map(vec4.data());
128 BOOST_CHECK(M_res.isApprox(M.
rotation()));
130 Motion::Vector3
v; v.setRandom();
131 Motion::Vector3 v_res =
log3(
exp3(v));
132 BOOST_CHECK(v_res.isApprox(v));
138 Eigen::Quaterniond
quat;
140 Eigen::Quaterniond quat_res;
142 BOOST_CHECK(quat_res.isApprox(quat) || quat_res.coeffs().isApprox(-quat.coeffs()));
144 Motion::Vector3
v; v.setRandom();
149 Motion::Vector3 v_est =
log3(M.
rotation().transpose() * R_next);
150 BOOST_CHECK(v_est.isApprox(v));
156 BOOST_CHECK(v_est.isApprox(v));
168 Motion::Vector3 dR; dR.setZero();
169 const double eps = 1e-8;
170 for (
int i = 0;
i < 3; ++
i)
177 BOOST_CHECK(Jfd.isApprox(Jlog, std::sqrt(eps)));
185 Motion::Vector3
v =
log3(
R);
189 Jexp3(Motion::Vector3::Zero(), Jexp);
190 BOOST_CHECK(Jexp.isIdentity());
194 Motion::Vector3 dv; dv.setZero();
195 const double eps = 1e-8;
196 for (
int i = 0;
i < 3; ++
i)
200 Jexp_fd.col(
i) =
log3(
R.transpose()*R_next) / eps;
203 BOOST_CHECK(Jexp_fd.isApprox(Jexp, std::sqrt(eps)));
206 template<
typename QuaternionLike,
typename Matrix43Like>
208 const Eigen::MatrixBase<Matrix43Like> & Jexp)
212 skew(0.5 * quat.vec(),Jout.template topRows<3>());
213 Jout.template topRows<3>().diagonal().array() += 0.5 * quat.w();
214 Jout.template bottomRows<1>() = -0.5 * quat.vec().transpose();
223 typedef Eigen::Matrix<Scalar,4,3> Matrix43;
224 Matrix43
Jexp3, Jexp3_fd;
227 const double eps = 1e-8;
229 for(
int i = 0;
i < 3; ++
i)
233 Jexp3_fd.col(
i) = (quat_plus.coeffs() - quat.coeffs()) / eps;
236 BOOST_CHECK(Jexp3.isApprox(Jexp3_fd,sqrt(eps)));
241 Matrix43 Jexp_quat_local;
245 Matrix43 Jcompositon = Jexp3 * Jlog;
246 BOOST_CHECK(Jcompositon.isApprox(Jexp_quat_local));
255 for(
int i = 0;
i < 3; ++
i)
259 Jexp3_fd.col(
i) = (quat_plus.coeffs() - quat.coeffs()) / eps;
262 BOOST_CHECK(Jexp3.isApprox(Jexp3_fd,sqrt(eps)));
272 const double eps = 1e-8;
274 typedef Eigen::Matrix<double,7,6> Matrix76;
275 Matrix76 Jexp6_fd, Jexp6_quat; Jexp6_quat.setZero();
276 typedef Eigen::Matrix<double,4,3> Matrix43;
280 Jexp6_quat.middleRows<3>(Motion::LINEAR).middleCols<3>(Motion::LINEAR) = M.
rotation();
281 Jexp6_quat.middleRows<4>(Motion::ANGULAR).middleCols<3>(Motion::ANGULAR) = Jexp3_quat;
282 for(
int i = 0;
i < 6; ++
i)
284 dv.toVector()[
i] =
eps;
285 M_next = M *
exp6(dv);
288 Jexp6_fd.middleRows<4>(Motion::ANGULAR).col(
i) = (quat_next.coeffs() -
quat.coeffs())/eps;
289 dv.toVector()[
i] = 0.;
292 BOOST_CHECK(Jexp6_quat.isApprox(Jexp6_fd,sqrt(eps)));
304 BOOST_CHECK((Jlog * Jexp).isIdentity());
312 BOOST_CHECK((Jexp * Jlog).isIdentity());
326 BOOST_CHECK(res.isApprox(res_ref));
337 BOOST_CHECK(v_res.
toVector().isApprox(v.toVector()));
350 for (
int i = 0;
i < 6; ++
i)
358 BOOST_CHECK(Jfd.isApprox(Jlog, sqrt(step)));
368 Ja = - Jlog * (Ma.
inverse() * Mb).toActionMatrixInverse();
375 for (
int i = 0;
i < 6; ++
i)
383 BOOST_CHECK(Jfda.isApprox(Ja, sqrt(step)));
384 BOOST_CHECK(Jfdb.isApprox(Jb, sqrt(step)));
393 Eigen::Matrix<double, 6, 6, Eigen::RowMajor> Jexp, Jlog;
397 BOOST_CHECK((Jlog * Jexp).isIdentity());
404 Eigen::Matrix<double, 6, 6> Jexp, Jlog;
408 BOOST_CHECK((Jexp * Jlog).isIdentity());
417 Matrix3
R (q.matrix());
421 Vector3 dR; dR.setZero();
423 for (
int k = 0; k < 3; ++k)
425 Vector3 e_k (Vector3::Zero());
431 Matrix3 R_dR =
R *
exp3(step * e_k);
432 Matrix3 Jlog_R, Jlog_R_dR;
434 Jlog3(R_dR, Jlog_R_dR);
436 Matrix3 Hlog_e_k_fd = (Jlog_R_dR - Jlog_R ) / step;
438 BOOST_CHECK(Hlog_e_k.isApprox(Hlog_e_k_fd, sqrt(step)));
446 typedef Eigen::Matrix4d Matrix4;
447 typedef pinocchio::Motion::Vector6 Vector6;
452 Vector3 v3(Vector3::Random());
454 BOOST_CHECK(R.transpose().isApprox(R.inverse(),
EPSILON));
455 BOOST_CHECK_SMALL(R.determinant() - 1.0,
EPSILON);
457 BOOST_CHECK(v3.isApprox(v3FromLog, EPSILON));
466 BOOST_CHECK(nu.linear().isApprox(nuFromLog.linear(),
EPSILON));
467 BOOST_CHECK(nu.angular().isApprox(nuFromLog.angular(),
EPSILON));
469 Vector6 v6(Vector6::Random());
476 Vector6 v6FromLog(nu2FromLog.
toVector());
477 BOOST_CHECK(v6.isApprox(v6FromLog, EPSILON));
488 BOOST_CHECK(B_bis.isApprox(B));
491 BOOST_CHECK(A_bis.isApprox(A));
494 BOOST_CHECK(B_bis.isApprox(B));
501 BOOST_AUTO_TEST_SUITE_END()
Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options > log3(const Eigen::MatrixBase< Matrix3Like > &R, typename Matrix3Like::Scalar &theta)
Same as log3.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
BOOST_AUTO_TEST_CASE(exp)
void Jexp3(const Eigen::MatrixBase< Vector3Like > &r, const Eigen::MatrixBase< Matrix3Like > &Jexp)
Derivative of .
bool isApprox(const Derived &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
boost::python::object matrix()
void Jlog3(const Scalar &theta, const Eigen::MatrixBase< Vector3Like > &log, const Eigen::MatrixBase< Matrix3Like > &Jlog)
Derivative of log3.
void Jexp3QuatLocal(const Eigen::QuaternionBase< QuaternionLike > &quat, const Eigen::MatrixBase< Matrix43Like > &Jexp)
void Jlog6(const SE3Tpl< Scalar, Options > &M, const Eigen::MatrixBase< Matrix6Like > &Jlog)
Derivative of log6 where and .
MotionTpl< Scalar, Options > log6(const SE3Tpl< Scalar, Options > &M)
Log: SE3 -> se3.
HomogeneousMatrixType toHomogeneousMatrix() const
void Jlog3(const Eigen::QuaternionBase< QuaternionLike > &quat, const Eigen::MatrixBase< Matrix3Like > &Jlog)
Computes the Jacobian of log3 operator for a unit quaternion.
void Jexp6(const MotionDense< MotionDerived > &nu, const Eigen::MatrixBase< Matrix6Like > &Jexp)
Derivative of exp6 Computed as the inverse of Jlog6.
void exp3(const Eigen::MatrixBase< Vector3Like > &v, Eigen::QuaternionBase< QuaternionLike > &quat_out)
Exp: so3 -> SO3 (quaternion)
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
void Jexp3CoeffWise(const Eigen::MatrixBase< Vector3Like > &v, const Eigen::MatrixBase< Matrix43Like > &Jexp)
Derivative of where is a small perturbation of at identity.
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options > exp3(const Eigen::MatrixBase< Vector3Like > &v)
Exp: so3 -> SO3.
void inverse(const Eigen::MatrixBase< MatrixIn > &m_in, const Eigen::MatrixBase< MatrixOut > &dest)
Eigen::Quaternion< Scalar, Options > Quaternion
Eigen::Matrix< typename QuaternionLike::Scalar, 3, 1, PINOCCHIO_EIGEN_PLAIN_TYPE(typename QuaternionLike::Vector3)::Options > log3(const Eigen::QuaternionBase< QuaternionLike > &quat, typename QuaternionLike::Scalar &theta)
Same as log3 but with a unit quaternion as input.
ConstLinearType linear() const
SE3Tpl inverse() const
aXb = bXa.inverse()
traits< SE3Tpl >::Matrix6 Matrix6
traits< SE3Tpl >::Matrix4 Matrix4
ConstLinearRef translation() const
traits< SE3Tpl >::Vector3 Vector3
void uniformRandom(const Eigen::QuaternionBase< Derived > &q)
Uniformly random quaternion sphere.
Main pinocchio namespace.
ToVectorConstReturnType toVector() const
void Hlog3(const Scalar &theta, const Eigen::MatrixBase< Vector3Like1 > &log, const Eigen::MatrixBase< Vector3Like2 > &v, const Eigen::MatrixBase< Matrix3Like > &vt_Hlog)
void skew(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector, i.e. the antisymmetric matrix representation o...
ConstAngularType angular() const
SE3Tpl< typename MotionDerived::Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(typename MotionDerived::Vector3)::Options > exp6(const MotionDense< MotionDerived > &nu)
Exp: se3 -> SE3.
traits< SE3Tpl >::Matrix3 Matrix3
static MotionTpl Random()
static SE3Tpl Interpolate(const SE3Tpl &A, const SE3Tpl &B, const OtherScalar &alpha)
Linear interpolation on the SE3 manifold.
ConstAngularRef rotation() const