Template Struct JointMotionSubspaceSphericalZYXTpl

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

Struct Documentation

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

Public Types

Values:

enumerator NV
typedef Eigen::Matrix<Scalar, 3, 3, Options> Matrix3

Public Functions

inline JointMotionSubspaceSphericalZYXTpl()
template<typename Matrix3Like>
inline JointMotionSubspaceSphericalZYXTpl(const Eigen::MatrixBase<Matrix3Like> &subspace)
template<typename Vector3Like>
inline JointMotion __mult__(const Eigen::MatrixBase<Vector3Like> &v) const
inline Matrix3 &operator()()
inline const Matrix3 &operator()() const
inline int nv_impl() const
inline ConstraintTranspose transpose() const
inline DenseBase matrix_impl() const
template<typename S1, int O1>
inline Eigen::Matrix<Scalar, 6, 3, Options> se3Action(const SE3Tpl<S1, O1> &m) const
template<typename S1, int O1>
inline Eigen::Matrix<Scalar, 6, 3, Options> se3ActionInverse(const SE3Tpl<S1, O1> &m) const
template<typename MotionDerived>
inline DenseBase motionAction(const MotionDense<MotionDerived> &m) const
inline Matrix3 &angularSubspace()
inline const Matrix3 &angularSubspace() const
inline bool isEqual(const JointMotionSubspaceSphericalZYXTpl &other) const

Protected Attributes

Matrix3 m_S
struct ConstraintTranspose : public pinocchio::JointMotionSubspaceTransposeBase<JointMotionSubspaceSphericalZYXTpl>

Public Functions

inline ConstraintTranspose(const JointMotionSubspaceSphericalZYXTpl &ref)
template<typename Derived>
inline const MatrixMatrixProduct<Eigen::Transpose<constMatrix3>, Eigen::Block<consttypenameForceDense<Derived>::Vector6, 3, 1>>::type operator*(const ForceDense<Derived> &phi) const
template<typename D>
inline const MatrixMatrixProduct<typenameEigen::Transpose<constMatrix3>, typenameEigen::MatrixBase<constD>::templateNRowsBlockXpr<3>::Type>::type operator*(const Eigen::MatrixBase<D> &F) const

Public Members

const JointMotionSubspaceSphericalZYXTpl &ref