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

#include <fwd.hpp>

Public Types

typedef JointModelBase< JointModelRevoluteUnboundedUnalignedTplBase
 
typedef Eigen::Matrix< Scalar, 3, 1, OptionsVector3
 

Public Member Functions

template<typename ConfigVector >
void calc (JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
 
template<typename ConfigVector , typename TangentVector >
void calc (JointDataDerived &data, 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 >
JointModelRevoluteUnboundedUnalignedTpl< NewScalar, Optionscast () const
 
JointDataDerived createData () const
 
const std::vector< bool > hasConfigurationLimit () const
 
const std::vector< bool > hasConfigurationLimitInTangent () const
 
JointIndex id () const
 
int idx_q () const
 
int idx_v () const
 
bool isEqual (const JointModelBase< Derived > &other) const
 
template<class OtherDerived >
bool isEqual (const JointModelBase< OtherDerived > &) const
 
bool isEqual (const JointModelRevoluteUnboundedUnalignedTpl &other) const
 
 JointModelRevoluteUnboundedUnalignedTpl ()
 
template<typename Vector3Like >
 JointModelRevoluteUnboundedUnalignedTpl (const Eigen::MatrixBase< Vector3Like > &axis)
 
 JointModelRevoluteUnboundedUnalignedTpl (const Scalar &x, const Scalar &y, const Scalar &z)
 
 PINOCCHIO_JOINT_TYPEDEF_TEMPLATE (JointDerived)
 
void setIndexes (JointIndex id, int q, int v)
 
std::string shortname () const
 

Static Public Member Functions

static std::string classname ()
 

Public Attributes

Vector3 axis
 3d main axis of the joint. More...
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointRevoluteUnboundedUnalignedTpl< _Scalar, _Options > JointDerived
 

Detailed Description

template<typename _Scalar, int _Options>
struct pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >

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

Member Typedef Documentation

◆ Base

template<typename _Scalar , int _Options>
typedef JointModelBase<JointModelRevoluteUnboundedUnalignedTpl> pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::Base

Definition at line 111 of file joint-revolute-unbounded-unaligned.hpp.

◆ Vector3

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

Definition at line 109 of file joint-revolute-unbounded-unaligned.hpp.

Constructor & Destructor Documentation

◆ JointModelRevoluteUnboundedUnalignedTpl() [1/3]

template<typename _Scalar , int _Options>
pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::JointModelRevoluteUnboundedUnalignedTpl ( )
inline

Definition at line 117 of file joint-revolute-unbounded-unaligned.hpp.

◆ JointModelRevoluteUnboundedUnalignedTpl() [2/3]

template<typename _Scalar , int _Options>
pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::JointModelRevoluteUnboundedUnalignedTpl ( const Scalar &  x,
const Scalar &  y,
const Scalar &  z 
)
inline

Definition at line 119 of file joint-revolute-unbounded-unaligned.hpp.

◆ JointModelRevoluteUnboundedUnalignedTpl() [3/3]

template<typename _Scalar , int _Options>
template<typename Vector3Like >
pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::JointModelRevoluteUnboundedUnalignedTpl ( const Eigen::MatrixBase< Vector3Like > &  axis)
inline

Definition at line 129 of file joint-revolute-unbounded-unaligned.hpp.

Member Function Documentation

◆ calc() [1/2]

template<typename _Scalar , int _Options>
template<typename ConfigVector >
void pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::calc ( JointDataDerived &  data,
const typename Eigen::MatrixBase< ConfigVector > &  qs 
) const
inline

Definition at line 155 of file joint-revolute-unbounded-unaligned.hpp.

◆ calc() [2/2]

template<typename _Scalar , int _Options>
template<typename ConfigVector , typename TangentVector >
void pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::calc ( JointDataDerived &  data,
const typename Eigen::MatrixBase< ConfigVector > &  qs,
const typename Eigen::MatrixBase< TangentVector > &  vs 
) const
inline

Definition at line 169 of file joint-revolute-unbounded-unaligned.hpp.

◆ calc_aba()

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

Definition at line 178 of file joint-revolute-unbounded-unaligned.hpp.

◆ cast()

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

Definition at line 195 of file joint-revolute-unbounded-unaligned.hpp.

◆ classname()

template<typename _Scalar , int _Options>
static std::string pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::classname ( )
inlinestatic

Definition at line 190 of file joint-revolute-unbounded-unaligned.hpp.

◆ createData()

template<typename _Scalar , int _Options>
JointDataDerived pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::createData ( ) const
inline

Definition at line 136 of file joint-revolute-unbounded-unaligned.hpp.

◆ hasConfigurationLimit()

template<typename _Scalar , int _Options>
const std::vector<bool> pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::hasConfigurationLimit ( ) const
inline

Definition at line 138 of file joint-revolute-unbounded-unaligned.hpp.

◆ hasConfigurationLimitInTangent()

template<typename _Scalar , int _Options>
const std::vector<bool> pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::hasConfigurationLimitInTangent ( ) const
inline

Definition at line 143 of file joint-revolute-unbounded-unaligned.hpp.

◆ id()

template<typename _Scalar , int _Options>
JointIndex pinocchio::JointModelBase< Derived >::id
inline

Definition at line 121 of file joint-model-base.hpp.

◆ idx_q()

template<typename _Scalar , int _Options>
int pinocchio::JointModelBase< Derived >::idx_q
inline

Definition at line 119 of file joint-model-base.hpp.

◆ idx_v()

template<typename _Scalar , int _Options>
int pinocchio::JointModelBase< Derived >::idx_v
inline

Definition at line 120 of file joint-model-base.hpp.

◆ isEqual() [1/3]

template<typename _Scalar , int _Options>
bool pinocchio::JointModelBase< Derived >::isEqual
inline

Definition at line 171 of file joint-model-base.hpp.

◆ isEqual() [2/3]

template<typename _Scalar , int _Options>
template<class OtherDerived >
bool pinocchio::JointModelBase< Derived >::isEqual ( class OtherDerived  )
inline

Definition at line 168 of file joint-model-base.hpp.

◆ isEqual() [3/3]

template<typename _Scalar , int _Options>
bool pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::isEqual ( const JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options > &  other) const
inline

Definition at line 149 of file joint-revolute-unbounded-unaligned.hpp.

◆ PINOCCHIO_JOINT_TYPEDEF_TEMPLATE()

template<typename _Scalar , int _Options>
pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::PINOCCHIO_JOINT_TYPEDEF_TEMPLATE ( JointDerived  )

◆ setIndexes()

template<typename _Scalar , int _Options>
void pinocchio::JointModelBase< Derived >::setIndexes
inline

Definition at line 127 of file joint-model-base.hpp.

◆ shortname()

template<typename _Scalar , int _Options>
std::string pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::shortname ( ) const
inline

Definition at line 191 of file joint-revolute-unbounded-unaligned.hpp.

Member Data Documentation

◆ axis

template<typename _Scalar , int _Options>
Vector3 pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::axis

3d main axis of the joint.

Definition at line 207 of file joint-revolute-unbounded-unaligned.hpp.

◆ JointDerived

template<typename _Scalar , int _Options>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointRevoluteUnboundedUnalignedTpl<_Scalar,_Options> pinocchio::JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options >::JointDerived

Definition at line 107 of file joint-revolute-unbounded-unaligned.hpp.


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


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