#include <fwd.hpp>
Public Types | |
typedef JointModelBase< JointModelFreeFlyerTpl > | Base |
Public Member Functions | |
template<typename TangentVector > | |
EIGEN_DONT_INLINE void | calc (JointDataDerived &data, const Blank, const typename Eigen::MatrixBase< TangentVector > &vs) 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 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 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 > | |
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 |
JointIndex | id () const |
int | idx_q () const |
int | idx_v () const |
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE (JointDerived) | |
void | setIndexes (JointIndex id, int q, int v) |
std::string | shortname () const |
Static Public Member Functions | |
static std::string | classname () |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointFreeFlyerTpl< _Scalar, _Options > | JointDerived |
Definition at line 110 of file multibody/joint/fwd.hpp.
typedef JointModelBase<JointModelFreeFlyerTpl> pinocchio::JointModelFreeFlyerTpl< _Scalar, _Options >::Base |
Definition at line 288 of file joint-free-flyer.hpp.
|
inline |
Definition at line 353 of file joint-free-flyer.hpp.
|
inline |
Definition at line 340 of file joint-free-flyer.hpp.
|
inline |
Definition at line 361 of file joint-free-flyer.hpp.
|
inline |
Definition at line 329 of file joint-free-flyer.hpp.
|
inline |
Definition at line 373 of file joint-free-flyer.hpp.
|
inline |
Definition at line 401 of file joint-free-flyer.hpp.
|
inlinestatic |
Definition at line 390 of file joint-free-flyer.hpp.
|
inline |
Definition at line 294 of file joint-free-flyer.hpp.
|
inline |
Definition at line 310 of file joint-free-flyer.hpp.
|
inline |
Definition at line 299 of file joint-free-flyer.hpp.
|
inline |
Definition at line 304 of file joint-free-flyer.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 164 of file joint-model-base.hpp.
pinocchio::JointModelFreeFlyerTpl< _Scalar, _Options >::PINOCCHIO_JOINT_TYPEDEF_TEMPLATE | ( | JointDerived | ) |
|
inline |
Definition at line 186 of file joint-model-base.hpp.
|
inline |
Definition at line 394 of file joint-free-flyer.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointFreeFlyerTpl<_Scalar, _Options> pinocchio::JointModelFreeFlyerTpl< _Scalar, _Options >::JointDerived |
Definition at line 285 of file joint-free-flyer.hpp.