Template Struct JointModelMimic
Defined in File joint-mimic.hpp
Inheritance Relationships
Base Type
public pinocchio::JointModelBase< JointModelMimic< JointModel > >
(Template Struct JointModelBase)
Struct Documentation
-
template<class JointModel>
struct JointModelMimic : public pinocchio::JointModelBase<JointModelMimic<JointModel>> Public Types
-
typedef JointModelBase<JointModelMimic> Base
Public Functions
-
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
-
inline JointModelMimic()
-
inline JointModelMimic(const JointModelBase<JointModel> &jmodel, const Scalar &scaling, const Scalar &offset)
-
inline int nq_impl() const
-
inline int nv_impl() const
-
inline int idx_q_impl() const
-
inline int idx_v_impl() const
-
inline void setIndexes_impl(JointIndex id, int, int)
-
inline JointDataDerived createData() const
-
inline const std::vector<bool> hasConfigurationLimit() const
-
inline const std::vector<bool> hasConfigurationLimitInTangent() const
- template<typename ConfigVector> inline EIGEN_DONT_INLINE void calc (JointDataDerived &jdata, const typename Eigen::MatrixBase< ConfigVector > &qs) const
- template<typename ConfigVector, typename TangentVector> inline EIGEN_DONT_INLINE void calc (JointDataDerived &jdata, 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 CastType<NewScalar, JointModelMimic>::type cast() const - Returns:
An expression of *this with the Scalar type casted to NewScalar.
-
inline const JointModel &jmodel() const
-
inline JointModel &jmodel()
-
inline const Scalar &scaling() const
-
inline Scalar &scaling()
-
inline const Scalar &offset() const
-
inline Scalar &offset()
-
template<typename D>
inline SizeDepType<NQ>::template SegmentReturn<D>::ConstType jointConfigSelector_impl(const Eigen::MatrixBase<D> &a) const
-
template<typename D>
inline SizeDepType<NQ>::template SegmentReturn<D>::Type jointConfigSelector_impl(Eigen::MatrixBase<D> &a) const
-
template<typename D>
inline SizeDepType<NV>::template SegmentReturn<D>::ConstType jointVelocitySelector_impl(const Eigen::MatrixBase<D> &a) const
-
template<typename D>
inline SizeDepType<NV>::template SegmentReturn<D>::Type jointVelocitySelector_impl(Eigen::MatrixBase<D> &a) const
-
template<typename D>
inline SizeDepType<NV>::template ColsReturn<D>::ConstType jointCols_impl(const Eigen::MatrixBase<D> &A) const
-
template<typename D>
inline SizeDepType<NV>::template ColsReturn<D>::Type jointCols_impl(Eigen::MatrixBase<D> &A) const
-
template<typename D>
inline SizeDepType<NV>::template RowsReturn<D>::ConstType jointRows_impl(const Eigen::MatrixBase<D> &A) const
-
template<typename D>
inline SizeDepType<NV>::template RowsReturn<D>::Type jointRows_impl(Eigen::MatrixBase<D> &A) const
-
template<typename D>
inline SizeDepType<NV>::template BlockReturn<D>::ConstType jointBlock_impl(const Eigen::MatrixBase<D> &Mat) const Returns a block of dimension nv()xnv() located at position idx_v(),idx_v() in the matrix Mat.
-
template<typename D>
inline SizeDepType<NV>::template BlockReturn<D>::Type jointBlock_impl(Eigen::MatrixBase<D> &Mat) const
-
inline JointIndex id() const
-
inline int idx_q() const
-
inline int idx_v() const
-
inline int nq() const
-
inline int nv() const
-
inline void setIndexes(JointIndex id, int q, int v)
Public Members
- EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef traits< JointModelMimic >::JointDerived JointDerived
Public Static Functions
-
static inline std::string classname()
-
typedef JointModelBase<JointModelMimic> Base