#include <fwd.hpp>
Public Types | |
enum | { MaxNVMimicked = traits<JointDerived>::MaxNVMimicked } |
typedef InertiaTpl< Scalar, Options > | Inertia |
typedef JointCollectionTpl< Scalar, Options > | JointCollection |
typedef JointMimicTpl< _Scalar, _Options, JointCollectionTpl > | JointDerived |
typedef JointModelTpl< Scalar, Options, JointCollectionTpl > | JointModel |
typedef MotionTpl< Scalar, Options > | Motion |
typedef SE3Tpl< Scalar, Options > | SE3 |
Public Member Functions | |
Base & | base () |
const Base & | base () const |
template<typename ConfigVector > | |
PINOCCHIO_DONT_INLINE void | calc (JointDataDerived &jdata, const typename Eigen::MatrixBase< ConfigVector > &qs) const |
template<typename ConfigVector , typename TangentVector > | |
PINOCCHIO_DONT_INLINE void | calc (JointDataDerived &jdata, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const |
template<typename VectorLike , typename Matrix6Like > | |
void | calc_aba (JointDataDerived &, const Eigen::MatrixBase< VectorLike > &, const Eigen::MatrixBase< Matrix6Like > &, const bool) const |
template<typename NewScalar > | |
CastType< NewScalar, JointModelMimicTpl >::type | cast () const |
JointDataDerived | createData () const |
void | disp (std::ostream &os) const |
const std::vector< bool > | hasConfigurationLimit () const |
const std::vector< bool > | hasConfigurationLimitInTangent () const |
JointModel & | jmodel () |
const JointModel & | jmodel () const |
template<typename D > | |
SizeDepType< NV >::template BlockReturn< D >::ConstType | jointBlock_impl (const Eigen::MatrixBase< D > &Mat) const |
template<typename D > | |
SizeDepType< NV >::template BlockReturn< D >::Type | jointBlock_impl (Eigen::MatrixBase< D > &Mat) const |
template<typename D > | |
SizeDepType< NV >::template ColsReturn< D >::ConstType | jointCols_impl (const Eigen::MatrixBase< D > &A) const |
template<typename D > | |
SizeDepType< NV >::template ColsReturn< D >::Type | jointCols_impl (Eigen::MatrixBase< D > &A) const |
template<typename D > | |
SizeDepType< NQ >::template SegmentReturn< D >::ConstType | JointMappedConfigSelector_impl (const Eigen::MatrixBase< D > &a) const |
template<typename D > | |
SizeDepType< NQ >::template SegmentReturn< D >::Type | JointMappedConfigSelector_impl (Eigen::MatrixBase< D > &a) const |
template<typename D > | |
SizeDepType< NQ >::template SegmentReturn< D >::ConstType | JointMappedVelocitySelector_impl (const Eigen::MatrixBase< D > &a) const |
template<typename D > | |
SizeDepType< NQ >::template SegmentReturn< D >::Type | JointMappedVelocitySelector_impl (Eigen::MatrixBase< D > &a) const |
JointModelMimicTpl () | |
template<typename JointModel > | |
JointModelMimicTpl (const JointModelBase< JointModel > &jmodel, const Scalar &scaling, const Scalar &offset) | |
template<typename JointModelMimicking , typename JointModelMimicked > | |
JointModelMimicTpl (const JointModelBase< JointModelMimicking > &jmodel_mimicking, const JointModelBase< JointModelMimicked > &jmodel_mimicked, const Scalar &scaling, const Scalar &offset) | |
template<typename D > | |
SizeDepType< NV >::template RowsReturn< D >::ConstType | jointRows_impl (const Eigen::MatrixBase< D > &A) const |
template<typename D > | |
SizeDepType< NV >::template RowsReturn< D >::Type | jointRows_impl (Eigen::MatrixBase< D > &A) const |
int | nq_impl () const |
int | nv_impl () const |
int | nvExtended_impl () const |
Scalar & | offset () |
const Scalar & | offset () const |
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE (JointDerived) | |
Scalar & | scaling () |
const Scalar & | scaling () const |
void | setIndexes_impl (JointIndex id, int, int, int vExtended) |
void | setMimicIndexes (JointIndex id, int q, int v, int vExtended) |
Specific way for mimic joints to set the mimicked q,v indexes. Used for manipulating tree (e.g. appendModel) More... | |
std::string | shortname () const |
Static Public Member Functions | |
static std::string | classname () |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointModelBase< JointModelMimicTpl > | Base |
Protected Attributes | |
JointModel | m_jmodel_mimicking |
int | m_nqExtended |
int | m_nvExtended |
Scalar | m_offset |
Scalar | m_scaling |
Definition at line 155 of file multibody/joint/fwd.hpp.
typedef InertiaTpl<Scalar, Options> pinocchio::JointModelMimicTpl< _Scalar, _Options, JointCollectionTpl >::Inertia |
Definition at line 575 of file joint-mimic.hpp.
typedef JointCollectionTpl<Scalar, Options> pinocchio::JointModelMimicTpl< _Scalar, _Options, JointCollectionTpl >::JointCollection |
Definition at line 570 of file joint-mimic.hpp.
typedef JointMimicTpl<_Scalar, _Options, JointCollectionTpl> pinocchio::JointModelMimicTpl< _Scalar, _Options, JointCollectionTpl >::JointDerived |
Definition at line 563 of file joint-mimic.hpp.
typedef JointModelTpl<Scalar, Options, JointCollectionTpl> pinocchio::JointModelMimicTpl< _Scalar, _Options, JointCollectionTpl >::JointModel |
Definition at line 571 of file joint-mimic.hpp.
typedef MotionTpl<Scalar, Options> pinocchio::JointModelMimicTpl< _Scalar, _Options, JointCollectionTpl >::Motion |
Definition at line 574 of file joint-mimic.hpp.
typedef SE3Tpl<Scalar, Options> pinocchio::JointModelMimicTpl< _Scalar, _Options, JointCollectionTpl >::SE3 |
Definition at line 573 of file joint-mimic.hpp.
anonymous enum |
Enumerator | |
---|---|
MaxNVMimicked |
Definition at line 565 of file joint-mimic.hpp.
|
inline |
Definition at line 586 of file joint-mimic.hpp.
|
inline |
Definition at line 591 of file joint-mimic.hpp.
|
inline |
Definition at line 598 of file joint-mimic.hpp.
|
inline |
Definition at line 618 of file joint-mimic.hpp.
|
inline |
Definition at line 622 of file joint-mimic.hpp.
|
inline |
Definition at line 694 of file joint-mimic.hpp.
|
inline |
Definition at line 703 of file joint-mimic.hpp.
|
inline |
Definition at line 719 of file joint-mimic.hpp.
|
inline |
Definition at line 743 of file joint-mimic.hpp.
|
inlinestatic |
Definition at line 731 of file joint-mimic.hpp.
|
inline |
Definition at line 676 of file joint-mimic.hpp.
|
inline |
Definition at line 876 of file joint-mimic.hpp.
|
inline |
Definition at line 682 of file joint-mimic.hpp.
|
inline |
Definition at line 687 of file joint-mimic.hpp.
|
inline |
Definition at line 759 of file joint-mimic.hpp.
|
inline |
Definition at line 755 of file joint-mimic.hpp.
|
inline |
Definition at line 861 of file joint-mimic.hpp.
|
inline |
Definition at line 870 of file joint-mimic.hpp.
|
inline |
Definition at line 826 of file joint-mimic.hpp.
|
inline |
Definition at line 834 of file joint-mimic.hpp.
|
inline |
Definition at line 793 of file joint-mimic.hpp.
|
inline |
Definition at line 801 of file joint-mimic.hpp.
|
inline |
Definition at line 809 of file joint-mimic.hpp.
|
inline |
Definition at line 817 of file joint-mimic.hpp.
|
inline |
Definition at line 843 of file joint-mimic.hpp.
|
inline |
Definition at line 851 of file joint-mimic.hpp.
|
inline |
Definition at line 627 of file joint-mimic.hpp.
|
inline |
Definition at line 631 of file joint-mimic.hpp.
|
inline |
Definition at line 635 of file joint-mimic.hpp.
|
inline |
Definition at line 777 of file joint-mimic.hpp.
|
inline |
Definition at line 773 of file joint-mimic.hpp.
pinocchio::JointModelMimicTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_JOINT_TYPEDEF_TEMPLATE | ( | JointDerived | ) |
|
inline |
Definition at line 768 of file joint-mimic.hpp.
|
inline |
Definition at line 764 of file joint-mimic.hpp.
|
inline |
Definition at line 645 of file joint-mimic.hpp.
|
inline |
Specific way for mimic joints to set the mimicked q,v indexes. Used for manipulating tree (e.g. appendModel)
id | Set the mimicking joint id |
q | Set the mimic joint idx_q (should point to the mimicked joint) |
v | Set the mimic joint idx_v (should point to the mimicked joint) |
vExtended | Set the mimicking idx_vExtended |
Definition at line 665 of file joint-mimic.hpp.
|
inline |
Definition at line 736 of file joint-mimic.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointModelBase<JointModelMimicTpl> pinocchio::JointModelMimicTpl< _Scalar, _Options, JointCollectionTpl >::Base |
Definition at line 562 of file joint-mimic.hpp.
|
protected |
Definition at line 784 of file joint-mimic.hpp.
|
protected |
Definition at line 786 of file joint-mimic.hpp.
|
protected |
Definition at line 786 of file joint-mimic.hpp.
|
protected |
Definition at line 785 of file joint-mimic.hpp.
|
protected |
Definition at line 785 of file joint-mimic.hpp.