#include <fwd.hpp>
Public Types | |
typedef InertiaTpl< Scalar, Options > | Inertia |
typedef JointCollectionTpl< Scalar, Options > | JointCollection |
typedef JointCompositeTpl< _Scalar, _Options, JointCollectionTpl > | JointDerived |
typedef JointModelTpl< Scalar, Options, JointCollectionTpl > | JointModelVariant |
typedef MotionTpl< Scalar, Options > | Motion |
typedef SE3Tpl< Scalar, Options > | SE3 |
Public Member Functions | |
template<typename JointModel > | |
JointModelDerived & | addJoint (const JointModelBase< JointModel > &jmodel, const SE3 &placement=SE3::Identity()) |
Add a joint to the vector of joints. More... | |
template<typename TangentVectorType > | |
void | calc (JointDataDerived &data, const Blank blank, const Eigen::MatrixBase< TangentVectorType > &vs) const |
template<typename ConfigVectorType > | |
void | calc (JointDataDerived &data, const Eigen::MatrixBase< ConfigVectorType > &qs) const |
template<typename ConfigVectorType , typename TangentVectorType > | |
void | calc (JointDataDerived &data, const Eigen::MatrixBase< ConfigVectorType > &qs, const Eigen::MatrixBase< TangentVectorType > &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 > | |
JointModelCompositeTpl< NewScalar, Options, JointCollectionTpl > | cast () const |
JointDataDerived | createData () const |
const std::vector< bool > | hasConfigurationLimit () const |
const std::vector< bool > | hasConfigurationLimitInTangent () const |
bool | isEqual (const JointModelCompositeTpl &other) const |
template<typename D > | |
SizeDepType< NV >::template ColsReturn< D >::ConstType | jointCols (const Eigen::MatrixBase< D > &A) const |
template<typename D > | |
SizeDepType< NV >::template ColsReturn< D >::Type | jointCols (Eigen::MatrixBase< D > &A) const |
template<typename D > | |
SizeDepType< Eigen::Dynamic >::template ColsReturn< D >::ConstType | jointCols_impl (const Eigen::MatrixBase< D > &A) const |
template<typename D > | |
SizeDepType< Eigen::Dynamic >::template ColsReturn< D >::Type | jointCols_impl (Eigen::MatrixBase< D > &A) const |
template<typename D > | |
SizeDepType< NQ >::template SegmentReturn< D >::ConstType | jointConfigSelector (const Eigen::MatrixBase< D > &a) const |
template<typename D > | |
SizeDepType< NQ >::template SegmentReturn< D >::Type | jointConfigSelector (Eigen::MatrixBase< D > &a) const |
template<typename D > | |
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::ConstType | jointConfigSelector_impl (const Eigen::MatrixBase< D > &a) const |
template<typename D > | |
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::Type | jointConfigSelector_impl (Eigen::MatrixBase< D > &a) const |
JointModelCompositeTpl () | |
Default contructor. More... | |
template<typename JointModel > | |
JointModelCompositeTpl (const JointModelBase< JointModel > &jmodel, const SE3 &placement=SE3::Identity()) | |
Constructor with one joint. More... | |
JointModelCompositeTpl (const JointModelCompositeTpl &other) | |
Copy constructor. More... | |
JointModelCompositeTpl (const size_t size) | |
Default contructor with a defined size. More... | |
template<typename D > | |
SizeDepType< NV >::template SegmentReturn< D >::ConstType | jointVelocitySelector (const Eigen::MatrixBase< D > &a) const |
template<typename D > | |
SizeDepType< NV >::template SegmentReturn< D >::Type | jointVelocitySelector (Eigen::MatrixBase< D > &a) const |
template<typename D > | |
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::ConstType | jointVelocitySelector_impl (const Eigen::MatrixBase< D > &a) const |
template<typename D > | |
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::Type | jointVelocitySelector_impl (Eigen::MatrixBase< D > &a) const |
int | nq_impl () const |
int | nv_impl () const |
JointModelCompositeTpl & | operator= (const JointModelCompositeTpl &other) |
typedef | PINOCCHIO_ALIGNED_STD_VECTOR (JointModelVariant) JointModelVector |
PINOCCHIO_ALIGNED_STD_VECTOR (SE3) jointPlacements | |
Vector of joint placements. Those placements correspond to the origin of the joint relatively to their parent. More... | |
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE (JointDerived) | |
void | setIndexes_impl (JointIndex id, int q, int v) |
Update the indexes of subjoints in the stack. More... | |
std::string | shortname () const |
Static Public Member Functions | |
static std::string | classname () |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointModelBase< JointModelCompositeTpl > | Base |
JointModelVector | joints |
Vector of joints contained in the joint composite. More... | |
int | njoints |
Number of joints contained in the JointModelComposite. More... | |
Protected Member Functions | |
void | updateJointIndexes () |
Update the indexes of the joints contained in the composition according to the position of the joint composite. More... | |
Protected Attributes | |
std::vector< int > | m_idx_q |
Keep information of both the dimension and the position of the joints in the composition. More... | |
std::vector< int > | m_idx_v |
Index in the tangent vector. More... | |
int | m_nq |
Dimensions of the config and tangent space of the composite joint. More... | |
std::vector< int > | m_nqs |
Dimension of the segment in the config vector. More... | |
int | m_nv |
std::vector< int > | m_nvs |
Dimension of the segment in the tangent vector. More... | |
Friends | |
template<typename , int , template< typename S, int O > class, typename , typename > | |
struct | JointCompositeCalcFirstOrderStep |
template<typename , int , template< typename S, int O > class, typename > | |
struct | JointCompositeCalcZeroOrderStep |
template<typename , int , template< typename, int > class> | |
struct | JointModelCompositeTpl |
struct | Serialize< JointModelCompositeTpl > |
Definition at line 141 of file multibody/joint/fwd.hpp.
typedef InertiaTpl<Scalar, Options> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::Inertia |
Definition at line 191 of file joint-composite.hpp.
typedef JointCollectionTpl<Scalar, Options> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointCollection |
Definition at line 186 of file joint-composite.hpp.
typedef JointCompositeTpl<_Scalar, _Options, JointCollectionTpl> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointDerived |
Definition at line 183 of file joint-composite.hpp.
typedef JointModelTpl<Scalar, Options, JointCollectionTpl> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointModelVariant |
Definition at line 187 of file joint-composite.hpp.
typedef MotionTpl<Scalar, Options> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::Motion |
Definition at line 190 of file joint-composite.hpp.
typedef SE3Tpl<Scalar, Options> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::SE3 |
Definition at line 189 of file joint-composite.hpp.
|
inline |
Default contructor.
Definition at line 203 of file joint-composite.hpp.
|
inline |
Default contructor with a defined size.
Definition at line 213 of file joint-composite.hpp.
|
inline |
Constructor with one joint.
jmodel | Model of the first joint. |
placement | Placement of the first joint w.r.t. the joint origin. |
Definition at line 235 of file joint-composite.hpp.
|
inline |
Copy constructor.
other | JointModel to copy. |
Definition at line 254 of file joint-composite.hpp.
|
inline |
Add a joint to the vector of joints.
jmodel | Model of the joint to add. |
placement | Placement of the joint relatively to its predecessor. |
Definition at line 278 of file joint-composite.hpp.
void pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::calc | ( | JointDataDerived & | data, |
const Blank | blank, | ||
const Eigen::MatrixBase< TangentVectorType > & | vs | ||
) | const |
void pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::calc | ( | JointDataDerived & | data, |
const Eigen::MatrixBase< ConfigVectorType > & | qs | ||
) | const |
void pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::calc | ( | JointDataDerived & | data, |
const Eigen::MatrixBase< ConfigVectorType > & | qs, | ||
const Eigen::MatrixBase< TangentVectorType > & | vs | ||
) | const |
|
inline |
Definition at line 345 of file joint-composite.hpp.
|
inline |
Definition at line 421 of file joint-composite.hpp.
|
inlinestatic |
Definition at line 380 of file joint-composite.hpp.
|
inline |
Definition at line 292 of file joint-composite.hpp.
|
inline |
Definition at line 301 of file joint-composite.hpp.
|
inline |
Definition at line 312 of file joint-composite.hpp.
|
inline |
Definition at line 406 of file joint-composite.hpp.
|
inline |
Definition at line 479 of file joint-composite.hpp.
|
inline |
Definition at line 484 of file joint-composite.hpp.
|
inline |
Definition at line 516 of file joint-composite.hpp.
|
inline |
Definition at line 522 of file joint-composite.hpp.
|
inline |
Definition at line 453 of file joint-composite.hpp.
|
inline |
Definition at line 459 of file joint-composite.hpp.
|
inline |
Definition at line 491 of file joint-composite.hpp.
|
inline |
Definition at line 497 of file joint-composite.hpp.
|
inline |
Definition at line 466 of file joint-composite.hpp.
|
inline |
Definition at line 472 of file joint-composite.hpp.
|
inline |
Definition at line 503 of file joint-composite.hpp.
|
inline |
Definition at line 509 of file joint-composite.hpp.
|
inline |
Definition at line 366 of file joint-composite.hpp.
|
inline |
Definition at line 362 of file joint-composite.hpp.
|
inline |
Definition at line 389 of file joint-composite.hpp.
typedef pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | JointModelVariant | ) |
pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | SE3 | ) |
Vector of joint placements. Those placements correspond to the origin of the joint relatively to their parent.
pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_JOINT_TYPEDEF_TEMPLATE | ( | JointDerived | ) |
|
inline |
Update the indexes of subjoints in the stack.
Definition at line 374 of file joint-composite.hpp.
|
inline |
Definition at line 384 of file joint-composite.hpp.
|
inlineprotected |
Update the indexes of the joints contained in the composition according to the position of the joint composite.
Definition at line 535 of file joint-composite.hpp.
|
friend |
Definition at line 330 of file joint-composite.hpp.
|
friend |
Definition at line 324 of file joint-composite.hpp.
|
friend |
Definition at line 531 of file joint-composite.hpp.
|
friend |
Definition at line 528 of file joint-composite.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointModelBase<JointModelCompositeTpl> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::Base |
Definition at line 182 of file joint-composite.hpp.
JointModelVector pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::joints |
Vector of joints contained in the joint composite.
Definition at line 446 of file joint-composite.hpp.
|
protected |
Keep information of both the dimension and the position of the joints in the composition.
Index in the config vector
Definition at line 565 of file joint-composite.hpp.
|
protected |
Index in the tangent vector.
Definition at line 569 of file joint-composite.hpp.
|
protected |
Dimensions of the config and tangent space of the composite joint.
Definition at line 560 of file joint-composite.hpp.
|
protected |
Dimension of the segment in the config vector.
Definition at line 567 of file joint-composite.hpp.
|
protected |
Definition at line 560 of file joint-composite.hpp.
|
protected |
Dimension of the segment in the tangent vector.
Definition at line 571 of file joint-composite.hpp.
int pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::njoints |
Number of joints contained in the JointModelComposite.
Definition at line 575 of file joint-composite.hpp.