Template Class InertiaTpl

Inheritance Relationships

Base Type

Class Documentation

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

Public Types

Values:

enumerator Options
typedef Eigen::Matrix<_Scalar, 10, 1, _Options> Vector10

Public Functions

SPATIAL_TYPEDEF_TEMPLATE(InertiaTpl)
inline InertiaTpl()
inline InertiaTpl(const Scalar mass, const Vector3 &com, const Matrix3 &rotational_inertia)
inline InertiaTpl(const Matrix6 &I6)
inline InertiaTpl(Scalar mass, const Vector3 &com, const Symmetric3 &rotational_inertia)
inline InertiaTpl(const InertiaTpl &clone)
inline InertiaTpl &operator=(const InertiaTpl &clone)
template<int O2>
inline InertiaTpl(const InertiaTpl<Scalar, O2> &clone)
inline void setZero()
inline void setIdentity()
inline void setRandom()
inline Matrix6 matrix_impl() const
inline Vector10 toDynamicParameters() const

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.

inline InertiaTpl &__equl__(const InertiaTpl &clone)
inline bool isEqual(const InertiaTpl &Y2) const
inline bool isApprox_impl(const InertiaTpl &other, const Scalar &prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
inline bool isZero_impl(const Scalar &prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
inline InertiaTpl __plus__(const InertiaTpl &Yb) const
inline InertiaTpl &__pequ__(const InertiaTpl &Yb)
template<typename MotionDerived>
inline ForceTpl<typename traits<MotionDerived>::Scalar, traits<MotionDerived>::Options> __mult__(const MotionDense<MotionDerived> &v) const
template<typename MotionDerived, typename ForceDerived>
inline void __mult__(const MotionDense<MotionDerived> &v, ForceDense<ForceDerived> &f) const
inline Scalar vtiv_impl(const Motion &v) const
inline Matrix6 variation(const Motion &v) const
inline Scalar mass() const
inline const Vector3 &lever() const
inline const Symmetric3 &inertia() const
inline Scalar &mass()
inline Vector3 &lever()
inline Symmetric3 &inertia()
inline InertiaTpl se3Action_impl(const SE3 &M) const

aI = aXb.act(bI)

inline InertiaTpl se3ActionInverse_impl(const SE3 &M) const

bI = aXb.actInv(aI)

inline Force vxiv(const Motion &v) const
inline void disp_impl(std::ostream &os) const
template<typename NewScalar>
inline InertiaTpl<NewScalar, Options> cast() const
Returns:

An expression of *this with the Scalar type casted to NewScalar.

Public Members

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Symmetric3::AlphaSkewSquare AlphaSkewSquare

Public Static Functions

static inline InertiaTpl Zero()
static inline InertiaTpl Identity()
static inline InertiaTpl Random()
static inline InertiaTpl FromSphere(const Scalar mass, const Scalar radius)

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

Parameters:
  • mass[in] of the sphere.

  • radius[in] of the sphere.

static inline 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).

Parameters:
  • mass[in] of the ellipsoid.

  • x[in] semi-axis dimension along the local X axis.

  • y[in] semi-axis dimension along the local Y axis.

  • z[in] semi-axis dimension along the local Z axis.

static inline 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.

Parameters:
  • mass[in] of the cylinder.

  • radius[in] of the cylinder.

  • length[in] of the cylinder.

static inline 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).

Parameters:
  • mass[in] of the box.

  • x[in] dimension along the local X axis.

  • y[in] dimension along the local Y axis.

  • z[in] dimension along the local Z axis.

template<typename Vector10Like>
static inline InertiaTpl FromDynamicParameters(const Eigen::MatrixBase<Vector10Like> &params)

Builds and inertia matrix from 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 \( I = I_C + mS^T(c)S(c) \) and \( I_C \) has its origin at the barycenter.

Parameters:

params[in] The dynamic parameters.

template<typename M6>
static inline void vxi_impl(const Motion &v, const InertiaTpl &I, const Eigen::MatrixBase<M6> &Iout)
template<typename M6>
static inline void ivx_impl(const Motion &v, const InertiaTpl &I, const Eigen::MatrixBase<M6> &Iout)

Protected Attributes

Scalar m_mass
Vector3 m_com
Symmetric3 m_inertia

Friends

friend class InertiaBase< InertiaTpl< _Scalar, _Options > >