Go to the documentation of this file.
    5 #ifndef __pinocchio_multibody_joint_composite_hpp__ 
    6 #define __pinocchio_multibody_joint_composite_hpp__ 
   19   template<
typename Scalar, 
int Options, 
template<
typename S, 
int O> 
class JointCollectionTpl>
 
   22   template<
typename _Scalar, 
int _Options, 
template<
typename S, 
int O> 
class JointCollectionTpl>
 
   44     typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> 
U_t;
 
   45     typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options> 
D_t;
 
   46     typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options> 
UD_t;
 
   56   template<
typename _Scalar, 
int _Options, 
template<
typename S, 
int O> 
class JointCollectionTpl>
 
   63   template<
typename _Scalar, 
int _Options, 
template<
typename S, 
int O> 
class JointCollectionTpl>
 
   70   template<
typename _Scalar, 
int _Options, 
template<
typename S, 
int O> 
class JointCollectionTpl>
 
   72   : 
public JointDataBase<JointDataCompositeTpl<_Scalar, _Options, JointCollectionTpl>>
 
   74     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
   92     , 
joint_q(ConfigVector_t::Zero(0))
 
   93     , 
joint_v(TangentVector_t::Zero(0))
 
   95     , 
M(Transformation_t::Identity())
 
  107     , iMlast(joint_data.
size())
 
  108     , pjMi(joint_data.
size())
 
  111     , 
S(Constraint_t::Zero(
nv))
 
  112     , 
M(Transformation_t::Identity())
 
  113     , 
v(Motion_t::Zero())
 
  114     , 
c(Motion_t::Zero())
 
  115     , 
U(U_t::Zero(6, 
nv))
 
  147       return std::string(
"JointDataComposite");
 
  154     void disp(std::ostream & os)
 const 
  156       os << 
"JointDataComposite containing following models:\n";
 
  157       for (
typename JointDataVector::const_iterator 
it = 
joints.begin(); 
it != 
joints.end(); ++
it)
 
  158         os << 
"  " << 
it->shortname() << std::endl;
 
  166     template<
typename S, 
int O> 
class JointCollectionTpl>
 
  172   template<
typename _Scalar, 
int _Options, 
template<
typename S, 
int O> 
class JointCollectionTpl>
 
  174   : 
public JointModelBase<JointModelCompositeTpl<_Scalar, _Options, JointCollectionTpl>>
 
  176     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  221       jointPlacements.reserve(
size);
 
  236     template<
typename Jo
intModel>
 
  262     , jointPlacements(other.jointPlacements)
 
  284     template<
typename Jo
intModel>
 
  303       typename JointDataDerived::JointDataVector jdata(
joints.size());
 
  304       for (
int i = 0; 
i < (int)
joints.size(); ++
i)
 
  306           ::pinocchio::createData<Scalar, Options, JointCollectionTpl>(
joints[(
size_t)
i]);
 
  307       return JointDataDerived(jdata, 
nq(), 
nv());
 
  312       std::vector<bool> 
vec;
 
  313       for (
size_t i = 0; 
i < 
joints.size(); ++
i)
 
  315         const std::vector<bool> & joint_cf_limit = 
joints[
i].hasConfigurationLimit();
 
  316         vec.insert(
vec.end(), joint_cf_limit.begin(), joint_cf_limit.end());
 
  323       std::vector<bool> 
vec;
 
  324       for (
size_t i = 0; 
i < 
joints.size(); ++
i)
 
  326         const std::vector<bool> & joint_cf_limit = 
joints[
i].hasConfigurationLimitInTangent();
 
  327         vec.insert(
vec.end(), joint_cf_limit.begin(), joint_cf_limit.end());
 
  332     template<
typename, 
int, 
template<
typename S, 
int O> 
class, 
typename>
 
  335     template<
typename ConfigVectorType>
 
  336     void calc(JointDataDerived & 
data, 
const Eigen::MatrixBase<ConfigVectorType> & 
qs) 
const;
 
  338     template<
typename, 
int, 
template<
typename S, 
int O> 
class, 
typename, 
typename>
 
  341     template<
typename ConfigVectorType, 
typename TangentVectorType>
 
  343       JointDataDerived & 
data,
 
  344       const Eigen::MatrixBase<ConfigVectorType> & 
