Go to the documentation of this file.
5 #ifndef __pinocchio_multibody_joint_generic_hpp__
6 #define __pinocchio_multibody_joint_generic_hpp__
10 #include "pinocchio/multibody/joint/joint-basic-visitors.hxx"
13 #include <boost/mpl/contains.hpp>
21 template<
typename S,
int O>
class JointCollectionTpl = JointCollectionDefaultTpl>
25 template<
typename _Scalar,
int _Options,
template<
typename S,
int O>
class JointCollectionTpl>
46 typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options>
U_t;
47 typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options>
D_t;
48 typedef Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options>
UD_t;
74 template<
typename _Scalar,
int _Options,
template<
typename S,
int O>
class JointCollectionTpl>
81 template<
typename _Scalar,
int _Options,
template<
typename S,
int O>
class JointCollectionTpl>
88 template<
typename _Scalar,
int _Options,
template<
typename S,
int O>
class JointCollectionTpl>
90 :
public JointDataBase<JointDataTpl<_Scalar, _Options, JointCollectionTpl>>
93 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
103 using Base::operator==;
104 using Base::operator!=;
123 Constraint_t
S()
const
127 Transformation_t
M()
const
168 template<
typename Jo
intDataDerived>
172 BOOST_MPL_ASSERT((boost::mpl::contains<typename JointDataVariant::types, JointDataDerived>));
226 template<
typename Jo
intDataDerived>
244 return !(*
this == other);
252 template<
typename S,
int O>
class JointCollectionTpl>
258 template<
typename _Scalar,
int _Options,
template<
typename S,
int O>
class JointCollectionTpl>
260 :
JointModelBase<JointModelTpl<_Scalar, _Options, JointCollectionTpl>>
263 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
276 using Base::operator==;
277 using Base::operator!=;
299 template<
typename Jo
intModelDerived>
304 (boost::mpl::contains<typename JointModelVariant::types, JointModelDerived>));
319 return ::pinocchio::createData<Scalar, Options, JointCollectionTpl>(*
this);
322 template<
typename Jo
intModelDerived>
328 template<
typename Jo
intModelDerived>
346 return !(*
this == other);
349 template<
typename ConfigVector>
350 void calc(JointDataDerived &
data,
const Eigen::MatrixBase<ConfigVector> &
q)
const
355 template<
typename TangentVector>
357 JointDataDerived &
data,
const Blank blank,
const Eigen::MatrixBase<TangentVector> &
v)
const
362 template<
typename ConfigVector,
typename TangentVector>
364 JointDataDerived &
data,
365 const Eigen::MatrixBase<ConfigVector> &
q,
366 const Eigen::MatrixBase<TangentVector> &
v)
const
371 template<
typename VectorLike,
typename Matrix6Like>
373 JointDataDerived &
data,
374 const Eigen::MatrixBase<VectorLike> & armature,
375 const Eigen::MatrixBase<Matrix6Like> & I,
376 const bool update_I)
const
420 template<
typename NewScalar>
423 return cast_joint<NewScalar, Scalar, Options, JointCollectionTpl>(*
this);
433 template<
typename S,
int O>
class JointCollectionTpl,
434 typename JointDataDerived>
439 return joint_data_generic == joint_data.
derived();
445 template<
typename S,
int O>
class JointCollectionTpl,
446 typename JointDataDerived>
451 return joint_data_generic != joint_data.
derived();
457 template<
typename S,
int O>
class JointCollectionTpl,
458 typename JointModelDerived>
463 return joint_model_generic == joint_model.
derived();
469 template<
typename S,
int O>
class JointCollectionTpl,
470 typename JointModelDerived>
475 return joint_model_generic != joint_model.
derived();
480 #endif // ifndef __pinocchio_multibody_joint_generic_hpp__
bool operator!=(const JointModelTpl &other) const
JointTpl< _Scalar, _Options, JointCollectionTpl > JointDerived
JointDataTpl< Scalar, Options, JointCollectionTpl >::ConfigVector_t joint_q(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataVariant through JointConfigVisitor to get the joint configuration vector.
JointDataBase< JointDataTpl > Base
const std::vector< bool > hasConfigurationLimitInTangent() const
TangentVector_t TangentVectorTypeRef
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > D_t
bool isEqual(const JointDataBase< Derived > &other) const
 
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
ConfigVector_t joint_q_accessor() const
void calc(JointDataDerived &data, const Eigen::MatrixBase< ConfigVector > &q, const Eigen::MatrixBase< TangentVector > &v) const
int idx_v(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxVVisitor to get the index in the full model tangent space corre...
TangentVector_t joint_v_accessor() const
int nv(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent space.
bool operator!=(const JointDataTpl &other) const
JointIndex id(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdVisitor to get the index of the joint in the kinematic chain.
JointIndex id_impl() const
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
static std::string classname()
Motion_t v_accessor() const
int nq(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNqVisitor to get the dimension of the joint configuration space.
bool operator==(const ConstraintDataBase< ConstraintDataDerived > &data1, const ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > &data2)
JointCollectionTpl< _Scalar, _Options > JointCollection
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > u_inertia(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataTpl through JointUInertiaVisitor to get the U matrix of the inertia matrix decomposi...
JointDataVariant & toVariant()
JointModelTpl(const JointModelBase< JointModelDerived > &jmodel)
const std::vector< bool > hasConfigurationLimit() const
JointModelTpl(const JointModelVariant &jmodel_variant)
JointModelVariant & toVariant()
bool isEqual(const JointModelBase< JointModelDerived > &other) const
bool isEqual(const JointDataBase< JointDataDerived > &other) const
void calc(JointDataDerived &data, const Blank blank, const Eigen::MatrixBase< TangentVector > &v) const
JointTpl< context::Scalar > Joint
JointCollection::JointDataVariant JointDataVariant
traits< JointDerived >::Scalar Scalar
bool isEqual(const JointDataTpl &other) const
bool hasSameIndexes(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel_generic, const JointModelBase< JointModelDerived > &jmodel)
Check whether JointModelTpl<Scalar,...> has the indexes than another JointModelDerived.
MotionTpl< Scalar, Options > Bias_t
MotionTpl< Scalar, Options > motion(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataTpl through JointMotionVisitor to get the joint internal motion as a dense motion.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointTpl< _Scalar, _Options, JointCollectionTpl > JointDerived
Transformation_t TansformTypeConstRef
JointModelTpl< NewScalar, Options, JointCollectionTpl > type
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
ConfigVector_t ConfigVectorTypeConstRef
void setIndexes(JointIndex id, int nq, int nv)
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > UD_t
const std::vector< bool > hasConfigurationLimitInTangent(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointConfigurationLimitInTangentVisitor to get the configurations limit...
const JointModelVariant & toVariant() const
ConfigVector_t joint_q() const
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > U_t
bool operator==(const JointDataTpl &other) const
JointModelTpl< NewScalar, Options, JointCollectionTpl > cast() const
JointDataTpl< context::Scalar > JointData
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > TangentVector_t
JointDataTpl< Scalar, Options, JointCollectionTpl >::TangentVector_t joint_v(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataVariant through JointConfigVisitor to get the joint velocity vector.
ConfigVector_t ConfigVectorTypeRef
JointDataDerived createData() const
std::string shortname(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointShortnameVisitor to get the shortname of the derived joint model.
static std::string classname()
JointCollectionDefault::JointModelVariant JointModelVariant
Motion_t MotionTypeConstRef
void calc_first_order(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcFirstOrderVisitor to comput...
SE3Tpl< Scalar, Options > joint_transform(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataTpl through JointTransformVisitor to get the joint internal transform (transform bet...
const std::vector< bool > hasConfigurationLimit(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointConfigurationLimitVisitor to get the configurations limits.
Constraint_t S_accessor() const
TangentVector_t joint_v() const
UD_t UDinv_accessor() const
D_t Dinv_accessor() const
void setIndexes(JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointIndex id, int q, int v)
Visit a JointModelTpl through JointSetIndexesVisitor to set the indexes of the joint in the kinematic...
bool isEqual(const JointModelTpl &other) const
traits< JointDerived >::Scalar Scalar
Bias_t c_accessor() const
void calc_aba(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Eigen::MatrixBase< VectorLike > &armature, const Eigen::MatrixBase< Matrix6Type > &I, const bool update_I)
Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcAbaVisitor to.
JointModelTpl< context::Scalar > JointModel
JointTpl< _Scalar, _Options, JointCollectionTpl > JointDerived
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > ConfigVector_t
bool operator==(const JointModelTpl &other) const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Constraint_t ConstraintTypeRef
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
MotionTpl< Scalar, Options > bias(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataTpl through JointBiasVisitor to get the joint bias as a dense motion.
PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived)
bool operator!=(const JointDataBase< JointDataDerived > &joint_data, const JointDataTpl< Scalar, Options, JointCollectionTpl > &joint_data_generic)
Constraint_t ConstraintTypeConstRef
JointDataTpl< Scalar, Options, JointCollectionTpl > JointDataDerived
bool hasSameIndexes(const JointModelBase< JointModelDerived > &other) const
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > dinv_inertia(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataTpl through JointDInvInertiaVisitor to get the D^{-1} matrix of the inertia matrix d...
const JointDataVariant & toVariant() const
JointMotionSubspaceTpl< Eigen::Dynamic, Scalar, Options > Constraint_t
JointModelTpl< Scalar, Options, JointCollectionTpl > JointModelDerived
JointCollectionTpl< Scalar, Options > JointCollection
JointCollection::JointModelVariant JointModelVariant
JointDataTpl(const JointDataBase< JointDataDerived > &jdata)
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > udinv_inertia(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataTpl through JointUDInvInertiaVisitor to get U*D^{-1} matrix of the inertia matrix de...
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointTpl< _Scalar, _Options, JointCollectionTpl > JointDerived
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > stu_inertia(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataTpl through JointStUInertiaVisitor to get St*I*S matrix of the inertia matrix decomp...
Common traits structure to fully define base classes for CRTP.
JointCollectionDefault::JointDataVariant JointDataVariant
void calc_zero_order(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Eigen::MatrixBase< ConfigVectorType > &q)
Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcZeroOrderVisitor to compute...
JointCollection::JointDataVariant JointDataVariant
PINOCCHIO_JOINT_USE_INDEXES(JointModelTpl)
Type of the cast of a class C templated by Scalar and Options, to a new NewScalar type....
std::string shortname() const
JointCollectionTpl< Scalar, Options > JointCollection
PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived)
virtual bool isEqual(const CollisionGeometry &other) const=0
Transformation_t M() const
JointMotionSubspaceTpl< Eigen::Dynamic, Scalar, Options > joint_motin_subspace_xd(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataVariant through JointConstraintVisitor to get the joint constraint as a dense constr...
typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointData) JointDataVector
JointDataTpl(const JointDataVariant &jdata_variant)
JointModelDerived & derived()
MotionTpl< Scalar, Options > Motion_t
SE3Tpl< Scalar, Options > Transformation_t
Transformation_t M_accessor() const
std::string shortname() const
TangentVector_t TangentVectorTypeConstRef
Transformation_t TansformTypeRef
Main pinocchio namespace.
void calc(JointDataDerived &data, const Eigen::MatrixBase< ConfigVector > &q) const
pinocchio
Author(s):
autogenerated on Sun Nov 10 2024 03:42:58