Template Struct InertiaBase
Defined in File inertia.hpp
Inheritance Relationships
Base Type
public pinocchio::NumericalBase< Derived >
(Template Struct NumericalBase)
Derived Types
public pinocchio::InertiaTpl< Scalar, Options >
(Template Struct InertiaTpl)public pinocchio::InertiaTpl< context::Scalar, context::Options >
(Template Struct InertiaTpl)
Struct Documentation
-
template<class Derived>
struct InertiaBase : public pinocchio::NumericalBase<Derived> Subclassed by pinocchio::InertiaTpl< Scalar, Options >, pinocchio::InertiaTpl< context::Scalar, context::Options >
Public Functions
-
inline Scalar mass() const
-
inline Scalar &mass()
-
inline const Vector3 &lever() const
-
inline Vector3 &lever()
-
inline const Symmetric3 &inertia() const
-
inline Symmetric3 &inertia()
-
template<typename Matrix6Like>
inline void matrix(const Eigen::MatrixBase<Matrix6Like> &mat) const
-
inline Matrix6 matrix() const
-
inline operator Matrix6() const
-
template<typename Matrix6Like>
inline void inverse(const Eigen::MatrixBase<Matrix6Like> &mat) const
-
inline Matrix6 inverse() const
-
template<typename MotionDerived>
inline ForceTpl<typename traits<MotionDerived>::Scalar, traits<MotionDerived>::Options> operator*(const MotionDense<MotionDerived> &v) const
-
template<typename MotionDerived>
inline Scalar vtiv(const MotionDense<MotionDerived> &v) const
-
template<typename MotionDerived>
inline Matrix6 variation(const MotionDense<MotionDerived> &v) const
-
template<typename MotionDerived>
inline Matrix6 vxi(const MotionDense<MotionDerived> &v) const
-
template<typename MotionDerived>
inline Matrix6 ivx(const MotionDense<MotionDerived> &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
-
template<typename S2, int O2>
inline Derived se3Action(const SE3Tpl<S2, O2> &M) const aI = aXb.act(bI)
-
template<typename S2, int O2>
inline Derived se3ActionInverse(const SE3Tpl<S2, O2> &M) const bI = aXb.actInv(aI)
-
inline void disp(std::ostream &os) const
Public Static Functions
-
template<typename MotionDerived, typename M6>
static inline void vxi(const MotionDense<MotionDerived> &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
.- 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 MotionDerived, typename M6>
static inline void ivx(const MotionDense<MotionDerived> &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
.- 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.
Friends
-
inline friend std::ostream &operator<<(std::ostream &os, const InertiaBase<Derived> &X)
-
inline Scalar mass() const