Template Class InertiaBase

Inheritance Relationships

Derived Type

Class Documentation

template<class Derived>
class InertiaBase

Subclassed by pinocchio::InertiaTpl< Scalar, Options >

Public Functions

inline Derived_t &derived()
inline const Derived_t &derived() const
inline Scalar mass() const
inline Scalar &mass()
inline const Vector3 &lever() const
inline Vector3 &lever()
inline const Symmetric3 &inertia() const
inline Symmetric3 &inertia()
inline Matrix6 matrix() const
inline operator Matrix6() const
inline Derived_t &operator=(const Derived_t &clone)
inline bool operator==(const Derived_t &other) const
inline bool operator!=(const Derived_t &other) const
inline Derived_t &operator+=(const Derived_t &Yb)
inline Derived_t operator+(const Derived_t &Yb) const
template<typename MotionDerived>
inline ForceTpl<typename traits<MotionDerived>::Scalar, traits<MotionDerived>::Options> operator*(const MotionDense<MotionDerived> &v) const
inline Scalar vtiv(const Motion &v) const
inline Matrix6 variation(const Motion &v) const
inline Matrix6 vxi(const Motion &v) const
inline Matrix6 ivx(const Motion &v) const
inline void setZero()
inline void setIdentity()
inline void setRandom()
inline bool isApprox(const Derived &other, const Scalar &prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
inline bool isZero(const Scalar &prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
inline Derived_t se3Action(const SE3 &M) const

aI = aXb.act(bI)

inline Derived_t se3ActionInverse(const SE3 &M) const

bI = aXb.actInv(aI)

inline void disp(std::ostream &os) const

Public Static Functions

template<typename M6>
static inline 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 \( \dot{I} = v \times^{*} I \).

Parameters:
  • v[in] The spatial velocity of the frame supporting the inertia.

  • I[in] The spatial inertia in motion.

  • Iout[out] The time derivative of the inertia I.

template<typename M6>
static inline 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 \( \dot{I} = v \times^{*} I \).

Parameters:
  • v[in] The spatial velocity of the frame supporting the inertia.

  • I[in] The spatial inertia in motion.

  • Iout[out] The time derivative of the inertia I.

Protected Types

typedef Derived Derived_t

Protected Functions

SPATIAL_TYPEDEF_TEMPLATE(Derived_t)

Friends

inline friend std::ostream &operator<<(std::ostream &os, const InertiaBase<Derived_t> &X)