Template Struct InertiaTpl

Inheritance Relationships

Base Type

Struct Documentation

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

Public Types

Values:

enumerator Options
typedef Symmetric3::AlphaSkewSquare AlphaSkewSquare
typedef Eigen::Matrix<Scalar, 10, 1, Options> Vector10
typedef Eigen::Matrix<Scalar, 10, 10, Options> Matrix10
typedef PseudoInertiaTpl<Scalar, Options> PseudoInertia
typedef LogCholeskyParametersTpl<Scalar, Options> LogCholeskyParameters

Public Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW SPATIAL_TYPEDEF_TEMPLATE(InertiaTpl)
inline InertiaTpl()
inline InertiaTpl(const Scalar &mass, const Vector3 &com, const Matrix3 &rotational_inertia)
inline explicit InertiaTpl(const Matrix6 &I6)
inline InertiaTpl(const Scalar &mass, const Vector3 &com, const Symmetric3 &rotational_inertia)
inline InertiaTpl(const InertiaTpl &clone)
inline InertiaTpl &operator=(const InertiaTpl &clone)
template<typename S2, int O2>
inline explicit InertiaTpl(const InertiaTpl<S2, O2> &clone)
inline void setZero()
inline void setIdentity()
inline void setRandom()
template<typename Matrix6Like>
inline void matrix_impl(const Eigen::MatrixBase<Matrix6Like> &M_) const
inline Matrix6 matrix_impl() const
template<typename Matrix6Like>
inline void inverse_impl(const Eigen::MatrixBase<Matrix6Like> &M_) const
inline Matrix6 inverse_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,mcx,mcy,mcz,Ixx,Ixy,Iyy,Ixz,Iyz,Izz]T where c is the center of mass, I=IC+mST(c)S(c) and IC has its origin at the barycenter and S(c) is the the skew matrix representation of the cross product operator.

inline PseudoInertia toPseudoInertia() const

Convert the InertiaTpl object to a 4x4 pseudo inertia matrix.

Returns:

A 4x4 pseudo inertia matrix.

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)
inline InertiaTpl __minus__(const InertiaTpl &Yb) const
inline InertiaTpl &__mequ__(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
template<typename MotionDerived>
inline Scalar vtiv_impl(const MotionDense<MotionDerived> &v) const
template<typename MotionDerived>
inline Matrix6 variation(const MotionDense<MotionDerived> &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()
template<typename S2, int O2>
inline InertiaTpl se3Action_impl(const SE3Tpl<S2, O2> &M) const

aI = aXb.act(bI)

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

bI = aXb.actInv(aI)

template<typename MotionDerived>
inline Force vxiv(const MotionDense<MotionDerived> &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 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.

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

Parameters:
  • mass[in] of the capsule.

  • radius[in] of the capsule.

  • height[in] of the capsule.

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,mcx,mcy,mcz,Ixx,Ixy,Iyy,Ixz,Iyz,Izz]T where I=IC+mST(c)S(c) and IC has its origin at the barycenter.

Parameters:

params[in] The dynamic parameters.

static inline InertiaTpl FromPseudoInertia(const PseudoInertia &pseudo_inertia)

Create an InertiaTpl object from a PseudoInertia object.

Parameters:

pseudo_inertia – A PseudoInertia object.

Returns:

An InertiaTpl object.

static inline InertiaTpl FromLogCholeskyParameters(const LogCholeskyParameters &log_cholesky)

Create an InertiaTpl object from log Cholesky parameters.

Parameters:

log_cholesky – A log cholesky parameters object

Returns:

An InertiaTpl object.

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

Protected Attributes

Scalar m_mass
Vector3 m_com
Symmetric3 m_inertia