Template Struct JointModelCompositeTpl

Inheritance Relationships

Base Type

Struct Documentation

template<typename _Scalar, int _Options, template<typename S, int O> class JointCollectionTpl>
struct JointModelCompositeTpl : public pinocchio::JointModelBase<JointModelCompositeTpl<_Scalar, _Options, JointCollectionTpl>>

Public Types

typedef JointCompositeTpl<_Scalar, _Options, JointCollectionTpl> JointDerived
typedef JointCollectionTpl<Scalar, Options> JointCollection
typedef JointModelTpl<Scalar, Options, JointCollectionTpl> JointModel
typedef JointModel JointModelVariant
typedef SE3Tpl<Scalar, Options> SE3
typedef MotionTpl<Scalar, Options> Motion
typedef InertiaTpl<Scalar, Options> Inertia

Public Functions

PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
typedef PINOCCHIO_ALIGNED_STD_VECTOR (JointModel) JointModelVector
inline JointModelCompositeTpl()

Default contructor.

inline JointModelCompositeTpl(const size_t size)

Default contructor with a defined size.

template<typename JointModel>
inline JointModelCompositeTpl(const JointModelBase<JointModel> &jmodel, const SE3 &placement = SE3::Identity())

Constructor with one joint.

Parameters:
  • jmodel – Model of the first joint.

  • placement – Placement of the first joint w.r.t. the joint origin.

inline JointModelCompositeTpl(const JointModelCompositeTpl &other)

Copy constructor.

Parameters:

other – JointModel to copy.

template<typename JointModel>
inline JointModelDerived &addJoint(const JointModelBase<JointModel> &jmodel, const SE3 &placement = SE3::Identity())

Add a joint to the vector of joints.

Parameters:
  • jmodel – Model of the joint to add.

  • placement – Placement of the joint relatively to its predecessor.

Returns:

A reference to *this

inline JointDataDerived createData() const
inline const std::vector<bool> hasConfigurationLimit() const
inline const std::vector<bool> hasConfigurationLimitInTangent() const
template<typename ConfigVectorType>
inline void calc(JointDataDerived &data, const Eigen::MatrixBase<ConfigVectorType> &qs) const
template<typename ConfigVectorType, typename TangentVectorType>
inline void calc(JointDataDerived &data, const Eigen::MatrixBase<ConfigVectorType> &qs, const Eigen::MatrixBase<TangentVectorType> &vs) const
template<typename Matrix6Like>
inline void calc_aba(JointDataDerived &data, const Eigen::MatrixBase<Matrix6Like> &I, const bool update_I) const
inline int nv_impl() const
inline int nq_impl() const
inline void setIndexes_impl(JointIndex id, int q, int v)

Update the indexes of subjoints in the stack.

inline std::string shortname() const
inline JointModelCompositeTpl &operator=(const JointModelCompositeTpl &other)
inline bool isEqual(const JointModelCompositeTpl &other) const
template<typename NewScalar>
inline JointModelCompositeTpl<NewScalar, Options, JointCollectionTpl> cast() const
Returns:

An expression of *this with the Scalar type casted to NewScalar.

PINOCCHIO_ALIGNED_STD_VECTOR (SE3) jointPlacements

Vector of joint placements. Those placements correspond to the origin of the joint relatively to their parent.

template<typename D>
inline SizeDepType<NQ>::template SegmentReturn<D>::ConstType jointConfigSelector(const Eigen::MatrixBase<D> &a) const
template<typename D>
inline SizeDepType<NQ>::template SegmentReturn<D>::Type jointConfigSelector(Eigen::MatrixBase<D> &a) const
template<typename D>
inline SizeDepType<NV>::template SegmentReturn<D>::ConstType jointVelocitySelector(const Eigen::MatrixBase<D> &a) const
template<typename D>
inline SizeDepType<NV>::template SegmentReturn<D>::Type jointVelocitySelector(Eigen::MatrixBase<D> &a) const
template<typename D>
inline SizeDepType<NV>::template ColsReturn<D>::ConstType jointCols(const Eigen::MatrixBase<D> &A) const
template<typename D>
inline SizeDepType<NV>::template ColsReturn<D>::Type jointCols(Eigen::MatrixBase<D> &A) const
template<typename D>
inline SizeDepType<Eigen::Dynamic>::template SegmentReturn<D>::ConstType jointConfigSelector_impl(const Eigen::MatrixBase<D> &a) const
template<typename D>
inline SizeDepType<Eigen::Dynamic>::template SegmentReturn<D>::Type jointConfigSelector_impl(Eigen::MatrixBase<D> &a) const
template<typename D>
inline SizeDepType<Eigen::Dynamic>::template SegmentReturn<D>::ConstType jointVelocitySelector_impl(const Eigen::MatrixBase<D> &a) const
template<typename D>
inline SizeDepType<Eigen::Dynamic>::template SegmentReturn<D>::Type jointVelocitySelector_impl(Eigen::MatrixBase<D> &a) const
template<typename D>
inline SizeDepType<Eigen::Dynamic>::template ColsReturn<D>::ConstType jointCols_impl(const Eigen::MatrixBase<D> &A) const
template<typename D>
inline SizeDepType<Eigen::Dynamic>::template ColsReturn<D>::Type jointCols_impl(Eigen::MatrixBase<D> &A) const

Public Members

EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointModelBase< JointModelCompositeTpl > Base
JointModelVector joints

Vector of joints contained in the joint composite.

int njoints

Number of joints contained in the JointModelComposite.

Public Static Functions

static inline std::string classname()

Protected Functions

inline void updateJointIndexes()

Update the indexes of the joints contained in the composition according to the position of the joint composite.

Protected Attributes

int m_nq

Dimensions of the config and tangent space of the composite joint.

int m_nv
std::vector<int> m_idx_q

Keep information of both the dimension and the position of the joints in the composition.

Index in the config vector

std::vector<int> m_nqs

Dimension of the segment in the config vector.

std::vector<int> m_idx_v

Index in the tangent vector.

std::vector<int> m_nvs

Dimension of the segment in the tangent vector.

Friends

friend struct JointCompositeCalcZeroOrderStep
friend struct JointCompositeCalcFirstOrderStep
friend struct Serialize< JointModelCompositeTpl >
friend struct JointModelCompositeTpl