7 #ifndef __pinocchio_spatial_inertia_hpp__
8 #define __pinocchio_spatial_inertia_hpp__
10 #include "pinocchio/math/fwd.hpp"
11 #include "pinocchio/spatial/symmetric3.hpp"
12 #include "pinocchio/spatial/force.hpp"
13 #include "pinocchio/spatial/motion.hpp"
14 #include "pinocchio/spatial/skew.hpp"
18 template<
class Derived>
21 SPATIAL_TYPEDEF_TEMPLATE(Derived);
25 return *
static_cast<Derived *
>(
this);
27 const Derived & derived()
const
29 return *
static_cast<const Derived *
>(
this);
32 Derived & const_cast_derived()
const
34 return *
const_cast<Derived *
>(&derived());
39 return static_cast<const Derived *
>(
this)->mass();
43 return static_cast<const Derived *
>(
this)->mass();
45 const Vector3 & lever()
const
47 return static_cast<const Derived *
>(
this)->lever();
51 return static_cast<const Derived *
>(
this)->lever();
55 return static_cast<const Derived *
>(
this)->inertia();
59 return static_cast<const Derived *
>(
this)->inertia();
62 template<
typename Matrix6Like>
63 void matrix(
const Eigen::MatrixBase<Matrix6Like> & mat)
const
65 derived().matrix_impl(mat);
67 Matrix6 matrix()
const
69 return derived().matrix_impl();
71 operator Matrix6()
const
76 template<
typename Matrix6Like>
77 void inverse(
const Eigen::MatrixBase<Matrix6Like> & mat)
const
79 derived().inverse_impl(mat);
81 Matrix6 inverse()
const
83 return derived().inverse_impl();
86 Derived & operator=(
const Derived & clone)
88 return derived().__equl__(clone);
90 bool operator==(
const Derived & other)
const
92 return derived().isEqual(other);
94 bool operator!=(
const Derived & other)
const
96 return !(*
this == other);
99 Derived & operator+=(
const Derived & Yb)
101 return derived().__pequ__(Yb);
103 Derived operator+(
const Derived & Yb)
const
105 return derived().__plus__(Yb);
107 Derived & operator-=(
const Derived & Yb)
109 return derived().__mequ__(Yb);
111 Derived operator-(
const Derived & Yb)
const
113 return derived().__minus__(Yb);
116 template<
typename MotionDerived>
120 return derived().__mult__(v);
123 template<
typename MotionDerived>
126 return derived().vtiv_impl(v);
129 template<
typename MotionDerived>
132 return derived().variation_impl(v);
143 template<
typename MotionDerived,
typename M6>
147 EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(M6, Matrix6);
148 Derived::vxi_impl(v, I, Iout);
151 template<
typename MotionDerived>
155 vxi(v, derived(), Iout);
167 template<
typename MotionDerived,
typename M6>
171 EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(M6, Matrix6);
172 Derived::ivx_impl(v, I, Iout);
175 template<
typename MotionDerived>
179 ivx(v, derived(), Iout);
189 derived().setIdentity();
193 derived().setRandom();
197 const Derived & other,
198 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const
200 return derived().isApprox_impl(other, prec);
203 bool isZero(
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const
205 return derived().isZero_impl(prec);
209 template<
typename S2,
int O2>
212 return derived().se3Action_impl(M);
216 template<
typename S2,
int O2>
219 return derived().se3ActionInverse_impl(M);
222 void disp(std::ostream & os)
const
224 static_cast<const Derived *
>(
this)->disp_impl(os);
226 friend std::ostream & operator<<(std::ostream & os,
const InertiaBase<Derived> & X)
234 template<
typename T,
int U>
238 typedef Eigen::Matrix<T, 3, 1, U> Vector3;
239 typedef Eigen::Matrix<T, 4, 1, U> Vector4;
240 typedef Eigen::Matrix<T, 6, 1, U> Vector6;
241 typedef Eigen::Matrix<T, 3, 3, U> Matrix3;
242 typedef Eigen::Matrix<T, 4, 4, U> Matrix4;
243 typedef Eigen::Matrix<T, 6, 6, U> Matrix6;
244 typedef Eigen::Matrix<T, 10, 10, U> Matrix10;
245 typedef Matrix6 ActionMatrix_t;
246 typedef Vector3 Angular_t;
247 typedef Vector3 Linear_t;
248 typedef const Vector3 ConstAngular_t;
249 typedef const Vector3 ConstLinear_t;
250 typedef Eigen::Quaternion<T, U> Quaternion_t;
264 template<
typename _Scalar,
int _Options>
267 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
275 typedef typename Symmetric3::AlphaSkewSquare AlphaSkewSquare;
276 typedef Eigen::Matrix<Scalar, 10, 1, Options> Vector10;
277 typedef Eigen::Matrix<Scalar, 10, 10, Options> Matrix10;
286 InertiaTpl(
const Scalar & mass,
const Vector3 & com,
const Matrix3 & rotational_inertia)
289 , m_inertia(rotational_inertia)
295 assert(check_expression_if_real<Scalar>(pinocchio::isZero(I6 - I6.transpose())));
296 mass() = I6(LINEAR, LINEAR);
297 const typename Matrix6::template ConstFixedBlockXpr<3, 3>::Type mc_cross =
298 I6.template block<3, 3>(ANGULAR, LINEAR);
299 lever() =
unSkew(mc_cross);
302 Matrix3 I3(mc_cross * mc_cross);
304 I3 += I6.template block<3, 3>(ANGULAR, ANGULAR);
312 , m_inertia(rotational_inertia)
317 : m_mass(clone.mass())
318 , m_com(clone.lever())
319 , m_inertia(clone.inertia())
325 m_mass = clone.mass();
326 m_com = clone.lever();
327 m_inertia = clone.inertia();
331 template<
typename S2,
int O2>
334 *
this = clone.template cast<Scalar>();
340 return InertiaTpl(Scalar(0), Vector3::Zero(), Symmetric3::Zero());
352 return InertiaTpl(Scalar(1), Vector3::Zero(), Symmetric3::Identity());
359 inertia().setIdentity();
366 Eigen::internal::random<Scalar>() + 1, Vector3::Random(), Symmetric3::RandomPositive());
390 FromEllipsoid(
const Scalar mass,
const Scalar x,
const Scalar y,
const Scalar z)
392 const Scalar a = mass * (y * y + z * z) / Scalar(5);
393 const Scalar b = mass * (x * x + z * z) / Scalar(5);
394 const Scalar c = mass * (y * y + x * x) / Scalar(5);
396 mass, Vector3::Zero(),
Symmetric3(a, Scalar(0), b, Scalar(0), Scalar(0), c));
409 const Scalar radius_square = radius * radius;
410 const Scalar a = mass * (radius_square / Scalar(4) + length * length / Scalar(12));
411 const Scalar c = mass * (radius_square / Scalar(2));
413 mass, Vector3::Zero(),
Symmetric3(a, Scalar(0), a, Scalar(0), Scalar(0), c));
426 const Scalar a = mass * (y * y + z * z) / Scalar(12);
427 const Scalar b = mass * (x * x + z * z) / Scalar(12);
428 const Scalar c = mass * (y * y + x * x) / Scalar(12);
430 mass, Vector3::Zero(),
Symmetric3(a, Scalar(0), b, Scalar(0), Scalar(0), c));
442 const Scalar pi = boost::math::constants::pi<Scalar>();
445 const Scalar v_cyl = pi * math::pow(radius, 2) * height;
446 const Scalar v_hs = Scalar(2) / Scalar(3) * math::pow(radius, 3) * pi;
447 const Scalar total_v = v_cyl + Scalar(2) * v_hs;
449 const Scalar m_cyl = mass * (v_cyl / total_v);
450 const Scalar m_hs = mass * (v_hs / total_v);
453 const Scalar dist_hc_cyl = height / Scalar(2) + Scalar(0.375) * radius;
457 m_cyl * (math::pow(height, 2) / Scalar(12) + math::pow(radius, 2) / Scalar(4));
458 const Scalar iz_c = m_cyl * math::pow(radius, 2) / Scalar(2);
462 const Scalar ix_hs = m_hs * math::pow(radius, 2) * Scalar(0.259375);
463 const Scalar iz_hs = m_hs * math::pow(radius, 2) * Scalar(0.4);
466 const Scalar ix = ix_c + Scalar(2) * (ix_hs + m_hs * math::pow(dist_hc_cyl, 2));
467 const Scalar iz = iz_c + Scalar(2) * iz_hs;
470 mass, Vector3::Zero(),
Symmetric3(ix, Scalar(0), ix, Scalar(0), Scalar(0), iz));
475 mass() =
static_cast<Scalar
>(std::rand()) /
static_cast<Scalar
>(RAND_MAX);
477 inertia().setRandom();
480 template<
typename Matrix6Like>
481 void matrix_impl(
const Eigen::MatrixBase<Matrix6Like> & M_)
const
483 Matrix6Like & M = M_.const_cast_derived();
485 M.template block<3, 3>(LINEAR, LINEAR).setZero();
486 M.template block<3, 3>(LINEAR, LINEAR).diagonal().fill(mass());
487 M.template block<3, 3>(ANGULAR, LINEAR) =
alphaSkew(mass(), lever());
488 M.template block<3, 3>(LINEAR, ANGULAR) = -M.template block<3, 3>(ANGULAR, LINEAR);
489 M.template block<3, 3>(ANGULAR, ANGULAR) =
490 (inertia() - AlphaSkewSquare(mass(), lever())).matrix();
493 Matrix6 matrix_impl()
const
500 template<
typename Matrix6Like>
501 void inverse_impl(
const Eigen::MatrixBase<Matrix6Like> & M_)
const
503 Matrix6Like & M = M_.const_cast_derived();
504 inertia().inverse(M.template block<3, 3>(ANGULAR, ANGULAR));
506 M.template block<3, 3>(LINEAR, ANGULAR).noalias() =
507 -M.template block<3, 3>(ANGULAR, ANGULAR).colwise().cross(lever());
508 M.template block<3, 3>(ANGULAR, LINEAR) = M.template block<3, 3>(LINEAR, ANGULAR).transpose();
510 const Scalar &cx = lever()[0], cy = lever()[1], cz = lever()[2];
512 M.template block<3, 3>(LINEAR, LINEAR).col(0).noalias() =
513 cy * M.template block<3, 3>(LINEAR, ANGULAR).col(2)
514 - cz * M.template block<3, 3>(LINEAR, ANGULAR).col(1);
516 M.template block<3, 3>(LINEAR, LINEAR).col(1).noalias() =
517 cz * M.template block<3, 3>(LINEAR, ANGULAR).col(0)
518 - cx * M.template block<3, 3>(LINEAR, ANGULAR).col(2);
520 M.template block<3, 3>(LINEAR, LINEAR).col(2).noalias() =
521 cx * M.template block<3, 3>(LINEAR, ANGULAR).col(1)
522 - cy * M.template block<3, 3>(LINEAR, ANGULAR).col(0);
524 const Scalar m_inv = Scalar(1) / mass();
525 M.template block<3, 3>(LINEAR, LINEAR).diagonal().array() += m_inv;
528 Matrix6 inverse_impl()
const
547 v.template segment<3>(1).noalias() = mass() * lever();
548 v.template segment<6>(4) = (inertia() - AlphaSkewSquare(mass(), lever())).data();
561 template<
typename Vector10Like>
564 PINOCCHIO_ASSERT_MATRIX_SPECIFIC_SIZE(Vector10Like, params, 10, 1);
566 const Scalar & mass = params[0];
567 Vector3 lever = params.template segment<3>(1);
571 mass, lever,
Symmetric3(params.template segment<6>(4)) + AlphaSkewSquare(mass, lever));
595 return pseudo_inertia;
614 mass() = clone.mass();
615 lever() = clone.lever();
616 inertia() = clone.inertia();
621 bool isEqual(
const InertiaTpl & Y2)
const
623 return (mass() == Y2.mass()) && (lever() == Y2.lever()) && (inertia() == Y2.inertia());
627 const InertiaTpl & other,
628 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const
631 return fabs(
static_cast<Scalar
>(mass() - other.mass())) <= prec
632 && lever().isApprox(other.lever(), prec) && inertia().isApprox(other.inertia(), prec);
635 bool isZero_impl(
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const
638 return fabs(mass()) <= prec && lever().isZero(prec) && inertia().isZero(prec);
641 InertiaTpl __plus__(
const InertiaTpl & Yb)
const
648 const Scalar eps = ::Eigen::NumTraits<Scalar>::epsilon();
650 const Scalar & mab = mass() + Yb.mass();
651 const Scalar mab_inv = Scalar(1) / math::max(mab, eps);
652 const Vector3 & AB = (lever() - Yb.lever()).eval();
654 mab, (mass() * lever() + Yb.mass() * Yb.lever()) * mab_inv,
655 inertia() + Yb.inertia()
656 - (mass() * Yb.mass() * mab_inv) *
typename Symmetric3::SkewSquare(AB));
659 InertiaTpl & __pequ__(
const InertiaTpl & Yb)
661 static const Scalar eps = ::Eigen::NumTraits<Scalar>::epsilon();
663 const InertiaTpl & Ya = *
this;
664 const Scalar & mab = mass() + Yb.mass();
665 const Scalar mab_inv = Scalar(1) / math::max(mab, eps);
666 const Vector3 & AB = (Ya.lever() - Yb.lever()).eval();
667 lever() *= (mass() * mab_inv);
668 lever() += (Yb.mass() * mab_inv) * Yb.lever();
669 inertia() += Yb.inertia();
670 inertia() -= (Ya.mass() * Yb.mass() * mab_inv) *
typename Symmetric3::SkewSquare(AB);
675 InertiaTpl __minus__(
const InertiaTpl & Yb)
const
682 const Scalar eps = ::Eigen::NumTraits<Scalar>::epsilon();
684 const Scalar ma = mass() - Yb.mass();
685 assert(check_expression_if_real<Scalar>(ma >= Scalar(0)));
687 const Scalar ma_inv = Scalar(1) / math::max(ma, eps);
688 const Vector3 c_a((mass() * lever() - Yb.mass() * Yb.lever()) * ma_inv);
690 const Vector3 AB = c_a - Yb.lever();
694 inertia() - Yb.inertia() + (ma * Yb.mass() / mass()) *
typename Symmetric3::SkewSquare(AB));
697 InertiaTpl & __mequ__(
const InertiaTpl & Yb)
699 static const Scalar eps = ::Eigen::NumTraits<Scalar>::epsilon();
701 const Scalar ma = mass() - Yb.mass();
702 assert(check_expression_if_real<Scalar>(ma >= Scalar(0)));
704 const Scalar ma_inv = Scalar(1) / math::max(ma, eps);
706 lever() *= (mass() * ma_inv);
707 lever().noalias() -= (Yb.mass() * ma_inv) * Yb.lever();
709 const Vector3 AB = lever() - Yb.lever();
710 inertia() -= Yb.inertia();
711 inertia() += (ma * Yb.mass() / mass()) *
typename Symmetric3::SkewSquare(AB);
717 template<
typename MotionDerived>
718 ForceTpl<typename traits<MotionDerived>::Scalar, traits<MotionDerived>::Options>
719 __mult__(
const MotionDense<MotionDerived> & v)
const
721 typedef ForceTpl<typename traits<MotionDerived>::Scalar, traits<MotionDerived>::Options>
728 template<
typename MotionDerived,
typename ForceDerived>
729 void __mult__(
const MotionDense<MotionDerived> & v, ForceDense<ForceDerived> & f)
const
731 f.linear().noalias() = mass() * (v.linear() - lever().cross(v.angular()));
732 Symmetric3::rhsMult(inertia(), v.angular(), f.angular());
733 f.angular() += lever().cross(f.linear());
737 template<
typename MotionDerived>
738 Scalar vtiv_impl(
const MotionDense<MotionDerived> & v)
const
740 const Vector3 cxw(lever().
cross(v.angular()));
741 Scalar res = mass() * (v.linear().squaredNorm() - Scalar(2) * v.linear().dot(cxw));
742 const Vector3 mcxcxw(-mass() * lever().
cross(cxw));
743 res += v.angular().dot(mcxcxw);
744 res += inertia().vtiv(v.angular());
749 template<
typename MotionDerived>
750 Matrix6 variation(
const MotionDense<MotionDerived> & v)
const
753 const Motion mv(v * mass());
755 res.template block<3, 3>(LINEAR, ANGULAR) =
757 res.template block<3, 3>(ANGULAR, LINEAR) =
758 res.template block<3, 3>(LINEAR, ANGULAR).transpose();
763 res.template block<3, 3>(ANGULAR, ANGULAR) =
766 res.template block<3, 3>(LINEAR, LINEAR) =
767 (inertia() - AlphaSkewSquare(mass(), lever())).matrix();
769 res.template block<3, 3>(ANGULAR, ANGULAR) -=
770 res.template block<3, 3>(LINEAR, LINEAR) *
skew(v.angular());
771 res.template block<3, 3>(ANGULAR, ANGULAR) +=
772 cross(v.angular(), res.template block<3, 3>(LINEAR, LINEAR));
774 res.template block<3, 3>(LINEAR, LINEAR).setZero();
778 template<
typename MotionDerived,
typename M6>
779 static void vxi_impl(
780 const MotionDense<MotionDerived> & v,
781 const InertiaTpl & I,
782 const Eigen::MatrixBase<M6> & Iout)
784 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6, 6, 6);
785 M6 & Iout_ = PINOCCHIO_EIGEN_CONST_CAST(M6, Iout);
788 alphaSkew(I.mass(), v.angular(), Iout_.template block<3, 3>(LINEAR, LINEAR));
790 const Vector3 mc(I.mass() * I.lever());
793 skewSquare(-v.angular(), mc, Iout_.template block<3, 3>(LINEAR, ANGULAR));
796 alphaSkew(I.mass(), v.linear(), Iout_.template block<3, 3>(ANGULAR, LINEAR));
797 Iout_.template block<3, 3>(ANGULAR, LINEAR) -= Iout_.template block<3, 3>(LINEAR, ANGULAR);
800 skewSquare(-v.linear(), mc, Iout_.template block<3, 3>(ANGULAR, ANGULAR));
807 Symmetric3 mcxcx(
typename Symmetric3::AlphaSkewSquare(I.mass(), I.lever()));
808 Iout_.template block<3, 3>(ANGULAR, ANGULAR) += I.inertia().vxs(v.angular());
809 Iout_.template block<3, 3>(ANGULAR, ANGULAR) -= mcxcx.vxs(v.angular());
812 template<
typename MotionDerived,
typename M6>
813 static void ivx_impl(
814 const MotionDense<MotionDerived> & v,
815 const InertiaTpl & I,
816 const Eigen::MatrixBase<M6> & Iout)
818 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6, 6, 6);
819 M6 & Iout_ = PINOCCHIO_EIGEN_CONST_CAST(M6, Iout);
822 alphaSkew(I.mass(), v.angular(), Iout_.template block<3, 3>(LINEAR, LINEAR));
825 const Vector3 mc(I.mass() * I.lever());
826 skewSquare(mc, v.angular(), Iout_.template block<3, 3>(ANGULAR, LINEAR));
829 alphaSkew(I.mass(), v.linear(), Iout_.template block<3, 3>(LINEAR, ANGULAR));
833 -I.lever(), Iout_.template block<3, 3>(ANGULAR, LINEAR),
834 Iout_.template block<3, 3>(ANGULAR, ANGULAR));
835 Iout_.template block<3, 3>(ANGULAR, ANGULAR) += I.inertia().svx(v.angular());
836 for (
int k = 0; k < 3; ++k)
837 Iout_.template block<3, 3>(ANGULAR, ANGULAR).col(k) +=
838 I.lever().cross(Iout_.template block<3, 3>(LINEAR, ANGULAR).col(k));
841 Iout_.template block<3, 3>(LINEAR, ANGULAR) -= Iout_.template block<3, 3>(ANGULAR, LINEAR);
849 const Vector3 & lever()
const
853 const Symmetric3 & inertia()
const
866 Symmetric3 & inertia()
872 template<
typename S2,
int O2>
879 mass(), M.translation() + M.rotation() * lever(), inertia().rotate(M.rotation()));
883 template<
typename S2,
int O2>
887 mass(), M.rotation().transpose() * (lever() - M.translation()),
888 inertia().rotate(M.rotation().transpose()));
891 template<
typename MotionDerived>
894 const Vector3 & mcxw = mass() * lever().cross(v.angular());
895 const Vector3 & mv_mcxw = mass() * v.linear() - mcxw;
897 v.angular().cross(mv_mcxw),
898 v.angular().cross(lever().
cross(mv_mcxw) + inertia() * v.angular())
899 - v.linear().cross(mcxw));
902 void disp_impl(std::ostream & os)
const
904 os <<
" m = " << mass() <<
"\n"
905 <<
" c = " << lever().transpose() <<
"\n"
907 << inertia().matrix() <<
"";
911 template<
typename NewScalar>
915 pinocchio::cast<NewScalar>(mass()), lever().
template cast<NewScalar>(),
916 inertia().
template cast<NewScalar>());
943 template<
typename _Scalar,
int _Options>
946 typedef _Scalar Scalar;
951 typedef Eigen::Matrix<Scalar, 4, 4, Options> Matrix4;
952 typedef Eigen::Matrix<Scalar, 3, 1, Options> Vector3;
953 typedef Eigen::Matrix<Scalar, 3, 3, Options> Matrix3;
954 typedef Eigen::Matrix<Scalar, 10, 1, Options> Vector10;
974 Matrix4 pseudo_inertia = Matrix4::Zero();
975 pseudo_inertia.template block<3, 3>(0, 0) =
sigma;
976 pseudo_inertia.template block<3, 1>(0, 3) =
h;
977 pseudo_inertia.template block<1, 3>(3, 0) =
h.transpose();
978 pseudo_inertia(3, 3) =
mass;
979 return pseudo_inertia;
989 Scalar
mass = pseudo_inertia(3, 3);
990 Vector3
h = pseudo_inertia.template block<3, 1>(0, 3);
991 Matrix3
sigma = pseudo_inertia.template block<3, 3>(0, 0);
1000 template<
typename Vector10Like>
1004 PINOCCHIO_ASSERT_MATRIX_SPECIFIC_SIZE(Vector10Like, dynamic_params, 10, 1);
1005 Scalar
mass = dynamic_params[0];
1006 Vector3
h = dynamic_params.template segment<3>(1);
1009 I_bar << dynamic_params[4], dynamic_params[5], dynamic_params[7],
1010 dynamic_params[5], dynamic_params[6], dynamic_params[8],
1011 dynamic_params[7], dynamic_params[8], dynamic_params[9];
1014 Matrix3
sigma = 0.5 * I_bar.trace() * Matrix3::Identity() - I_bar;
1024 Matrix3 I_bar =
sigma.trace() * Matrix3::Identity() -
sigma;
1026 Vector10 dynamic_params;
1027 dynamic_params[0] =
mass;
1028 dynamic_params.template segment<3>(1) =
h;
1029 dynamic_params[4] = I_bar(0, 0);
1030 dynamic_params[5] = I_bar(0, 1);
1031 dynamic_params[6] = I_bar(1, 1);
1032 dynamic_params[7] = I_bar(0, 2);
1033 dynamic_params[8] = I_bar(1, 2);
1034 dynamic_params[9] = I_bar(2, 2);
1036 return dynamic_params;
1072 template<
typename NewScalar>
1076 pinocchio::cast<NewScalar>(
mass),
h.template cast<NewScalar>(),
1077 sigma.template cast<NewScalar>());
1080 void disp_impl(std::ostream & os)
const
1082 os <<
" m = " <<
mass <<
"\n"
1083 <<
" h = " <<
h.transpose() <<
"\n"
1088 friend std::ostream & operator<<(std::ostream & os,
const PseudoInertiaTpl & pi)
1102 template<
typename _Scalar,
int _Options>
1105 typedef _Scalar Scalar;
1110 typedef Eigen::Matrix<Scalar, 10, 1, Options> Vector10;
1111 typedef Eigen::Matrix<Scalar, 10, 10, Options> Matrix10;
1133 Vector10 dynamic_params;
1146 const Scalar exp_d1 = exp(d1);
1147 const Scalar exp_d2 = exp(d2);
1148 const Scalar exp_d3 = exp(d3);
1150 dynamic_params[0] = 1;
1151 dynamic_params[1] = t1;
1152 dynamic_params[2] = t2;
1153 dynamic_params[3] = t3;
1154 dynamic_params[4] = pow(s23, 2) + pow(t2, 2) + pow(t3, 2) + pow(exp_d2, 2) + pow(exp_d3, 2);
1155 dynamic_params[5] = -s12 * exp_d2 - s13 * s23 - t1 * t2;
1156 dynamic_params[6] = pow(s12, 2) + pow(s13, 2) + pow(t1, 2) + pow(t3, 2) + pow(exp_d1, 2) + pow(exp_d3, 2);
1157 dynamic_params[7] = -s13 * exp_d3 - t1 * t3;
1158 dynamic_params[8] = -s23 * exp_d3 - t2 * t3;
1159 dynamic_params[9] = pow(s12, 2) + pow(s13, 2) + pow(s23, 2) + pow(t1, 2) + pow(t2, 2) + pow(exp_d1, 2) + pow(exp_d2, 2);
1161 const Scalar exp_2_alpha = exp(2 * alpha);
1162 dynamic_params *= exp_2_alpha;
1165 return dynamic_params;
1197 Matrix10 jacobian = Matrix10::Zero();
1210 const Scalar exp_2alpha = exp(2 * alpha);
1211 const Scalar exp_2d1 = exp(2 * d1);
1212 const Scalar exp_2d2 = exp(2 * d2);
1213 const Scalar exp_2d3 = exp(2 * d3);
1215 const Scalar exp_d2 = exp(d2);
1216 const Scalar exp_d3 = exp(d3);
1219 jacobian(0, 0) = 2 * exp_2alpha;
1221 jacobian(1, 0) = 2 * t1 * exp_2alpha;
1222 jacobian(1, 7) = exp_2alpha;
1224 jacobian(2, 0) = 2 * t2 * exp_2alpha;
1225 jacobian(2, 8) = exp_2alpha;
1227 jacobian(3, 0) = 2 * t3 * exp_2alpha;
1228 jacobian(3, 9) = exp_2alpha;
1230 jacobian(4, 0) = 2 * (pow(s23, 2) + pow(t2, 2) + pow(t3, 2) + exp_2d2 + exp_2d3) * exp_2alpha;
1231 jacobian(4, 2) = 2 * exp_2alpha * exp_2d2;
1232 jacobian(4, 3) = 2 * exp_2alpha * exp_2d3;
1233 jacobian(4, 5) = 2 * s23 * exp_2alpha;
1234 jacobian(4, 8) = 2 * t2 * exp_2alpha;
1235 jacobian(4, 9) = 2 * t3 * exp_2alpha;
1237 jacobian(5, 0) = -2 * (s12 * exp_d2 + s13 * s23 + t1 * t2) * exp_2alpha;
1238 jacobian(5, 2) = -s12 * exp_2alpha * exp_d2;
1239 jacobian(5, 4) = -exp_2alpha * exp_d2;
1240 jacobian(5, 5) = -s13 * exp_2alpha;
1241 jacobian(5, 6) = -s23 * exp_2alpha;
1242 jacobian(5, 7) = -t2 * exp_2alpha;
1243 jacobian(5, 8) = -t1 * exp_2alpha;
1245 jacobian(6, 0) = 2 * (pow(s12, 2) + pow(s13, 2) + pow(t1, 2) + pow(t3, 2) + exp_2d1 + exp_2d3) * exp_2alpha;
1246 jacobian(6, 1) = 2 * exp_2alpha * exp_2d1;
1247 jacobian(6, 3) = 2 * exp_2alpha * exp_2d3;
1248 jacobian(6, 4) = 2 * s12 * exp_2alpha;
1249 jacobian(6, 6) = 2 * s13 * exp_2alpha;
1250 jacobian(6, 7) = 2 * t1 * exp_2alpha;
1251 jacobian(6, 9) = 2 * t3 * exp_2alpha;
1253 jacobian(7, 0) = -2 * (s13 * exp_d3 + t1 * t3) * exp_2alpha;
1254 jacobian(7, 3) = -s13 * exp_2alpha * exp_d3;
1255 jacobian(7, 6) = -exp_2alpha * exp_d3;
1256 jacobian(7, 7) = -t3 * exp_2alpha;
1257 jacobian(7, 9) = -t1 * exp_2alpha;
1259 jacobian(8, 0) = -2 * (s23 * exp_d3 + t2 * t3) * exp_2alpha;
1260 jacobian(8, 3) = -s23 * exp_2alpha * exp_d3;
1261 jacobian(8, 5) = -exp_2alpha * exp_d3;
1262 jacobian(8, 8) = -t3 * exp_2alpha;
1263 jacobian(8, 9) = -t2 * exp_2alpha;
1265 jacobian(9, 0) = 2 * (pow(s12, 2) + pow(s13, 2) + pow(s23, 2) + pow(t1, 2) + pow(t2, 2) + exp_2d1 + exp_2d2) * exp_2alpha;
1266 jacobian(9, 1) = 2 * exp_2alpha * exp_2d1;
1267 jacobian(9, 2) = 2 * exp_2alpha * exp_2d2;
1268 jacobian(9, 4) = 2 * s12 * exp_2alpha;
1269 jacobian(9, 5) = 2 * s23 * exp_2alpha;
1270 jacobian(9, 6) = 2 * s13 * exp_2alpha;
1271 jacobian(9, 7) = 2 * t1 * exp_2alpha;
1272 jacobian(9, 8) = 2 * t2 * exp_2alpha;
1279 template<
typename NewScalar>
1285 void disp_impl(std::ostream & os)
const
Main pinocchio namespace.
void skewSquare(const Eigen::MatrixBase< V1 > &u, const Eigen::MatrixBase< V2 > &v, const Eigen::MatrixBase< Matrix3 > &C)
Computes the square cross product linear operator C(u,v) such that for any vector w,...
void alphaSkew(const Scalar alpha, const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector multiplied by a given scalar....
void cross(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3xIn > &Min, const Eigen::MatrixBase< Matrix3xOut > &Mout)
Applies the cross product onto the columns of M.
void unSkew(const Eigen::MatrixBase< Matrix3 > &M, const Eigen::MatrixBase< Vector3 > &v)
Inverse of skew operator. From a given skew-symmetric matrix M of dimension 3x3, it extracts the supp...
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...
static void vxi(const MotionDense< MotionDerived > &v, const Derived &I, const Eigen::MatrixBase< M6 > &Iout)
Time variation operator. It computes the time derivative of an inertia I corresponding to the formula...
Derived se3Action(const SE3Tpl< S2, O2 > &M) const
aI = aXb.act(bI)
Derived se3ActionInverse(const SE3Tpl< S2, O2 > &M) const
bI = aXb.actInv(aI)
static void ivx(const MotionDense< MotionDerived > &v, const Derived &I, const Eigen::MatrixBase< M6 > &Iout)
Time variation operator. It computes the time derivative of an inertia I corresponding to the formula...
static InertiaTpl FromSphere(const Scalar mass, const Scalar radius)
Computes the Inertia of a sphere defined by its mass and its radius.
static InertiaTpl FromBox(const Scalar mass, const Scalar x, const Scalar y, const Scalar z)
Computes the Inertia of a box defined by its mass and main dimensions (x,y,z).
PseudoInertia toPseudoInertia() const
Convert the InertiaTpl object to a 4x4 pseudo inertia matrix.
static InertiaTpl FromEllipsoid(const Scalar mass, const Scalar x, const Scalar y, const Scalar z)
Computes the Inertia of an ellipsoid defined by its mass and main semi-axis dimensions (x,...
static InertiaTpl FromDynamicParameters(const Eigen::MatrixBase< Vector10Like > ¶ms)
InertiaTpl< NewScalar, Options > cast() const
Vector10 toDynamicParameters() const
InertiaTpl se3Action_impl(const SE3Tpl< S2, O2 > &M) const
aI = aXb.act(bI)
static InertiaTpl FromPseudoInertia(const PseudoInertia &pseudo_inertia)
Create an InertiaTpl object from a PseudoInertia object.
static InertiaTpl FromCapsule(const Scalar mass, const Scalar radius, const Scalar height)
Computes the Inertia of a capsule defined by its mass, radius and length along the Z axis....
static InertiaTpl FromCylinder(const Scalar mass, const Scalar radius, const Scalar length)
Computes the Inertia of a cylinder defined by its mass, radius and length along the Z axis.
static InertiaTpl FromLogCholeskyParameters(const LogCholeskyParameters &log_cholesky)
Create an InertiaTpl object from log Cholesky parameters.
InertiaTpl se3ActionInverse_impl(const SE3Tpl< S2, O2 > &M) const
bI = aXb.actInv(aI)
A structure representing log Cholesky parameters.
InertiaTpl< Scalar, Options > toInertia() const
Converts the LogCholeskyParametersTpl object to an InertiaTpl object.
Matrix10 calculateJacobian() const
Calculates the Jacobian of the log Cholesky parameters.
Vector10 parameters
10-dimensional vector of log Cholesky parameters
PseudoInertia toPseudoInertia() const
Converts the LogCholeskyParametersTpl object to a PseudoInertiaTpl object.
Vector10 toDynamicParameters() const
Converts the LogCholeskyParametersTpl object to dynamic parameters.
LogCholeskyParametersTpl(const Vector10 &log_cholesky)
Constructor for LogCholeskyParametersTpl.
LogCholeskyParametersTpl< NewScalar, Options > cast() const
A structure representing a pseudo inertia matrix.
InertiaTpl< Scalar, Options > toInertia() const
Converts the PseudoInertiaTpl object to an InertiaTpl object.
static PseudoInertiaTpl FromMatrix(const Matrix4 &pseudo_inertia)
Constructs a PseudoInertiaTpl object from a 4x4 pseudo inertia matrix.
static PseudoInertiaTpl FromInertia(const InertiaTpl< Scalar, Options > &inertia)
Constructs a PseudoInertiaTpl object from an InertiaTpl object.
static PseudoInertiaTpl FromLogCholeskyParameters(const LogCholeskyParameters &log_cholesky)
Constructs a PseudoInertiaTpl object from log Cholesky parameters.
Matrix3 sigma
3x3 matrix part of the pseudo inertia
Matrix4 toMatrix() const
Converts the PseudoInertiaTpl object to a 4x4 matrix.
Vector10 toDynamicParameters() const
Converts the PseudoInertiaTpl object to dynamic parameters.
Vector3 h
Vector part of the pseudo inertia.
static PseudoInertiaTpl FromDynamicParameters(const Eigen::MatrixBase< Vector10Like > &dynamic_params)
Constructs a PseudoInertiaTpl object from dynamic parameters.
PseudoInertiaTpl< NewScalar, Options > cast() const
Scalar mass
Mass of the pseudo inertia.
Common traits structure to fully define base classes for CRTP.