qs,
 
  345       const Eigen::MatrixBase<TangentVectorType> & vs) 
const;
 
  347     template<
typename TangentVectorType>
 
  349       JointDataDerived & 
data,
 
  351       const Eigen::MatrixBase<TangentVectorType> & vs) 
const;
 
  353     template<
typename VectorLike, 
typename Matrix6Like>
 
  355       JointDataDerived & 
data,
 
  356       const Eigen::MatrixBase<VectorLike> & armature,
 
  357       const Eigen::MatrixBase<Matrix6Like> & I,
 
  358       const bool update_I)
 const 
  360       data.U.noalias() = I * 
data.S.matrix();
 
  361       data.StU.noalias() = 
data.S.matrix().transpose() * 
data.U;
 
  362       data.StU.diagonal() += armature;
 
  389       Base::setIndexes_impl(
id, 
q, 
v, vExtended);
 
  395       return std::string(
"JointModelComposite");
 
  415       jointPlacements = other.jointPlacements;
 
  439     template<
typename NewScalar>
 
  457       res.jointPlacements.resize(jointPlacements.size());
 
  458       for (
size_t k = 0; k < jointPlacements.size(); ++k)
 
  460         res.joints[k] = 
joints[k].template cast<NewScalar>();
 
  461         res.jointPlacements[k] = jointPlacements[k].template cast<NewScalar>();
 
  477       return a.segment(Base::i_q, 
nq());
 
  483       return a.segment(Base::i_q, 
nq());
 
  490       return a.segment(Base::i_q, 
nq());
 
  496       return a.segment(Base::i_q, 
nq());
 
  503       return a.segment(Base::i_v, 
nv());
 
  509       return a.segment(Base::i_v, 
nv());
 
  516       return a.segment(Base::i_v, 
nv());
 
  522       return a.segment(Base::i_v, 
nv());
 
  529       return A.middleCols(Base::i_v, 
nv());
 
  535       return A.middleCols(Base::i_vExtended, 
nvExtended());
 
  540       return A.middleCols(Base::i_v, 
nv());
 
  546       return A.middleCols(Base::i_vExtended, 
nvExtended());
 
  553       return a.segment(Base::i_q, 
nq());
 
  559       return a.segment(Base::i_q, 
nq());
 
  566       return a.segment(Base::i_q, 
nq());
 
  572       return a.segment(Base::i_q, 
nq());
 
  579       return a.segment(Base::i_v, 
nv());
 
  585       return a.segment(Base::i_v, 
nv());
 
  592       return a.segment(Base::i_v, 
nv());
 
  598       return a.segment(Base::i_v, 
nv());
 
  605       return A.middleCols(Base::i_v, 
nv());
 
  611       return A.middleCols(Base::i_vExtended, 
nvExtended());
 
  617       return A.middleCols(Base::i_v, 
nv());
 
  623       return A.middleCols(Base::i_vExtended, 
nvExtended());
 
  626     void disp(std::ostream & os)
 const 
  631       os << 
"JointModelComposite containing following models:\n";
 
  632       for (
typename JointModelVector::const_iterator 
it = 
joints.begin(); 
it != 
joints.end(); ++
it)
 
  633         os << 
"  " << 
it->shortname() << std::endl;
 
  639     template<
typename, 
int, 
template<
typename, 
int> 
class>
 
  657       for (
size_t i = 0; 
i < 
joints.size(); ++
i)
 
  699 #include <boost/type_traits.hpp> 
  703   template<
typename Scalar, 
int Options, 
template<
typename S, 
int O> 
class JointCollectionTpl>
 
  704   struct has_nothrow_constructor<
 
  706   : 
public integral_constant<bool, true>
 
  710   template<
typename Scalar, 
int Options, 
template<
typename S, 
int O> 
class JointCollectionTpl>
 
  712   : 
public integral_constant<bool, true>
 
  716   template<
typename Scalar, 
int Options, 
template<
typename S, 
int O> 
class JointCollectionTpl>
 
  717   struct has_nothrow_constructor<
 
  719   : 
public integral_constant<bool, true>
 
  723   template<
typename Scalar, 
int Options, 
template<
typename S, 
int O> 
class JointCollectionTpl>
 
  725   : 
