5 #ifndef __pinocchio_multibody_liegroup_special_euclidean_operation_hpp__
6 #define __pinocchio_multibody_liegroup_special_euclidean_operation_hpp__
24 template<
int Dim,
typename Scalar,
int Options = 0>
29 template<
int Dim,
typename Scalar,
int Options>
34 template<
typename _Scalar,
int _Options>
47 template<
typename _Scalar,
int _Options>
49 :
public LieGroupBase<SpecialEuclideanOperationTpl<2, _Scalar, _Options>>
57 typedef Eigen::Matrix<Scalar, 2, 2, Options>
Matrix2;
58 typedef Eigen::Matrix<Scalar, 2, 1, Options>
Vector2;
60 template<
typename TangentVector,
typename Matrix2Like,
typename Vector2Like>
62 const Eigen::MatrixBase<TangentVector> &
v,
63 const Eigen::MatrixBase<Matrix2Like> & R,
64 const Eigen::MatrixBase<Vector2Like> &
t)
67 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix2Like, 2, 2);
68 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector2Like, 2);
79 vcross -= -
v(1) *
R.col(0) +
v(0) *
R.col(1);
81 Scalar omega_abs = math::fabs(omega);
84 vcross.coeff(0),
v.coeff(0));
88 vcross.coeff(1),
v.coeff(1));
92 template<
typename Matrix2Like,
typename Vector2Like,
typename Matrix3Like>
94 const Eigen::MatrixBase<Matrix2Like> & R,
95 const Eigen::MatrixBase<Vector2Like> &
t,
96 const Eigen::MatrixBase<Matrix3Like> & M,
99 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix2Like, 2, 2);
100 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector2Like, 2);
110 Mout.template topLeftCorner<2, 2>() =
R.transpose();
111 Mout.template topRightCorner<2, 1>() = tinv;
112 Mout.template bottomLeftCorner<1, 2>().setZero();
116 Mout.template topLeftCorner<2, 2>() +=
R.transpose();
117 Mout.template topRightCorner<2, 1>() += tinv;
121 Mout.template topLeftCorner<2, 2>() -=
R.transpose();
122 Mout.template topRightCorner<2, 1>() -= tinv;
126 assert(
false &&
"Wrong Op requesed value");
131 template<
typename Matrix2Like,
typename Vector2Like,
typename TangentVector>
133 const Eigen::MatrixBase<Matrix2Like> & R,
134 const Eigen::MatrixBase<Vector2Like> &
p,
135 const Eigen::MatrixBase<TangentVector> &
v)
137 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix2Like, 2, 2);
138 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector2Like, 2);
146 const Scalar1 tabs = math::fabs(
t);
147 const Scalar1
t2 =
t *
t;
154 static_cast<Scalar>(tabs * st / (2 * (1 - ct))));
156 vout.template head<2>().noalias() =
alpha *
p;
157 vout(0) +=
t / 2 *
p(1);
158 vout(1) += -
t / 2 *
p(0);
162 template<
typename Matrix2Like,
typename Vector2Like,
typename JacobianOutLike>
164 const Eigen::MatrixBase<Matrix2Like> & R,
165 const Eigen::MatrixBase<Vector2Like> &
p,
166 const Eigen::MatrixBase<JacobianOutLike> &
J)
168 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix2Like, 2, 2);
169 EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector2Like, 2);
177 const Scalar1 tabs = math::fabs(
t);
178 Scalar1
alpha, alpha_dot;
182 Scalar1 inv_2_1_ct = 0.5 / (1 - ct);
186 static_cast<Scalar>(
t * st * inv_2_1_ct));
189 static_cast<Scalar>((st -
t) * inv_2_1_ct));
196 Jout.template topLeftCorner<2, 2>().noalias() =
V *
R;
197 Jout.template topRightCorner<2, 1>() << alpha_dot *
p[0] +
p[1] / 2,
198 -
p(0) / 2 + alpha_dot *
p(1);
199 Jout.template bottomLeftCorner<1, 2>().setZero();
226 return std::string(
"SE(2)");
229 template<
class ConfigL_t,
class ConfigR_t,
class Tangent_t>
231 const Eigen::MatrixBase<ConfigL_t> &
q0,
232 const Eigen::MatrixBase<ConfigR_t> &
q1,
233 const Eigen::MatrixBase<Tangent_t> &
d)
243 Vector2 t(R0.transpose() * (t1 - t0));
248 template<ArgumentPosition arg,
class ConfigL_t,
class ConfigR_t,
class JacobianOut_t>
250 const Eigen::MatrixBase<ConfigL_t> &
q0,
251 const Eigen::MatrixBase<ConfigR_t> &
q1,
252 const Eigen::MatrixBase<JacobianOut_t> &
J)
const
262 Vector2 t(R0.transpose() * (t1 - t0));
276 J0.template topLeftCorner<2, 2>().noalias() = -
R.transpose();
277 J0.template topRightCorner<2, 1>().noalias() = R1.transpose() * pcross;
278 J0.template bottomLeftCorner<1, 2>().setZero();
280 J0.applyOnTheLeft(J1);
282 else if (arg ==
ARG1)
288 template<
class ConfigIn_t,
class Velocity_t,
class ConfigOut_t>
290 const Eigen::MatrixBase<ConfigIn_t> &
q,
291 const Eigen::MatrixBase<Velocity_t> &
v,
292 const Eigen::MatrixBase<ConfigOut_t> &
qout)
304 out.template head<2>().noalias() = R0 *
t + t0;
305 out.template tail<2>().noalias() = R0 *
R.col(0);
308 template<
class Config_t,
class Jacobian_t>
310 const Eigen::MatrixBase<Config_t> &
q,
const Eigen::MatrixBase<Jacobian_t> &
J)
312 assert(
J.rows() ==
nq() &&
J.cols() ==
nv() &&
"J is not of the right dimension");
319 Jout.template topLeftCorner<2, 2>() << c_theta, -s_theta, s_theta, c_theta;
320 Jout.template bottomRightCorner<2, 1>() << -s_theta, c_theta;
323 template<
class Config_t,
class Tangent_t,
class JacobianOut_t>
325 const Eigen::MatrixBase<Config_t> & ,
326 const Eigen::MatrixBase<Tangent_t> &
v,
327 const Eigen::MatrixBase<JacobianOut_t> &
J,
339 toInverseActionMatrix(
R,
t, Jout, op);
342 template<
class Config_t,
class Tangent_t,
class JacobianOut_t>
344 const Eigen::MatrixBase<Config_t> & ,
345 const Eigen::MatrixBase<Tangent_t> &
v,
346 const Eigen::MatrixBase<JacobianOut_t> &
J,
352 nu.toVector() <<
v.template head<2>(), 0, 0, 0,
v[2];
355 Eigen::Matrix<Scalar, 6, 6> Jtmp6;
362 Jout << Jtmp6.template topLeftCorner<2, 2>(), Jtmp6.template topRightCorner<2, 1>(),
363 Jtmp6.template bottomLeftCorner<1, 2>(), Jtmp6.template bottomRightCorner<1, 1>();
366 Jout.template topLeftCorner<2, 2>() += Jtmp6.template topLeftCorner<2, 2>();
367 Jout.template topRightCorner<2, 1>() += Jtmp6.template topRightCorner<2, 1>();
368 Jout.template bottomLeftCorner<1, 2>() += Jtmp6.template bottomLeftCorner<1, 2>();
369 Jout.template bottomRightCorner<1, 1>() += Jtmp6.template bottomRightCorner<1, 1>();
372 Jout.template topLeftCorner<2, 2>() -= Jtmp6.template topLeftCorner<2, 2>();
373 Jout.template topRightCorner<2, 1>() -= Jtmp6.template topRightCorner<2, 1>();
374 Jout.template bottomLeftCorner<1, 2>() -= Jtmp6.template bottomLeftCorner<1, 2>();
375 Jout.template bottomRightCorner<1, 1>() -= Jtmp6.template bottomRightCorner<1, 1>();
378 assert(
false &&
"Wrong Op requesed value");
383 template<
class Config_t,
class Tangent_t,
class JacobianIn_t,
class JacobianOut_t>
385 const Eigen::MatrixBase<Config_t> & ,
386 const Eigen::MatrixBase<Tangent_t> &
v,
387 const Eigen::MatrixBase<JacobianIn_t> & Jin,
388 const Eigen::MatrixBase<JacobianOut_t> & J_out)
398 Vector2 tinv = (
R.transpose() *
t).reverse();
401 Jout.template topRows<2>().noalias() =
R.transpose() * Jin.template topRows<2>();
402 Jout.template topRows<2>().noalias() += tinv * Jin.template bottomRows<1>();
403 Jout.template bottomRows<1>() = Jin.template bottomRows<1>();
406 template<
class Config_t,
class Tangent_t,
class JacobianIn_t,
class JacobianOut_t>
408 const Eigen::MatrixBase<Config_t> & ,
409 const Eigen::MatrixBase<Tangent_t> &
v,
410 const Eigen::MatrixBase<JacobianIn_t> & Jin,
411 const Eigen::MatrixBase<JacobianOut_t> & J_out)
415 nu.toVector() <<
v.template head<2>(), 0, 0, 0,
v[2];
419 Eigen::Matrix<Scalar, 6, 6> Jtmp6;
423 Jout.template topRows<2>().noalias() =
424 Jtmp6.template topLeftCorner<2, 2>() * Jin.template topRows<2>();
425 Jout.template topRows<2>().noalias() +=
426 Jtmp6.template topRightCorner<2, 1>() * Jin.template bottomRows<1>();
427 Jout.template bottomRows<1>().noalias() =
428 Jtmp6.template bottomLeftCorner<1, 2>() * Jin.template topRows<2>();
429 Jout.template bottomRows<1>().noalias() +=
430 Jtmp6.template bottomRightCorner<1, 1>() * Jin.template bottomRows<1>();
433 template<
class Config_t,
class Tangent_t,
class Jacobian_t>
435 const Eigen::MatrixBase<Config_t> & ,
436 const Eigen::MatrixBase<Tangent_t> &
v,
437 const Eigen::MatrixBase<Jacobian_t> &
J)
447 Vector2 tinv = (
R.transpose() *
t).reverse();
450 Jout.template topRows<2>() =
R.transpose() * Jout.template topRows<2>();
452 Jout.template topRows<2>().noalias() += tinv * Jout.template bottomRows<1>();
455 template<
class Config_t,
class Tangent_t,
class Jacobian_t>
457 const Eigen::MatrixBase<Config_t> & ,
458 const Eigen::MatrixBase<Tangent_t> &
v,
459 const Eigen::MatrixBase<Jacobian_t> &
J)
463 nu.toVector() <<
v.template head<2>(), 0, 0, 0,
v[2];
467 Eigen::Matrix<Scalar, 6, 6> Jtmp6;
471 Jout.template topRows<2>() =
472 Jtmp6.template topLeftCorner<2, 2>() * Jout.template topRows<2>();
473 Jout.template topRows<2>().noalias() +=
474 Jtmp6.template topRightCorner<2, 1>() * Jout.template bottomRows<1>();
475 Jout.template bottomRows<1>() =
476 Jtmp6.template bottomRightCorner<1, 1>() * Jout.template bottomRows<1>();
477 Jout.template bottomRows<1>().noalias() +=
478 Jtmp6.template bottomLeftCorner<1, 2>() * Jout.template topRows<2>();
481 template<
class Config_t>
487 template<
class Config_t>
492 return abs(norm -
Scalar(1.0)) < prec;
495 template<
class Config_t>
501 template<
class ConfigL_t,
class ConfigR_t,
class ConfigOut_t>
503 const Eigen::MatrixBase<ConfigL_t> & lower,
504 const Eigen::MatrixBase<ConfigR_t> & upper,
505 const Eigen::MatrixBase<ConfigOut_t> &
qout)
510 template<
class ConfigL_t,
class ConfigR_t>
512 const Eigen::MatrixBase<ConfigL_t> &
q0,
513 const Eigen::MatrixBase<ConfigR_t> &
q1,
520 template<
typename Matrix2Like,
typename Vector2Like,
typename Vector4Like>
522 const Eigen::MatrixBase<Matrix2Like> & R,
523 const Eigen::MatrixBase<Vector2Like> &
t,
524 const Eigen::MatrixBase<Vector4Like> &
q)
526 EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Matrix2Like,
Matrix2);
527 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Vector2Like,
Vector2);
528 EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(
ConfigVector_t, Vector4Like);
536 template<
typename _Scalar,
int _Options>
549 template<
typename _Scalar,
int _Options>
551 :
public LieGroupBase<SpecialEuclideanOperationTpl<3, _Scalar, _Options>>
584 n.template head<6>().setZero();
591 return std::string(
"SE(3)");
594 template<
class ConfigL_t,
class ConfigR_t,
class Tangent_t>
596 const Eigen::MatrixBase<ConfigL_t> &
q0,
597 const Eigen::MatrixBase<ConfigR_t> &
q1,
598 const Eigen::MatrixBase<Tangent_t> &
d)
609 const Vector3 dv_pre =
q1.derived().template head<3>() -
q0.derived().template head<3>();
610 const Vector3 dv = quat0.conjugate() * dv_pre;
612 log6(quat0.conjugate() * quat1,
dv).toVector();
617 template<ArgumentPosition arg,
class ConfigL_t,
class ConfigR_t,
class JacobianOut_t>
619 const Eigen::MatrixBase<ConfigL_t> &
q0,
620 const Eigen::MatrixBase<ConfigR_t> &
q1,
621 const Eigen::MatrixBase<JacobianOut_t> &
J)
632 const Vector3 dv_pre =
q1.derived().template head<3>() -
q0.derived().template head<3>();
633 const Vector3 trans = quat0.conjugate() * dv_pre;
635 const Quaternion_t quat_diff = quat0.conjugate() * quat1;
637 const SE3 M(quat_diff, trans);
647 const Vector3 p1_p0 = quat1.conjugate() * dv_pre;
650 J0.template bottomRightCorner<3, 3>() = J0.template topLeftCorner<3, 3>() =
651 -
M.rotation().transpose();
652 J0.template topRightCorner<3, 3>().noalias() =
653 skew(p1_p0) *
M.rotation().transpose();
654 J0.template bottomLeftCorner<3, 3>().setZero();
655 J0.applyOnTheLeft(J1);
657 else if (arg ==
ARG1)
663 template<
class ConfigIn_t,
class Velocity_t,
class ConfigOut_t>
665 const Eigen::MatrixBase<ConfigIn_t> &
q,
666 const Eigen::MatrixBase<Velocity_t> &
v,
667 const Eigen::MatrixBase<ConfigOut_t> &
qout)
683 Eigen::Matrix<Scalar, 7, 1, Options> expv;
686 out.template head<3>() = (
quat * expv.template head<3>()) +
q.derived().template head<3>();
689 res_quat =
quat * quat1;
691 const Scalar dot_product = res_quat.dot(
quat);
692 for (Eigen::DenseIndex k = 0; k < 4; ++k)
696 res_quat.coeffs().coeff(k));
707 template<
class Config_t,
class Jacobian_t>
709 const Eigen::MatrixBase<Config_t> &
q,
const Eigen::MatrixBase<Jacobian_t> &
J)
711 assert(
J.rows() ==
nq() &&
J.cols() ==
nv() &&
"J is not of the right dimension");
723 Jout.template topLeftCorner<3, 3>() = quat_map.toRotationMatrix();
726 typedef Eigen::Matrix<Scalar, 4, 3, JacobianPlainType::Options | Eigen::RowMajor> Jacobian43;
730 Jacobian43 Jexp3QuatCoeffWise;
744 if (quat_map.coeffs()[3] >=
Scalar(0))
747 Jexp3QuatCoeffWise * Jlog;
750 -Jexp3QuatCoeffWise * Jlog;
753 template<
class Config_t,
class Tangent_t,
class JacobianOut_t>
755 const Eigen::MatrixBase<Config_t> & ,
756 const Eigen::MatrixBase<Tangent_t> &
v,
757 const Eigen::MatrixBase<JacobianOut_t> &
J,
774 assert(
false &&
"Wrong Op requesed value");
779 template<
class Config_t,
class Tangent_t,
class JacobianOut_t>
781 const Eigen::MatrixBase<Config_t> & ,
782 const Eigen::MatrixBase<Tangent_t> &
v,
783 const Eigen::MatrixBase<JacobianOut_t> &
J,
798 assert(
false &&
"Wrong Op requesed value");
803 template<
class Config_t,
class Tangent_t,
class JacobianIn_t,
class JacobianOut_t>
805 const Eigen::MatrixBase<Config_t> & ,
806 const Eigen::MatrixBase<Tangent_t> &
v,
807 const Eigen::MatrixBase<JacobianIn_t> & Jin,
808 const Eigen::MatrixBase<JacobianOut_t> & J_out)
811 Eigen::Matrix<Scalar, 6, 6> Jtmp6;
814 Jout.template topRows<3>().noalias() =
815 Jtmp6.template topLeftCorner<3, 3>() * Jin.template topRows<3>();
816 Jout.template topRows<3>().noalias() +=
817 Jtmp6.template topRightCorner<3, 3>() * Jin.template bottomRows<3>();
818 Jout.template bottomRows<3>().noalias() =
819 Jtmp6.template bottomRightCorner<3, 3>() * Jin.template bottomRows<3>();
822 template<
class Config_t,
class Tangent_t,
class JacobianIn_t,
class JacobianOut_t>
824 const Eigen::MatrixBase<Config_t> & ,
825 const Eigen::MatrixBase<Tangent_t> &
v,
826 const Eigen::MatrixBase<JacobianIn_t> & Jin,
827 const Eigen::MatrixBase<JacobianOut_t> & J_out)
832 Eigen::Matrix<Scalar, 6, 6> Jtmp6;
836 Jout.template topRows<3>().noalias() =
837 Jtmp6.template topLeftCorner<3, 3>() * Jin.template topRows<3>();
838 Jout.template topRows<3>().noalias() +=
839 Jtmp6.template topRightCorner<3, 3>() * Jin.template bottomRows<3>();
840 Jout.template bottomRows<3>().noalias() =
841 Jtmp6.template bottomRightCorner<3, 3>() * Jin.template bottomRows<3>();
844 template<
class Config_t,
class Tangent_t,
class Jacobian_t>
846 const Eigen::MatrixBase<Config_t> & ,
847 const Eigen::MatrixBase<Tangent_t> &
v,
848 const Eigen::MatrixBase<Jacobian_t> & J_out)
851 Eigen::Matrix<Scalar, 6, 6> Jtmp6;
855 Jout.template topRows<3>() =
856 Jtmp6.template topLeftCorner<3, 3>() * Jout.template topRows<3>();
857 Jout.template topRows<3>().noalias() +=
858 Jtmp6.template topRightCorner<3, 3>() * Jout.template bottomRows<3>();
859 Jout.template bottomRows<3>() =
860 Jtmp6.template bottomRightCorner<3, 3>() * Jout.template bottomRows<3>();
863 template<
class Config_t,
class Tangent_t,
class Jacobian_t>
865 const Eigen::MatrixBase<Config_t> & ,
866 const Eigen::MatrixBase<Tangent_t> &
v,
867 const Eigen::MatrixBase<Jacobian_t> & J_out)
872 Eigen::Matrix<Scalar, 6, 6> Jtmp6;
876 Jout.template topRows<3>() =
877 Jtmp6.template topLeftCorner<3, 3>() * Jout.template topRows<3>();
878 Jout.template topRows<3>().noalias() +=
879 Jtmp6.template topRightCorner<3, 3>() * Jout.template bottomRows<3>();
880 Jout.template bottomRows<3>() =
881 Jtmp6.template bottomRightCorner<3, 3>() * Jout.template bottomRows<3>();
884 template<
class ConfigL_t,
class ConfigR_t>
886 const Eigen::MatrixBase<ConfigL_t> &
q0,
const Eigen::MatrixBase<ConfigR_t> &
q1)
891 difference_impl(
q0,
q1,
t);
893 return t.squaredNorm();
896 template<
class Config_t>
902 template<
class Config_t>
907 return abs(norm -
Scalar(1.0)) < prec;
910 template<
class Config_t>
916 template<
class ConfigL_t,
class ConfigR_t,
class ConfigOut_t>
918 const Eigen::MatrixBase<ConfigL_t> & lower,
919 const Eigen::MatrixBase<ConfigR_t> & upper,
920 const Eigen::MatrixBase<ConfigOut_t> &
qout)
925 template<
class ConfigL_t,
class ConfigR_t>
927 const Eigen::MatrixBase<ConfigL_t> &
q0,
928 const Eigen::MatrixBase<ConfigR_t> &
q1,
937 #endif // ifndef __pinocchio_multibody_liegroup_special_euclidean_operation_hpp__