|
template<typename Vector3Derived , typename QuaternionDerived > |
EIGEN_DONT_INLINE void | calc (JointDataDerived &data, const typename Eigen::MatrixBase< Vector3Derived > &trans, const typename Eigen::QuaternionBase< QuaternionDerived > &quat) const |
|
template<typename ConfigVector > |
EIGEN_DONT_INLINE void | calc (JointDataDerived &data, const typename Eigen::PlainObjectBase< ConfigVector > &qs) const |
|
template<typename ConfigVector > |
EIGEN_DONT_INLINE void | calc (JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const |
|
template<typename ConfigVector , typename TangentVector > |
EIGEN_DONT_INLINE void | calc (JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const |
|
template<typename Matrix6Like > |
void | calc_aba (JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const |
|
template<typename NewScalar > |
JointModelFreeFlyerTpl< NewScalar, Options > | cast () const |
|
JointDataDerived | createData () const |
|
template<typename ConfigVectorLike > |
void | forwardKinematics (Transformation_t &M, const Eigen::MatrixBase< ConfigVectorLike > &q_joint) const |
|
const std::vector< bool > | hasConfigurationLimit () const |
|
const std::vector< bool > | hasConfigurationLimitInTangent () const |
|
| PINOCCHIO_JOINT_TYPEDEF_TEMPLATE (JointDerived) |
|
std::string | shortname () const |
|
void | calc (JointDataDerived &data, const Eigen::MatrixBase< ConfigVectorType > &qs) const |
|
void | calc (JointDataDerived &data, const Eigen::MatrixBase< ConfigVectorType > &qs, const Eigen::MatrixBase< TangentVectorType > &vs) const |
|
void | calc_aba (JointDataDerived &data, const Eigen::MatrixBase< Matrix6Type > &I, const bool update_I=false) const |
|
CastType< NewScalar, JointModelFreeFlyerTpl< _Scalar, _Options > >::type | cast () const |
|
JointDataDerived | createData () const |
|
JointModelDerived & | derived () |
|
const JointModelDerived & | derived () const |
|
void | disp (std::ostream &os) const |
|
const std::vector< bool > | hasConfigurationLimit () const |
|
const std::vector< bool > | hasConfigurationLimitInTangent () const |
|
bool | hasSameIndexes (const JointModelBase< OtherDerived > &other) const |
|
JointIndex | id () const |
|
JointIndex | id_impl () const |
|
int | idx_q () const |
|
int | idx_q_impl () const |
|
int | idx_v () const |
|
int | idx_v_impl () const |
|
bool | isEqual (const JointModelBase< OtherDerived > &) const |
|
bool | isEqual (const JointModelBase< JointModelFreeFlyerTpl< _Scalar, _Options > > &other) const |
|
SizeDepType< NV >::template BlockReturn< D >::ConstType | jointBlock (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...
|
|
SizeDepType< NV >::template BlockReturn< D >::Type | jointBlock (Eigen::MatrixBase< D > &Mat) const |
|
SizeDepType< NV >::template BlockReturn< D >::ConstType | jointBlock_impl (const Eigen::MatrixBase< D > &Mat) const |
|
SizeDepType< NV >::template BlockReturn< D >::Type | jointBlock_impl (Eigen::MatrixBase< D > &Mat) const |
|
SizeDepType< NV >::template ColsReturn< D >::ConstType | jointCols (const Eigen::MatrixBase< D > &A) const |
|
SizeDepType< NV >::template ColsReturn< D >::Type | jointCols (Eigen::MatrixBase< D > &A) const |
|
SizeDepType< NV >::template ColsReturn< D >::ConstType | jointCols_impl (const Eigen::MatrixBase< D > &A) const |
|
SizeDepType< NV >::template ColsReturn< D >::Type | jointCols_impl (Eigen::MatrixBase< D > &A) const |
|
SizeDepType< NQ >::template SegmentReturn< D >::ConstType | jointConfigSelector (const Eigen::MatrixBase< D > &a) const |
|
SizeDepType< NQ >::template SegmentReturn< D >::Type | jointConfigSelector (Eigen::MatrixBase< D > &a) const |
|
SizeDepType< NQ >::template SegmentReturn< D >::ConstType | jointConfigSelector_impl (const Eigen::MatrixBase< D > &a) const |
|
SizeDepType< NQ >::template SegmentReturn< D >::Type | jointConfigSelector_impl (Eigen::MatrixBase< D > &a) const |
|
SizeDepType< NV >::template RowsReturn< D >::ConstType | jointRows (const Eigen::MatrixBase< D > &A) const |
|
SizeDepType< NV >::template RowsReturn< D >::Type | jointRows (Eigen::MatrixBase< D > &A) const |
|
SizeDepType< NV >::template RowsReturn< D >::ConstType | jointRows_impl (const Eigen::MatrixBase< D > &A) const |
|
SizeDepType< NV >::template RowsReturn< D >::Type | jointRows_impl (Eigen::MatrixBase< D > &A) const |
|
SizeDepType< NV >::template SegmentReturn< D >::ConstType | jointVelocitySelector (const Eigen::MatrixBase< D > &a) const |
|
SizeDepType< NV >::template SegmentReturn< D >::Type | jointVelocitySelector (Eigen::MatrixBase< D > &a) const |
|
SizeDepType< NV >::template SegmentReturn< D >::ConstType | jointVelocitySelector_impl (const Eigen::MatrixBase< D > &a) const |
|
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 |
|
bool | operator!= (const JointModelBase< OtherDerived > &other) const |
|
bool | operator== (const JointModelBase< OtherDerived > &other) const |
|
| PINOCCHIO_JOINT_TYPEDEF_TEMPLATE (JointDerived) |
|
void | setIndexes (JointIndex id, int q, int v) |
|
void | setIndexes_impl (JointIndex id, int q, int v) |
|
std::string | shortname () const |
|
template<typename _Scalar, int _Options>
struct pinocchio::JointModelFreeFlyerTpl< _Scalar, _Options >
Definition at line 63 of file src/multibody/joint/fwd.hpp.