public integral_constant<bool, true>
 
  733 #include "pinocchio/multibody/joint/joint-composite.hxx" 
  735 #endif // ifndef __pinocchio_multibody_joint_composite_hpp__ 
  
JointDataDerived createData() const
JointDataCompositeTpl(const JointDataVector &joint_data, const int nq, const int nv)
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
SizeDepType< NV >::template ColsReturn< D >::ConstType jointExtendedModelCols(const Eigen::MatrixBase< D > &A) const
JointCollectionTpl< Scalar, Options > JointCollection
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::ConstType jointConfigSelector_impl(const Eigen::MatrixBase< D > &a) const
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::ConstType JointMappedVelocitySelector_impl(const Eigen::MatrixBase< D > &a) const
void disp(std::ostream &os) const
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > ConfigVector_t
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
JointModelCompositeTpl(const JointModelBase< JointModel > &jmodel, const SE3 &placement=SE3::Identity())
Constructor with one joint.
int idx_v(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxVVisitor to get the index in the model tangent space correspond...
int nv(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent space.
JointIndex id(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdVisitor to get the index of the joint in the kinematic chain.
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
int nq(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNqVisitor to get the dimension of the joint configuration space.
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > D_t
JointModelCompositeTpl< NewScalar, Options, JointCollectionTpl > type
JointDataVector joints
Vector of joints.
friend struct JointCompositeCalcZeroOrderStep
JointModelCompositeTpl(const JointModelCompositeTpl &other)
Copy constructor.
std::vector< int > m_idx_q
Keep information of both the dimension and the position of the joints in the composition.
JointCompositeTpl< _Scalar, _Options, JointCollectionTpl > JointDerived
SizeDepType< NV >::template SegmentReturn< D >::Type JointMappedVelocitySelector(Eigen::MatrixBase< D > &a) const
JointModelCompositeTpl & operator=(const JointModelCompositeTpl &other)
SizeDepType< NV >::template ColsReturn< D >::Type jointCols(Eigen::MatrixBase< D > &A) const
SizeDepType< NQ >::template SegmentReturn< D >::Type JointMappedConfigSelector(Eigen::MatrixBase< D > &a) const
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::ConstType jointVelocitySelector_impl(const Eigen::MatrixBase< D > &a) const
JointCompositeTpl< _Scalar, _Options, JointCollectionTpl > JointDerived
JointModelDerived & addJoint(const JointModelBase< JointModel > &jmodel, const SE3 &placement=SE3::Identity())
Add a joint to the vector of joints.
SizeDepType< NV >::template SegmentReturn< D >::ConstType JointMappedVelocitySelector(const Eigen::MatrixBase< D > &a) const
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
static std::string classname()
void updateJointIndexes()
Update the indexes of the joints contained in the composition according to the position of the joint ...
SizeDepType< Eigen::Dynamic >::template ColsReturn< D >::ConstType jointCols_impl(const Eigen::MatrixBase< D > &A) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointModelBase< JointModelCompositeTpl > Base
SizeDepType< NQ >::template SegmentReturn< D >::ConstType JointMappedConfigSelector(const Eigen::MatrixBase< D > &a) const
SizeDepType< NQ >::template SegmentReturn< D >::Type jointConfigSelector(Eigen::MatrixBase< D > &a) const
MotionTpl< Scalar, Options > Motion
int nvExtended_impl() const
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::Type jointVelocitySelector_impl(Eigen::MatrixBase< D > &a) const
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > UD_t
PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived)
JointModelVector joints
Vector of joints contained in the joint composite.
SizeDepType< Eigen::Dynamic >::template ColsReturn< D >::Type jointExtendedModelCols_impl(Eigen::MatrixBase< D > &A) const
friend struct JointCompositeCalcFirstOrderStep
SizeDepType< Eigen::Dynamic >::template ColsReturn< D >::ConstType jointExtendedModelCols_impl(const Eigen::MatrixBase< D > &A) const
SizeDepType< NV >::template SegmentReturn< D >::Type jointVelocitySelector(Eigen::MatrixBase< D > &a) const
const MotionDense< Motion2 > const SE3Tpl< SE3Scalar, SE3Options > & placement
JointCompositeTpl< _Scalar, _Options, JointCollectionTpl > JointDerived
InertiaTpl< Scalar, Options > Inertia
bool isEqual(const JointModelCompositeTpl &other) const
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > TangentVector_t
JointModelCompositeTpl< NewScalar, Options, JointCollectionTpl > cast() const
JointDataTpl< Scalar, Options, JointCollectionTpl > JointDataVariant
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
MotionTpl< Scalar, Options > Bias_t
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointDataBase< JointDataCompositeTpl > Base
void disp(std::ostream &os) const
std::vector< int > m_nvExtendeds
Dimension of the segment in the jacobian matrix.
SizeDepType< NV >::template ColsReturn< D >::ConstType jointCols(const Eigen::MatrixBase< D > &A) const
JointDataCompositeTpl< Scalar, Options, JointCollectionTpl > JointDataDerived
int njoints
Number of joints contained in the JointModelComposite.
SizeDepType< NQ >::template SegmentReturn< D >::ConstType jointConfigSelector(const Eigen::MatrixBase< D > &a) const
static std::string classname()
int m_nq
Dimensions of the config and tangent space of the composite joint.
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::ConstType JointMappedConfigSelector_impl(const Eigen::MatrixBase< D > &a) const
int nvExtended(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNvExtendVisitor to get the dimension of the joint extended tangent...
void calc(JointDataDerived &data, const Eigen::MatrixBase< ConfigVectorType > &qs) const
std::string shortname() const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
int idx_vExtended(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdvExtendedVisitor to get the index in the model extended tangent ...
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
bool comparison_eq(const LhsType &lhs_value, const RhsType &rhs_value)
void setIndexes(JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointIndex id, int q, int v, int vExtended)
Visit a JointModelTpl through JointSetIndexesVisitor to set the indexes of the joint in the kinematic...
SizeDepType< NV >::template ColsReturn< D >::Type jointExtendedModelCols(Eigen::MatrixBase< D > &A) const
std::string shortname() const
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > U_t
typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointModelVariant) JointModelVector
JointModelTpl< Scalar, Options, JointCollectionTpl > JointModelVariant
MotionTpl< Scalar, Options > Motion_t
const std::vector< bool > hasConfigurationLimitInTangent() const
const std::vector< bool > hasConfigurationLimit() const
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::Type jointConfigSelector_impl(Eigen::MatrixBase< D > &a) const
std::vector< int > m_nvs
Dimension of the segment in the tangent vector.
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::Type JointMappedVelocitySelector_impl(Eigen::MatrixBase< D > &a) const
SizeDepType< Eigen::Dynamic >::template SegmentReturn< D >::Type JointMappedConfigSelector_impl(Eigen::MatrixBase< D > &a) const
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointDataVariant) JointDataVector
boost::mpl::false_ is_mimicable_t
JointModelCompositeTpl< Scalar, Options, JointCollectionTpl > JointModelDerived
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR typedef JointCollectionTpl< Scalar, Options > JointCollection
JointModelCompositeTpl(const size_t size)
Default contructor with a defined size.
std::vector< int > m_nqs
Dimension of the segment in the config vector.
std::vector< int > m_idx_v
Index in the tangent vector.
JointModelCompositeTpl()
Default contructor.
Common traits structure to fully define base classes for CRTP.
void setIndexes_impl(JointIndex id, int q, int v, int vExtended)
Update the indexes of subjoints in the stack.
SE3Tpl< Scalar, Options > SE3
JointCompositeTpl< _Scalar, _Options, JointCollectionTpl > JointDerived
Type of the cast of a class C templated by Scalar and Options, to a new NewScalar type....
virtual bool isEqual(const CollisionGeometry &other) const=0
JointMotionSubspaceTpl< Eigen::Dynamic, Scalar, Options > Constraint_t
SE3Tpl< Scalar, Options > Transformation_t
AABB & operator=(const AABB &other)=default
JointCollectionTpl< Scalar, Options > JointCollection
std::vector< int > m_idx_vExtended
Index in the jacobian matrix.
JointModelDerived & derived()
SizeDepType< Eigen::Dynamic >::template ColsReturn< D >::Type jointCols_impl(Eigen::MatrixBase< D > &A) const
SizeDepType< NV >::template SegmentReturn< D >::ConstType jointVelocitySelector(const Eigen::MatrixBase< D > &a) const
Main pinocchio namespace.
pinocchio
Author(s): 
autogenerated on Wed May 28 2025 02:41:19