#include <fwd.hpp>
Public Types | |
typedef JointModelBase< JointModelHelicalTpl > | Base |
typedef Eigen::Matrix< Scalar, 3, 1, _Options > | Vector3 |
Public Member Functions | |
template<typename TangentVector > | |
PINOCCHIO_DONT_INLINE void | calc (JointDataDerived &data, const Blank, const typename Eigen::MatrixBase< TangentVector > &vs) const |
template<typename ConfigVector > | |
PINOCCHIO_DONT_INLINE void | calc (JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const |
template<typename ConfigVector , typename TangentVector > | |
PINOCCHIO_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, axis > | cast () const |
JointDataDerived | createData () const |
Vector3 | getMotionAxis () const |
const std::vector< bool > | hasConfigurationLimit () const |
const std::vector< bool > | hasConfigurationLimitInTangent () const |
JointIndex | id () const |
int | idx_q () const |
int | idx_v () const |
int | idx_vExtended () const |
JointModelHelicalTpl () | |
JointModelHelicalTpl (const Scalar &h) | |
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE (JointDerived) | |
void | setIndexes (JointIndex id, int q, int v) |
void | setIndexes (JointIndex id, int q, int v, int vExtended) |
std::string | shortname () const |
Static Public Member Functions | |
static std::string | classname () |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointHelicalTpl< _Scalar, _Options, axis > | JointDerived |
Scalar | m_pitch |
Definition at line 60 of file multibody/joint/fwd.hpp.
typedef JointModelBase<JointModelHelicalTpl> pinocchio::JointModelHelicalTpl< _Scalar, _Options, axis >::Base |
Definition at line 839 of file joint-helical.hpp.
typedef Eigen::Matrix<Scalar, 3, 1, _Options> pinocchio::JointModelHelicalTpl< _Scalar, _Options, axis >::Vector3 |
Definition at line 846 of file joint-helical.hpp.
|
inline |
Definition at line 853 of file joint-helical.hpp.
|
inlineexplicit |
Definition at line 857 of file joint-helical.hpp.
|
inline |
Definition at line 885 of file joint-helical.hpp.
|
inline |
Definition at line 874 of file joint-helical.hpp.
|
inline |
Definition at line 894 of file joint-helical.hpp.
|
inline |
Definition at line 907 of file joint-helical.hpp.
|
inline |
Definition at line 950 of file joint-helical.hpp.
|
inlinestatic |
Definition at line 923 of file joint-helical.hpp.
|
inline |
Definition at line 848 of file joint-helical.hpp.
|
inline |
Definition at line 932 of file joint-helical.hpp.
|
inline |
Definition at line 862 of file joint-helical.hpp.
|
inline |
Definition at line 867 of file joint-helical.hpp.
|
inline |
Definition at line 183 of file joint-model-base.hpp.
|
inline |
Definition at line 171 of file joint-model-base.hpp.
|
inline |
Definition at line 175 of file joint-model-base.hpp.
|
inline |
Definition at line 179 of file joint-model-base.hpp.
pinocchio::JointModelHelicalTpl< _Scalar, _Options, axis >::PINOCCHIO_JOINT_TYPEDEF_TEMPLATE | ( | JointDerived | ) |
|
inline |
Definition at line 205 of file joint-model-base.hpp.
|
inline |
Definition at line 210 of file joint-model-base.hpp.
|
inline |
Definition at line 927 of file joint-helical.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointHelicalTpl<_Scalar, _Options, axis> pinocchio::JointModelHelicalTpl< _Scalar, _Options, axis >::JointDerived |
Definition at line 836 of file joint-helical.hpp.
Scalar pinocchio::JointModelHelicalTpl< _Scalar, _Options, axis >::m_pitch |
Definition at line 958 of file joint-helical.hpp.