Template Struct JointModelRevoluteUnboundedUnalignedTpl
Defined in File joint-revolute-unbounded-unaligned.hpp
Inheritance Relationships
Base Type
public pinocchio::JointModelBase< JointModelRevoluteUnboundedUnalignedTpl< _Scalar, _Options > >
(Template Struct JointModelBase)
Struct Documentation
-
template<typename _Scalar, int _Options>
struct JointModelRevoluteUnboundedUnalignedTpl : public pinocchio::JointModelBase<JointModelRevoluteUnboundedUnalignedTpl<_Scalar, _Options>> Public Types
-
typedef Eigen::Matrix<Scalar, 3, 1, Options> Vector3
-
typedef JointModelBase<JointModelRevoluteUnboundedUnalignedTpl> Base
Public Functions
-
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
-
inline JointModelRevoluteUnboundedUnalignedTpl()
-
inline JointModelRevoluteUnboundedUnalignedTpl(const Scalar &x, const Scalar &y, const Scalar &z)
-
template<typename Vector3Like>
inline JointModelRevoluteUnboundedUnalignedTpl(const Eigen::MatrixBase<Vector3Like> &axis)
-
inline JointDataDerived createData() const
-
inline const std::vector<bool> hasConfigurationLimit() const
-
inline const std::vector<bool> hasConfigurationLimitInTangent() const
-
inline bool isEqual(const JointModelRevoluteUnboundedUnalignedTpl &other) const
-
template<typename ConfigVector>
inline void calc(JointDataDerived &data, const typename Eigen::MatrixBase<ConfigVector> &qs) const
-
template<typename ConfigVector, typename TangentVector>
inline void calc(JointDataDerived &data, const typename Eigen::MatrixBase<ConfigVector> &qs, const typename Eigen::MatrixBase<TangentVector> &vs) const
-
template<typename Matrix6Like>
inline void calc_aba(JointDataDerived &data, const Eigen::MatrixBase<Matrix6Like> &I, const bool update_I) const
-
inline std::string shortname() const
-
template<typename NewScalar>
inline JointModelRevoluteUnboundedUnalignedTpl<NewScalar, Options> cast() const - Returns:
An expression of *this with the Scalar type casted to NewScalar.
-
inline JointIndex id() const
-
inline int idx_q() const
-
inline int idx_v() const
-
inline void setIndexes(JointIndex id, int q, int v)
-
template<class OtherDerived>
inline bool isEqual(const JointModelBase<OtherDerived>&) const
-
inline bool isEqual(const JointModelBase<Derived> &other) const
Public Members
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointRevoluteUnboundedUnalignedTpl< _Scalar, _Options > JointDerived
Public Static Functions
-
static inline std::string classname()
-
typedef Eigen::Matrix<Scalar, 3, 1, Options> Vector3