spatial/inertia.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2021 CNRS INRIA
3 // Copyright (c) 2016 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #ifndef __pinocchio_spatial_inertia_hpp__
7 #define __pinocchio_spatial_inertia_hpp__
8 
9 #include "pinocchio/math/fwd.hpp"
14 
15 namespace pinocchio
16 {
17  template<class Derived>
18  struct InertiaBase : NumericalBase<Derived>
19  {
20  SPATIAL_TYPEDEF_TEMPLATE(Derived);
21 
22  Derived & derived()
23  {
24  return *static_cast<Derived *>(this);
25  }
26  const Derived & derived() const
27  {
28  return *static_cast<const Derived *>(this);
29  }
30 
31  Derived & const_cast_derived() const
32  {
33  return *const_cast<Derived *>(&derived());
34  }
35 
36  Scalar mass() const
37  {
38  return static_cast<const Derived *>(this)->mass();
39  }
41  {
42  return static_cast<const Derived *>(this)->mass();
43  }
44  const Vector3 & lever() const
45  {
46  return static_cast<const Derived *>(this)->lever();
47  }
49  {
50  return static_cast<const Derived *>(this)->lever();
51  }
52  const Symmetric3 & inertia() const
53  {
54  return static_cast<const Derived *>(this)->inertia();
55  }
57  {
58  return static_cast<const Derived *>(this)->inertia();
59  }
60 
61  template<typename Matrix6Like>
62  void matrix(const Eigen::MatrixBase<Matrix6Like> & mat) const
63  {
64  derived().matrix_impl(mat);
65  }
66  Matrix6 matrix() const
67  {
68  return derived().matrix_impl();
69  }
70  operator Matrix6() const
71  {
72  return matrix();
73  }
74 
75  template<typename Matrix6Like>
76  void inverse(const Eigen::MatrixBase<Matrix6Like> & mat) const
77  {
78  derived().inverse_impl(mat);
79  }
80  Matrix6 inverse() const
81  {
82  return derived().inverse_impl();
83  }
84 
85  Derived & operator=(const Derived & clone)
86  {
87  return derived().__equl__(clone);
88  }
89  bool operator==(const Derived & other) const
90  {
91  return derived().isEqual(other);
92  }
93  bool operator!=(const Derived & other) const
94  {
95  return !(*this == other);
96  }
97 
98  Derived & operator+=(const Derived & Yb)
99  {
100  return derived().__pequ__(Yb);
101  }
102  Derived operator+(const Derived & Yb) const
103  {
104  return derived().__plus__(Yb);
105  }
106  Derived & operator-=(const Derived & Yb)
107  {
108  return derived().__mequ__(Yb);
109  }
110  Derived operator-(const Derived & Yb) const
111  {
112  return derived().__minus__(Yb);
113  }
114 
115  template<typename MotionDerived>
118  {
119  return derived().__mult__(v);
120  }
121 
122  template<typename MotionDerived>
124  {
125  return derived().vtiv_impl(v);
126  }
127 
128  template<typename MotionDerived>
129  Matrix6 variation(const MotionDense<MotionDerived> & v) const
130  {
131  return derived().variation_impl(v);
132  }
133 
142  template<typename MotionDerived, typename M6>
143  static void
144  vxi(const MotionDense<MotionDerived> & v, const Derived & I, const Eigen::MatrixBase<M6> & Iout)
145  {
146  EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(M6, Matrix6);
147  Derived::vxi_impl(v, I, Iout);
148  }
149 
150  template<typename MotionDerived>
151  Matrix6 vxi(const MotionDense<MotionDerived> & v) const
152  {
153  Matrix6 Iout;
154  vxi(v, derived(), Iout);
155  return Iout;
156  }
157 
166  template<typename MotionDerived, typename M6>
167  static void
168  ivx(const MotionDense<MotionDerived> & v, const Derived & I, const Eigen::MatrixBase<M6> & Iout)
169  {
170  EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(M6, Matrix6);
171  Derived::ivx_impl(v, I, Iout);
172  }
173 
174  template<typename MotionDerived>
175  Matrix6 ivx(const MotionDense<MotionDerived> & v) const
176  {
177  Matrix6 Iout;
178  ivx(v, derived(), Iout);
179  return Iout;
180  }
181 
182  void setZero()
183  {
184  derived().setZero();
185  }
186  void setIdentity()
187  {
188  derived().setIdentity();
189  }
190  void setRandom()
191  {
192  derived().setRandom();
193  }
194 
195  bool isApprox(
196  const Derived & other,
197  const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
198  {
199  return derived().isApprox_impl(other, prec);
200  }
201 
202  bool isZero(const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
203  {
204  return derived().isZero_impl(prec);
205  }
206 
208  template<typename S2, int O2>
209  Derived se3Action(const SE3Tpl<S2, O2> & M) const
210  {
211  return derived().se3Action_impl(M);
212  }
213 
215  template<typename S2, int O2>
216  Derived se3ActionInverse(const SE3Tpl<S2, O2> & M) const
217  {
218  return derived().se3ActionInverse_impl(M);
219  }
220 
221  void disp(std::ostream & os) const
222  {
223  static_cast<const Derived *>(this)->disp_impl(os);
224  }
225  friend std::ostream & operator<<(std::ostream & os, const InertiaBase<Derived> & X)
226  {
227  X.disp(os);
228  return os;
229  }
230  };
231 
232  // class InertiaBase
233  template<typename T, int U>
234  struct traits<InertiaTpl<T, U>>
235  {
236  typedef T Scalar;
237  typedef Eigen::Matrix<T, 3, 1, U> Vector3;
238  typedef Eigen::Matrix<T, 4, 1, U> Vector4;
239  typedef Eigen::Matrix<T, 6, 1, U> Vector6;
240  typedef Eigen::Matrix<T, 3, 3, U> Matrix3;
241  typedef Eigen::Matrix<T, 4, 4, U> Matrix4;
242  typedef Eigen::Matrix<T, 6, 6, U> Matrix6;
243  typedef Eigen::Matrix<T, 10, 10, U> Matrix10;
246  typedef Vector3 Linear_t;
247  typedef const Vector3 ConstAngular_t;
248  typedef const Vector3 ConstLinear_t;
249  typedef Eigen::Quaternion<T, U> Quaternion_t;
250  typedef SE3Tpl<T, U> SE3;
256  enum
257  {
258  LINEAR = 0,
259  ANGULAR = 3
260  };
261  }; // traits InertiaTpl
262 
263  template<typename _Scalar, int _Options>
264  struct InertiaTpl : public InertiaBase<InertiaTpl<_Scalar, _Options>>
265  {
266  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
267 
269  enum
270  {
271  Options = _Options
272  };
273 
274  typedef typename Symmetric3::AlphaSkewSquare AlphaSkewSquare;
275  typedef Eigen::Matrix<Scalar, 10, 1, Options> Vector10;
276  typedef Eigen::Matrix<Scalar, 10, 10, Options> Matrix10;
279 
280  // Constructors
282  {
283  }
284 
285  InertiaTpl(const Scalar & mass, const Vector3 & com, const Matrix3 & rotational_inertia)
286  : m_mass(mass)
287  , m_com(com)
288  , m_inertia(rotational_inertia)
289  {
290  }
291 
292  explicit InertiaTpl(const Matrix6 & I6)
293  {
294  assert(check_expression_if_real<Scalar>(pinocchio::isZero(I6 - I6.transpose())));
295  mass() = I6(LINEAR, LINEAR);
296  const typename Matrix6::template ConstFixedBlockXpr<3, 3>::Type mc_cross =
297  I6.template block<3, 3>(ANGULAR, LINEAR);
298  lever() = unSkew(mc_cross);
299  lever() /= mass();
300 
301  Matrix3 I3(mc_cross * mc_cross);
302  I3 /= mass();
303  I3 += I6.template block<3, 3>(ANGULAR, ANGULAR);
304  const Symmetric3 S3(I3);
305  inertia() = S3;
306  }
307 
308  InertiaTpl(const Scalar & mass, const Vector3 & com, const Symmetric3 & rotational_inertia)
309  : m_mass(mass)
310  , m_com(com)
311  , m_inertia(rotational_inertia)
312  {
313  }
314 
315  InertiaTpl(const InertiaTpl & clone) // Copy constructor
316  : m_mass(clone.mass())
317  , m_com(clone.lever())
318  , m_inertia(clone.inertia())
319  {
320  }
321 
322  InertiaTpl & operator=(const InertiaTpl & clone) // Copy assignment operator
323  {
324  m_mass = clone.mass();
325  m_com = clone.lever();
326  m_inertia = clone.inertia();
327  return *this;
328  }
329 
330  template<typename S2, int O2>
332  {
333  *this = clone.template cast<Scalar>();
334  }
335 
336  // Initializers
337  static InertiaTpl Zero()
338  {
339  return InertiaTpl(Scalar(0), Vector3::Zero(), Symmetric3::Zero());
340  }
341 
342  void setZero()
343  {
344  mass() = Scalar(0);
345  lever().setZero();
346  inertia().setZero();
347  }
348 
350  {
351  return InertiaTpl(Scalar(1), Vector3::Zero(), Symmetric3::Identity());
352  }
353 
354  void setIdentity()
355  {
356  mass() = Scalar(1);
357  lever().setZero();
358  inertia().setIdentity();
359  }
360 
362  {
363  // We have to shoot "I" definite positive and not only symmetric.
364  return InertiaTpl(
365  Eigen::internal::random<Scalar>() + 1, Vector3::Random(), Symmetric3::RandomPositive());
366  }
367 
375  {
377  }
378 
388  static InertiaTpl
389  FromEllipsoid(const Scalar mass, const Scalar x, const Scalar y, const Scalar z)
390  {
391  const Scalar a = mass * (y * y + z * z) / Scalar(5);
392  const Scalar b = mass * (x * x + z * z) / Scalar(5);
393  const Scalar c = mass * (y * y + x * x) / Scalar(5);
394  return InertiaTpl(
395  mass, Vector3::Zero(), Symmetric3(a, Scalar(0), b, Scalar(0), Scalar(0), c));
396  }
397 
407  {
408  const Scalar radius_square = radius * radius;
409  const Scalar a = mass * (radius_square / Scalar(4) + length * length / Scalar(12));
410  const Scalar c = mass * (radius_square / Scalar(2));
411  return InertiaTpl(
412  mass, Vector3::Zero(), Symmetric3(a, Scalar(0), a, Scalar(0), Scalar(0), c));
413  }
414 
423  static InertiaTpl FromBox(const Scalar mass, const Scalar x, const Scalar y, const Scalar z)
424  {
425  const Scalar a = mass * (y * y + z * z) / Scalar(12);
426  const Scalar b = mass * (x * x + z * z) / Scalar(12);
427  const Scalar c = mass * (y * y + x * x) / Scalar(12);
428  return InertiaTpl(
429  mass, Vector3::Zero(), Symmetric3(a, Scalar(0), b, Scalar(0), Scalar(0), c));
430  }
431 
440  {
441  const Scalar pi = boost::math::constants::pi<Scalar>();
442 
443  // first need to compute mass repartition between cylinder and halfsphere
444  const Scalar v_cyl = pi * math::pow(radius, 2) * height;
445  const Scalar v_hs = Scalar(2) / Scalar(3) * math::pow(radius, 3) * pi;
446  const Scalar total_v = v_cyl + Scalar(2) * v_hs;
447 
448  const Scalar m_cyl = mass * (v_cyl / total_v);
449  const Scalar m_hs = mass * (v_hs / total_v);
450 
451  // Then Distance between halfSphere center and cylindere center.
452  const Scalar dist_hc_cyl = height / Scalar(2) + Scalar(0.375) * radius;
453 
454  // Computes inertia terms
455  const Scalar ix_c =
456  m_cyl * (math::pow(height, 2) / Scalar(12) + math::pow(radius, 2) / Scalar(4));
457  const Scalar iz_c = m_cyl * math::pow(radius, 2) / Scalar(2);
458 
459  // For halfsphere inertia see, "Dynamics: Theory and Applications" McGraw-Hill, New York,
460  // 1985, by T.R. Kane and D.A. Levinson, Appendix 23.
461  const Scalar ix_hs = m_hs * math::pow(radius, 2) * Scalar(0.259375);
462  const Scalar iz_hs = m_hs * math::pow(radius, 2) * Scalar(0.4);
463 
464  // Put everything together using the parallel axis theorem
465  const Scalar ix = ix_c + Scalar(2) * (ix_hs + m_hs * math::pow(dist_hc_cyl, 2));
466  const Scalar iz = iz_c + Scalar(2) * iz_hs;
467 
468  return InertiaTpl(
469  mass, Vector3::Zero(), Symmetric3(ix, Scalar(0), ix, Scalar(0), Scalar(0), iz));
470  }
471 
472  void setRandom()
473  {
474  mass() = static_cast<Scalar>(std::rand()) / static_cast<Scalar>(RAND_MAX);
475  lever().setRandom();
476  inertia().setRandom();
477  }
478 
479  template<typename Matrix6Like>
480  void matrix_impl(const Eigen::MatrixBase<Matrix6Like> & M_) const
481  {
482  Matrix6Like & M = M_.const_cast_derived();
483 
484  M.template block<3, 3>(LINEAR, LINEAR).setZero();
485  M.template block<3, 3>(LINEAR, LINEAR).diagonal().fill(mass());
486  M.template block<3, 3>(ANGULAR, LINEAR) = alphaSkew(mass(), lever());
487  M.template block<3, 3>(LINEAR, ANGULAR) = -M.template block<3, 3>(ANGULAR, LINEAR);
488  M.template block<3, 3>(ANGULAR, ANGULAR) =
489  (inertia() - AlphaSkewSquare(mass(), lever())).matrix();
490  }
491 
492  Matrix6 matrix_impl() const
493  {
494  Matrix6 M;
495  matrix_impl(M);
496  return M;
497  }
498 
499  template<typename Matrix6Like>
500  void inverse_impl(const Eigen::MatrixBase<Matrix6Like> & M_) const
501  {
502  Matrix6Like & M = M_.const_cast_derived();
503  inertia().inverse(M.template block<3, 3>(ANGULAR, ANGULAR));
504 
505  M.template block<3, 3>(LINEAR, ANGULAR).noalias() =
506  -M.template block<3, 3>(ANGULAR, ANGULAR).colwise().cross(lever());
507  M.template block<3, 3>(ANGULAR, LINEAR) = M.template block<3, 3>(LINEAR, ANGULAR).transpose();
508 
509  const Scalar &cx = lever()[0], cy = lever()[1], cz = lever()[2];
510 
511  M.template block<3, 3>(LINEAR, LINEAR).col(0).noalias() =
512  cy * M.template block<3, 3>(LINEAR, ANGULAR).col(2)
513  - cz * M.template block<3, 3>(LINEAR, ANGULAR).col(1);
514 
515  M.template block<3, 3>(LINEAR, LINEAR).col(1).noalias() =
516  cz * M.template block<3, 3>(LINEAR, ANGULAR).col(0)
517  - cx * M.template block<3, 3>(LINEAR, ANGULAR).col(2);
518 
519  M.template block<3, 3>(LINEAR, LINEAR).col(2).noalias() =
520  cx * M.template block<3, 3>(LINEAR, ANGULAR).col(1)
521  - cy * M.template block<3, 3>(LINEAR, ANGULAR).col(0);
522 
523  const Scalar m_inv = Scalar(1) / mass();
524  M.template block<3, 3>(LINEAR, LINEAR).diagonal().array() += m_inv;
525  }
526 
527  Matrix6 inverse_impl() const
528  {
529  Matrix6 res;
530  inverse_impl(res);
531  return res;
532  }
533 
542  {
543  Vector10 v;
544 
545  v[0] = mass();
546  v.template segment<3>(1).noalias() = mass() * lever();
547  v.template segment<6>(4) = (inertia() - AlphaSkewSquare(mass(), lever())).data();
548 
549  return v;
550  }
551 
560  template<typename Vector10Like>
561  static InertiaTpl FromDynamicParameters(const Eigen::MatrixBase<Vector10Like> & params)
562  {
563  PINOCCHIO_ASSERT_MATRIX_SPECIFIC_SIZE(Vector10Like, params, 10, 1);
564 
565  const Scalar & mass = params[0];
566  Vector3 lever = params.template segment<3>(1);
567  lever /= mass;
568 
569  return InertiaTpl(
570  mass, lever, Symmetric3(params.template segment<6>(4)) + AlphaSkewSquare(mass, lever));
571  }
572 
581  static InertiaTpl FromPseudoInertia(const PseudoInertia & pseudo_inertia)
582  {
583  return pseudo_inertia.toInertia();
584  }
585 
592  {
593  PseudoInertia pseudo_inertia = PseudoInertia::FromInertia(*this);
594  return pseudo_inertia;
595  }
596 
605  {
606  Vector10 dynamic_params = log_cholesky.toDynamicParameters();
607  return FromDynamicParameters(dynamic_params);
608  }
609 
610  // Arithmetic operators
612  {
613  mass() = clone.mass();
614  lever() = clone.lever();
615  inertia() = clone.inertia();
616  return *this;
617  }
618 
619  // Required by std::vector boost::python bindings.
620  bool isEqual(const InertiaTpl & Y2) const
621  {
622  return (mass() == Y2.mass()) && (lever() == Y2.lever()) && (inertia() == Y2.inertia());
623  }
624 
626  const InertiaTpl & other,
627  const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
628  {
629  using math::fabs;
630  return fabs(static_cast<Scalar>(mass() - other.mass())) <= prec
631  && lever().isApprox(other.lever(), prec) && inertia().isApprox(other.inertia(), prec);
632  }
633 
634  bool isZero_impl(const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
635  {
636  using math::fabs;
637  return fabs(mass()) <= prec && lever().isZero(prec) && inertia().isZero(prec);
638  }
639 
640  InertiaTpl __plus__(const InertiaTpl & Yb) const
641  {
642  /* Y_{a+b} = ( m_a+m_b,
643  * (m_a*c_a + m_b*c_b ) / (m_a + m_b),
644  * I_a + I_b - (m_a*m_b)/(m_a+m_b) * AB_x * AB_x )
645  */
646 
647  const Scalar eps = ::Eigen::NumTraits<Scalar>::epsilon();
648 
649  const Scalar & mab = mass() + Yb.mass();
650  const Scalar mab_inv = Scalar(1) / math::max(mab, eps);
651  const Vector3 & AB = (lever() - Yb.lever()).eval();
652  return InertiaTpl(
653  mab, (mass() * lever() + Yb.mass() * Yb.lever()) * mab_inv,
654  inertia() + Yb.inertia()
655  - (mass() * Yb.mass() * mab_inv) * typename Symmetric3::SkewSquare(AB));
656  }
657 
659  {
660  static const Scalar eps = ::Eigen::NumTraits<Scalar>::epsilon();
661 
662  const InertiaTpl & Ya = *this;
663  const Scalar & mab = mass() + Yb.mass();
664  const Scalar mab_inv = Scalar(1) / math::max(mab, eps);
665  const Vector3 & AB = (Ya.lever() - Yb.lever()).eval();
666  lever() *= (mass() * mab_inv);
667  lever() += (Yb.mass() * mab_inv) * Yb.lever(); // c *= mab_inv;
668  inertia() += Yb.inertia();
669  inertia() -= (Ya.mass() * Yb.mass() * mab_inv) * typename Symmetric3::SkewSquare(AB);
670  mass() = mab;
671  return *this;
672  }
673 
674  InertiaTpl __minus__(const InertiaTpl & Yb) const
675  {
676  /* Y_{a} = ( m_{a+b}+m_b,
677  * (m_{a+b}*c_{a+b} - m_b*c_b ) / (m_a),
678  * I_{a+b} - I_b + (m_a*m_b)/(m_a+m_b) * AB_x * AB_x )
679  */
680 
681  const Scalar eps = ::Eigen::NumTraits<Scalar>::epsilon();
682 
683  const Scalar ma = mass() - Yb.mass();
684  assert(check_expression_if_real<Scalar>(ma >= Scalar(0)));
685 
686  const Scalar ma_inv = Scalar(1) / math::max(ma, eps);
687  const Vector3 c_a((mass() * lever() - Yb.mass() * Yb.lever()) * ma_inv);
688 
689  const Vector3 AB = c_a - Yb.lever();
690 
691  return InertiaTpl(
692  ma, c_a,
693  inertia() - Yb.inertia() + (ma * Yb.mass() / mass()) * typename Symmetric3::SkewSquare(AB));
694  }
695 
697  {
698  static const Scalar eps = ::Eigen::NumTraits<Scalar>::epsilon();
699 
700  const Scalar ma = mass() - Yb.mass();
701  assert(check_expression_if_real<Scalar>(ma >= Scalar(0)));
702 
703  const Scalar ma_inv = Scalar(1) / math::max(ma, eps);
704 
705  lever() *= (mass() * ma_inv);
706  lever().noalias() -= (Yb.mass() * ma_inv) * Yb.lever();
707 
708  const Vector3 AB = lever() - Yb.lever();
709  inertia() -= Yb.inertia();
710  inertia() += (ma * Yb.mass() / mass()) * typename Symmetric3::SkewSquare(AB);
711  mass() = ma;
712 
713  return *this;
714  }
715 
716  template<typename MotionDerived>
719  {
721  ReturnType;
722  ReturnType f;
723  __mult__(v, f);
724  return f;
725  }
726 
727  template<typename MotionDerived, typename ForceDerived>
729  {
730  f.linear().noalias() = mass() * (v.linear() - lever().cross(v.angular()));
731  Symmetric3::rhsMult(inertia(), v.angular(), f.angular());
732  f.angular() += lever().cross(f.linear());
733  // f.angular().noalias() = c.cross(f.linear()) + I*v.angular();
734  }
735 
736  template<typename MotionDerived>
738  {
739  const Vector3 cxw(lever().cross(v.angular()));
740  Scalar res = mass() * (v.linear().squaredNorm() - Scalar(2) * v.linear().dot(cxw));
741  const Vector3 mcxcxw(-mass() * lever().cross(cxw));
742  res += v.angular().dot(mcxcxw);
743  res += inertia().vtiv(v.angular());
744 
745  return res;
746  }
747 
748  template<typename MotionDerived>
749  Matrix6 variation(const MotionDense<MotionDerived> & v) const
750  {
751  Matrix6 res;
752  const Motion mv(v * mass());
753 
754  res.template block<3, 3>(LINEAR, ANGULAR) =
755  -skew(mv.linear()) - skewSquare(mv.angular(), lever()) + skewSquare(lever(), mv.angular());
756  res.template block<3, 3>(ANGULAR, LINEAR) =
757  res.template block<3, 3>(LINEAR, ANGULAR).transpose();
758 
759  // res.template block<3,3>(LINEAR,LINEAR) = mv.linear()*c.transpose(); // use as
760  // temporary variable res.template block<3,3>(ANGULAR,ANGULAR) = res.template
761  // block<3,3>(LINEAR,LINEAR) - res.template block<3,3>(LINEAR,LINEAR).transpose();
762  res.template block<3, 3>(ANGULAR, ANGULAR) =
763  -skewSquare(mv.linear(), lever()) - skewSquare(lever(), mv.linear());
764 
765  res.template block<3, 3>(LINEAR, LINEAR) =
766  (inertia() - AlphaSkewSquare(mass(), lever())).matrix();
767 
768  res.template block<3, 3>(ANGULAR, ANGULAR) -=
769  res.template block<3, 3>(LINEAR, LINEAR) * skew(v.angular());
770  res.template block<3, 3>(ANGULAR, ANGULAR) +=
771  cross(v.angular(), res.template block<3, 3>(LINEAR, LINEAR));
772 
773  res.template block<3, 3>(LINEAR, LINEAR).setZero();
774  return res;
775  }
776 
777  template<typename MotionDerived, typename M6>
778  static void vxi_impl(
780  const InertiaTpl & I,
781  const Eigen::MatrixBase<M6> & Iout)
782  {
783  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6, 6, 6);
784  M6 & Iout_ = PINOCCHIO_EIGEN_CONST_CAST(M6, Iout);
785 
786  // Block 1,1
787  alphaSkew(I.mass(), v.angular(), Iout_.template block<3, 3>(LINEAR, LINEAR));
788  // Iout_.template block<3,3>(LINEAR,LINEAR) = alphaSkew(I.mass(),v.angular());
789  const Vector3 mc(I.mass() * I.lever());
790 
791  // Block 1,2
792  skewSquare(-v.angular(), mc, Iout_.template block<3, 3>(LINEAR, ANGULAR));
793 
795  alphaSkew(I.mass(), v.linear(), Iout_.template block<3, 3>(ANGULAR, LINEAR));
796  Iout_.template block<3, 3>(ANGULAR, LINEAR) -= Iout_.template block<3, 3>(LINEAR, ANGULAR);
797 
799  skewSquare(-v.linear(), mc, Iout_.template block<3, 3>(ANGULAR, ANGULAR));
800 
801  // TODO: I do not why, but depending on the CPU, these three lines can give
802  // wrong output.
803  // typename Symmetric3::AlphaSkewSquare mcxcx(I.mass(),I.lever());
804  // const Symmetric3 I_mcxcx(I.inertia() - mcxcx);
805  // Iout_.template block<3,3>(ANGULAR,ANGULAR) += I_mcxcx.vxs(v.angular());
806  Symmetric3 mcxcx(typename Symmetric3::AlphaSkewSquare(I.mass(), I.lever()));
807  Iout_.template block<3, 3>(ANGULAR, ANGULAR) += I.inertia().vxs(v.angular());
808  Iout_.template block<3, 3>(ANGULAR, ANGULAR) -= mcxcx.vxs(v.angular());
809  }
810 
811  template<typename MotionDerived, typename M6>
812  static void ivx_impl(
814  const InertiaTpl & I,
815  const Eigen::MatrixBase<M6> & Iout)
816  {
817  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6, 6, 6);
818  M6 & Iout_ = PINOCCHIO_EIGEN_CONST_CAST(M6, Iout);
819 
820  // Block 1,1
821  alphaSkew(I.mass(), v.angular(), Iout_.template block<3, 3>(LINEAR, LINEAR));
822 
823  // Block 2,1
824  const Vector3 mc(I.mass() * I.lever());
825  skewSquare(mc, v.angular(), Iout_.template block<3, 3>(ANGULAR, LINEAR));
826 
827  // Block 1,2
828  alphaSkew(I.mass(), v.linear(), Iout_.template block<3, 3>(LINEAR, ANGULAR));
829 
830  // Block 2,2
831  cross(
832  -I.lever(), Iout_.template block<3, 3>(ANGULAR, LINEAR),
833  Iout_.template block<3, 3>(ANGULAR, ANGULAR));
834  Iout_.template block<3, 3>(ANGULAR, ANGULAR) += I.inertia().svx(v.angular());
835  for (int k = 0; k < 3; ++k)
836  Iout_.template block<3, 3>(ANGULAR, ANGULAR).col(k) +=
837  I.lever().cross(Iout_.template block<3, 3>(LINEAR, ANGULAR).col(k));
838 
839  // Block 1,2
840  Iout_.template block<3, 3>(LINEAR, ANGULAR) -= Iout_.template block<3, 3>(ANGULAR, LINEAR);
841  }
842 
843  // Getters
844  Scalar mass() const
845  {
846  return m_mass;
847  }
848  const Vector3 & lever() const
849  {
850  return m_com;
851  }
852  const Symmetric3 & inertia() const
853  {
854  return m_inertia;
855  }
856 
858  {
859  return m_mass;
860  }
862  {
863  return m_com;
864  }
866  {
867  return m_inertia;
868  }
869 
871  template<typename S2, int O2>
873  {
874  /* The multiplication RIR' has a particular form that could be used, however it
875  * does not seems to be more efficient, see http://stackoverflow.m_comom/questions/
876  * 13215467/eigen-best-way-to-evaluate-asa-transpose-and-store-the-result-in-a-symmetric .*/
877  return InertiaTpl(
878  mass(), M.translation() + M.rotation() * lever(), inertia().rotate(M.rotation()));
879  }
880 
882  template<typename S2, int O2>
884  {
885  return InertiaTpl(
886  mass(), M.rotation().transpose() * (lever() - M.translation()),
887  inertia().rotate(M.rotation().transpose()));
888  }
889 
890  template<typename MotionDerived>
892  {
893  const Vector3 & mcxw = mass() * lever().cross(v.angular());
894  const Vector3 & mv_mcxw = mass() * v.linear() - mcxw;
895  return Force(
896  v.angular().cross(mv_mcxw),
897  v.angular().cross(lever().cross(mv_mcxw) + inertia() * v.angular())
898  - v.linear().cross(mcxw));
899  }
900 
901  void disp_impl(std::ostream & os) const
902  {
903  os << " m = " << mass() << "\n"
904  << " c = " << lever().transpose() << "\n"
905  << " I = \n"
906  << inertia().matrix() << "";
907  }
908 
910  template<typename NewScalar>
912  {
914  pinocchio::cast<NewScalar>(mass()), lever().template cast<NewScalar>(),
915  inertia().template cast<NewScalar>());
916  }
917 
918  // TODO: adjust code
919  // /// \brief Check whether *this is a valid inertia, resulting from a positive mass
920  // distribution bool isValid() const
921  // {
922  // return
923  // (m_mass > Scalar(0) && m_inertia.isValid())
924  // || (m_mass == Scalar(0) && (m_inertia.data().array() == Scalar(0)).all());
925  // }
926 
927  protected:
931 
932  }; // class InertiaTpl
933 
942  template<typename _Scalar, int _Options>
943  struct PseudoInertiaTpl
944  {
945  typedef _Scalar Scalar;
946  enum
947  {
948  Options = _Options,
949  };
950  typedef Eigen::Matrix<Scalar, 4, 4, Options> Matrix4;
951  typedef Eigen::Matrix<Scalar, 3, 1, Options> Vector3;
952  typedef Eigen::Matrix<Scalar, 3, 3, Options> Matrix3;
953  typedef Eigen::Matrix<Scalar, 10, 1, Options> Vector10;
955 
959 
961  : mass(mass)
962  , h(h)
963  , sigma(sigma)
964  {
965  }
966 
972  {
973  Matrix4 pseudo_inertia = Matrix4::Zero();
974  pseudo_inertia.template block<3, 3>(0, 0) = sigma;
975  pseudo_inertia.template block<3, 1>(0, 3) = h;
976  pseudo_inertia.template block<1, 3>(3, 0) = h.transpose();
977  pseudo_inertia(3, 3) = mass;
978  return pseudo_inertia;
979  }
980 
986  static PseudoInertiaTpl FromMatrix(const Matrix4 & pseudo_inertia)
987  {
988  Scalar mass = pseudo_inertia(3, 3);
989  Vector3 h = pseudo_inertia.template block<3, 1>(0, 3);
990  Matrix3 sigma = pseudo_inertia.template block<3, 3>(0, 0);
991  return PseudoInertiaTpl(mass, h, sigma);
992  }
993 
999  template<typename Vector10Like>
1000  static PseudoInertiaTpl
1001  FromDynamicParameters(const Eigen::MatrixBase<Vector10Like> & dynamic_params)
1002  {
1003  PINOCCHIO_ASSERT_MATRIX_SPECIFIC_SIZE(Vector10Like, dynamic_params, 10, 1);
1004  Scalar mass = dynamic_params[0];
1005  Vector3 h = dynamic_params.template segment<3>(1);
1006  Matrix3 I_bar;
1007  // clang-format off
1008  I_bar << dynamic_params[4], dynamic_params[5], dynamic_params[7],
1009  dynamic_params[5], dynamic_params[6], dynamic_params[8],
1010  dynamic_params[7], dynamic_params[8], dynamic_params[9];
1011  // clang-format on
1012 
1013  Matrix3 sigma = 0.5 * I_bar.trace() * Matrix3::Identity() - I_bar;
1014  return PseudoInertiaTpl(mass, h, sigma);
1015  }
1016 
1022  {
1023  Matrix3 I_bar = sigma.trace() * Matrix3::Identity() - sigma;
1024 
1025  Vector10 dynamic_params;
1026  dynamic_params[0] = mass;
1027  dynamic_params.template segment<3>(1) = h;
1028  dynamic_params[4] = I_bar(0, 0);
1029  dynamic_params[5] = I_bar(0, 1);
1030  dynamic_params[6] = I_bar(1, 1);
1031  dynamic_params[7] = I_bar(0, 2);
1032  dynamic_params[8] = I_bar(1, 2);
1033  dynamic_params[9] = I_bar(2, 2);
1034 
1035  return dynamic_params;
1036  }
1037 
1044  {
1045  Vector10 dynamic_params = inertia.toDynamicParameters();
1046  return FromDynamicParameters(dynamic_params);
1047  }
1048 
1054  {
1055  Vector10 dynamic_params = toDynamicParameters();
1057  }
1058 
1065  {
1066  Vector10 dynamic_params = log_cholesky.toDynamicParameters();
1067  return FromDynamicParameters(dynamic_params);
1068  }
1069 
1071  template<typename NewScalar>
1073  {
1075  pinocchio::cast<NewScalar>(mass), h.template cast<NewScalar>(),
1076  sigma.template cast<NewScalar>());
1077  }
1078 
1079  void disp_impl(std::ostream & os) const
1080  {
1081  os << " m = " << mass << "\n"
1082  << " h = " << h.transpose() << "\n"
1083  << " sigma = \n"
1084  << sigma << "";
1085  }
1086 
1087  friend std::ostream & operator<<(std::ostream & os, const PseudoInertiaTpl & pi)
1088  {
1089  pi.disp_impl(os);
1090  return os;
1091  }
1092  };
1093 
1101  template<typename _Scalar, int _Options>
1102  struct LogCholeskyParametersTpl
1103  {
1104  typedef _Scalar Scalar;
1105  enum
1106  {
1107  Options = _Options,
1108  };
1109  typedef Eigen::Matrix<Scalar, 10, 1, Options> Vector10;
1110  typedef Eigen::Matrix<Scalar, 10, 10, Options> Matrix10;
1112 
1114 
1118  explicit LogCholeskyParametersTpl(const Vector10 & log_cholesky)
1119  : parameters(log_cholesky)
1120  {
1121  }
1127  {
1128  using math::exp;
1129  using math::pow;
1130 
1131  // clang-format off
1132  Vector10 dynamic_params;
1133 
1134  const Scalar alpha = parameters[0];
1135  const Scalar d1 = parameters[1];
1136  const Scalar d2 = parameters[2];
1137  const Scalar d3 = parameters[3];
1138  const Scalar s12 = parameters[4];
1139  const Scalar s23 = parameters[5];
1140  const Scalar s13 = parameters[6];
1141  const Scalar t1 = parameters[7];
1142  const Scalar t2 = parameters[8];
1143  const Scalar t3 = parameters[9];
1144 
1145  const Scalar exp_d1 = exp(d1);
1146  const Scalar exp_d2 = exp(d2);
1147  const Scalar exp_d3 = exp(d3);
1148 
1149  dynamic_params[0] = 1;
1150  dynamic_params[1] = t1;
1151  dynamic_params[2] = t2;
1152  dynamic_params[3] = t3;
1153  dynamic_params[4] = pow(s23, 2) + pow(t2, 2) + pow(t3, 2) + pow(exp_d2, 2) + pow(exp_d3, 2);
1154  dynamic_params[5] = -s12 * exp_d2 - s13 * s23 - t1 * t2;
1155  dynamic_params[6] = pow(s12, 2) + pow(s13, 2) + pow(t1, 2) + pow(t3, 2) + pow(exp_d1, 2) + pow(exp_d3, 2);
1156  dynamic_params[7] = -s13 * exp_d3 - t1 * t3;
1157  dynamic_params[8] = -s23 * exp_d3 - t2 * t3;
1158  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);
1159 
1160  const Scalar exp_2_alpha = exp(2 * alpha);
1161  dynamic_params *= exp_2_alpha;
1162  // clang-format on
1163 
1164  return dynamic_params;
1165  }
1166 
1172  {
1173  Vector10 dynamic_params = toDynamicParameters();
1174  return PseudoInertia::FromDynamicParameters(dynamic_params);
1175  }
1176 
1182  {
1183  Vector10 dynamic_params = toDynamicParameters();
1185  }
1186 
1192  {
1193  using math::exp;
1194  using math::pow;
1195 
1196  Matrix10 jacobian = Matrix10::Zero();
1197 
1198  const Scalar alpha = parameters[0];
1199  const Scalar d1 = parameters[1];
1200  const Scalar d2 = parameters[2];
1201  const Scalar d3 = parameters[3];
1202  const Scalar s12 = parameters[4];
1203  const Scalar s23 = parameters[5];
1204  const Scalar s13 = parameters[6];
1205  const Scalar t1 = parameters[7];
1206  const Scalar t2 = parameters[8];
1207  const Scalar t3 = parameters[9];
1208 
1209  const Scalar exp_2alpha = exp(2 * alpha);
1210  const Scalar exp_2d1 = exp(2 * d1);
1211  const Scalar exp_2d2 = exp(2 * d2);
1212  const Scalar exp_2d3 = exp(2 * d3);
1213  const Scalar exp_d1 = exp(d1);
1214  const Scalar exp_d2 = exp(d2);
1215  const Scalar exp_d3 = exp(d3);
1216 
1217  // clang-format off
1218  jacobian(0, 0) = 2 * exp_2alpha;
1219 
1220  jacobian(1, 0) = 2 * t1 * exp_2alpha;
1221  jacobian(1, 7) = exp_2alpha;
1222 
1223  jacobian(2, 0) = 2 * t2 * exp_2alpha;
1224  jacobian(2, 8) = exp_2alpha;
1225 
1226  jacobian(3, 0) = 2 * t3 * exp_2alpha;
1227  jacobian(3, 9) = exp_2alpha;
1228 
1229  jacobian(4, 0) = 2 * (pow(s23, 2) + pow(t2, 2) + pow(t3, 2) + exp_2d2 + exp_2d3) * exp_2alpha;
1230  jacobian(4, 2) = 2 * exp_2alpha * exp_2d2;
1231  jacobian(4, 3) = 2 * exp_2alpha * exp_2d3;
1232  jacobian(4, 5) = 2 * s23 * exp_2alpha;
1233  jacobian(4, 8) = 2 * t2 * exp_2alpha;
1234  jacobian(4, 9) = 2 * t3 * exp_2alpha;
1235 
1236  jacobian(5, 0) = -2 * (s12 * exp_d2 + s13 * s23 + t1 * t2) * exp_2alpha;
1237  jacobian(5, 2) = -s12 * exp_2alpha * exp_d2;
1238  jacobian(5, 4) = -exp_2alpha * exp_d2;
1239  jacobian(5, 5) = -s13 * exp_2alpha;
1240  jacobian(5, 6) = -s23 * exp_2alpha;
1241  jacobian(5, 7) = -t2 * exp_2alpha;
1242  jacobian(5, 8) = -t1 * exp_2alpha;
1243 
1244  jacobian(6, 0) = 2 * (pow(s12, 2) + pow(s13, 2) + pow(t1, 2) + pow(t3, 2) + exp_2d1 + exp_2d3) * exp_2alpha;
1245  jacobian(6, 1) = 2 * exp_2alpha * exp_2d1;
1246  jacobian(6, 3) = 2 * exp_2alpha * exp_2d3;
1247  jacobian(6, 4) = 2 * s12 * exp_2alpha;
1248  jacobian(6, 6) = 2 * s13 * exp_2alpha;
1249  jacobian(6, 7) = 2 * t1 * exp_2alpha;
1250  jacobian(6, 9) = 2 * t3 * exp_2alpha;
1251 
1252  jacobian(7, 0) = -2 * (s13 * exp_d3 + t1 * t3) * exp_2alpha;
1253  jacobian(7, 3) = -s13 * exp_2alpha * exp_d3;
1254  jacobian(7, 6) = -exp_2alpha * exp_d3;
1255  jacobian(7, 7) = -t3 * exp_2alpha;
1256  jacobian(7, 9) = -t1 * exp_2alpha;
1257 
1258  jacobian(8, 0) = -2 * (s23 * exp_d3 + t2 * t3) * exp_2alpha;
1259  jacobian(8, 3) = -s23 * exp_2alpha * exp_d3;
1260  jacobian(8, 5) = -exp_2alpha * exp_d3;
1261  jacobian(8, 8) = -t3 * exp_2alpha;
1262  jacobian(8, 9) = -t2 * exp_2alpha;
1263 
1264  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;
1265  jacobian(9, 1) = 2 * exp_2alpha * exp_2d1;
1266  jacobian(9, 2) = 2 * exp_2alpha * exp_2d2;
1267  jacobian(9, 4) = 2 * s12 * exp_2alpha;
1268  jacobian(9, 5) = 2 * s23 * exp_2alpha;
1269  jacobian(9, 6) = 2 * s13 * exp_2alpha;
1270  jacobian(9, 7) = 2 * t1 * exp_2alpha;
1271  jacobian(9, 8) = 2 * t2 * exp_2alpha;
1272  // clang-format on
1273 
1274  return jacobian;
1275  }
1276 
1278  template<typename NewScalar>
1280  {
1281  return LogCholeskyParametersTpl<NewScalar, Options>(parameters.template cast<NewScalar>());
1282  }
1283 
1284  void disp_impl(std::ostream & os) const
1285  {
1286  os << " alpha: " << parameters[0] << "\n"
1287  << " d1: " << parameters[1] << "\n"
1288  << " d2: " << parameters[2] << "\n"
1289  << " d3: " << parameters[3] << "\n"
1290  << " s12: " << parameters[4] << "\n"
1291  << " s23: " << parameters[5] << "\n"
1292  << " s13: " << parameters[6] << "\n"
1293  << " t1: " << parameters[7] << "\n"
1294  << " t2: " << parameters[8] << "\n"
1295  << " t3: " << parameters[9] << "";
1296  }
1297 
1298  friend std::ostream & operator<<(std::ostream & os, const LogCholeskyParametersTpl & lcp)
1299  {
1300  lcp.disp_impl(os);
1301  return os;
1302  }
1303  };
1304 
1305 } // namespace pinocchio
1306 
1307 #endif // ifndef __pinocchio_spatial_inertia_hpp__
simulation-contact-dynamics.T
int T
Definition: simulation-contact-dynamics.py:89
pinocchio::InertiaTpl
Definition: spatial/fwd.hpp:58
pinocchio::PseudoInertiaTpl
A structure representing a pseudo inertia matrix.
Definition: spatial/fwd.hpp:62
pinocchio::traits< InertiaTpl< T, U > >::ConstAngular_t
const typedef Vector3 ConstAngular_t
Definition: spatial/inertia.hpp:247
pinocchio::InertiaTpl::isEqual
bool isEqual(const InertiaTpl &Y2) const
Definition: spatial/inertia.hpp:620
pinocchio::InertiaBase::operator-
Derived operator-(const Derived &Yb) const
Definition: spatial/inertia.hpp:110
pinocchio::InertiaTpl::vxi_impl
static void vxi_impl(const MotionDense< MotionDerived > &v, const InertiaTpl &I, const Eigen::MatrixBase< M6 > &Iout)
Definition: spatial/inertia.hpp:778
pinocchio::LogCholeskyParametersTpl::LogCholeskyParametersTpl
LogCholeskyParametersTpl(const Vector10 &log_cholesky)
Constructor for LogCholeskyParametersTpl.
Definition: spatial/inertia.hpp:1118
pinocchio::InertiaTpl::m_com
Vector3 m_com
Definition: spatial/inertia.hpp:929
pinocchio::PseudoInertiaTpl::FromLogCholeskyParameters
static PseudoInertiaTpl FromLogCholeskyParameters(const LogCholeskyParameters &log_cholesky)
Constructs a PseudoInertiaTpl object from log Cholesky parameters.
Definition: spatial/inertia.hpp:1064
pinocchio::InertiaTpl::__plus__
InertiaTpl __plus__(const InertiaTpl &Yb) const
Definition: spatial/inertia.hpp:640
pinocchio::NumericalBase
Definition: fwd.hpp:89
pinocchio::Symmetric3
Symmetric3Tpl< context::Scalar, context::Options > Symmetric3
Definition: spatial/fwd.hpp:70
pinocchio::InertiaTpl::__mequ__
InertiaTpl & __mequ__(const InertiaTpl &Yb)
Definition: spatial/inertia.hpp:696
pinocchio::InertiaTpl::FromEllipsoid
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,...
Definition: spatial/inertia.hpp:389
pinocchio::InertiaBase::setRandom
void setRandom()
Definition: spatial/inertia.hpp:190
pinocchio::PseudoInertiaTpl::h
Vector3 h
Vector part of the pseudo inertia.
Definition: spatial/inertia.hpp:957
pinocchio::traits< InertiaTpl< T, U > >::Scalar
T Scalar
Definition: spatial/inertia.hpp:236
pinocchio::Symmetric3Tpl::vxs
static void vxs(const Eigen::MatrixBase< Vector3 > &v, const Symmetric3Tpl &S3, const Eigen::MatrixBase< Matrix3 > &M)
Performs the operation . This operation is equivalent to applying the cross product of v on each colu...
Definition: spatial/symmetric3.hpp:351
pinocchio::InertiaBase::inverse
Matrix6 inverse() const
Definition: spatial/inertia.hpp:80
d1
float d1
pinocchio::InertiaBase::mass
Scalar mass() const
Definition: spatial/inertia.hpp:36
pinocchio::InertiaTpl::setZero
void setZero()
Definition: spatial/inertia.hpp:342
pinocchio::InertiaTpl::lever
const Vector3 & lever() const
Definition: spatial/inertia.hpp:848
pinocchio::traits< InertiaTpl< T, U > >::ConstLinear_t
const typedef Vector3 ConstLinear_t
Definition: spatial/inertia.hpp:248
pinocchio::PseudoInertiaTpl::Vector10
Eigen::Matrix< Scalar, 10, 1, Options > Vector10
Definition: spatial/inertia.hpp:953
pinocchio::LogCholeskyParametersTpl::Vector10
Eigen::Matrix< Scalar, 10, 1, Options > Vector10
Definition: spatial/inertia.hpp:1109
pinocchio::InertiaTpl::lever
Vector3 & lever()
Definition: spatial/inertia.hpp:861
pinocchio::InertiaTpl::variation
Matrix6 variation(const MotionDense< MotionDerived > &v) const
Definition: spatial/inertia.hpp:749
pinocchio::InertiaBase::vxi
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...
Definition: spatial/inertia.hpp:144
pinocchio::isZero
bool isZero(const Eigen::MatrixBase< MatrixLike > &m, const typename MatrixLike::RealScalar &prec=Eigen::NumTraits< typename MatrixLike::Scalar >::dummy_precision())
Definition: math/matrix.hpp:59
pinocchio::InertiaTpl::PseudoInertia
PseudoInertiaTpl< Scalar, Options > PseudoInertia
Definition: spatial/inertia.hpp:277
pinocchio::InertiaTpl::FromPseudoInertia
static InertiaTpl FromPseudoInertia(const PseudoInertia &pseudo_inertia)
Create an InertiaTpl object from a PseudoInertia object.
Definition: spatial/inertia.hpp:581
y
y
pinocchio::InertiaBase::derived
const Derived & derived() const
Definition: spatial/inertia.hpp:26
pinocchio.explog.exp
def exp(x)
Definition: bindings/python/pinocchio/explog.py:13
pinocchio::InertiaTpl::__minus__
InertiaTpl __minus__(const InertiaTpl &Yb) const
Definition: spatial/inertia.hpp:674
pinocchio::PseudoInertiaTpl::cast
PseudoInertiaTpl< NewScalar, Options > cast() const
Definition: spatial/inertia.hpp:1072
c
Vec3f c
PINOCCHIO_EIGEN_CONST_CAST
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
Definition: eigen-macros.hpp:51
pinocchio::SE3Tpl
Definition: context/casadi.hpp:29
pinocchio::InertiaTpl::InertiaTpl
InertiaTpl(const Scalar &mass, const Vector3 &com, const Matrix3 &rotational_inertia)
Definition: spatial/inertia.hpp:285
pinocchio::PseudoInertiaTpl::toDynamicParameters
Vector10 toDynamicParameters() const
Converts the PseudoInertiaTpl object to dynamic parameters.
Definition: spatial/inertia.hpp:1021
pinocchio::InertiaBase::operator==
bool operator==(const Derived &other) const
Definition: spatial/inertia.hpp:89
pinocchio::PseudoInertiaTpl::toInertia
InertiaTpl< Scalar, Options > toInertia() const
Converts the PseudoInertiaTpl object to an InertiaTpl object.
Definition: spatial/inertia.hpp:1053
pinocchio::InertiaTpl::InertiaTpl
InertiaTpl(const InertiaTpl &clone)
Definition: spatial/inertia.hpp:315
pinocchio::InertiaTpl::InertiaTpl
InertiaTpl(const InertiaTpl< S2, O2 > &clone)
Definition: spatial/inertia.hpp:331
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::NumericalBase::Scalar
traits< Derived >::Scalar Scalar
Definition: fwd.hpp:91
pinocchio::LogCholeskyParametersTpl::toPseudoInertia
PseudoInertia toPseudoInertia() const
Converts the LogCholeskyParametersTpl object to a PseudoInertiaTpl object.
Definition: spatial/inertia.hpp:1171
pinocchio::InertiaBase::ivx
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...
Definition: spatial/inertia.hpp:168
pinocchio::Symmetric3Tpl::isApprox
bool isApprox(const Symmetric3Tpl &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Definition: spatial/symmetric3.hpp:146
pinocchio::LogCholeskyParametersTpl::parameters
Vector10 parameters
10-dimensional vector of log Cholesky parameters
Definition: spatial/inertia.hpp:1113
pinocchio::InertiaTpl::ivx_impl
static void ivx_impl(const MotionDense< MotionDerived > &v, const InertiaTpl &I, const Eigen::MatrixBase< M6 > &Iout)
Definition: spatial/inertia.hpp:812
pinocchio::InertiaBase::operator=
Derived & operator=(const Derived &clone)
Definition: spatial/inertia.hpp:85
rotate
Vec3f rotate(Vec3f input, FCL_REAL w, Vec3f vec)
pinocchio::MotionDense
Definition: context/casadi.hpp:36
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::PseudoInertiaTpl::LogCholeskyParameters
LogCholeskyParametersTpl< Scalar, Options > LogCholeskyParameters
Definition: spatial/inertia.hpp:954
pinocchio::InertiaBase::matrix
void matrix(const Eigen::MatrixBase< Matrix6Like > &mat) const
Definition: spatial/inertia.hpp:62
pinocchio::InertiaTpl::vxiv
Force vxiv(const MotionDense< MotionDerived > &v) const
Definition: spatial/inertia.hpp:891
pinocchio::InertiaBase::matrix
Matrix6 matrix() const
Definition: spatial/inertia.hpp:66
pinocchio::res
ReturnType res
Definition: spatial/classic-acceleration.hpp:57
pinocchio::InertiaTpl::inverse_impl
void inverse_impl(const Eigen::MatrixBase< Matrix6Like > &M_) const
Definition: spatial/inertia.hpp:500
pinocchio::Symmetric3Tpl::setRandom
void setRandom()
Definition: spatial/symmetric3.hpp:105
motion.hpp
autodiff-rnea.f
f
Definition: autodiff-rnea.py:24
pinocchio::InertiaTpl::isZero_impl
bool isZero_impl(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Definition: spatial/inertia.hpp:634
pinocchio::PseudoInertiaTpl::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: spatial/inertia.hpp:951
pinocchio::PseudoInertiaTpl::Matrix3
Eigen::Matrix< Scalar, 3, 3, Options > Matrix3
Definition: spatial/inertia.hpp:952
b
Vec3f b
pinocchio::traits< InertiaTpl< T, U > >::PseudoInertia
PseudoInertiaTpl< T, U > PseudoInertia
Definition: spatial/inertia.hpp:254
pinocchio::Symmetric3Tpl::vtiv
Scalar vtiv(const Vector3 &v) const
Definition: spatial/symmetric3.hpp:323
pinocchio::InertiaTpl::isApprox_impl
bool isApprox_impl(const InertiaTpl &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Definition: spatial/inertia.hpp:625
skew.hpp
pinocchio::InertiaTpl::toPseudoInertia
PseudoInertia toPseudoInertia() const
Convert the InertiaTpl object to a 4x4 pseudo inertia matrix.
Definition: spatial/inertia.hpp:591
height
FCL_REAL height() const
pinocchio::InertiaBase::operator+=
Derived & operator+=(const Derived &Yb)
Definition: spatial/inertia.hpp:98
pinocchio::InertiaBase::se3Action
Derived se3Action(const SE3Tpl< S2, O2 > &M) const
aI = aXb.act(bI)
Definition: spatial/inertia.hpp:209
pinocchio::InertiaTpl::Zero
static InertiaTpl Zero()
Definition: spatial/inertia.hpp:337
pinocchio::PseudoInertiaTpl::disp_impl
void disp_impl(std::ostream &os) const
Definition: spatial/inertia.hpp:1079
pinocchio::LogCholeskyParametersTpl::Scalar
_Scalar Scalar
Definition: spatial/inertia.hpp:1104
pinocchio::PseudoInertiaTpl::operator<<
friend std::ostream & operator<<(std::ostream &os, const PseudoInertiaTpl &pi)
Definition: spatial/inertia.hpp:1087
pinocchio::traits< InertiaTpl< T, U > >::Matrix3
Eigen::Matrix< T, 3, 3, U > Matrix3
Definition: spatial/inertia.hpp:240
pinocchio::InertiaBase::operator+
Derived operator+(const Derived &Yb) const
Definition: spatial/inertia.hpp:102
pinocchio::traits< InertiaTpl< T, U > >::ActionMatrix_t
Matrix6 ActionMatrix_t
Definition: spatial/inertia.hpp:244
pinocchio::PseudoInertiaTpl::sigma
Matrix3 sigma
3x3 matrix part of the pseudo inertia
Definition: spatial/inertia.hpp:958
pinocchio::InertiaBase::mass
Scalar & mass()
Definition: spatial/inertia.hpp:40
pinocchio::InertiaBase::se3ActionInverse
Derived se3ActionInverse(const SE3Tpl< S2, O2 > &M) const
bI = aXb.actInv(aI)
Definition: spatial/inertia.hpp:216
reachable-workspace-with-collisions.alpha
float alpha
Definition: reachable-workspace-with-collisions.py:162
pinocchio::InertiaTpl::mass
Scalar & mass()
Definition: spatial/inertia.hpp:857
pinocchio::PseudoInertiaTpl::mass
Scalar mass
Mass of the pseudo inertia.
Definition: spatial/inertia.hpp:956
pinocchio::InertiaTpl::inertia
const Symmetric3 & inertia() const
Definition: spatial/inertia.hpp:852
pinocchio::InertiaTpl::m_inertia
Symmetric3 m_inertia
Definition: spatial/inertia.hpp:930
pinocchio::InertiaTpl::Options
@ Options
Definition: spatial/inertia.hpp:271
pinocchio::InertiaBase::operator!=
bool operator!=(const Derived &other) const
Definition: spatial/inertia.hpp:93
pinocchio::InertiaBase::derived
Derived & derived()
Definition: spatial/inertia.hpp:22
pinocchio::InertiaTpl::mass
Scalar mass() const
Definition: spatial/inertia.hpp:844
pinocchio::InertiaTpl::FromLogCholeskyParameters
static InertiaTpl FromLogCholeskyParameters(const LogCholeskyParameters &log_cholesky)
Create an InertiaTpl object from log Cholesky parameters.
Definition: spatial/inertia.hpp:604
pinocchio::InertiaBase::lever
Vector3 & lever()
Definition: spatial/inertia.hpp:48
pinocchio::traits< InertiaTpl< T, U > >::Vector6
Eigen::Matrix< T, 6, 1, U > Vector6
Definition: spatial/inertia.hpp:239
pinocchio::InertiaTpl::setRandom
void setRandom()
Definition: spatial/inertia.hpp:472
pinocchio::InertiaTpl::inertia
Symmetric3 & inertia()
Definition: spatial/inertia.hpp:865
pinocchio::traits< InertiaTpl< T, U > >::Force
ForceTpl< T, U > Force
Definition: spatial/inertia.hpp:251
pinocchio::InertiaBase::variation
Matrix6 variation(const MotionDense< MotionDerived > &v) const
Definition: spatial/inertia.hpp:129
t2
dictionary t2
pinocchio::traits< InertiaTpl< T, U > >::SE3
SE3Tpl< T, U > SE3
Definition: spatial/inertia.hpp:250
pinocchio::skew
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...
Definition: skew.hpp:22
pinocchio::InertiaBase::operator-=
Derived & operator-=(const Derived &Yb)
Definition: spatial/inertia.hpp:106
pinocchio::LogCholeskyParametersTpl
A structure representing log Cholesky parameters.
Definition: spatial/fwd.hpp:64
pinocchio::LogCholeskyParametersTpl::toInertia
InertiaTpl< Scalar, Options > toInertia() const
Converts the LogCholeskyParametersTpl object to an InertiaTpl object.
Definition: spatial/inertia.hpp:1181
pinocchio::PseudoInertiaTpl::Matrix4
Eigen::Matrix< Scalar, 4, 4, Options > Matrix4
Definition: spatial/inertia.hpp:950
pinocchio::InertiaTpl::InertiaTpl
InertiaTpl()
Definition: spatial/inertia.hpp:281
symmetric3.hpp
pinocchio::InertiaBase::isApprox
bool isApprox(const Derived &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Definition: spatial/inertia.hpp:195
mat
mat
pinocchio::Symmetric3Tpl::inverse
void inverse(const Eigen::MatrixBase< Matrix3Like > &res_) const
Definition: spatial/symmetric3.hpp:164
pinocchio::InertiaBase::disp
void disp(std::ostream &os) const
Definition: spatial/inertia.hpp:221
fwd.hpp
pinocchio::ForceTpl
Definition: context/casadi.hpp:25
pinocchio::InertiaTpl::InertiaTpl
InertiaTpl(const Matrix6 &I6)
Definition: spatial/inertia.hpp:292
pinocchio::traits< InertiaTpl< T, U > >::Symmetric3
Symmetric3Tpl< T, U > Symmetric3
Definition: spatial/inertia.hpp:253
pinocchio::InertiaTpl::FromCapsule
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....
Definition: spatial/inertia.hpp:439
x
x
pinocchio::InertiaBase::setIdentity
void setIdentity()
Definition: spatial/inertia.hpp:186
pinocchio::InertiaBase::inertia
Symmetric3 & inertia()
Definition: spatial/inertia.hpp:56
pinocchio::InertiaTpl::Random
static InertiaTpl Random()
Definition: spatial/inertia.hpp:361
pinocchio::InertiaBase::inertia
const Symmetric3 & inertia() const
Definition: spatial/inertia.hpp:52
pinocchio::InertiaTpl::__mult__
ForceTpl< typename traits< MotionDerived >::Scalar, traits< MotionDerived >::Options > __mult__(const MotionDense< MotionDerived > &v) const
Definition: spatial/inertia.hpp:718
M
M
pinocchio::InertiaTpl::__pequ__
InertiaTpl & __pequ__(const InertiaTpl &Yb)
Definition: spatial/inertia.hpp:658
pinocchio::context::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: context/generic.hpp:53
pinocchio::PseudoInertiaTpl::FromInertia
static PseudoInertiaTpl FromInertia(const InertiaTpl< Scalar, Options > &inertia)
Constructs a PseudoInertiaTpl object from an InertiaTpl object.
Definition: spatial/inertia.hpp:1043
pinocchio::Symmetric3Tpl::isZero
bool isZero(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Definition: spatial/symmetric3.hpp:153
pinocchio::traits< InertiaTpl< T, U > >::Vector3
Eigen::Matrix< T, 3, 1, U > Vector3
Definition: spatial/inertia.hpp:237
pinocchio::traits< InertiaTpl< T, U > >::Matrix6
Eigen::Matrix< T, 6, 6, U > Matrix6
Definition: spatial/inertia.hpp:242
pinocchio::LogCholeskyParametersTpl::calculateJacobian
Matrix10 calculateJacobian() const
Calculates the Jacobian of the log Cholesky parameters.
Definition: spatial/inertia.hpp:1191
pinocchio::InertiaBase::inverse
void inverse(const Eigen::MatrixBase< Matrix6Like > &mat) const
Definition: spatial/inertia.hpp:76
pinocchio::Symmetric3Tpl< context::Scalar, context::Options >::rhsMult
static void rhsMult(const Symmetric3Tpl &S3, const Eigen::MatrixBase< V3in > &vin, const Eigen::MatrixBase< V3out > &vout)
Definition: spatial/symmetric3.hpp:490
pinocchio::InertiaTpl::inverse_impl
Matrix6 inverse_impl() const
Definition: spatial/inertia.hpp:527
pinocchio::PseudoInertiaTpl::FromMatrix
static PseudoInertiaTpl FromMatrix(const Matrix4 &pseudo_inertia)
Constructs a PseudoInertiaTpl object from a 4x4 pseudo inertia matrix.
Definition: spatial/inertia.hpp:986
pinocchio::InertiaTpl::toDynamicParameters
Vector10 toDynamicParameters() const
Definition: spatial/inertia.hpp:541
pinocchio::jacobian
void jacobian(const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel, ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > &cdata, const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< JacobianMatrix > &jacobian_matrix)
Definition: constraint-model-visitor.hpp:199
pinocchio::InertiaBase::setZero
void setZero()
Definition: spatial/inertia.hpp:182
pinocchio::skewSquare
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,...
Definition: skew.hpp:182
pinocchio::InertiaTpl::SPATIAL_TYPEDEF_TEMPLATE
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SPATIAL_TYPEDEF_TEMPLATE(InertiaTpl)
pinocchio::Symmetric3Tpl::matrix
Matrix3 matrix() const
Definition: spatial/symmetric3.hpp:304
pinocchio::PseudoInertiaTpl::Scalar
_Scalar Scalar
Definition: spatial/inertia.hpp:945
a
Vec3f a
pinocchio::InertiaTpl::disp_impl
void disp_impl(std::ostream &os) const
Definition: spatial/inertia.hpp:901
clone
virtual CollisionGeometry * clone() const=0
pinocchio::PseudoInertiaTpl::FromDynamicParameters
static PseudoInertiaTpl FromDynamicParameters(const Eigen::MatrixBase< Vector10Like > &dynamic_params)
Constructs a PseudoInertiaTpl object from dynamic parameters.
Definition: spatial/inertia.hpp:1001
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1084
pinocchio::InertiaTpl::__equl__
InertiaTpl & __equl__(const InertiaTpl &clone)
Definition: spatial/inertia.hpp:611
pinocchio::InertiaTpl::matrix_impl
void matrix_impl(const Eigen::MatrixBase< Matrix6Like > &M_) const
Definition: spatial/inertia.hpp:480
pinocchio::LogCholeskyParametersTpl::PseudoInertia
PseudoInertiaTpl< Scalar, Options > PseudoInertia
Definition: spatial/inertia.hpp:1111
pinocchio::InertiaTpl::Vector10
Eigen::Matrix< Scalar, 10, 1, Options > Vector10
Definition: spatial/inertia.hpp:275
pinocchio::InertiaTpl::matrix_impl
Matrix6 matrix_impl() const
Definition: spatial/inertia.hpp:492
pinocchio::Symmetric3Tpl< context::Scalar, context::Options >
pinocchio::Force
ForceTpl< context::Scalar, context::Options > Force
Definition: spatial/fwd.hpp:68
pinocchio::LogCholeskyParametersTpl::cast
LogCholeskyParametersTpl< NewScalar, Options > cast() const
Definition: spatial/inertia.hpp:1279
pinocchio::InertiaBase::vxi
Matrix6 vxi(const MotionDense< MotionDerived > &v) const
Definition: spatial/inertia.hpp:151
pinocchio::InertiaBase::const_cast_derived
Derived & const_cast_derived() const
Definition: spatial/inertia.hpp:31
pinocchio::InertiaBase::isZero
bool isZero(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Definition: spatial/inertia.hpp:202
ocp.U
U
Definition: ocp.py:80
pinocchio::InertiaTpl::FromDynamicParameters
static InertiaTpl FromDynamicParameters(const Eigen::MatrixBase< Vector10Like > &params)
Definition: spatial/inertia.hpp:561
pinocchio::InertiaTpl::Identity
static InertiaTpl Identity()
Definition: spatial/inertia.hpp:349
pinocchio::InertiaBase::vtiv
Scalar vtiv(const MotionDense< MotionDerived > &v) const
Definition: spatial/inertia.hpp:123
pinocchio::traits< InertiaTpl< T, U > >::Matrix10
Eigen::Matrix< T, 10, 10, U > Matrix10
Definition: spatial/inertia.hpp:243
pinocchio::traits< InertiaTpl< T, U > >::Angular_t
Vector3 Angular_t
Definition: spatial/inertia.hpp:245
pinocchio::ForceDense
Definition: context/casadi.hpp:34
pinocchio::LogCholeskyParametersTpl::disp_impl
void disp_impl(std::ostream &os) const
Definition: spatial/inertia.hpp:1284
pinocchio::Symmetric3Tpl< context::Scalar, context::Options >::Identity
static Symmetric3Tpl Identity()
Definition: spatial/symmetric3.hpp:117
pinocchio::traits< InertiaTpl< T, U > >::Motion
MotionTpl< T, U > Motion
Definition: spatial/inertia.hpp:252
pinocchio::LogCholeskyParametersTpl::Options
@ Options
Definition: spatial/inertia.hpp:1107
pinocchio::cross
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.
Definition: skew.hpp:228
pinocchio::InertiaBase::operator<<
friend std::ostream & operator<<(std::ostream &os, const InertiaBase< Derived > &X)
Definition: spatial/inertia.hpp:225
pinocchio::LogCholeskyParametersTpl::toDynamicParameters
Vector10 toDynamicParameters() const
Converts the LogCholeskyParametersTpl object to dynamic parameters.
Definition: spatial/inertia.hpp:1126
pinocchio::InertiaTpl::AlphaSkewSquare
Symmetric3::AlphaSkewSquare AlphaSkewSquare
Definition: spatial/inertia.hpp:274
pinocchio::InertiaBase::SPATIAL_TYPEDEF_TEMPLATE
SPATIAL_TYPEDEF_TEMPLATE(Derived)
pinocchio::InertiaBase::ivx
Matrix6 ivx(const MotionDense< MotionDerived > &v) const
Definition: spatial/inertia.hpp:175
pinocchio::PseudoInertiaTpl::PseudoInertiaTpl
PseudoInertiaTpl(Scalar mass, const Vector3 &h, const Matrix3 &sigma)
Definition: spatial/inertia.hpp:960
pinocchio::InertiaTpl::se3Action_impl
InertiaTpl se3Action_impl(const SE3Tpl< S2, O2 > &M) const
aI = aXb.act(bI)
Definition: spatial/inertia.hpp:872
dcrba.eps
int eps
Definition: dcrba.py:458
pinocchio::PseudoInertiaTpl::toMatrix
Matrix4 toMatrix() const
Converts the PseudoInertiaTpl object to a 4x4 matrix.
Definition: spatial/inertia.hpp:971
pinocchio::traits< InertiaTpl< T, U > >::Vector4
Eigen::Matrix< T, 4, 1, U > Vector4
Definition: spatial/inertia.hpp:238
pinocchio::InertiaTpl::FromBox
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).
Definition: spatial/inertia.hpp:423
pinocchio::traits< InertiaTpl< T, U > >::Matrix4
Eigen::Matrix< T, 4, 4, U > Matrix4
Definition: spatial/inertia.hpp:241
pinocchio::traits< InertiaTpl< T, U > >::Linear_t
Vector3 Linear_t
Definition: spatial/inertia.hpp:246
pinocchio::traits
Common traits structure to fully define base classes for CRTP.
Definition: fwd.hpp:71
pinocchio::Symmetric3Tpl::setIdentity
void setIdentity()
Definition: spatial/symmetric3.hpp:121
pinocchio::InertiaTpl::FromSphere
static InertiaTpl FromSphere(const Scalar mass, const Scalar radius)
Computes the Inertia of a sphere defined by its mass and its radius.
Definition: spatial/inertia.hpp:374
pinocchio::InertiaTpl::InertiaTpl
InertiaTpl(const Scalar &mass, const Vector3 &com, const Symmetric3 &rotational_inertia)
Definition: spatial/inertia.hpp:308
PINOCCHIO_ASSERT_MATRIX_SPECIFIC_SIZE
#define PINOCCHIO_ASSERT_MATRIX_SPECIFIC_SIZE(type, M, nrows, ncols)
Ensure that a matrix (or vector) is of correct size (compile-time and run-time assertion)
Definition: include/pinocchio/macros.hpp:75
pinocchio::Symmetric3Tpl< context::Scalar, context::Options >::Zero
static Symmetric3Tpl Zero()
Definition: spatial/symmetric3.hpp:92
pinocchio::traits< InertiaTpl< T, U > >::Quaternion_t
Eigen::Quaternion< T, U > Quaternion_t
Definition: spatial/inertia.hpp:249
pinocchio::alphaSkew
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....
Definition: skew.hpp:134
pinocchio.utils.rand
def rand(n)
Definition: bindings/python/pinocchio/utils.py:41
pinocchio::MotionTpl
Definition: context/casadi.hpp:27
pinocchio::Symmetric3Tpl< context::Scalar, context::Options >::RandomPositive
static Symmetric3Tpl RandomPositive()
Definition: spatial/symmetric3.hpp:291
pinocchio::Symmetric3Tpl::setZero
void setZero()
Definition: spatial/symmetric3.hpp:96
pinocchio::InertiaBase::lever
const Vector3 & lever() const
Definition: spatial/inertia.hpp:44
pinocchio::InertiaBase
Definition: spatial/inertia.hpp:18
pinocchio::InertiaTpl::__mult__
void __mult__(const MotionDense< MotionDerived > &v, ForceDense< ForceDerived > &f) const
Definition: spatial/inertia.hpp:728
pinocchio::InertiaBase::operator*
ForceTpl< typename traits< MotionDerived >::Scalar, traits< MotionDerived >::Options > operator*(const MotionDense< MotionDerived > &v) const
Definition: spatial/inertia.hpp:117
pinocchio::unSkew
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...
Definition: skew.hpp:93
force.hpp
pinocchio::InertiaTpl::se3ActionInverse_impl
InertiaTpl se3ActionInverse_impl(const SE3Tpl< S2, O2 > &M) const
bI = aXb.actInv(aI)
Definition: spatial/inertia.hpp:883
pinocchio::InertiaTpl::FromCylinder
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.
Definition: spatial/inertia.hpp:406
pinocchio::InertiaTpl::operator=
InertiaTpl & operator=(const InertiaTpl &clone)
Definition: spatial/inertia.hpp:322
pinocchio::InertiaTpl::LogCholeskyParameters
LogCholeskyParametersTpl< Scalar, Options > LogCholeskyParameters
Definition: spatial/inertia.hpp:278
pinocchio::InertiaTpl::Matrix10
Eigen::Matrix< Scalar, 10, 10, Options > Matrix10
Definition: spatial/inertia.hpp:276
pinocchio::LogCholeskyParametersTpl::Matrix10
Eigen::Matrix< Scalar, 10, 10, Options > Matrix10
Definition: spatial/inertia.hpp:1110
pinocchio::InertiaTpl::vtiv_impl
Scalar vtiv_impl(const MotionDense< MotionDerived > &v) const
Definition: spatial/inertia.hpp:737
CppAD::max
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
Definition: autodiff/cppad.hpp:181
length
FCL_REAL length[2]
pinocchio::traits< InertiaTpl< T, U > >::LogCholeskyParameters
LogCholeskyParametersTpl< T, U > LogCholeskyParameters
Definition: spatial/inertia.hpp:255
pinocchio::InertiaTpl::setIdentity
void setIdentity()
Definition: spatial/inertia.hpp:354
X
pinocchio::InertiaTpl::m_mass
Scalar m_mass
Definition: spatial/inertia.hpp:928
robot-wrapper-viewer.com
com
Definition: robot-wrapper-viewer.py:45
radius
FCL_REAL radius
pinocchio::LogCholeskyParametersTpl::operator<<
friend std::ostream & operator<<(std::ostream &os, const LogCholeskyParametersTpl &lcp)
Definition: spatial/inertia.hpp:1298
pinocchio::PseudoInertiaTpl::Options
@ Options
Definition: spatial/inertia.hpp:948
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27
pinocchio::InertiaTpl::cast
InertiaTpl< NewScalar, Options > cast() const
Definition: spatial/inertia.hpp:911


pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:29