Public Types | Public Member Functions | Static Public Member Functions | Protected Attributes | List of all members
pinocchio::InertiaTpl< _Scalar, _Options > Struct Template Reference

#include <fwd.hpp>

Public Types

enum  { Options = _Options }
 
typedef Symmetric3::AlphaSkewSquare AlphaSkewSquare
 
typedef Eigen::Matrix< Scalar, 10, 1, OptionsVector10
 

Public Member Functions

InertiaTpl__equl__ (const InertiaTpl &clone)
 
InertiaTpl__mequ__ (const InertiaTpl &Yb)
 
InertiaTpl __minus__ (const InertiaTpl &Yb) const
 
template<typename MotionDerived >
ForceTpl< typename traits< MotionDerived >::Scalar, traits< MotionDerived >::Options__mult__ (const MotionDense< MotionDerived > &v) const
 
template<typename MotionDerived , typename ForceDerived >
void __mult__ (const MotionDense< MotionDerived > &v, ForceDense< ForceDerived > &f) const
 
InertiaTpl__pequ__ (const InertiaTpl &Yb)
 
InertiaTpl __plus__ (const InertiaTpl &Yb) const
 
template<typename NewScalar >
InertiaTpl< NewScalar, Optionscast () const
 
void disp_impl (std::ostream &os) const
 
Symmetric3inertia ()
 
const Symmetric3inertia () const
 
 InertiaTpl ()
 
 InertiaTpl (const InertiaTpl &clone)
 
template<typename S2 , int O2>
 InertiaTpl (const InertiaTpl< S2, O2 > &clone)
 
 InertiaTpl (const Matrix6 &I6)
 
 InertiaTpl (const Scalar &mass, const Vector3 &com, const Matrix3 &rotational_inertia)
 
 InertiaTpl (const Scalar &mass, const Vector3 &com, const Symmetric3 &rotational_inertia)
 
Matrix6 inverse_impl () const
 
template<typename Matrix6Like >
void inverse_impl (const Eigen::MatrixBase< Matrix6Like > &M_) const
 
bool isApprox_impl (const InertiaTpl &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
bool isEqual (const InertiaTpl &Y2) const
 
bool isZero_impl (const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
Vector3 & lever ()
 
const Vector3 & lever () const
 
Scalar & mass ()
 
Scalar mass () const
 
Matrix6 matrix_impl () const
 
template<typename Matrix6Like >
void matrix_impl (const Eigen::MatrixBase< Matrix6Like > &M_) const
 
InertiaTploperator= (const InertiaTpl &clone)
 
template<typename S2 , int O2>
InertiaTpl se3Action_impl (const SE3Tpl< S2, O2 > &M) const
 aI = aXb.act(bI) More...
 
template<typename S2 , int O2>
InertiaTpl se3ActionInverse_impl (const SE3Tpl< S2, O2 > &M) const
 bI = aXb.actInv(aI) More...
 
void setIdentity ()
 
void setRandom ()
 
void setZero ()
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SPATIAL_TYPEDEF_TEMPLATE (InertiaTpl)
 
Vector10 toDynamicParameters () const
 
template<typename MotionDerived >
Matrix6 variation (const MotionDense< MotionDerived > &v) const
 
template<typename MotionDerived >
Scalar vtiv_impl (const MotionDense< MotionDerived > &v) const
 
template<typename MotionDerived >
Force vxiv (const MotionDense< MotionDerived > &v) const
 

Static Public Member Functions

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). More...
 
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. Assumes a uniform density. More...
 
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. More...
 
template<typename Vector10Like >
static InertiaTpl FromDynamicParameters (const Eigen::MatrixBase< Vector10Like > &params)
 
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,y,z). More...
 
static InertiaTpl FromSphere (const Scalar mass, const Scalar radius)
 Computes the Inertia of a sphere defined by its mass and its radius. More...
 
static InertiaTpl Identity ()
 
template<typename MotionDerived , typename M6 >
static void ivx_impl (const MotionDense< MotionDerived > &v, const InertiaTpl &I, const Eigen::MatrixBase< M6 > &Iout)
 
static InertiaTpl Random ()
 
template<typename MotionDerived , typename M6 >
static void vxi_impl (const MotionDense< MotionDerived > &v, const InertiaTpl &I, const Eigen::MatrixBase< M6 > &Iout)
 
static InertiaTpl Zero ()
 

Protected Attributes

Vector3 m_com
 
