|  | 
| template<int Op, typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename ForceType , typename ExpressionType > | 
| void | pinocchio::applyConstraintOnForceVisitor (JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, ForceType F, ExpressionType R) | 
|  | Apply joint constraint (motion subspace) on a force.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| MotionTpl< Scalar, Options > | pinocchio::bias (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) | 
|  | Visit a JointDataTpl through JointBiasVisitor to get the joint bias as a dense motion.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename VectorLike , typename Matrix6Type > | 
| void | pinocchio::calc_aba (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Type > &I, const bool update_I) | 
|  | Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcAbaVisitor to.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename TangentVectorType > | 
| void | pinocchio::calc_first_order (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Blank blank, const Eigen::MatrixBase< TangentVectorType > &v) | 
|  | Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcFirstOrderVisitor to compute the joint data kinematics at order one.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename ConfigVectorType , typename TangentVectorType > | 
| void | pinocchio::calc_first_order (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v) | 
|  | Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcFirstOrderVisitor to compute the joint data kinematics at order one.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename ConfigVectorType > | 
| void | pinocchio::calc_zero_order (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Eigen::MatrixBase< ConfigVectorType > &q) | 
|  | Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcZeroOrderVisitor to compute the joint data kinematics at order zero.  More... 
 | 
|  | 
| template<typename NewScalar , typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| CastType< NewScalar, JointModelTpl< Scalar, Options, JointCollectionTpl > >::type | pinocchio::cast_joint (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) | 
|  | Visit a JointModelTpl<Scalar,...> to cast it into JointModelTpl<NewScalar,...>  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename ConfigVectorIn , typename ConfigVectorOut > | 
| void | pinocchio::configVectorAffineTransform (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, const Eigen::MatrixBase< ConfigVectorIn > &qIn, const Scalar &scaling, const Scalar &offset, const Eigen::MatrixBase< ConfigVectorOut > &qOut) | 
|  | Apply the correct affine transform, on a joint configuration, depending on the joint type.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| JointDataTpl< Scalar, Options, JointCollectionTpl > | pinocchio::createData (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) | 
|  | Visit a JointModelTpl through CreateData visitor to create a JointDataTpl.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > | pinocchio::dinv_inertia (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) | 
|  | Visit a JointDataTpl through JointDInvInertiaVisitor to get the D^{-1} matrix of the inertia matrix decomposition.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| const std::vector< bool > | pinocchio::hasConfigurationLimit (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) | 
|  | Visit a JointModelTpl through JointConfigurationLimitVisitor to get the configurations limits.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| const std::vector< bool > | pinocchio::hasConfigurationLimitInTangent (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) | 
|  | Visit a JointModelTpl through JointConfigurationLimitInTangentVisitor to get the configurations limits in tangent space.  More... 
 | 
|  | 
| template<typename NewScalar , typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename JointModelDerived > | 
| bool | pinocchio::hasSameIndexes (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel_generic, const JointModelBase< JointModelDerived > &jmodel) | 
|  | Check whether JointModelTpl<Scalar,...> has the indexes than another JointModelDerived.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| JointIndex | pinocchio::id (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) | 
|  | Visit a JointModelTpl through JointIdVisitor to get the index of the joint in the kinematic chain.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| int | pinocchio::idx_q (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) | 
|  | Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space corresponding to the first degree of freedom of the Joint.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| int | pinocchio::idx_v (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) | 
|  | Visit a JointModelTpl through JointIdxVVisitor to get the index in the model tangent space corresponding to the first joint tangent space degree.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| int | pinocchio::idx_vExtended (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) | 
|  | Visit a JointModelTpl through JointIdvExtendedVisitor to get the index in the model extended tangent space corresponding to the joint first joint extended tangent space degree.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename JointDataDerived > | 
| bool | pinocchio::isEqual (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jmodel_generic, const JointDataBase< JointDataDerived > &jmodel) | 
|  | Visit a JointDataTpl<Scalar,...> to compare it to another JointData.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl, typename JointModelDerived > | 
| bool | pinocchio::isEqual (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel_generic, const JointModelBase< JointModelDerived > &jmodel) | 
|  | Visit a JointModelTpl<Scalar,...> to compare it to JointModelDerived.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| JointMotionSubspaceTpl< Eigen::Dynamic, Scalar, Options > | pinocchio::joint_motin_subspace_xd (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) | 
|  | Visit a JointDataVariant through JointConstraintVisitor to get the joint constraint as a dense constraint.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| JointDataTpl< Scalar, Options, JointCollectionTpl >::ConfigVector_t | pinocchio::joint_q (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) | 
|  | Visit a JointDataVariant through JointConfigVisitor to get the joint configuration vector.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| SE3Tpl< Scalar, Options > | pinocchio::joint_transform (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) | 
|  | Visit a JointDataTpl through JointTransformVisitor to get the joint internal transform (transform between the entry frame and the exit frame of the joint).  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| JointDataTpl< Scalar, Options, JointCollectionTpl >::TangentVector_t | pinocchio::joint_v (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) | 
|  | Visit a JointDataVariant through JointConfigVisitor to get the joint velocity vector.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| MotionTpl< Scalar, Options > | pinocchio::motion (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) | 
|  | Visit a JointDataTpl through JointMotionVisitor to get the joint internal motion as a dense motion.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| int | pinocchio::nq (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) | 
|  | Visit a JointModelTpl through JointNqVisitor to get the dimension of the joint configuration space.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| int | pinocchio::nv (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) | 
|  | Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent space.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| int | pinocchio::nvExtended (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) | 
|  | Visit a JointModelTpl through JointNvExtendVisitor to get the dimension of the joint extended tangent space.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| void | pinocchio::setIndexes (JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointIndex id, int q, int v) | 
|  | Visit a JointModelTpl through JointSetIndexesVisitor to set the indexes of the joint in the kinematic chain.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| void | pinocchio::setIndexes (JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointIndex id, int q, int v, int vExtended) | 
|  | Visit a JointModelTpl through JointSetIndexesVisitor to set the indexes of the joint in the kinematic chain.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| std::string | pinocchio::shortname (const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel) | 
|  | Visit a JointModelTpl through JointShortnameVisitor to get the shortname of the derived joint model.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > | pinocchio::stu_inertia (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) | 
|  | Visit a JointDataTpl through JointStUInertiaVisitor to get St*I*S matrix of the inertia matrix decomposition.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > | pinocchio::u_inertia (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) | 
|  | Visit a JointDataTpl through JointUInertiaVisitor to get the U matrix of the inertia matrix decomposition.  More... 
 | 
|  | 
| template<typename Scalar , int Options, template< typename S, int O > class JointCollectionTpl> | 
| Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > | pinocchio::udinv_inertia (const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata) | 
|  | Visit a JointDataTpl through JointUDInvInertiaVisitor to get U*D^{-1} matrix of the inertia matrix decomposition.  More... 
 | 
|  |