#include <fwd.hpp>
Public Types | |
typedef JointModelBase< JointModelUniversalTpl > | Base |
typedef Eigen::Matrix< Scalar, 3, 3, _Options > | Matrix3 |
typedef Eigen::Matrix< Scalar, 3, 1, _Options > | Vector3 |
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 > | |
JointModelUniversalTpl< NewScalar, Options > | 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_v () const |
bool | isEqual (const JointModelBase< Derived > &other) const |
template<class OtherDerived > | |
bool | isEqual (const JointModelBase< OtherDerived > &) const |
bool | isEqual (const JointModelUniversalTpl &other) const |
JointModelUniversalTpl () | |
template<typename Vector3Like > | |
JointModelUniversalTpl (const Eigen::MatrixBase< Vector3Like > &axis1_, const Eigen::MatrixBase< Vector3Like > &axis2_) | |
JointModelUniversalTpl (const Scalar &x1, const Scalar &y1, const Scalar &z1, const Scalar &x2, const Scalar &y2, const Scalar &z2) | |
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 | |
Vector3 | axis1 |
3d main axii of the joint. More... | |
Vector3 | axis2 |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointUniversalTpl< _Scalar, _Options > | JointDerived |
Definition at line 102 of file multibody/joint/fwd.hpp.
typedef JointModelBase<JointModelUniversalTpl> pinocchio::JointModelUniversalTpl< _Scalar, _Options >::Base |
Definition at line 412 of file joint-universal.hpp.
typedef Eigen::Matrix<Scalar, 3, 3, _Options> pinocchio::JointModelUniversalTpl< _Scalar, _Options >::Matrix3 |
Definition at line 410 of file joint-universal.hpp.
typedef Eigen::Matrix<Scalar, 3, 1, _Options> pinocchio::JointModelUniversalTpl< _Scalar, _Options >::Vector3 |
Definition at line 409 of file joint-universal.hpp.
|
inline |
Definition at line 418 of file joint-universal.hpp.
|
inline |
Definition at line 422 of file joint-universal.hpp.
|
inline |
Definition at line 438 of file joint-universal.hpp.
|
inline |
Definition at line 500 of file joint-universal.hpp.
|
inline |
Definition at line 474 of file joint-universal.hpp.
|
inline |
Definition at line 522 of file joint-universal.hpp.
|
inline |
Definition at line 570 of file joint-universal.hpp.
|
inline |
Definition at line 599 of file joint-universal.hpp.
|
inlinestatic |
Definition at line 588 of file joint-universal.hpp.
|
inline |
Definition at line 451 of file joint-universal.hpp.
|
inline |
Definition at line 456 of file joint-universal.hpp.
|
inline |
Definition at line 461 of file joint-universal.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.
|
inline |
Definition at line 247 of file joint-model-base.hpp.
|
inline |
Definition at line 242 of file joint-model-base.hpp.
|
inline |
Definition at line 467 of file joint-universal.hpp.
pinocchio::JointModelUniversalTpl< _Scalar, _Options >::PINOCCHIO_JOINT_TYPEDEF_TEMPLATE | ( | JointDerived | ) |
|
inline |
Definition at line 186 of file joint-model-base.hpp.
|
inline |
Definition at line 592 of file joint-universal.hpp.
Vector3 pinocchio::JointModelUniversalTpl< _Scalar, _Options >::axis1 |
3d main axii of the joint.
Definition at line 609 of file joint-universal.hpp.
Vector3 pinocchio::JointModelUniversalTpl< _Scalar, _Options >::axis2 |
Definition at line 610 of file joint-universal.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointUniversalTpl<_Scalar, _Options> pinocchio::JointModelUniversalTpl< _Scalar, _Options >::JointDerived |
Definition at line 407 of file joint-universal.hpp.