Template Struct JointMotionSubspaceHelicalUnalignedTpl

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Struct Documentation

template<typename _Scalar, int _Options>
struct JointMotionSubspaceHelicalUnalignedTpl : public pinocchio::JointMotionSubspaceBase<JointMotionSubspaceHelicalUnalignedTpl<_Scalar, _Options>>

Public Types

Values:

enumerator NV
typedef traits<JointMotionSubspaceHelicalUnalignedTpl>::Vector3 Vector3

Public Functions

inline JointMotionSubspaceHelicalUnalignedTpl()
template<typename Vector3Like>
inline JointMotionSubspaceHelicalUnalignedTpl(const Eigen::MatrixBase<Vector3Like> &axis, const Scalar &h)
template<typename Vector1Like>
inline JointMotion __mult__(const Eigen::MatrixBase<Vector1Like> &v) const
template<typename S1, int O1>
inline SE3GroupAction<JointMotionSubspaceHelicalUnalignedTpl>::ReturnType se3Action(const SE3Tpl<S1, O1> &m) const
template<typename S1, int O1>
inline SE3GroupAction<JointMotionSubspaceHelicalUnalignedTpl>::ReturnType se3ActionInverse(const SE3Tpl<S1, O1> &m) const
inline int nv_impl() const
inline TransposeConst transpose() const
inline DenseBase matrix_impl() const
template<typename MotionDerived>
inline MotionAlgebraAction<JointMotionSubspaceHelicalUnalignedTpl, MotionDerived>::ReturnType motionAction(const MotionDense<MotionDerived> &m) const
inline bool isEqual(const JointMotionSubspaceHelicalUnalignedTpl &other) const
inline Vector3 &axis()
inline const Vector3 &axis() const
inline Scalar &h()
inline const Scalar &h() const

Public Members

Vector3 m_axis
Scalar m_pitch
struct TransposeConst : public pinocchio::JointMotionSubspaceTransposeBase<JointMotionSubspaceHelicalUnalignedTpl>

Public Functions

inline TransposeConst(const JointMotionSubspaceHelicalUnalignedTpl &ref)
template<typename ForceDerived>
inline ConstraintForceOp<JointMotionSubspaceHelicalUnalignedTpl, ForceDerived>::ReturnType operator*(const ForceDense<ForceDerived> &f) const
template<typename Derived>
inline ConstraintForceSetOp<JointMotionSubspaceHelicalUnalignedTpl, Derived>::ReturnType operator*(const Eigen::MatrixBase<Derived> &F) const

[CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block)

Public Members

const JointMotionSubspaceHelicalUnalignedTpl &ref