Classes | Public Types | Public Member Functions | Private Attributes | Friends | List of all members
pinocchio::ForceSetTpl< _Scalar, _Options > Class Template Reference

#include <force-set.hpp>

Classes

struct  Block
 

Public Types

enum  { Options = _Options }
 
typedef Eigen::Matrix< Scalar, 3, 3, OptionsMatrix3
 
typedef Eigen::Matrix< Scalar, 3, Eigen::Dynamic, OptionsMatrix3x
 
typedef Eigen::Matrix< Scalar, 6, 6, OptionsMatrix6
 
typedef Eigen::Matrix< Scalar, 6, Eigen::Dynamic, OptionsMatrix6x
 
typedef _Scalar Scalar
 
typedef SE3Tpl< Scalar, OptionsSE3
 
typedef Eigen::Matrix< Scalar, 3, 1, OptionsVector3
 
typedef Eigen::Matrix< Scalar, 6, 1, OptionsVector6
 

Public Member Functions

const Matrix3xangular () const
 
Block block (const int &idx, const int &len)
 
 ForceSetTpl (const int &ncols)
 
 ForceSetTpl (const Matrix3x &linear, const Matrix3x &angular)
 
const Matrix3xlinear () const
 
Matrix6x matrix () const
 
 operator Matrix6x () const
 
ForceSetTpl se3Action (const SE3 &m) const
 af = aXb.act(bf) More...
 
ForceSetTpl se3ActionInverse (const SE3 &m) const
 bf = aXb.actInv(af) More...
 

Private Attributes

Matrix3x m_f
 
Matrix3x m_n
 
int size
 

Friends

std::ostream & operator<< (std::ostream &os, const ForceSetTpl &phi)
 

Detailed Description

template<typename _Scalar, int _Options>
class pinocchio::ForceSetTpl< _Scalar, _Options >

Definition at line 14 of file force-set.hpp.

Member Typedef Documentation

template<typename _Scalar , int _Options>
typedef Eigen::Matrix<Scalar,3,3,Options> pinocchio::ForceSetTpl< _Scalar, _Options >::Matrix3

Definition at line 20 of file force-set.hpp.

template<typename _Scalar , int _Options>
typedef Eigen::Matrix<Scalar,3,Eigen::Dynamic,Options> pinocchio::ForceSetTpl< _Scalar, _Options >::Matrix3x

Definition at line 25 of file force-set.hpp.

template<typename _Scalar , int _Options>
typedef Eigen::Matrix<Scalar,6,6,Options> pinocchio::ForceSetTpl< _Scalar, _Options >::Matrix6

Definition at line 22 of file force-set.hpp.

template<typename _Scalar , int _Options>
typedef Eigen::Matrix<Scalar,6,Eigen::Dynamic,Options> pinocchio::ForceSetTpl< _Scalar, _Options >::Matrix6x

Definition at line 26 of file force-set.hpp.

template<typename _Scalar , int _Options>
typedef _Scalar pinocchio::ForceSetTpl< _Scalar, _Options >::Scalar

Definition at line 17 of file force-set.hpp.

template<typename _Scalar , int _Options>
typedef SE3Tpl<Scalar,Options> pinocchio::ForceSetTpl< _Scalar, _Options >::SE3

Definition at line 23 of file force-set.hpp.

template<typename _Scalar , int _Options>
typedef Eigen::Matrix<Scalar,3,1,Options> pinocchio::ForceSetTpl< _Scalar, _Options >::Vector3

Definition at line 19 of file force-set.hpp.

template<typename _Scalar , int _Options>
typedef Eigen::Matrix<Scalar,6,1,Options> pinocchio::ForceSetTpl< _Scalar, _Options >::Vector6

Definition at line 21 of file force-set.hpp.

Member Enumeration Documentation

template<typename _Scalar , int _Options>
anonymous enum
Enumerator
Options 

Definition at line 18 of file force-set.hpp.

Constructor & Destructor Documentation

template<typename _Scalar , int _Options>
pinocchio::ForceSetTpl< _Scalar, _Options >::ForceSetTpl ( const int &  ncols)
inline

Definition at line 30 of file force-set.hpp.

template<typename _Scalar , int _Options>
pinocchio::ForceSetTpl< _Scalar, _Options >::ForceSetTpl ( const Matrix3x linear,
const Matrix3x angular 
)
inline

Definition at line 32 of file force-set.hpp.

Member Function Documentation

template<typename _Scalar , int _Options>
const Matrix3x& pinocchio::ForceSetTpl< _Scalar, _Options >::angular ( ) const
inline

Definition at line 47 of file force-set.hpp.

template<typename _Scalar , int _Options>
Block pinocchio::ForceSetTpl< _Scalar, _Options >::block ( const int &  idx,
const int &  len 
)
inline

Definition at line 140 of file force-set.hpp.

template<typename _Scalar , int _Options>
const Matrix3x& pinocchio::ForceSetTpl< _Scalar, _Options >::linear ( ) const
inline

Definition at line 46 of file force-set.hpp.

template<typename _Scalar , int _Options>
Matrix6x pinocchio::ForceSetTpl< _Scalar, _Options >::matrix ( ) const
inline

Definition at line 36 of file force-set.hpp.

template<typename _Scalar , int _Options>
pinocchio::ForceSetTpl< _Scalar, _Options >::operator Matrix6x ( ) const
inline

Definition at line 43 of file force-set.hpp.

template<typename _Scalar , int _Options>
ForceSetTpl pinocchio::ForceSetTpl< _Scalar, _Options >::se3Action ( const SE3 m) const
inline

af = aXb.act(bf)

Definition at line 50 of file force-set.hpp.

template<typename _Scalar , int _Options>
ForceSetTpl pinocchio::ForceSetTpl< _Scalar, _Options >::se3ActionInverse ( const SE3 m) const
inline

bf = aXb.actInv(af)

Definition at line 57 of file force-set.hpp.

Friends And Related Function Documentation

template<typename _Scalar , int _Options>
std::ostream& operator<< ( std::ostream &  os,
const ForceSetTpl< _Scalar, _Options > &  phi 
)
friend

Definition at line 64 of file force-set.hpp.

Member Data Documentation

template<typename _Scalar , int _Options>
Matrix3x pinocchio::ForceSetTpl< _Scalar, _Options >::m_f
private

Definition at line 153 of file force-set.hpp.

template<typename _Scalar , int _Options>
Matrix3x pinocchio::ForceSetTpl< _Scalar, _Options >::m_n
private

Definition at line 153 of file force-set.hpp.

template<typename _Scalar , int _Options>
int pinocchio::ForceSetTpl< _Scalar, _Options >::size
private

Definition at line 152 of file force-set.hpp.


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


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