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

#include <fwd.hpp>

Inheritance diagram for pinocchio::InertiaTpl< _Scalar, _Options >:
Inheritance graph
[legend]

Public Types

enum  { Options = _Options }
 
typedef Eigen::Matrix< _Scalar, 10, 1, _Options > Vector10
 

Public Member Functions

InertiaTpl__equl__ (const InertiaTpl &clone)
 
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
 
const Symmetric3inertia () const
 
Symmetric3inertia ()
 
 InertiaTpl ()
 
 InertiaTpl (const Scalar mass, const Vector3 &com, const Matrix3 &rotational_inertia)
 
 InertiaTpl (const Matrix6 &I6)
 
 InertiaTpl (Scalar mass, const Vector3 &com, const Symmetric3 &rotational_inertia)
 
 InertiaTpl (const InertiaTpl &clone)
 
template<int O2>
 InertiaTpl (const InertiaTpl< Scalar, O2 > &clone)
 
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
 
const Vector3 & lever () const
 
Vector3 & lever ()
 
Scalar mass () const
 
Scalar & mass ()
 
Matrix6 matrix_impl () const
 
InertiaTploperator= (const InertiaTpl &clone)
 
InertiaTpl se3Action_impl (const SE3 &M) const
 aI = aXb.act(bI) More...
 
InertiaTpl se3ActionInverse_impl (const SE3 &M) const
 bI = aXb.actInv(aI) More...
 
void setIdentity ()
 
void setRandom ()
 
void setZero ()
 
 SPATIAL_TYPEDEF_TEMPLATE (InertiaTpl)
 
Vector10 toDynamicParameters () const
 
Matrix6 variation (const Motion &v) const
 
Scalar vtiv_impl (const Motion &v) const
 
Force vxiv (const Motion &v) const
 
- Public Member Functions inherited from pinocchio::InertiaBase< InertiaTpl< _Scalar, _Options > >
Derived_tderived ()
 
const Derived_tderived () const
 
void disp (std::ostream &os) const
 
const Symmetric3inertia () const
 
Symmetric3inertia ()
 