Symmetric3 m_inertia
 
Scalar m_mass
 

Detailed Description

template<typename _Scalar, int _Options>
struct pinocchio::InertiaTpl< _Scalar, _Options >

Definition at line 58 of file spatial/fwd.hpp.

Member Typedef Documentation

◆ AlphaSkewSquare

template<typename _Scalar , int _Options>
typedef Symmetric3::AlphaSkewSquare pinocchio::InertiaTpl< _Scalar, _Options >::AlphaSkewSquare

Definition at line 272 of file spatial/inertia.hpp.

◆ Vector10

template<typename _Scalar , int _Options>
typedef Eigen::Matrix<Scalar, 10, 1, Options> pinocchio::InertiaTpl< _Scalar, _Options >::Vector10

Definition at line 273 of file spatial/inertia.hpp.

Member Enumeration Documentation

◆ anonymous enum

template<typename _Scalar , int _Options>
anonymous enum
Enumerator
Options 

Definition at line 267 of file spatial/inertia.hpp.

Constructor & Destructor Documentation

◆ InertiaTpl() [1/6]

template<typename _Scalar , int _Options>
pinocchio::InertiaTpl< _Scalar, _Options >::InertiaTpl ( )
inline

Definition at line 276 of file spatial/inertia.hpp.

◆ InertiaTpl() [2/6]

template<typename _Scalar , int _Options>
pinocchio::InertiaTpl< _Scalar, _Options >::InertiaTpl ( const Scalar &  mass,
const Vector3 &  com,
const Matrix3 &  rotational_inertia 
)
inline

Definition at line 280 of file spatial/inertia.hpp.

◆ InertiaTpl() [3/6]

template<typename _Scalar , int _Options>
pinocchio::InertiaTpl< _Scalar, _Options >::InertiaTpl ( const Matrix6 &  I6)
inlineexplicit

Definition at line 287 of file spatial/inertia.hpp.

◆ InertiaTpl() [4/6]

template<typename _Scalar , int _Options>
pinocchio::InertiaTpl< _Scalar, _Options >::InertiaTpl ( const Scalar &  mass,
const Vector3 &  com,
const Symmetric3 rotational_inertia 
)
inline

Definition at line 303 of file spatial/inertia.hpp.

◆ InertiaTpl() [5/6]

template<typename _Scalar , int _Options>
pinocchio::InertiaTpl< _Scalar, _Options >::InertiaTpl ( const InertiaTpl< _Scalar, _Options > &  clone)
inline

Definition at line 310 of file spatial/inertia.hpp.

◆ InertiaTpl() [6/6]

template<typename _Scalar , int _Options>
template<typename S2 , int O2>
pinocchio::InertiaTpl< _Scalar, _Options >::InertiaTpl ( const InertiaTpl< S2, O2 > &  clone)
inlineexplicit

Definition at line 326 of file spatial/inertia.hpp.

Member Function Documentation

◆ __equl__()

template<typename _Scalar , int _Options>
InertiaTpl& pinocchio::InertiaTpl< _Scalar, _Options >::__equl__ ( const InertiaTpl< _Scalar, _Options > &  clone)
inline

Definition at line 569 of file spatial/inertia.hpp.

◆ __mequ__()

template<typename _Scalar , int _Options>
InertiaTpl& pinocchio::InertiaTpl< _Scalar, _Options >::__mequ__ ( const InertiaTpl< _Scalar, _Options > &  Yb)
inline

Definition at line 654 of file spatial/inertia.hpp.

◆ __minus__()

template<typename _Scalar , int _Options>
InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::__minus__ ( const InertiaTpl< _Scalar, _Options > &  Yb) const
inline

Definition at line 632 of file spatial/inertia.hpp.

◆ __mult__() [1/2]

template<typename _Scalar , int _Options>
template<typename MotionDerived >
ForceTpl<typename traits<MotionDerived>::Scalar, traits<MotionDerived>::Options> pinocchio::InertiaTpl< _Scalar, _Options >::__mult__ ( const MotionDense< MotionDerived > &  v) const
inline

Definition at line 676 of file spatial/inertia.hpp.

◆ __mult__() [2/2]

template<typename _Scalar , int _Options>
template<typename MotionDerived , typename ForceDerived >
void pinocchio::InertiaTpl< _Scalar, _Options >::__mult__ ( const MotionDense< MotionDerived > &  v,
ForceDense< ForceDerived > &  f 
) const
inline

