#include <joint-mimic.hpp>
Public Types | |
typedef JointModelBase< JointModelMimic > | Base |
Public Member Functions | |
Base & | base () |
const Base & | base () const |
template<typename TangentVector > | |
EIGEN_DONT_INLINE void | calc (JointDataDerived &jdata, const Blank blank, const typename Eigen::MatrixBase< TangentVector > &vs) const |
template<typename ConfigVector > | |
EIGEN_DONT_INLINE void | calc (JointDataDerived &jdata, const typename Eigen::MatrixBase< ConfigVector > &qs) const |
template<typename ConfigVector , typename TangentVector > | |
EIGEN_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 &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const |
template<typename NewScalar > | |
CastType< NewScalar, JointModelMimic >::type | cast () const |
JointDataDerived | createData () const |
const std::vector< bool > | hasConfigurationLimit () const |
const std::vector< bool > | hasConfigurationLimitInTangent () const |
JointIndex | id () const |
int | idx_q () const |
int | idx_q_impl () const |
int | idx_v () const |
int | idx_v_impl () const |
JointModel & | jmodel () |
const JointModel & | jmodel () const |
template<typename D > | |
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. More... | |
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 | jointConfigSelector_impl (const Eigen::MatrixBase< D > &a) const |
template<typename D > | |
SizeDepType< NQ >::template SegmentReturn< D >::Type | jointConfigSelector_impl (Eigen::MatrixBase< D > &a) const |
JointModelMimic () | |
JointModelMimic (const JointModelBase< JointModel > &jmodel, 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 |
template<typename D > | |
SizeDepType< NV >::template SegmentReturn< D >::ConstType | jointVelocitySelector_impl (const Eigen::MatrixBase< D > &a) const |
template<typename D > | |
SizeDepType< NV >::template SegmentReturn< D >::Type | jointVelocitySelector_impl (Eigen::MatrixBase< D > &a) const |
int | nq () const |
int | nq_impl () const |
int | nv () const |
int | nv_impl () const |
Scalar & | offset () |
const Scalar & | offset () const |
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE (JointDerived) | |
Scalar & | scaling () |
const Scalar & | scaling () const |
void | setIndexes (JointIndex id, int q, int v) |
void | setIndexes_impl (JointIndex id, int, int) |
std::string | shortname () const |
Static Public Member Functions | |
static std::string | classname () |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef traits< JointModelMimic >::JointDerived | JointDerived |
Protected Attributes | |
JointModel | m_jmodel_ref |
Scalar | m_offset |
Scalar | m_scaling |
Definition at line 307 of file joint-mimic.hpp.
typedef JointModelBase<JointModelMimic> pinocchio::JointModelMimic< JointModel >::Base |
Definition at line 581 of file joint-mimic.hpp.
|
inline |
Definition at line 589 of file joint-mimic.hpp.
|
inline |
Definition at line 593 of file joint-mimic.hpp.
|
inline |
Definition at line 601 of file joint-mimic.hpp.
|
inline |
Definition at line 605 of file joint-mimic.hpp.
|
inline |
Definition at line 661 of file joint-mimic.hpp.
|
inline |
Definition at line 652 of file joint-mimic.hpp.
|
inline |
Definition at line 671 of file joint-mimic.hpp.
|
inline |
Definition at line 684 of file joint-mimic.hpp.
|
inline |
Definition at line 708 of file joint-mimic.hpp.
|
inlinestatic |
Definition at line 695 of file joint-mimic.hpp.
|
inline |
Definition at line 635 of file joint-mimic.hpp.
|
inline |
Definition at line 640 of file joint-mimic.hpp.
|
inline |
Definition at line 645 of file joint-mimic.hpp.
|
inline |
Definition at line 168 of file joint-model-base.hpp.
|
inline |
Definition at line 160 of file joint-model-base.hpp.
|
inline |
Definition at line 619 of file joint-mimic.hpp.
|
inline |
Definition at line 164 of file joint-model-base.hpp.
|
inline |
Definition at line 623 of file joint-mimic.hpp.
|
inline |
Definition at line 723 of file joint-mimic.hpp.
|
inline |
Definition at line 719 of file joint-mimic.hpp.
|
inline |
Returns a block of dimension nv()xnv() located at position idx_v(),idx_v() in the matrix Mat.
Definition at line 825 of file joint-mimic.hpp.
|
inline |
Definition at line 835 of file joint-mimic.hpp.
|
inline |
Definition at line 790 of file joint-mimic.hpp.
|
inline |
Definition at line 798 of file joint-mimic.hpp.
|
inline |
Definition at line 756 of file joint-mimic.hpp.
|
inline |
Definition at line 764 of file joint-mimic.hpp.
|
inline |
Definition at line 807 of file joint-mimic.hpp.
|
inline |
Definition at line 815 of file joint-mimic.hpp.
|
inline |
Definition at line 773 of file joint-mimic.hpp.
|
inline |
Definition at line 781 of file joint-mimic.hpp.
|
inline |
Definition at line 145 of file joint-model-base.hpp.
|
inline |
Definition at line 610 of file joint-mimic.hpp.
|
inline |
Definition at line 141 of file joint-model-base.hpp.
|
inline |
Definition at line 614 of file joint-mimic.hpp.
|
inline |
Definition at line 741 of file joint-mimic.hpp.
|
inline |
Definition at line 737 of file joint-mimic.hpp.
pinocchio::JointModelMimic< JointModel >::PINOCCHIO_JOINT_TYPEDEF_TEMPLATE | ( | JointDerived | ) |
|
inline |
Definition at line 732 of file joint-mimic.hpp.
|
inline |
Definition at line 728 of file joint-mimic.hpp.
|
inline |
Definition at line 186 of file joint-model-base.hpp.
|
inline |
Definition at line 628 of file joint-mimic.hpp.
|
inline |
Definition at line 701 of file joint-mimic.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef traits<JointModelMimic>::JointDerived pinocchio::JointModelMimic< JointModel >::JointDerived |
Definition at line 577 of file joint-mimic.hpp.
|
protected |
Definition at line 748 of file joint-mimic.hpp.
|
protected |
Definition at line 749 of file joint-mimic.hpp.
|
protected |
Definition at line 749 of file joint-mimic.hpp.