Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | Friends | List of all members
pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl > Struct Template Reference

#include <fwd.hpp>

Public Types

typedef InertiaTpl< Scalar, OptionsInertia
 
typedef JointCollectionTpl< Scalar, OptionsJointCollection
 
typedef JointCompositeTpl< _Scalar, _Options, JointCollectionTpl > JointDerived
 
typedef JointModelTpl< Scalar, Options, JointCollectionTpl > JointModel
 
typedef JointModel JointModelVariant
 
typedef MotionTpl< Scalar, OptionsMotion
 
typedef SE3Tpl< Scalar, OptionsSE3
 

Public Member Functions

template<typename JointModel >
JointModelDerived & addJoint (const JointModelBase< JointModel > &jmodel, const SE3 &placement=SE3::Identity())
 Add a joint to the vector of joints. More...
 
template<typename ConfigVectorType >
void calc (JointDataDerived &data, const Eigen::MatrixBase< ConfigVectorType > &qs) const
 
template<typename ConfigVectorType , typename TangentVectorType >
void calc (JointDataDerived &data, const Eigen::MatrixBase< ConfigVectorType > &qs, const Eigen::MatrixBase< TangentVectorType > &vs) const
 
template<typename Matrix6Like >
void calc_aba (JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
 
template<typename NewScalar >
JointModelCompositeTpl< NewScalar, Options, JointCollectionTpl > cast () const
 
JointDataDerived createData () const
 
const std::vector< bool > hasConfigurationLimit () const
 
const std::vector< bool > hasConfigurationLimitInTangent () const
 
bool isEqual (const JointModelCompositeTpl &other) const
 
template<typename D >
SizeDepType< NV >::template ColsReturn< D >::ConstType jointCols (const Eigen::MatrixBase< D > &A) const
 
template<typename D >
SizeDepType< NV >::template ColsReturn< D >::Type jointCols (Eigen::MatrixBase< D > &A) const
 
template<typename D >
SizeDepType< Eigen::Dynamic >::template ColsReturn< D >::ConstType jointCols_impl (const Eigen::MatrixBase< D > &A) const
 
template<typename D >
SizeDepType< Eigen::Dynamic >::template ColsReturn< D >::Type jointCols_impl (Eigen::MatrixBase< D > &A) const
 
template<typename D >
SizeDepType< NQ >::template SegmentReturn< D >::ConstType jointConfigSelector (const Eigen::MatrixBase< D > &a) const
 
template<typename D >
SizeDepType< NQ >::template SegmentReturn< D >::Type jointConfigSelector (Eigen::MatrixBase< D > &a) const
 
template<typename D >
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::ConstType jointConfigSelector_impl (const Eigen::MatrixBase< D > &a) const
 
template<typename D >
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::Type jointConfigSelector_impl (Eigen::MatrixBase< D > &a) const
 
 JointModelCompositeTpl ()
 Default contructor. More...
 
template<typename JointModel >
 JointModelCompositeTpl (const JointModelBase< JointModel > &jmodel, const SE3 &placement=SE3::Identity())
 Constructor with one joint. More...
 
 JointModelCompositeTpl (const JointModelCompositeTpl &other)
 Copy constructor. More...
 
 JointModelCompositeTpl (const size_t size)
 Default contructor with a defined size. More...
 
template<typename D >
SizeDepType< NV >::template SegmentReturn< D >::ConstType jointVelocitySelector (const Eigen::MatrixBase< D > &a) const
 
template<typename D >
SizeDepType< NV >::template SegmentReturn< D >::Type jointVelocitySelector (Eigen::MatrixBase< D > &a) const
 
template<typename D >
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::ConstType jointVelocitySelector_impl (const Eigen::MatrixBase< D > &a) const
 
template<typename D >
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::Type jointVelocitySelector_impl (Eigen::MatrixBase< D > &a) const
 
int nq_impl () const
 
int nv_impl () const
 
JointModelCompositeTploperator= (const JointModelCompositeTpl &other)
 
typedef PINOCCHIO_ALIGNED_STD_VECTOR (JointModel) JointModelVector
 
 PINOCCHIO_ALIGNED_STD_VECTOR (SE3) jointPlacements
 Vector of joint placements. Those placements correspond to the origin of the joint relatively to their parent. More...
 
 PINOCCHIO_JOINT_TYPEDEF_TEMPLATE (JointDerived)
 
void setIndexes_impl (JointIndex id, int q, int v)
 Update the indexes of subjoints in the stack. More...
 
std::string shortname () const
 

Static Public Member Functions

static std::string classname ()
 

Public Attributes

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointModelBase< JointModelCompositeTplBase
 
JointModelVector joints
 Vector of joints contained in the joint composite. More...
 
int njoints
 Number of joints contained in the JointModelComposite. More...
 

Protected Member Functions

void updateJointIndexes ()
 Update the indexes of the joints contained in the composition according to the position of the joint composite. More...
 

Protected Attributes

std::vector< int > m_idx_q
 Keep information of both the dimension and the position of the joints in the composition. More...
 
std::vector< int > m_idx_v
 Index in the tangent vector. More...
 
int m_nq
 Dimensions of the config and tangent space of the composite joint. More...
 
std::vector< int > m_nqs
 Dimension of the segment in the config vector. More...
 
int m_nv
 
std::vector< int > m_nvs
 Dimension of the segment in the tangent vector. More...
 

Friends

template<typename , int , template< typename S, int O > class, typename , typename >
struct JointCompositeCalcFirstOrderStep
 
template<typename , int , template< typename S, int O > class, typename >
struct JointCompositeCalcZeroOrderStep
 
template<typename , int , template< typename, int > class>
struct JointModelCompositeTpl
 
struct Serialize< JointModelCompositeTpl >
 

Detailed Description

template<typename _Scalar, int _Options, template< typename S, int O > class JointCollectionTpl>
struct pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >

Definition at line 85 of file multibody/joint/fwd.hpp.

Member Typedef Documentation

◆ Inertia

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
typedef InertiaTpl<Scalar,Options> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::Inertia

Definition at line 164 of file joint-composite.hpp.

◆ JointCollection

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
typedef JointCollectionTpl<Scalar,Options> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointCollection

Definition at line 158 of file joint-composite.hpp.

◆ JointDerived

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
typedef JointCompositeTpl<_Scalar,_Options,JointCollectionTpl> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointDerived

Definition at line 155 of file joint-composite.hpp.

◆ JointModel

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
typedef JointModelTpl<Scalar,Options,JointCollectionTpl> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointModel

Definition at line 159 of file joint-composite.hpp.

◆ JointModelVariant

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
typedef JointModel pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointModelVariant

Definition at line 160 of file joint-composite.hpp.

◆ Motion

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
typedef MotionTpl<Scalar,Options> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::Motion

Definition at line 163 of file joint-composite.hpp.

◆ SE3

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
typedef SE3Tpl<Scalar,Options> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::SE3

Definition at line 162 of file joint-composite.hpp.

Constructor & Destructor Documentation

◆ JointModelCompositeTpl() [1/4]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointModelCompositeTpl ( )
inline

Default contructor.

Definition at line 176 of file joint-composite.hpp.

◆ JointModelCompositeTpl() [2/4]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointModelCompositeTpl ( const size_t  size)
inline

Default contructor with a defined size.

Definition at line 185 of file joint-composite.hpp.

◆ JointModelCompositeTpl() [3/4]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename JointModel >
pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointModelCompositeTpl ( const JointModelBase< JointModel > &  jmodel,
const SE3 placement = SE3::Identity() 
)
inline

Constructor with one joint.

Parameters
jmodelModel of the first joint.
placementPlacement of the first joint w.r.t. the joint origin.

Definition at line 204 of file joint-composite.hpp.

◆ JointModelCompositeTpl() [4/4]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointModelCompositeTpl ( const JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl > &  other)
inline

Copy constructor.

Parameters
otherJointModel to copy.

Definition at line 220 of file joint-composite.hpp.

Member Function Documentation

◆ addJoint()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename JointModel >
JointModelDerived& pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::addJoint ( const JointModelBase< JointModel > &  jmodel,
const SE3 placement = SE3::Identity() 
)
inline

Add a joint to the vector of joints.

Parameters
jmodelModel of the joint to add.
placementPlacement of the joint relatively to its predecessor.
Returns
A reference to *this

Definition at line 241 of file joint-composite.hpp.

◆ calc() [1/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename ConfigVectorType >
void pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::calc ( JointDataDerived &  data,
const Eigen::MatrixBase< ConfigVectorType > &  qs 
) const

◆ calc() [2/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename ConfigVectorType , typename TangentVectorType >
void pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::calc ( JointDataDerived &  data,
const Eigen::MatrixBase< ConfigVectorType > &  qs,
const Eigen::MatrixBase< TangentVectorType > &  vs 
) const

◆ calc_aba()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename Matrix6Like >
void pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::calc_aba ( JointDataDerived &  data,
const Eigen::MatrixBase< Matrix6Like > &  I,
const bool  update_I 
) const
inline

Definition at line 304 of file joint-composite.hpp.

◆ cast()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename NewScalar >
JointModelCompositeTpl<NewScalar,Options,JointCollectionTpl> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::cast ( ) const
inline
Returns
An expression of *this with the Scalar type casted to NewScalar.

Definition at line 369 of file joint-composite.hpp.

◆ classname()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
static std::string pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::classname ( )
inlinestatic

Definition at line 333 of file joint-composite.hpp.

◆ createData()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
JointDataDerived pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::createData ( ) const
inline

Definition at line 255 of file joint-composite.hpp.

◆ hasConfigurationLimit()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
const std::vector<bool> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::hasConfigurationLimit ( ) const
inline

Definition at line 263 of file joint-composite.hpp.

◆ hasConfigurationLimitInTangent()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
const std::vector<bool> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::hasConfigurationLimitInTangent ( ) const
inline

Definition at line 276 of file joint-composite.hpp.

◆ isEqual()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
bool pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::isEqual ( const JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl > &  other) const
inline

Definition at line 353 of file joint-composite.hpp.

◆ jointCols() [1/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename D >
SizeDepType<NV>::template ColsReturn<D>::ConstType pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::jointCols ( const Eigen::MatrixBase< D > &  A) const
inline

Definition at line 414 of file joint-composite.hpp.

◆ jointCols() [2/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename D >
SizeDepType<NV>::template ColsReturn<D>::Type pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::jointCols ( Eigen::MatrixBase< D > &  A) const
inline

Definition at line 417 of file joint-composite.hpp.

◆ jointCols_impl() [1/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename D >
SizeDepType<Eigen::Dynamic>::template ColsReturn<D>::ConstType pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::jointCols_impl ( const Eigen::MatrixBase< D > &  A) const
inline

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

◆ jointCols_impl() [2/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename D >
SizeDepType<Eigen::Dynamic>::template ColsReturn<D>::Type pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::jointCols_impl ( Eigen::MatrixBase< D > &  A) const
inline

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

◆ jointConfigSelector() [1/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename D >
SizeDepType<NQ>::template SegmentReturn<D>::ConstType pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::jointConfigSelector ( const Eigen::MatrixBase< D > &  a) const
inline

Definition at line 400 of file joint-composite.hpp.

◆ jointConfigSelector() [2/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename D >
SizeDepType<NQ>::template SegmentReturn<D>::Type pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::jointConfigSelector ( Eigen::MatrixBase< D > &  a) const
inline

Definition at line 403 of file joint-composite.hpp.

◆ jointConfigSelector_impl() [1/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename D >
SizeDepType<Eigen::Dynamic>::template SegmentReturn<D>::ConstType pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::jointConfigSelector_impl ( const Eigen::MatrixBase< D > &  a) const
inline

Definition at line 421 of file joint-composite.hpp.

◆ jointConfigSelector_impl() [2/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename D >
SizeDepType<Eigen::Dynamic>::template SegmentReturn<D>::Type pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::jointConfigSelector_impl ( Eigen::MatrixBase< D > &  a) const
inline

Definition at line 424 of file joint-composite.hpp.

◆ jointVelocitySelector() [1/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename D >
SizeDepType<NV>::template SegmentReturn<D>::ConstType pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::jointVelocitySelector ( const Eigen::MatrixBase< D > &  a) const
inline

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

◆ jointVelocitySelector() [2/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename D >
SizeDepType<NV>::template SegmentReturn<D>::Type pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::jointVelocitySelector ( Eigen::MatrixBase< D > &  a) const
inline

Definition at line 410 of file joint-composite.hpp.

◆ jointVelocitySelector_impl() [1/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename D >
SizeDepType<Eigen::Dynamic>::template SegmentReturn<D>::ConstType pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::jointVelocitySelector_impl ( const Eigen::MatrixBase< D > &  a) const
inline

Definition at line 427 of file joint-composite.hpp.

◆ jointVelocitySelector_impl() [2/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename D >
SizeDepType<Eigen::Dynamic>::template SegmentReturn<D>::Type pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::jointVelocitySelector_impl ( Eigen::MatrixBase< D > &  a) const
inline

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

◆ nq_impl()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
int pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::nq_impl ( ) const
inline

Definition at line 322 of file joint-composite.hpp.

◆ nv_impl()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
int pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::nv_impl ( ) const
inline

Definition at line 321 of file joint-composite.hpp.

◆ operator=()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
JointModelCompositeTpl& pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::operator= ( const JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl > &  other)
inline

Definition at line 336 of file joint-composite.hpp.

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [1/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
typedef pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( JointModel  )

◆ PINOCCHIO_ALIGNED_STD_VECTOR() [2/2]

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR ( SE3  )

Vector of joint placements. Those placements correspond to the origin of the joint relatively to their parent.

◆ PINOCCHIO_JOINT_TYPEDEF_TEMPLATE()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_JOINT_TYPEDEF_TEMPLATE ( JointDerived  )

◆ setIndexes_impl()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
void pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::setIndexes_impl ( JointIndex  id,
int  q,
int  v 
)
inline

Update the indexes of subjoints in the stack.

Definition at line 327 of file joint-composite.hpp.

◆ shortname()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
std::string pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::shortname ( ) const
inline

Definition at line 334 of file joint-composite.hpp.

◆ updateJointIndexes()

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
void pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::updateJointIndexes ( )
inlineprotected

Update the indexes of the joints contained in the composition according to the position of the joint composite.

Definition at line 449 of file joint-composite.hpp.

Friends And Related Function Documentation

◆ JointCompositeCalcFirstOrderStep

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename , int , template< typename S, int O > class, typename , typename >
friend struct JointCompositeCalcFirstOrderStep
friend

Definition at line 296 of file joint-composite.hpp.

◆ JointCompositeCalcZeroOrderStep

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename , int , template< typename S, int O > class, typename >
friend struct JointCompositeCalcZeroOrderStep
friend

Definition at line 290 of file joint-composite.hpp.

◆ JointModelCompositeTpl

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
template<typename , int , template< typename, int > class>
friend struct JointModelCompositeTpl
friend

Definition at line 445 of file joint-composite.hpp.

◆ Serialize< JointModelCompositeTpl >

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
friend struct Serialize< JointModelCompositeTpl >
friend

Definition at line 442 of file joint-composite.hpp.

Member Data Documentation

◆ Base

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointModelBase<JointModelCompositeTpl> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::Base

Definition at line 154 of file joint-composite.hpp.

◆ joints

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
JointModelVector pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::joints

Vector of joints contained in the joint composite.

Definition at line 394 of file joint-composite.hpp.

◆ m_idx_q

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
std::vector<int> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::m_idx_q
protected

Keep information of both the dimension and the position of the joints in the composition.

Index in the config vector

Definition at line 478 of file joint-composite.hpp.

◆ m_idx_v

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
std::vector<int> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::m_idx_v
protected

Index in the tangent vector.

Definition at line 482 of file joint-composite.hpp.

◆ m_nq

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
int pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::m_nq
protected

Dimensions of the config and tangent space of the composite joint.

Definition at line 473 of file joint-composite.hpp.

◆ m_nqs

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
std::vector<int> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::m_nqs
protected

Dimension of the segment in the config vector.

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

◆ m_nv

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
int pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::m_nv
protected

Definition at line 473 of file joint-composite.hpp.

◆ m_nvs

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
std::vector<int> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::m_nvs
protected

Dimension of the segment in the tangent vector.

Definition at line 484 of file joint-composite.hpp.

◆ njoints

template<typename _Scalar , int _Options, template< typename S, int O > class JointCollectionTpl>
int pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::njoints

Number of joints contained in the JointModelComposite.

Definition at line 488 of file joint-composite.hpp.


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


pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:44:01