#include <fwd.hpp>
| Public Types | |
| typedef JointModelBase< JointModelPlanarTpl > | Base | 
| Public Member Functions | |
| template<typename TangentVector > | |
| void | calc (JointDataDerived &data, const Blank, const typename Eigen::MatrixBase< TangentVector > &vs) const | 
| template<typename ConfigVector > | |
| void | calc (JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const | 
| template<typename ConfigVector , typename TangentVector > | |
| void | calc (JointDataDerived &data, 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 > | |
| JointModelPlanarTpl< NewScalar, Options > | cast () const | 
| JointDataDerived | createData () const | 
| template<typename ConfigVector > | |
| void | forwardKinematics (Transformation_t &M, const Eigen::MatrixBase< ConfigVector > &q_joint) const | 
| const std::vector< bool > | hasConfigurationLimit () const | 
| const std::vector< bool > | hasConfigurationLimitInTangent () const | 
| JointIndex | id () const | 
| int | idx_q () const | 
| int | idx_v () const | 
| int | idx_vExtended () const | 
| PINOCCHIO_JOINT_TYPEDEF_TEMPLATE (JointDerived) | |
| void | setIndexes (JointIndex id, int q, int v) | 
| void | setIndexes (JointIndex id, int q, int v, int vExtended) | 
| std::string | shortname () const | 
| Static Public Member Functions | |
| static std::string | classname () | 
| Public Attributes | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPlanarTpl< _Scalar, _Options > | JointDerived | 
Definition at line 118 of file multibody/joint/fwd.hpp.
| typedef JointModelBase<JointModelPlanarTpl> pinocchio::JointModelPlanarTpl< _Scalar, _Options >::Base | 
Definition at line 568 of file joint-planar.hpp.
| 
 | inline | 
Definition at line 613 of file joint-planar.hpp.
| 
 | inline | 
Definition at line 601 of file joint-planar.hpp.
| 
 | inline | 
Definition at line 626 of file joint-planar.hpp.
| 
 | inline | 
Definition at line 643 of file joint-planar.hpp.
| 
 | inline | 
Definition at line 675 of file joint-planar.hpp.
| 
 | inlinestatic | 
Definition at line 664 of file joint-planar.hpp.
| 
 | inline | 
Definition at line 575 of file joint-planar.hpp.
| 
 | inline | 
Definition at line 592 of file joint-planar.hpp.
| 
 | inline | 
Definition at line 580 of file joint-planar.hpp.
| 
 | inline | 
Definition at line 585 of file joint-planar.hpp.
| 
 | inline | 
Definition at line 183 of file joint-model-base.hpp.
| 
 | inline | 
Definition at line 171 of file joint-model-base.hpp.
| 
 | inline | 
Definition at line 175 of file joint-model-base.hpp.
| 
 | inline | 
Definition at line 179 of file joint-model-base.hpp.
| pinocchio::JointModelPlanarTpl< _Scalar, _Options >::PINOCCHIO_JOINT_TYPEDEF_TEMPLATE | ( | JointDerived | ) | 
| 
 | inline | 
Definition at line 205 of file joint-model-base.hpp.
| 
 | inline | 
Definition at line 210 of file joint-model-base.hpp.
| 
 | inline | 
Definition at line 668 of file joint-planar.hpp.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPlanarTpl<_Scalar, _Options> pinocchio::JointModelPlanarTpl< _Scalar, _Options >::JointDerived | 
Definition at line 565 of file joint-planar.hpp.