Definition at line 686 of file spatial/inertia.hpp.

◆ __pequ__()

template<typename _Scalar , int _Options>
InertiaTpl& pinocchio::InertiaTpl< _Scalar, _Options >::__pequ__ ( const InertiaTpl< _Scalar, _Options > &  Yb)
inline

Definition at line 616 of file spatial/inertia.hpp.

◆ __plus__()

template<typename _Scalar , int _Options>
InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::__plus__ ( const InertiaTpl< _Scalar, _Options > &  Yb) const
inline

Definition at line 598 of file spatial/inertia.hpp.

◆ cast()

template<typename _Scalar , int _Options>
template<typename NewScalar >
InertiaTpl<NewScalar, Options> pinocchio::InertiaTpl< _Scalar, _Options >::cast ( ) const
inline
Returns
An expression of *this with the Scalar type casted to NewScalar.

Definition at line 869 of file spatial/inertia.hpp.

◆ disp_impl()

template<typename _Scalar , int _Options>
void pinocchio::InertiaTpl< _Scalar, _Options >::disp_impl ( std::ostream &  os) const
inline

Definition at line 859 of file spatial/inertia.hpp.

◆ FromBox()

template<typename _Scalar , int _Options>
static InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::FromBox ( const Scalar  mass,
const Scalar  x,
const Scalar  y,
const Scalar  z 
)
inlinestatic

Computes the Inertia of a box defined by its mass and main dimensions (x,y,z).

Parameters
[in]massof the box.
[in]xdimension along the local X axis.
[in]ydimension along the local Y axis.
[in]zdimension along the local Z axis.

Definition at line 418 of file spatial/inertia.hpp.

◆ FromCapsule()

template<typename _Scalar , int _Options>
static InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::FromCapsule ( const Scalar  mass,
const Scalar  radius,
const Scalar  height 
)
inlinestatic

Computes the Inertia of a capsule defined by its mass, radius and length along the Z axis. Assumes a uniform density.

Parameters
[in]massof the capsule.
[in]radiusof the capsule.
[in]heightof the capsule.

Definition at line 434 of file spatial/inertia.hpp.

◆ FromCylinder()

template<typename _Scalar , int _Options>
static InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::FromCylinder ( const Scalar  mass,
const Scalar  radius,
const Scalar  length 
)
inlinestatic

Computes the Inertia of a cylinder defined by its mass, radius and length along the Z axis.

Parameters
[in]massof the cylinder.
[in]radiusof the cylinder.
[in]lengthof the cylinder.

Definition at line 401 of file spatial/inertia.hpp.

◆ FromDynamicParameters()

template<typename _Scalar , int _Options>
template<typename Vector10Like >
static InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::FromDynamicParameters ( const Eigen::MatrixBase< Vector10Like > &  params)
inlinestatic

Builds and inertia matrix from a vector of dynamic parameters.

Parameters
[in]paramsThe dynamic parameters.

The parameters are given as $ v = [m, mc_x, mc_y, mc_z, I_{xx}, I_{xy}, I_{yy}, I_{xz}, I_{yz}, I_{zz}]^T $ where $ I = I_C + mS^T(c)S(c) $ and $ I_C $ has its origin at the barycenter.

Definition at line 556 of file spatial/inertia.hpp.

◆ FromEllipsoid()

template<typename _Scalar , int _Options>
static InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::FromEllipsoid ( const Scalar  mass,
const Scalar  x,
const Scalar  y,
const Scalar  z 
)
inlinestatic

Computes the Inertia of an ellipsoid defined by its mass and main semi-axis dimensions (x,y,z).

Parameters
[in]massof the ellipsoid.
[in]xsemi-axis dimension along the local X axis.
[in]ysemi-axis dimension along the local Y axis.
[in]zsemi-axis dimension along the local Z axis.

Definition at line 384 of file spatial/inertia.hpp.

◆ FromSphere()

template<typename _Scalar , int _Options>
static InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::FromSphere ( const Scalar  mass,
const Scalar  radius 
)
inlinestatic

Computes the Inertia of a sphere defined by its mass and its radius.

Parameters
[in]massof the sphere.
[in]radiusof the sphere.

Definition at line 369 of file spatial/inertia.hpp.

◆ Identity()

template<typename _Scalar , int _Options>
static InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::Identity ( )
inlinestatic

Definition at line 344 of file spatial/inertia.hpp.

◆ inertia() [1/2]

