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

#include <fwd.hpp>

Public Types

typedef JointModelBase< JointModelHelicalTplBase
 

Public Member Functions

template<typename TangentVector >
EIGEN_DONT_INLINE void calc (JointDataDerived &data, const Blank, const typename Eigen::MatrixBase< TangentVector > &vs) const
 
template<typename ConfigVector >
EIGEN_DONT_INLINE void calc (JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
 
template<typename ConfigVector , typename TangentVector >
EIGEN_DONT_INLINE void calc (JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
 
template<typename VectorLike , typename Matrix6Like >
void calc_aba (JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
 
template<typename NewScalar >
JointModelHelicalTpl< NewScalar, Options, axiscast () 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
 
 JointModelHelicalTpl ()
 
 JointModelHelicalTpl (const Scalar &h)
 
 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

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointHelicalTpl< _Scalar, _Options, axisJointDerived
 
Scalar m_pitch
 

Detailed Description

template<typename _Scalar, int _Options, int axis>
struct pinocchio::JointModelHelicalTpl< _Scalar, _Options, axis >

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

Member Typedef Documentation

◆ Base

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

Definition at line 836 of file joint-helical.hpp.

Constructor & Destructor Documentation

◆ JointModelHelicalTpl() [1/2]

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

Definition at line 847 of file joint-helical.hpp.

◆ JointModelHelicalTpl() [2/2]

template<typename _Scalar , int _Options, int axis>
pinocchio::JointModelHelicalTpl< _Scalar, _Options, axis >::JointModelHelicalTpl ( const Scalar &  h)
inlineexplicit

Definition at line 851 of file joint-helical.hpp.

Member Function Documentation

◆ calc() [1/3]

template<typename _Scalar , int _Options, int axis>
template<typename TangentVector >
EIGEN_DONT_INLINE void pinocchio::JointModelHelicalTpl< _Scalar, _Options, axis >::calc ( JointDataDerived &  data,
const  Blank,
const typename Eigen::MatrixBase< TangentVector > &  vs 
) const
inline

Definition at line 879 of file joint-helical.hpp.

◆ calc() [2/3]

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

Definition at line 868 of file joint-helical.hpp.

◆ calc() [3/3]

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

Definition at line 888 of file joint-helical.hpp.

◆ calc_aba()

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

Definition at line 901 of file joint-helical.hpp.

◆ cast()

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

Definition at line 928 of file joint-helical.hpp.

◆ classname()

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

Definition at line 917 of file joint-helical.hpp.

◆ createData()

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

Definition at line 842 of file joint-helical.hpp.

◆ hasConfigurationLimit()

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

Definition at line 856 of file joint-helical.hpp.

◆ hasConfigurationLimitInTangent()

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

Definition at line 861 of file joint-helical.hpp.

◆ id()

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

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

◆ idx_q()

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

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

◆ idx_v()

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

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

◆ PINOCCHIO_JOINT_TYPEDEF_TEMPLATE()

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

◆ setIndexes()

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

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

◆ shortname()

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

Definition at line 921 of file joint-helical.hpp.

Member Data Documentation

◆ JointDerived

template<typename _Scalar , int _Options, int axis>
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointHelicalTpl<_Scalar, _Options, axis> pinocchio::JointModelHelicalTpl< _Scalar, _Options, axis >::JointDerived

Definition at line 833 of file joint-helical.hpp.

◆ m_pitch

template<typename _Scalar , int _Options, int axis>
Scalar pinocchio::JointModelHelicalTpl< _Scalar, _Options, axis >::m_pitch

Definition at line 936 of file joint-helical.hpp.


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


pinocchio
Author(s):
autogenerated on Wed Jun 19 2024 02:41:19