Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Protected Attributes | List of all members
pinocchio::JointModelMimic< JointModel > Struct Template Reference

#include <joint-mimic.hpp>

Inheritance diagram for pinocchio::JointModelMimic< JointModel >:
Inheritance graph
[legend]

Public Types

typedef JointModelBase< JointModelMimicBase
 

Public Member Functions

Basebase ()
 
const Basebase () const
 
template<typename ConfigVector >
EIGEN_DONT_INLINE void calc (JointDataDerived &jdata, const typename Eigen::MatrixBase< ConfigVector > &qs) const
 
template<typename ConfigVector , typename TangentVector >
EIGEN_DONT_INLINE void calc (JointDataDerived &jdata, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
 
template<typename Matrix6Like >
void calc_aba (JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
 
template<typename NewScalar >
CastType< NewScalar, JointModelMimic >::type cast () const
 
JointDataDerived createData () const
 
int idx_q_impl () const
 
int idx_v_impl () const
 
const JointModeljmodel () const
 
JointModeljmodel ()
 
template<typename D >
SizeDepType< NV >::template BlockReturn< D >::ConstType jointBlock_impl (const Eigen::MatrixBase< D > &Mat) const
 Returns a block of dimension nv()xnv() located at position idx_v(),idx_v() in the matrix Mat. More...
 
template<typename D >
SizeDepType< NV >::template BlockReturn< D >::Type jointBlock_impl (Eigen::MatrixBase< D > &Mat) const
 
template<typename D >
SizeDepType< NV >::template ColsReturn< D >::ConstType jointCols_impl (const Eigen::MatrixBase< D > &A) const
 
template<typename D >
SizeDepType< NV >::template ColsReturn< D >::Type jointCols_impl (Eigen::MatrixBase< D > &A) const
 
template<typename D >
SizeDepType< NQ >::template SegmentReturn< D >::ConstType jointConfigSelector_impl (const Eigen::MatrixBase< D > &a) const
 
template<typename D >
SizeDepType< NQ >::template SegmentReturn< D >::Type jointConfigSelector_impl (Eigen::MatrixBase< D > &a) const
 
 JointModelMimic ()
 
 JointModelMimic (const JointModelBase< JointModel > &jmodel, const Scalar &scaling, const Scalar &offset)
 
template<typename D >
SizeDepType< NV >::template RowsReturn< D >::ConstType jointRows_impl (const Eigen::MatrixBase< D > &A) const
 
template<typename D >
SizeDepType< NV >::template RowsReturn< D >::Type jointRows_impl (Eigen::MatrixBase< D > &A) const
 
template<typename D >
SizeDepType< NV >::template SegmentReturn< D >::ConstType jointVelocitySelector_impl (const Eigen::MatrixBase< D > &a) const
 
template<typename D >
SizeDepType< NV >::template SegmentReturn< D >::Type jointVelocitySelector_impl (Eigen::MatrixBase< D > &a) const
 
int nq_impl () const
 
int nv_impl () const
 
const Scalar & offset () const
 
Scalar & offset ()
 
 PINOCCHIO_JOINT_TYPEDEF_TEMPLATE (JointDerived)
 
const Scalar & scaling () const
 
Scalar & scaling ()
 
void setIndexes_impl (JointIndex id, int, int)
 
std::string shortname () const
 
- Public Member Functions inherited from pinocchio::JointModelBase< JointModelMimic< JointModel > >
void calc (JointDataDerived &data, const Eigen::MatrixBase< ConfigVectorType > &qs) const
 
void calc (JointDataDerived &data, const Eigen::MatrixBase< ConfigVectorType > &qs, const Eigen::MatrixBase< TangentVectorType > &vs) const
 
void calc_aba (JointDataDerived &data, const Eigen::MatrixBase< Matrix6Type > &I, const bool update_I=false) const
 
CastType< NewScalar, JointModelMimic< JointModel > >::type cast () const
 
JointDataDerived createData () const
 
JointModelDerived & derived ()
 
const JointModelDerived & derived () const
 
void disp (std::ostream &os) const
 
bool hasSameIndexes (const JointModelBase< OtherDerived > &other) const
 
JointIndex id () const
 
JointIndex id_impl () const
 
int idx_q () const
 
int idx_q_impl () const
 
int idx_v () const
 
int idx_v_impl () const
 
bool isEqual (const JointModelBase< OtherDerived > &) const
 
bool isEqual (const JointModelBase< JointModelMimic< JointModel > > &other) const
 
SizeDepType< NV >::template BlockReturn< D >::ConstType jointBlock (const Eigen::MatrixBase< D > &Mat) const
 Returns a block of dimension nv()xnv() located at position idx_v(),idx_v() in the matrix Mat. More...
 
SizeDepType< NV >::template BlockReturn< D >::Type jointBlock (Eigen::MatrixBase< D > &Mat) const
 
SizeDepType< NV >::template BlockReturn< D >::ConstType jointBlock_impl (const Eigen::MatrixBase< D > &Mat) const
 
SizeDepType< NV >::template BlockReturn< D >::Type jointBlock_impl (Eigen::MatrixBase< D > &Mat) const
 
SizeDepType< NV >::template ColsReturn< D >::ConstType jointCols (const Eigen::MatrixBase< D > &A) const
 
SizeDepType< NV >::template ColsReturn< D >::Type jointCols (Eigen::MatrixBase< D > &A) const
 
SizeDepType< NV >::template ColsReturn< D >::ConstType jointCols_impl (const Eigen::MatrixBase< D > &A) const
 
SizeDepType< NV >::template ColsReturn< D >::Type jointCols_impl (Eigen::MatrixBase< D > &A) const
 
SizeDepType< NQ >::template SegmentReturn< D >::ConstType jointConfigSelector (const Eigen::MatrixBase< D > &a) const
 
SizeDepType< NQ >::template SegmentReturn< D >::Type jointConfigSelector (Eigen::MatrixBase< D > &a) const
 
SizeDepType< NQ >::template SegmentReturn< D >::ConstType jointConfigSelector_impl (const Eigen::MatrixBase< D > &a) const
 
SizeDepType< NQ >::template SegmentReturn< D >::Type jointConfigSelector_impl (Eigen::MatrixBase< D > &a) const
 
SizeDepType< NV >::template RowsReturn< D >::ConstType jointRows (const Eigen::MatrixBase< D > &A) const
 
SizeDepType< NV >::template RowsReturn< D >::Type jointRows (Eigen::MatrixBase< D > &A) const
 
SizeDepType< NV >::template RowsReturn< D >::ConstType jointRows_impl (const Eigen::MatrixBase< D > &A) const
 
SizeDepType< NV >::template RowsReturn< D >::Type jointRows_impl (Eigen::MatrixBase< D > &A) const
 
SizeDepType< NV >::template SegmentReturn< D >::ConstType jointVelocitySelector (const Eigen::MatrixBase< D > &a) const
 
SizeDepType< NV >::template SegmentReturn< D >::Type jointVelocitySelector (Eigen::MatrixBase< D > &a) const
 
SizeDepType< NV >::template SegmentReturn< D >::ConstType jointVelocitySelector_impl (const Eigen::MatrixBase< D > &a) const
 
SizeDepType< NV >::template SegmentReturn< D >::Type jointVelocitySelector_impl (Eigen::MatrixBase< D > &a) const
 
int nq () const
 
int nq_impl () const
 
int nv () const
 
int nv_impl () const
 
bool operator!= (const JointModelBase< OtherDerived > &other) const
 
bool operator== (const JointModelBase< OtherDerived > &other) const
 
 PINOCCHIO_JOINT_TYPEDEF_TEMPLATE (JointDerived)
 
void setIndexes (JointIndex id, int q, int v)
 
void setIndexes_impl (JointIndex id, int q, int v)
 
std::string shortname () const
 

Static Public Member Functions

static std::string classname ()
 
- Static Public Member Functions inherited from pinocchio::JointModelBase< JointModelMimic< JointModel > >
static std::string classname ()
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef traits< JointModelMimic >::JointDerived JointDerived
 
- Public Attributes inherited from pinocchio::JointModelBase< JointModelMimic< JointModel > >
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef traits< JointModelMimic< JointModel > >::JointDerived JointDerived
 

Protected Attributes

JointModel m_jmodel_ref
 
Scalar m_offset
 
Scalar m_scaling
 
- Protected Attributes inherited from pinocchio::JointModelBase< JointModelMimic< JointModel > >
JointIndex i_id
 
int i_q
 
int i_v
 

Additional Inherited Members

- Protected Member Functions inherited from pinocchio::JointModelBase< JointModelMimic< JointModel > >
 JointModelBase ()
 
 JointModelBase (const JointModelBase &clone)
 
JointModelBaseoperator= (const JointModelBase &clone)
 

Detailed Description

template<class JointModel>
struct pinocchio::JointModelMimic< JointModel >

Definition at line 237 of file joint-mimic.hpp.

Member Typedef Documentation

template<class JointModel>
typedef JointModelBase<JointModelMimic> pinocchio::JointModelMimic< JointModel >::Base

Definition at line 411 of file joint-mimic.hpp.

Constructor & Destructor Documentation

template<class JointModel>
pinocchio::JointModelMimic< JointModel >::JointModelMimic ( )
inline

Definition at line 419 of file joint-mimic.hpp.

template<class JointModel>
pinocchio::JointModelMimic< JointModel >::JointModelMimic ( const JointModelBase< JointModel > &  jmodel,
const Scalar &  scaling,
const Scalar &  offset 
)
inline

Definition at line 422 of file joint-mimic.hpp.

Member Function Documentation

template<class JointModel>
Base& pinocchio::JointModelMimic< JointModel >::base ( )
inline

Definition at line 430 of file joint-mimic.hpp.

template<class JointModel>
const Base& pinocchio::JointModelMimic< JointModel >::base ( ) const
inline

Definition at line 431 of file joint-mimic.hpp.

template<class JointModel>
template<typename ConfigVector >
EIGEN_DONT_INLINE void pinocchio::JointModelMimic< JointModel >::calc ( JointDataDerived &  jdata,
const typename Eigen::MatrixBase< ConfigVector > &  qs 
) const
inline

Definition at line 453 of file joint-mimic.hpp.

template<class JointModel>
template<typename ConfigVector , typename TangentVector >
EIGEN_DONT_INLINE void pinocchio::JointModelMimic< JointModel >::calc ( JointDataDerived &  jdata,
const typename Eigen::MatrixBase< ConfigVector > &  qs,
const typename Eigen::MatrixBase< TangentVector > &  vs 
) const
inline

Definition at line 465 of file joint-mimic.hpp.

template<class JointModel>
template<typename Matrix6Like >
void pinocchio::JointModelMimic< JointModel >::calc_aba ( JointDataDerived &  data,
const Eigen::MatrixBase< Matrix6Like > &  I,
const bool  update_I 
) const
inline

Definition at line 480 of file joint-mimic.hpp.

template<class JointModel>
template<typename NewScalar >
CastType<NewScalar,JointModelMimic>::type pinocchio::JointModelMimic< JointModel >::cast ( ) const
inline
Returns
An expression of *this with the Scalar type casted to NewScalar.

Definition at line 502 of file joint-mimic.hpp.

template<class JointModel>
static std::string pinocchio::JointModelMimic< JointModel >::classname ( )
inlinestatic

Definition at line 490 of file joint-mimic.hpp.

template<class JointModel>
JointDataDerived pinocchio::JointModelMimic< JointModel >::createData ( ) const
inline

Definition at line 446 of file joint-mimic.hpp.

template<class JointModel>
int pinocchio::JointModelMimic< JointModel >::idx_q_impl ( ) const
inline

Definition at line 436 of file joint-mimic.hpp.

template<class JointModel>
int pinocchio::JointModelMimic< JointModel >::idx_v_impl ( ) const
inline

Definition at line 437 of file joint-mimic.hpp.

template<class JointModel>
const JointModel& pinocchio::JointModelMimic< JointModel >::jmodel ( ) const
inline

Definition at line 513 of file joint-mimic.hpp.

template<class JointModel>
JointModel& pinocchio::JointModelMimic< JointModel >::jmodel ( )
inline

Definition at line 514 of file joint-mimic.hpp.

template<class JointModel>
template<typename D >
SizeDepType<NV>::template BlockReturn<D>::ConstType pinocchio::JointModelMimic< JointModel >::jointBlock_impl ( const Eigen::MatrixBase< D > &  Mat) const
inline

Returns a block of dimension nv()xnv() located at position idx_v(),idx_v() in the matrix Mat.

Definition at line 618 of file joint-mimic.hpp.

template<class JointModel>
template<typename D >
SizeDepType<NV>::template BlockReturn<D>::Type pinocchio::JointModelMimic< JointModel >::jointBlock_impl ( Eigen::MatrixBase< D > &  Mat) const
inline

Definition at line 628 of file joint-mimic.hpp.

template<class JointModel>
template<typename D >
SizeDepType<NV>::template ColsReturn<D>::ConstType pinocchio::JointModelMimic< JointModel >::jointCols_impl ( const Eigen::MatrixBase< D > &  A) const
inline

Definition at line 576 of file joint-mimic.hpp.

template<class JointModel>
template<typename D >
SizeDepType<NV>::template ColsReturn<D>::Type pinocchio::JointModelMimic< JointModel >::jointCols_impl ( Eigen::MatrixBase< D > &  A) const
inline

Definition at line 586 of file joint-mimic.hpp.

template<class JointModel>
template<typename D >
SizeDepType<NQ>::template SegmentReturn<D>::ConstType pinocchio::JointModelMimic< JointModel >::jointConfigSelector_impl ( const Eigen::MatrixBase< D > &  a) const
inline

Definition at line 534 of file joint-mimic.hpp.

template<class JointModel>
template<typename D >
SizeDepType<NQ>::template SegmentReturn<D>::Type pinocchio::JointModelMimic< JointModel >::jointConfigSelector_impl ( Eigen::MatrixBase< D > &  a) const
inline

Definition at line 544 of file joint-mimic.hpp.

template<class JointModel>
template<typename D >
SizeDepType<NV>::template RowsReturn<D>::ConstType pinocchio::JointModelMimic< JointModel >::jointRows_impl ( const Eigen::MatrixBase< D > &  A) const
inline

Definition at line 597 of file joint-mimic.hpp.

template<class JointModel>
template<typename D >
SizeDepType<NV>::template RowsReturn<D>::Type pinocchio::JointModelMimic< JointModel >::jointRows_impl ( Eigen::MatrixBase< D > &  A) const
inline

Definition at line 607 of file joint-mimic.hpp.

template<class JointModel>
template<typename D >
SizeDepType<NV>::template SegmentReturn<D>::ConstType pinocchio::JointModelMimic< JointModel >::jointVelocitySelector_impl ( const Eigen::MatrixBase< D > &  a) const
inline

Definition at line 555 of file joint-mimic.hpp.

template<class JointModel>
template<typename D >
SizeDepType<NV>::template SegmentReturn<D>::Type pinocchio::JointModelMimic< JointModel >::jointVelocitySelector_impl ( Eigen::MatrixBase< D > &  a) const
inline

Definition at line 565 of file joint-mimic.hpp.

template<class JointModel>
int pinocchio::JointModelMimic< JointModel >::nq_impl ( ) const
inline

Definition at line 433 of file joint-mimic.hpp.

template<class JointModel>
int pinocchio::JointModelMimic< JointModel >::nv_impl ( ) const
inline

Definition at line 434 of file joint-mimic.hpp.

template<class JointModel>
const Scalar& pinocchio::JointModelMimic< JointModel >::offset ( ) const
inline

Definition at line 519 of file joint-mimic.hpp.

template<class JointModel>
Scalar& pinocchio::JointModelMimic< JointModel >::offset ( )
inline

Definition at line 520 of file joint-mimic.hpp.

template<class JointModel>
pinocchio::JointModelMimic< JointModel >::PINOCCHIO_JOINT_TYPEDEF_TEMPLATE ( JointDerived  )
template<class JointModel>
const Scalar& pinocchio::JointModelMimic< JointModel >::scaling ( ) const
inline

Definition at line 516 of file joint-mimic.hpp.

template<class JointModel>
Scalar& pinocchio::JointModelMimic< JointModel >::scaling ( )
inline

Definition at line 517 of file joint-mimic.hpp.

template<class JointModel>
void pinocchio::JointModelMimic< JointModel >::setIndexes_impl ( JointIndex  id,
int  ,
int   
)
inline

Definition at line 439 of file joint-mimic.hpp.

template<class JointModel>
std::string pinocchio::JointModelMimic< JointModel >::shortname ( ) const
inline

Definition at line 495 of file joint-mimic.hpp.

Member Data Documentation

template<class JointModel>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef traits<JointModelMimic>::JointDerived pinocchio::JointModelMimic< JointModel >::JointDerived

Definition at line 407 of file joint-mimic.hpp.

template<class JointModel>
JointModel pinocchio::JointModelMimic< JointModel >::m_jmodel_ref
protected

Definition at line 525 of file joint-mimic.hpp.

template<class JointModel>
Scalar pinocchio::JointModelMimic< JointModel >::m_offset
protected

Definition at line 526 of file joint-mimic.hpp.

template<class JointModel>
Scalar pinocchio::JointModelMimic< JointModel >::m_scaling
protected

Definition at line 526 of file joint-mimic.hpp.


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


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