#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 > | JointModel |
typedef JointModel | 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 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 Matrix6Like > | |
void | calc_aba (JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const |
template<typename NewScalar > | |
JointModelCompositeTpl< NewScalar, Options, JointCollectionTpl > | cast () const |
JointDataDerived | createData () 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... | |
JointModelCompositeTpl (const size_t size) | |
Default contructor with a defined size. 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... | |
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 (JointModel) 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 |
Public Member Functions inherited from pinocchio::JointModelBase< JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl > > | |
void | calc (JointDataDerived &data, const Eigen::MatrixBase< ConfigVectorType > &qs) const |
void | calc (JointDataDerived &data, const Eigen::MatrixBase< ConfigVectorType > &qs, const Eigen::MatrixBase< TangentVectorType > &vs) const |
void | calc_aba (JointDataDerived &data, const Eigen::MatrixBase< Matrix6Type > &I, const bool update_I=false) const |
CastType< NewScalar, JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl > >::type | cast () const |
JointDataDerived | createData () const |
JointModelDerived & | derived () |
const JointModelDerived & | derived () const |
void | disp (std::ostream &os) const |
bool | hasSameIndexes (const JointModelBase< OtherDerived > &other) const |
JointIndex | id () const |
JointIndex | id_impl () const |
int | idx_q () const |
int | idx_q_impl () const |
int | idx_v () const |
int | idx_v_impl () const |
bool | isEqual (const JointModelBase< OtherDerived > &) const |
bool | isEqual (const JointModelBase< JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl > > &other) const |
SizeDepType< NV >::template BlockReturn< D >::ConstType | jointBlock (const Eigen::MatrixBase< D > &Mat) const |
Returns a block of dimension nv()xnv() located at position idx_v(),idx_v() in the matrix Mat. More... | |
SizeDepType< NV >::template BlockReturn< D >::Type | jointBlock (Eigen::MatrixBase< D > &Mat) const |
SizeDepType< NV >::template BlockReturn< D >::ConstType | jointBlock_impl (const Eigen::MatrixBase< D > &Mat) const |
SizeDepType< NV >::template BlockReturn< D >::Type | jointBlock_impl (Eigen::MatrixBase< D > &Mat) const |
SizeDepType< NV >::template ColsReturn< D >::ConstType | jointCols (const Eigen::MatrixBase< D > &A) const |
SizeDepType< NV >::template ColsReturn< D >::Type | jointCols (Eigen::MatrixBase< D > &A) const |
SizeDepType< NV >::template ColsReturn< D >::ConstType | jointCols_impl (const Eigen::MatrixBase< D > &A) const |
SizeDepType< NV >::template ColsReturn< D >::Type | jointCols_impl (Eigen::MatrixBase< D > &A) const |
SizeDepType< NQ >::template SegmentReturn< D >::ConstType | jointConfigSelector (const Eigen::MatrixBase< D > &a) const |
SizeDepType< NQ >::template SegmentReturn< D >::Type | jointConfigSelector (Eigen::MatrixBase< D > &a) const |
SizeDepType< NQ >::template SegmentReturn< D >::ConstType | jointConfigSelector_impl (const Eigen::MatrixBase< D > &a) const |
SizeDepType< NQ >::template SegmentReturn< D >::Type | jointConfigSelector_impl (Eigen::MatrixBase< D > &a) const |
SizeDepType< NV >::template RowsReturn< D >::ConstType | jointRows (const Eigen::MatrixBase< D > &A) const |
SizeDepType< NV >::template RowsReturn< D >::Type | jointRows (Eigen::MatrixBase< D > &A) const |
SizeDepType< NV >::template RowsReturn< D >::ConstType | jointRows_impl (const Eigen::MatrixBase< D > &A) const |
SizeDepType< NV >::template RowsReturn< D >::Type | jointRows_impl (Eigen::MatrixBase< D > &A) const |
SizeDepType< NV >::template SegmentReturn< D >::ConstType | jointVelocitySelector (const Eigen::MatrixBase< D > &a) const |
SizeDepType< NV >::template SegmentReturn< D >::Type | jointVelocitySelector (Eigen::MatrixBase< D > &a) const |
SizeDepType< NV >::template SegmentReturn< D >::ConstType | jointVelocitySelector_impl (const Eigen::MatrixBase< D > &a) const |
SizeDepType< NV >::template SegmentReturn< D >::Type | jointVelocitySelector_impl (Eigen::MatrixBase< D > &a) const |
int | nq () const |
int | nq_impl () const |
int | nv () const |
int | nv_impl () const |
bool | operator!= (const JointModelBase< OtherDerived > &other) const |
bool | operator== (const JointModelBase< OtherDerived > &other) const |
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE (JointDerived) | |
void | setIndexes (JointIndex id, int q, int v) |
void | setIndexes_impl (JointIndex id, int q, int v) |
std::string | shortname () const |
Static Public Member Functions | |
static std::string | classname () |
Static Public Member Functions inherited from pinocchio::JointModelBase< JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl > > | |
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... | |
Public Attributes inherited from pinocchio::JointModelBase< JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl > > | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef traits< JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl > >::JointDerived | JointDerived |
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 Member Functions inherited from pinocchio::JointModelBase< JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl > > | |
JointModelBase () | |
JointModelBase (const JointModelBase &clone) | |
JointModelBase & | operator= (const JointModelBase &clone) |
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... | |
Protected Attributes inherited from pinocchio::JointModelBase< JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl > > | |
JointIndex | i_id |
int | i_q |
int | i_v |
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 85 of file src/multibody/joint/fwd.hpp.
typedef InertiaTpl<Scalar,Options> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::Inertia |
Definition at line 164 of file joint-composite.hpp.
typedef JointCollectionTpl<Scalar,Options> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointCollection |
Definition at line 158 of file joint-composite.hpp.
typedef JointCompositeTpl<_Scalar,_Options,JointCollectionTpl> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointDerived |
Definition at line 155 of file joint-composite.hpp.
typedef JointModelTpl<Scalar,Options,JointCollectionTpl> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointModel |
Definition at line 159 of file joint-composite.hpp.
typedef JointModel pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::JointModelVariant |
Definition at line 160 of file joint-composite.hpp.
typedef MotionTpl<Scalar,Options> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::Motion |
Definition at line 163 of file joint-composite.hpp.
typedef SE3Tpl<Scalar,Options> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::SE3 |
Definition at line 162 of file joint-composite.hpp.
|
inline |
Default contructor.
Definition at line 176 of file joint-composite.hpp.
|
inline |
Default contructor with a defined size.
Definition at line 185 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 204 of file joint-composite.hpp.
|
inline |
Copy constructor.
other | JointModel to copy. |
Definition at line 220 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 241 of file joint-composite.hpp.
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 278 of file joint-composite.hpp.
|
inline |
Definition at line 344 of file joint-composite.hpp.
|
inlinestatic |
Definition at line 307 of file joint-composite.hpp.
|
inline |
Definition at line 255 of file joint-composite.hpp.
|
inline |
Definition at line 327 of file joint-composite.hpp.
|
inline |
Definition at line 389 of file joint-composite.hpp.
|
inline |
Definition at line 392 of file joint-composite.hpp.
|
inline |
Definition at line 409 of file joint-composite.hpp.
|
inline |
Definition at line 412 of file joint-composite.hpp.
|
inline |
Definition at line 375 of file joint-composite.hpp.
|
inline |
Definition at line 378 of file joint-composite.hpp.
|
inline |
Definition at line 396 of file joint-composite.hpp.
|
inline |
Definition at line 399 of file joint-composite.hpp.
|
inline |
Definition at line 382 of file joint-composite.hpp.
|
inline |
Definition at line 385 of file joint-composite.hpp.
|
inline |
Definition at line 402 of file joint-composite.hpp.
|
inline |
Definition at line 405 of file joint-composite.hpp.
|
inline |
Definition at line 296 of file joint-composite.hpp.
|
inline |
Definition at line 295 of file joint-composite.hpp.
|
inline |
Definition at line 310 of file joint-composite.hpp.
typedef pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::PINOCCHIO_ALIGNED_STD_VECTOR | ( | JointModel | ) |
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 301 of file joint-composite.hpp.
|
inline |
Definition at line 308 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 424 of file joint-composite.hpp.
|
friend |
Definition at line 270 of file joint-composite.hpp.
|
friend |
Definition at line 264 of file joint-composite.hpp.
|
friend |
Definition at line 420 of file joint-composite.hpp.
|
friend |
Definition at line 417 of file joint-composite.hpp.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointModelBase<JointModelCompositeTpl> pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::Base |
Definition at line 154 of file joint-composite.hpp.
JointModelVector pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::joints |
Vector of joints contained in the joint composite.
Definition at line 369 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 453 of file joint-composite.hpp.
|
protected |
Index in the tangent vector.
Definition at line 457 of file joint-composite.hpp.
|
protected |
Dimensions of the config and tangent space of the composite joint.
Definition at line 448 of file joint-composite.hpp.
|
protected |
Dimension of the segment in the config vector.
Definition at line 455 of file joint-composite.hpp.
|
protected |
Definition at line 448 of file joint-composite.hpp.
|
protected |
Dimension of the segment in the tangent vector.
Definition at line 459 of file joint-composite.hpp.
int pinocchio::JointModelCompositeTpl< _Scalar, _Options, JointCollectionTpl >::njoints |
Number of joints contained in the JointModelComposite.
Definition at line 463 of file joint-composite.hpp.