template<typename _Scalar , int _Options>
Symmetric3& pinocchio::InertiaTpl< _Scalar, _Options >::inertia ( )
inline

Definition at line 823 of file spatial/inertia.hpp.

◆ inertia() [2/2]

template<typename _Scalar , int _Options>
const Symmetric3& pinocchio::InertiaTpl< _Scalar, _Options >::inertia ( ) const
inline

Definition at line 810 of file spatial/inertia.hpp.

◆ inverse_impl() [1/2]

template<typename _Scalar , int _Options>
Matrix6 pinocchio::InertiaTpl< _Scalar, _Options >::inverse_impl ( ) const
inline

Definition at line 522 of file spatial/inertia.hpp.

◆ inverse_impl() [2/2]

template<typename _Scalar , int _Options>
template<typename Matrix6Like >
void pinocchio::InertiaTpl< _Scalar, _Options >::inverse_impl ( const Eigen::MatrixBase< Matrix6Like > &  M_) const
inline

Definition at line 495 of file spatial/inertia.hpp.

◆ isApprox_impl()

template<typename _Scalar , int _Options>
bool pinocchio::InertiaTpl< _Scalar, _Options >::isApprox_impl ( const InertiaTpl< _Scalar, _Options > &  other,
const Scalar &  prec = Eigen::NumTraits<Scalar>::dummy_precision() 
) const
inline

Definition at line 583 of file spatial/inertia.hpp.

◆ isEqual()

template<typename _Scalar , int _Options>
bool pinocchio::InertiaTpl< _Scalar, _Options >::isEqual ( const InertiaTpl< _Scalar, _Options > &  Y2) const
inline

Definition at line 578 of file spatial/inertia.hpp.

◆ isZero_impl()

