Public Member Functions | Static Public Member Functions | Friends | List of all members
pinocchio::InertiaBase< Derived > Struct Template Reference

#include <inertia.hpp>

Inheritance diagram for pinocchio::InertiaBase< Derived >:
Inheritance graph
[legend]

Public Member Functions

Derived & const_cast_derived () const
 
Derived & derived ()
 
const Derived & derived () const
 
void disp (std::ostream &os) const
 
Symmetric3inertia ()
 
const Symmetric3inertia () const
 
Matrix6 inverse () const
 
template<typename Matrix6Like >
void inverse (const Eigen::MatrixBase< Matrix6Like > &mat) const
 
bool isApprox (const Derived &other, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
bool isZero (const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
 
template<typename MotionDerived >
Matrix6 ivx (const MotionDense< MotionDerived > &v) const
 
Vector3 & lever ()
 
const Vector3 & lever () const
 
Scalarmass ()
 
Scalar mass () const
 
Matrix6 matrix () const
 
template<typename Matrix6Like >
void matrix (const Eigen::MatrixBase< Matrix6Like > &mat) const
 
 operator Matrix6 () const
 
bool operator!= (const Derived &other) const
 
template<typename MotionDerived >
ForceTpl< typename traits< MotionDerived >::Scalar, traits< MotionDerived >::Optionsoperator* (const MotionDense< MotionDerived > &v) const
 
Derived operator+ (const Derived &Yb) const
 
Derived & operator+= (const Derived &Yb)
 
Derived operator- (const Derived &Yb) const
 
Derived & operator-= (const Derived &Yb)
 
Derived & operator= (const Derived &clone)
 
bool operator== (const Derived &other) const
 
template<typename S2 , int O2>
Derived se3Action (const SE3Tpl< S2, O2 > &M) const
 aI = aXb.act(bI) More...
 
template<typename S2 , int O2>
Derived se3ActionInverse (const SE3Tpl< S2, O2 > &M) const
 bI = aXb.actInv(aI) More...
 
void setIdentity ()
 
void setRandom ()
 
void setZero ()
 
 SPATIAL_TYPEDEF_TEMPLATE (Derived)
 
template<typename MotionDerived >
Matrix6 variation (const MotionDense< MotionDerived > &v) const
 
template<typename MotionDerived >
Scalar vtiv (const MotionDense< MotionDerived > &v) const
 
template<typename MotionDerived >
Matrix6 vxi (const MotionDense< MotionDerived > &v) const
 

Static Public Member Functions

template<typename MotionDerived , typename M6 >
static 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 $ \dot{I} = v \times^{*} I $. More...
 
template<typename MotionDerived , typename M6 >
static 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 $ \dot{I} = v \times^{*} I $. More...
 

Friends

std::ostream & operator<< (std::ostream &os, const InertiaBase< Derived > &X)
 

Additional Inherited Members

- Public Types inherited from pinocchio::NumericalBase< Derived >
typedef traits< Derived >::Scalar Scalar
 

Detailed Description

template<class Derived>
struct pinocchio::InertiaBase< Derived >

Definition at line 19 of file spatial/inertia.hpp.

Member Function Documentation

◆ const_cast_derived()

template<class Derived >
Derived& pinocchio::InertiaBase< Derived >::const_cast_derived ( ) const
inline

Definition at line 32 of file spatial/inertia.hpp.

◆ derived() [1/2]

template<class Derived >
Derived& pinocchio::InertiaBase< Derived >::derived ( )
inline

Definition at line 23 of file spatial/inertia.hpp.

◆ derived() [2/2]

template<class Derived >
const Derived& pinocchio::InertiaBase< Derived >::derived ( ) const
inline

Definition at line 27 of file spatial/inertia.hpp.

◆ disp()

template<class Derived >
void pinocchio::InertiaBase< Derived >::disp ( std::ostream &  os) const
inline

Definition at line 222 of file spatial/inertia.hpp.

◆ inertia() [1/2]

template<class Derived >
Symmetric3& pinocchio::InertiaBase< Derived >::inertia ( )
inline

Definition at line 57 of file spatial/inertia.hpp.

◆ inertia() [2/2]

template<class Derived >
const Symmetric3& pinocchio::InertiaBase< Derived >::inertia ( ) const
inline

Definition at line 53 of file spatial/inertia.hpp.

◆ inverse() [1/2]

template<class Derived >
Matrix6 pinocchio::InertiaBase< Derived >::inverse ( ) const
inline

Definition at line 81 of file spatial/inertia.hpp.

◆ inverse() [2/2]

template<class Derived >
template<typename Matrix6Like >
void pinocchio::InertiaBase< Derived >::inverse ( const Eigen::MatrixBase< Matrix6Like > &  mat) const
inline

Definition at line 77 of file spatial/inertia.hpp.

◆ isApprox()

template<class Derived >
bool pinocchio::InertiaBase< Derived >::isApprox ( const Derived &  other,
const Scalar prec = Eigen::NumTraits<Scalar>::dummy_precision() 
) const
inline

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

◆ isZero()

template<class Derived >
bool pinocchio::InertiaBase< Derived >::isZero ( const Scalar prec = Eigen::NumTraits<Scalar>::dummy_precision()) const
inline

Definition at line 203 of file spatial/inertia.hpp.

◆ ivx() [1/2]

template<class Derived >
template<typename MotionDerived >
Matrix6 pinocchio::InertiaBase< Derived >::ivx ( const MotionDense< MotionDerived > &  v) const
inline

Definition at line 176 of file spatial/inertia.hpp.

◆ ivx() [2/2]

template<class Derived >
template<typename MotionDerived , typename M6 >
static void pinocchio::InertiaBase< Derived >::ivx ( const MotionDense< MotionDerived > &  v,
const Derived &  I,
const Eigen::MatrixBase< M6 > &  Iout 
)
inlinestatic

Time variation operator. It computes the time derivative of an inertia I corresponding to the formula $ \dot{I} = v \times^{*} I $.

Parameters
[in]vThe spatial velocity of the frame supporting the inertia.
[in]IThe spatial inertia in motion.
[out]IoutThe time derivative of the inertia I.

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

◆ lever() [1/2]

template<class Derived >
Vector3& pinocchio::InertiaBase< Derived >::lever ( )
inline

Definition at line 49 of file spatial/inertia.hpp.

◆ lever() [2/2]

template<class Derived >
const Vector3& pinocchio::InertiaBase< Derived >::lever ( ) const
inline

Definition at line 45 of file spatial/inertia.hpp.

◆ mass() [1/2]

template<class Derived >
Scalar& pinocchio::InertiaBase< Derived >::mass ( )
inline

Definition at line 41 of file spatial/inertia.hpp.

◆ mass() [2/2]

template<class Derived >
Scalar pinocchio::InertiaBase< Derived >::mass ( ) const
inline

Definition at line 37 of file spatial/inertia.hpp.

◆ matrix() [1/2]

template<class Derived >
Matrix6 pinocchio::InertiaBase< Derived >::matrix ( ) const
inline

Definition at line 67 of file spatial/inertia.hpp.

◆ matrix() [2/2]

template<class Derived >
template<typename Matrix6Like >
void pinocchio::InertiaBase< Derived >::matrix ( const Eigen::MatrixBase< Matrix6Like > &  mat) const
inline

Definition at line 63 of file spatial/inertia.hpp.

◆ operator Matrix6()

template<class Derived >
pinocchio::InertiaBase< Derived >::operator Matrix6 ( ) const
inline

Definition at line 71 of file spatial/inertia.hpp.

◆ operator!=()

template<class Derived >
bool pinocchio::InertiaBase< Derived >::operator!= ( const Derived &  other) const
inline

Definition at line 94 of file spatial/inertia.hpp.

◆ operator*()

template<class Derived >
template<typename MotionDerived >
ForceTpl<typename traits<MotionDerived>::Scalar, traits<MotionDerived>::Options> pinocchio::InertiaBase< Derived >::operator* ( const MotionDense< MotionDerived > &  v) const
inline

Definition at line 118 of file spatial/inertia.hpp.

◆ operator+()

template<class Derived >
Derived pinocchio::InertiaBase< Derived >::operator+ ( const Derived &  Yb) const
inline

Definition at line 103 of file spatial/inertia.hpp.

◆ operator+=()

template<class Derived >
Derived& pinocchio::InertiaBase< Derived >::operator+= ( const Derived &  Yb)
inline

Definition at line 99 of file spatial/inertia.hpp.

◆ operator-()

template<class Derived >
Derived pinocchio::InertiaBase< Derived >::operator- ( const Derived &  Yb) const
inline

Definition at line 111 of file spatial/inertia.hpp.

◆ operator-=()

template<class Derived >
Derived& pinocchio::InertiaBase< Derived >::operator-= ( const Derived &  Yb)
inline

Definition at line 107 of file spatial/inertia.hpp.

◆ operator=()

template<class Derived >
Derived& pinocchio::InertiaBase< Derived >::operator= ( const Derived &  clone)
inline

Definition at line 86 of file spatial/inertia.hpp.

◆ operator==()

template<class Derived >
bool pinocchio::InertiaBase< Derived >::operator== ( const Derived &  other) const
inline

Definition at line 90 of file spatial/inertia.hpp.

◆ se3Action()

template<class Derived >
template<typename S2 , int O2>
Derived pinocchio::InertiaBase< Derived >::se3Action ( const SE3Tpl< S2, O2 > &  M) const
inline

aI = aXb.act(bI)

Definition at line 210 of file spatial/inertia.hpp.

◆ se3ActionInverse()

template<class Derived >
template<typename S2 , int O2>
Derived pinocchio::InertiaBase< Derived >::se3ActionInverse ( const SE3Tpl< S2, O2 > &  M) const
inline

bI = aXb.actInv(aI)

Definition at line 217 of file spatial/inertia.hpp.

◆ setIdentity()

template<class Derived >
void pinocchio::InertiaBase< Derived >::setIdentity ( )
inline

Definition at line 187 of file spatial/inertia.hpp.

◆ setRandom()

template<class Derived >
void pinocchio::InertiaBase< Derived >::setRandom ( )
inline

Definition at line 191 of file spatial/inertia.hpp.

◆ setZero()

template<class Derived >
void pinocchio::InertiaBase< Derived >::setZero ( )
inline

Definition at line 183 of file spatial/inertia.hpp.

◆ SPATIAL_TYPEDEF_TEMPLATE()

template<class Derived >
pinocchio::InertiaBase< Derived >::SPATIAL_TYPEDEF_TEMPLATE ( Derived  )

◆ variation()

template<class Derived >
template<typename MotionDerived >
Matrix6 pinocchio::InertiaBase< Derived >::variation ( const MotionDense< MotionDerived > &  v) const
inline

Definition at line 130 of file spatial/inertia.hpp.

◆ vtiv()

template<class Derived >
template<typename MotionDerived >
Scalar pinocchio::InertiaBase< Derived >::vtiv ( const MotionDense< MotionDerived > &  v) const
inline

Definition at line 124 of file spatial/inertia.hpp.

◆ vxi() [1/2]

template<class Derived >
template<typename MotionDerived >
Matrix6 pinocchio::InertiaBase< Derived >::vxi ( const MotionDense< MotionDerived > &  v) const
inline

Definition at line 152 of file spatial/inertia.hpp.

◆ vxi() [2/2]

template<class Derived >
template<typename MotionDerived , typename M6 >
static void pinocchio::InertiaBase< Derived >::vxi ( const MotionDense< MotionDerived > &  v,
const Derived &  I,
const Eigen::MatrixBase< M6 > &  Iout 
)
inlinestatic

Time variation operator. It computes the time derivative of an inertia I corresponding to the formula $ \dot{I} = v \times^{*} I $.

Parameters
[in]vThe spatial velocity of the frame supporting the inertia.
[in]IThe spatial inertia in motion.
[out]IoutThe time derivative of the inertia I.

Definition at line 145 of file spatial/inertia.hpp.

Friends And Related Function Documentation

◆ operator<<

template<class Derived >
std::ostream& operator<< ( std::ostream &  os,
const InertiaBase< Derived > &  X 
)
friend

Definition at line 226 of file spatial/inertia.hpp.


The documentation for this struct was generated from the following file:


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:52