6 #ifndef __pinocchio_inertia_hpp__ 7 #define __pinocchio_inertia_hpp__ 11 #include "pinocchio/math/fwd.hpp" 12 #include "pinocchio/spatial/symmetric3.hpp" 13 #include "pinocchio/spatial/force.hpp" 14 #include "pinocchio/spatial/motion.hpp" 15 #include "pinocchio/spatial/skew.hpp" 20 template<
class Derived>
29 Derived_t &
derived() {
return *
static_cast<Derived_t*
>(
this); }
30 const Derived_t &
derived()
const {
return *
static_cast<const Derived_t*
>(
this); }
34 const Vector3 &
lever()
const {
return static_cast<const Derived_t*
>(
this)->
lever(); }
35 Vector3 &
lever() {
return static_cast<const Derived_t*
>(
this)->
lever(); }
40 operator Matrix6 ()
const {
return matrix(); }
44 bool operator!=(
const Derived_t & other)
const {
return !(*
this == other); }
49 template<
typename MotionDerived>
52 {
return derived().__mult__(v); }
65 static void vxi(
const Motion &
v,
const Derived & I,
const Eigen::MatrixBase<M6> & Iout)
67 EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(M6, Matrix6);
68 Derived::vxi_impl(v,I,Iout);
86 static void ivx(
const Motion &
v,
const Derived & I,
const Eigen::MatrixBase<M6> & Iout)
88 EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(M6, Matrix6);
89 Derived::ivx_impl(v,I,Iout);
103 bool isApprox(
const Derived & other,
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const 104 {
return derived().isApprox_impl(other, prec); }
106 bool isZero(
const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const 107 {
return derived().isZero_impl(prec); }
115 void disp(std::ostream & os)
const {
static_cast<const Derived_t*
>(
this)->disp_impl(os); }
116 friend std::ostream & operator << (std::ostream & os,const InertiaBase<Derived_t> & X)
125 template<
typename T,
int U>
151 template<
typename _Scalar,
int _Options>
158 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
162 typedef typename Eigen::Matrix<_Scalar, 10, 1, _Options>
Vector10;
170 : m_mass(mass), m_com(com), m_inertia(rotational_inertia)
175 assert((I6 - I6.transpose()).isMuchSmallerThan(I6));
176 mass() = I6(LINEAR, LINEAR);
177 const Matrix3 & mc_cross = I6.template block <3,3>(ANGULAR,LINEAR);
181 Matrix3 I3 (mc_cross * mc_cross);
183 I3 += I6.template block<3,3>(ANGULAR,ANGULAR);
189 : m_mass(mass), m_com(com), m_inertia(rotational_inertia)
198 m_mass = clone.
mass();
199 m_com = clone.
lever();
206 : m_mass(clone.
mass())
207 , m_com(clone.
lever())
236 return InertiaTpl(Eigen::internal::random<Scalar>()+1,
249 return FromEllipsoid(mass,radius,radius,radius);
283 const Scalar radius_square = radius * radius;
320 M.template block<3,3>(LINEAR, LINEAR ).
setZero();
321 M.template block<3,3>(LINEAR, LINEAR ).diagonal().fill (
mass());
323 M.template block<3,3>(LINEAR, ANGULAR) = -M.template block<3,3>(ANGULAR, LINEAR);
340 v.template segment<3>(1).noalias() =
mass() *
lever();
354 template<
typename Vector10Like>
360 Vector3
lever = params.template segment<3>(1);
363 return InertiaTpl(mass, lever,
Symmetric3(params.template segment<6>(4)) + AlphaSkewSquare(mass,lever));
380 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
const 383 return fabs(static_cast<Scalar>(
mass() - other.
mass())) <= prec
391 return fabs(
mass()) <= prec
392 &&
lever().isZero(prec)
403 const Scalar eps = ::Eigen::NumTraits<Scalar>::epsilon();
407 const Vector3 & AB = (
lever()-Yb.
lever()).eval();
415 const Scalar eps = ::Eigen::NumTraits<Scalar>::epsilon();
420 const Vector3 & AB = (Ya.
lever()-Yb.
lever()).eval();
427 template<
typename MotionDerived>
437 template<
typename MotionDerived,
typename ForceDerived>
451 res += v.
angular().dot(mcxcxw);
463 res.template block<3,3>(ANGULAR,LINEAR) = res.template block<3,3>(LINEAR,ANGULAR).transpose();
471 res.template block<3,3>(ANGULAR,ANGULAR) -= res.template block<3,3>(LINEAR,LINEAR) *
skew(v.
angular());
472 res.template block<3,3>(ANGULAR,ANGULAR) +=
cross(v.
angular(),res.template block<3,3>(LINEAR,LINEAR));
474 res.template block<3,3>(LINEAR,LINEAR).
setZero();
478 template<
typename M6>
481 const Eigen::MatrixBase<M6> & Iout)
483 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6,6,6);
497 Iout_.template block<3,3>(ANGULAR,LINEAR) -= Iout_.template block<3,3>(LINEAR,ANGULAR);
509 Iout_.template block<3,3>(ANGULAR,ANGULAR) -= mcxcx.
vxs(v.
angular());
513 template<
typename M6>
516 const Eigen::MatrixBase<M6> & Iout)
518 EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6,6,6);
532 cross(-I.
lever(),Iout_.template block<3,3>(ANGULAR,LINEAR),Iout_.template block<3,3>(ANGULAR,ANGULAR));
534 for(
int k = 0; k < 3; ++k)
535 Iout_.template block<3,3>(ANGULAR,ANGULAR).col(k) += I.
lever().cross(Iout_.template block<3,3>(LINEAR,ANGULAR).col(k));
538 Iout_.template block<3,3>(LINEAR,ANGULAR) -= Iout_.template block<3,3>(ANGULAR,LINEAR);
544 const Vector3 &
lever()
const {
return m_com; }
573 const Vector3 & mv_mcxw =
mass()*v.
linear()-mcxw;
581 <<
" m = " <<
mass() <<
"\n" 582 <<
" c = " <<
lever().transpose() <<
"\n" 587 template<
typename NewScalar>
591 lever().template cast<NewScalar>(),
592 inertia().template cast<NewScalar>());
613 #endif // ifndef __pinocchio_inertia_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Force vxiv(const Motion &v) const
InertiaTpl(const Scalar mass, const Vector3 &com, const Matrix3 &rotational_inertia)
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...
InertiaTpl & __pequ__(const InertiaTpl &Yb)
#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) ...
bool isZero_impl(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
ForceTpl< double, 0 > Force
InertiaTpl se3Action_impl(const SE3 &M) const
aI = aXb.act(bI)
const Vector3 & lever() const
Symmetric3Tpl rotate(const Eigen::MatrixBase< D > &R) const
const Vector3 ConstAngular_t
Derived_t & operator+=(const Derived_t &Yb)
static InertiaTpl Random()
Matrix6 matrix_impl() const
Eigen::Quaternion< T, U > Quaternion_t
InertiaTpl se3ActionInverse_impl(const SE3 &M) const
bI = aXb.actInv(aI)
Eigen::Matrix< _Scalar, 10, 1, _Options > Vector10
Scalar vtiv_impl(const Motion &v) const
AD< Scalar > max(const AD< Scalar > &x, const AD< Scalar > &y)
Vector10 toDynamicParameters() const
static InertiaTpl FromSphere(const Scalar mass, const Scalar radius)
Computes the Inertia of a sphere defined by its mass and its radius.
void disp(std::ostream &os) const
Derived_t se3ActionInverse(const SE3 &M) const
bI = aXb.actInv(aI)
static Symmetric3Tpl Zero()
Eigen::Matrix< T, 3, 1, U > Vector3
ConstAngularType angular() const
Return the angular part of the force vector.
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...
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
Matrix6 variation(const Motion &v) const
bool isApprox(const Derived &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
bool operator!=(const Derived_t &other) const
bool isZero(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Matrix6 vxi(const Motion &v) const
bool isZero(const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Matrix6 variation(const Motion &v) const
ConstLinearType linear() const
Return the linear part of the force vector.
Symmetric3Tpl< T, U > Symmetric3
Eigen::Matrix< T, 6, 1, U > Vector6
const Symmetric3 & inertia() const
Eigen::Matrix< T, 6, 6, U > Matrix6
const Vector3 & lever() const
void disp_impl(std::ostream &os) const
static Symmetric3Tpl RandomPositive()
ConstLinearType linear() const
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.
InertiaTpl< NewScalar, Options > cast() const
static void svx(const Eigen::MatrixBase< Vector3 > &v, const Symmetric3Tpl &S3, const Eigen::MatrixBase< Matrix3 > &M)
Performs the operation .
ForceTpl< typename traits< MotionDerived >::Scalar, traits< MotionDerived >::Options > operator*(const MotionDense< MotionDerived > &v) const
ForceTpl< typename traits< MotionDerived >::Scalar, traits< MotionDerived >::Options > __mult__(const MotionDense< MotionDerived > &v) const
Derived_t & operator=(const Derived_t &clone)
Eigen::Matrix< T, 4, 4, U > Matrix4
InertiaTpl & __equl__(const InertiaTpl &clone)
static void rhsMult(const Symmetric3Tpl &S3, const Eigen::MatrixBase< V3in > &vin, const Eigen::MatrixBase< V3out > &vout)
static InertiaTpl Identity()
static Symmetric3Tpl Identity()
bool isEqual(const InertiaTpl &Y2) const
InertiaTpl(Scalar mass, const Vector3 &com, const Symmetric3 &rotational_inertia)
static InertiaTpl FromDynamicParameters(const Eigen::MatrixBase< Vector10Like > ¶ms)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Symmetric3::AlphaSkewSquare AlphaSkewSquare
Scalar vtiv(const Vector3 &v) const
InertiaTpl & operator=(const InertiaTpl &clone)
ConstLinearRef translation() const
SPATIAL_TYPEDEF_TEMPLATE(Derived_t)
InertiaTpl(const InertiaTpl< Scalar, O2 > &clone)
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...
Main pinocchio namespace.
bool isApprox(const Symmetric3Tpl &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
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).
static void ivx_impl(const Motion &v, const InertiaTpl &I, const Eigen::MatrixBase< M6 > &Iout)
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. i.e. the antisymmetric matrix representation of the cross product operator ( )
Common traits structure to fully define base classes for CRTP.
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...
static void ivx(const Motion &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...
Symmetric3Tpl< double, 0 > Symmetric3
bool isApprox_impl(const InertiaTpl &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
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...
Matrix6 ivx(const Motion &v) const
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...
bool operator==(const Derived_t &other) const
Eigen::Matrix< T, 4, 1, U > Vector4
Scalar vtiv(const Motion &v) const
static void vxi_impl(const Motion &v, const InertiaTpl &I, const Eigen::MatrixBase< M6 > &Iout)
ConstAngularType angular() const
const Symmetric3 & inertia() const
Eigen::Matrix< T, 3, 3, U > Matrix3
const Vector3 ConstLinear_t
ConstAngularRef rotation() const
static void vxi(const Motion &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...
InertiaTpl(const Matrix6 &I6)
InertiaTpl __plus__(const InertiaTpl &Yb) const
const Derived_t & derived() const
Derived_t se3Action(const SE3 &M) const
aI = aXb.act(bI)
void __mult__(const MotionDense< MotionDerived > &v, ForceDense< ForceDerived > &f) const
Derived_t operator+(const Derived_t &Yb) const
InertiaTpl(const InertiaTpl &clone)