template<typename _Scalar , int _Options>
bool pinocchio::InertiaTpl< _Scalar, _Options >::isZero_impl ( const Scalar &  prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
inline

Definition at line 592 of file spatial/inertia.hpp.

◆ ivx_impl()

template<typename _Scalar , int _Options>
template<typename MotionDerived , typename M6 >
static void pinocchio::InertiaTpl< _Scalar, _Options >::ivx_impl ( const MotionDense< MotionDerived > &  v,
const InertiaTpl< _Scalar, _Options > &  I,
const Eigen::MatrixBase< M6 > &  Iout 
)
inlinestatic

Definition at line 770 of file spatial/inertia.hpp.

◆ lever() [1/2]

template<typename _Scalar , int _Options>
Vector3& pinocchio::InertiaTpl< _Scalar, _Options >::lever ( )
inline

Definition at line 819 of file spatial/inertia.hpp.

◆ lever() [2/2]

template<typename _Scalar , int _Options>
const Vector3& pinocchio::InertiaTpl< _Scalar, _Options >::lever ( ) const
inline

Definition at line 806 of file spatial/inertia.hpp.

◆ mass() [1/2]

template<typename _Scalar , int _Options>
Scalar& pinocchio::InertiaTpl< _Scalar, _Options >::mass ( )
inline

Definition at line 815 of file spatial/inertia.hpp.

◆ mass() [2/2]

template<typename _Scalar , int _Options>
Scalar pinocchio::InertiaTpl< _Scalar, _Options >::mass ( ) const
inline

Definition at line 802 of file spatial/inertia.hpp.

◆ matrix_impl() [1/2]

template<typename _Scalar , int _Options>
Matrix6 pinocchio::InertiaTpl< _Scalar, _Options >::matrix_impl ( ) const
inline

Definition at line 487 of file spatial/inertia.hpp.

◆ matrix_impl() [2/2]

template<typename _Scalar , int _Options>
template<typename Matrix6Like >
void pinocchio::InertiaTpl< _Scalar, _Options >::matrix_impl ( const Eigen::MatrixBase< Matrix6Like > &  M_) const
inline

Definition at line 475 of file spatial/inertia.hpp.

◆ operator=()

template<typename _Scalar , int _Options>
InertiaTpl& pinocchio::InertiaTpl< _Scalar, _Options >::operator= ( const InertiaTpl< _Scalar, _Options > &  clone)
inline

Definition at line 317 of file spatial/inertia.hpp.

◆ Random()

template<typename _Scalar , int _Options>
static InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::Random ( )
inlinestatic

Definition at line 356 of file spatial/inertia.hpp.

◆ se3Action_impl()

template<typename _Scalar , int _Options>
template<typename S2 , int O2>
InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::se3Action_impl ( const SE3Tpl< S2, O2 > &  M) const
inline

aI = aXb.act(bI)

Definition at line 830 of file spatial/inertia.hpp.

◆ se3ActionInverse_impl()

template<typename _Scalar , int _Options>
template<typename S2 , int O2>
InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::se3ActionInverse_impl ( const SE3Tpl< S2, O2 > &  M) const
inline

bI = aXb.actInv(aI)

Definition at line 841 of file spatial/inertia.hpp.

◆ setIdentity()

template<typename _Scalar , int _Options>
void pinocchio::InertiaTpl< _Scalar, _Options >::setIdentity ( )
inline

Definition at line 349 of file spatial/inertia.hpp.

◆ setRandom()

template<typename _Scalar , int _Options>
void pinocchio::InertiaTpl< _Scalar, _Options >::setRandom ( )
inline

Definition at line 467 of file spatial/inertia.hpp.

◆ setZero()

template<typename _Scalar , int _Options>
void pinocchio::InertiaTpl< _Scalar, _Options >::setZero ( )
inline

Definition at line 337 of file spatial/inertia.hpp.

◆ SPATIAL_TYPEDEF_TEMPLATE()

template<typename _Scalar , int _Options>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW pinocchio::InertiaTpl< _Scalar, _Options >::SPATIAL_TYPEDEF_TEMPLATE ( InertiaTpl< _Scalar, _Options >  )

◆ toDynamicParameters()

template<typename _Scalar , int _Options>
Vector10 pinocchio::InertiaTpl< _Scalar, _Options >::toDynamicParameters ( ) const
inline

Returns the representation of the matrix as a vector of dynamic parameters. The parameters are given as $ v = [m, mc_x, mc_y, mc_z, I_{xx}, I_{xy}, I_{yy}, I_{xz}, I_{yz}, I_{zz}]^T $ where $ c $ is the center of mass, $ I = I_C + mS^T(c)S(c) $ and $ I_C $ has its origin at the barycenter and $ S(c) $ is the the skew matrix representation of the cross product operator.

Definition at line 536 of file spatial/inertia.hpp.

◆ variation()

template<typename _Scalar , int _Options>
template<typename MotionDerived >
Matrix6 pinocchio::InertiaTpl< _Scalar, _Options >::variation ( const MotionDense< MotionDerived > &  v) const
inline

Definition at line 707 of file spatial/inertia.hpp.

◆ vtiv_impl()

template<typename _Scalar , int _Options>
template<typename MotionDerived >
Scalar pinocchio::InertiaTpl< _Scalar, _Options >::vtiv_impl ( const MotionDense< MotionDerived > &  v) const
inline

Definition at line 695 of file spatial/inertia.hpp.

◆ vxi_impl()

template<typename _Scalar , int _Options>
template<typename MotionDerived , typename M6 >
static void pinocchio::InertiaTpl< _Scalar, _Options >::vxi_impl ( const MotionDense< MotionDerived > &  v,
const InertiaTpl< _Scalar, _Options > &  I,
const Eigen::MatrixBase< M6 > &  Iout 
)
inlinestatic

Definition at line 736 of file spatial/inertia.hpp.

◆ vxiv()

template<typename _Scalar , int _Options>
template<typename MotionDerived >
Force pinocchio::InertiaTpl< _Scalar, _Options >::vxiv ( const MotionDense< MotionDerived > &  v) const
inline

Definition at line 849 of file spatial/inertia.hpp.

◆ Zero()

template<typename _Scalar , int _Options>
static InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::Zero ( )
inlinestatic

Definition at line 332 of file spatial/inertia.hpp.

Member Data Documentation

◆ m_com

template<typename _Scalar , int _Options>
Vector3 pinocchio::InertiaTpl< _Scalar, _Options >::m_com
protected

Definition at line 887 of file spatial/inertia.hpp.

◆ m_inertia

template<typename _Scalar , int _Options>
Symmetric3 pinocchio::InertiaTpl< _Scalar, _Options >::m_inertia
protected

Definition at line 888 of file spatial/inertia.hpp.

◆ m_mass

template<typename _Scalar , int _Options>
Scalar pinocchio::InertiaTpl< _Scalar, _Options >::m_mass
protected

Definition at line 886 of file spatial/inertia.hpp.


The documentation for this struct was generated from the following files:


pinocchio
Author(s):
autogenerated on Wed Jun 19 2024 02:41:19