bool isApprox (const InertiaTpl< _Scalar, _Options > &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
bool isZero (const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
Matrix6 ivx (const Motion &v) const
 
const Vector3 & lever () const
 
Vector3 & lever ()
 
Scalar mass () const
 
Scalar & mass ()
 
Matrix6 matrix () const
 
 operator Matrix6 () const
 
bool operator!= (const Derived_t &other) const
 
ForceTpl< typename traits< MotionDerived >::Scalar, traits< MotionDerived >::Options > operator* (const MotionDense< MotionDerived > &v) const
 
Derived_t operator+ (const Derived_t &Yb) const
 
Derived_toperator+= (const Derived_t &Yb)
 
Derived_toperator= (const Derived_t &clone)
 
bool operator== (const Derived_t &other) const
 
Derived_t se3Action (const SE3 &M) const
 aI = aXb.act(bI) More...
 
Derived_t se3ActionInverse (const SE3 &M) const
 bI = aXb.actInv(aI) More...
 
void setIdentity ()
 
void setRandom ()
 
void setZero ()
 
Matrix6 variation (const Motion &v) const
 
Scalar vtiv (const Motion &v) const
 
Matrix6 vxi (const Motion &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 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 M6 >
static void ivx_impl (const Motion &v, const InertiaTpl &I, const Eigen::MatrixBase< M6 > &Iout)
 
static InertiaTpl Random ()
 
template<typename M6 >
static void vxi_impl (const Motion &v, const InertiaTpl &I, const Eigen::MatrixBase< M6 > &Iout)
 
static InertiaTpl Zero ()
 
- Static Public Member Functions inherited from pinocchio::InertiaBase< InertiaTpl< _Scalar, _Options > >
static void ivx (const Motion &v, const InertiaTpl< _Scalar, _Options > &I, const Eigen::MatrixBase< M6 > &Iout)
 Time variation operator. It computes the time derivative of an inertia I corresponding to the formula $ \dot{I} = v \times^{*} I $. More...
 
static void vxi (const Motion &v, const InertiaTpl< _Scalar, _Options > &I, const Eigen::MatrixBase< M6 > &Iout)
 Time variation operator. It computes the time derivative of an inertia I corresponding to the formula $ \dot{I} = v \times^{*} I $. More...
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Symmetric3::AlphaSkewSquare AlphaSkewSquare
 

Protected Attributes

Vector3 m_com
 
Symmetric3 m_inertia
 
Scalar m_mass
 

Friends

class InertiaBase< InertiaTpl< _Scalar, _Options > >
 

Additional Inherited Members

- Protected Types inherited from pinocchio::InertiaBase< InertiaTpl< _Scalar, _Options > >
typedef InertiaTpl< _Scalar, _Options > Derived_t
 
- Protected Member Functions inherited from pinocchio::InertiaBase< InertiaTpl< _Scalar, _Options > >
 SPATIAL_TYPEDEF_TEMPLATE (Derived_t)
 

Detailed Description

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

Definition at line 52 of file src/spatial/fwd.hpp.

Member Typedef Documentation

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

Definition at line 162 of file src/spatial/inertia.hpp.

Member Enumeration Documentation

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

Definition at line 157 of file src/spatial/inertia.hpp.

Constructor & Destructor Documentation

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

Definition at line 166 of file src/spatial/inertia.hpp.

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

Definition at line 169 of file src/spatial/inertia.hpp.

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

Definition at line 173 of file src/spatial/inertia.hpp.

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

Definition at line 188 of file src/spatial/inertia.hpp.

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

Definition at line 192 of file src/spatial/inertia.hpp.

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

Definition at line 205 of file src/spatial/inertia.hpp.

Member Function Documentation

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

Definition at line 367 of file src/spatial/inertia.hpp.

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 429 of file src/spatial/inertia.hpp.

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 438 of file src/spatial/inertia.hpp.

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

Definition at line 413 of file src/spatial/inertia.hpp.

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

Definition at line 396 of file src/spatial/inertia.hpp.

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 588 of file src/spatial/inertia.hpp.

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

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

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 298 of file src/spatial/inertia.hpp.

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 279 of file src/spatial/inertia.hpp.

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 355 of file src/spatial/inertia.hpp.

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 260 of file src/spatial/inertia.hpp.

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 247 of file src/spatial/inertia.hpp.

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

Definition at line 221 of file src/spatial/inertia.hpp.

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

Definition at line 545 of file src/spatial/inertia.hpp.

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

Definition at line 549 of file src/spatial/inertia.hpp.

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 379 of file src/spatial/inertia.hpp.

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

Definition at line 374 of file src/spatial/inertia.hpp.

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 388 of file src/spatial/inertia.hpp.

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

Definition at line 514 of file src/spatial/inertia.hpp.

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

Definition at line 544 of file src/spatial/inertia.hpp.

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

Definition at line 548 of file src/spatial/inertia.hpp.

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

Definition at line 543 of file src/spatial/inertia.hpp.

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

Definition at line 547 of file src/spatial/inertia.hpp.

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

Definition at line 316 of file src/spatial/inertia.hpp.

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

Definition at line 196 of file src/spatial/inertia.hpp.

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

Definition at line 233 of file src/spatial/inertia.hpp.

template<typename _Scalar, int _Options>
InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::se3Action_impl ( const SE3 M) const
inline

aI = aXb.act(bI)

Definition at line 552 of file src/spatial/inertia.hpp.

template<typename _Scalar, int _Options>
InertiaTpl pinocchio::InertiaTpl< _Scalar, _Options >::se3ActionInverse_impl ( const SE3 M) const
inline

bI = aXb.actInv(aI)

Definition at line 563 of file src/spatial/inertia.hpp.

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

Definition at line 228 of file src/spatial/inertia.hpp.

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

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

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

Definition at line 219 of file src/spatial/inertia.hpp.

template<typename _Scalar, int _Options>
pinocchio::InertiaTpl< _Scalar, _Options >::SPATIAL_TYPEDEF_TEMPLATE ( InertiaTpl< _Scalar, _Options >  )
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 335 of file src/spatial/inertia.hpp.

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

Definition at line 457 of file src/spatial/inertia.hpp.

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

Definition at line 446 of file src/spatial/inertia.hpp.

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

Definition at line 479 of file src/spatial/inertia.hpp.

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

Definition at line 570 of file src/spatial/inertia.hpp.

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

Definition at line 212 of file src/spatial/inertia.hpp.

Friends And Related Function Documentation

template<typename _Scalar, int _Options>
friend class InertiaBase< InertiaTpl< _Scalar, _Options > >
friend

Definition at line 155 of file src/spatial/inertia.hpp.

Member Data Documentation

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

Definition at line 160 of file src/spatial/inertia.hpp.

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

Definition at line 606 of file src/spatial/inertia.hpp.

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

Definition at line 607 of file src/spatial/inertia.hpp.

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

Definition at line 605 of file src/spatial/inertia.hpp.


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


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:06