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

#include <inertia.hpp>

Public Member Functions

Derived_tderived ()
 
const Derived_tderived () const
 
void disp (std::ostream &os) const
 
const Symmetric3inertia () const
 
Symmetric3inertia ()
 
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
 
Matrix6 ivx (const Motion &v) const
 
const Vector3 & lever () const
 
Vector3 & lever ()
 
Scalar mass () const
 
Scalar & mass ()
 
Matrix6 matrix () const
 
 operator Matrix6 () const
 
bool operator!= (const Derived_t &other) const
 
template<typename MotionDerived >
ForceTpl< typename traits< MotionDerived >::Scalar, traits< MotionDerived >::Optionsoperator* (const MotionDense< MotionDerived > &v) const
 
Derived_t operator+ (const Derived_t &Yb) const
 
Derived_toperator+= (const Derived_t &Yb)
 
Derived_toperator= (const Derived_t &clone)
 
bool operator== (const Derived_t &other) const
 
Derived_t se3Action (const SE3 &M) const
 aI = aXb.act(bI) More...
 
Derived_t se3ActionInverse (const SE3 &M) const
 bI = aXb.actInv(aI) More...
 
void setIdentity ()
 
void setRandom ()
 
void setZero ()
 
Matrix6 variation (const Motion &v) const
 
Scalar vtiv (const Motion &v) const
 
Matrix6 vxi (const Motion &v) const
 

Static Public Member Functions

template<typename M6 >
static 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 $. More...
 
template<typename M6 >
static 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 $. More...
 

Protected Types

typedef Derived Derived_t
 

Protected Member Functions

 SPATIAL_TYPEDEF_TEMPLATE (Derived_t)
 

Friends

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

Detailed Description

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

Definition at line 21 of file src/spatial/inertia.hpp.

Member Typedef Documentation

template<class Derived>
typedef Derived pinocchio::InertiaBase< Derived >::Derived_t
protected

Definition at line 25 of file src/spatial/inertia.hpp.

Member Function Documentation

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

Definition at line 29 of file src/spatial/inertia.hpp.

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

Definition at line 30 of file src/spatial/inertia.hpp.

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

Definition at line 115 of file src/spatial/inertia.hpp.

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

Definition at line 36 of file src/spatial/inertia.hpp.

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

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

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

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

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

Definition at line 106 of file src/spatial/inertia.hpp.

template<class Derived>
template<typename M6 >
static void pinocchio::InertiaBase< Derived >::ivx ( const Motion 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 86 of file src/spatial/inertia.hpp.

template<class Derived>
Matrix6 pinocchio::InertiaBase< Derived >::ivx ( const Motion v) const
inline

Definition at line 92 of file src/spatial/inertia.hpp.

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

Definition at line 34 of file src/spatial/inertia.hpp.

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

Definition at line 35 of file src/spatial/inertia.hpp.

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

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

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

Definition at line 33 of file src/spatial/inertia.hpp.

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

Definition at line 39 of file src/spatial/inertia.hpp.

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

Definition at line 40 of file src/spatial/inertia.hpp.

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

Definition at line 44 of file src/spatial/inertia.hpp.

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 51 of file src/spatial/inertia.hpp.

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

Definition at line 47 of file src/spatial/inertia.hpp.

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

Definition at line 46 of file src/spatial/inertia.hpp.

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

Definition at line 42 of file src/spatial/inertia.hpp.

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

Definition at line 43 of file src/spatial/inertia.hpp.

template<class Derived>
Derived_t pinocchio::InertiaBase< Derived >::se3Action ( const SE3 M) const
inline

aI = aXb.act(bI)

Definition at line 110 of file src/spatial/inertia.hpp.

template<class Derived>
Derived_t pinocchio::InertiaBase< Derived >::se3ActionInverse ( const SE3 M) const
inline

bI = aXb.actInv(aI)

Definition at line 113 of file src/spatial/inertia.hpp.

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

Definition at line 100 of file src/spatial/inertia.hpp.

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

Definition at line 101 of file src/spatial/inertia.hpp.

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

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

template<class Derived>
pinocchio::InertiaBase< Derived >::SPATIAL_TYPEDEF_TEMPLATE ( Derived_t  )
protected
template<class Derived>
Matrix6 pinocchio::InertiaBase< Derived >::variation ( const Motion v) const
inline

Definition at line 55 of file src/spatial/inertia.hpp.

template<class Derived>
Scalar pinocchio::InertiaBase< Derived >::vtiv ( const Motion v) const
inline

Definition at line 54 of file src/spatial/inertia.hpp.

template<class Derived>
template<typename M6 >
static void pinocchio::InertiaBase< Derived >::vxi ( const Motion 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 65 of file src/spatial/inertia.hpp.

template<class Derived>
Matrix6 pinocchio::InertiaBase< Derived >::vxi ( const Motion v) const
inline

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

Friends And Related Function Documentation

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

Definition at line 116 of file src/spatial/inertia.hpp.


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


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:06