5 #ifndef __pinocchio_joint_generic_hpp__ 6 #define __pinocchio_joint_generic_hpp__ 8 #include "pinocchio/multibody/joint/joint-collection.hpp" 9 #include "pinocchio/multibody/joint/joint-composite.hpp" 10 #include "pinocchio/multibody/joint/joint-basic-visitors.hxx" 11 #include "pinocchio/container/aligned-vector.hpp" 13 #include <boost/mpl/contains.hpp> 18 template<
typename Scalar,
int Options = 0,
template<
typename S,
int O>
class JointCollectionTpl = JointCollectionDefaultTpl>
22 template<
typename _Scalar,
int _Options,
template<
typename S,
int O>
class JointCollectionTpl>
42 typedef Eigen::Matrix<Scalar,6,Eigen::Dynamic,Options>
U_t;
43 typedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic,Options>
D_t;
44 typedef Eigen::Matrix<Scalar,6,Eigen::Dynamic,Options>
UD_t;
65 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
69 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
73 template<
typename _Scalar,
int _Options,
template<
typename S,
int O>
class JointCollectionTpl>
75 :
public JointDataBase< JointDataTpl<_Scalar,_Options,JointCollectionTpl> >
78 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
88 using Base::operator==;
89 using Base::operator!=;
91 JointDataVariant &
toVariant() {
return *
static_cast<JointDataVariant*
>(
this); }
92 const JointDataVariant &
toVariant()
const {
return *
static_cast<const JointDataVariant*
>(
this); }
96 Motion_t
v()
const {
return motion(*
this); }
97 Bias_t
c()
const {
return bias(*
this); }
109 : JointDataVariant(jdata_variant)
112 template<
typename Jo
intDataDerived>
114 : JointCollection::JointDataVariant((JointDataVariant)jdata.derived())
116 BOOST_MPL_ASSERT((boost::mpl::contains<typename JointDataVariant::types,JointDataDerived>));
131 template<
typename Jo
intDataDerived>
149 return !(*
this == other);
154 template<
typename NewScalar,
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
160 template<
typename _Scalar,
int _Options,
template<
typename S,
int O>
class JointCollectionTpl>
162 :
JointModelBase< JointModelTpl<_Scalar,_Options,JointCollectionTpl> >
165 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
178 using Base::operator==;
179 using Base::operator!=;
184 : JointCollection::JointModelVariant(jmodel_variant)
188 template<
typename Jo
intModelDerived>
190 : JointModelVariant((JointModelVariant)jmodel.derived())
192 BOOST_MPL_ASSERT((boost::mpl::contains<typename JointModelVariant::types,JointModelDerived>));
196 {
return *
static_cast<JointModelVariant*
>(
this); }
199 {
return *
static_cast<const JointModelVariant*
>(
this); }
202 { return ::pinocchio::createData<Scalar,Options,JointCollectionTpl>(*this); }
204 template<
typename Jo
intModelDerived>
210 template<
typename Jo
intModelDerived>
228 return !(*
this == other);
231 template<
typename ConfigVector>
232 void calc(JointDataDerived & data,
233 const Eigen::MatrixBase<ConfigVector> &
q)
const 236 template<
typename ConfigVector,
typename TangentVector>
237 void calc(JointDataDerived & data,
238 const Eigen::MatrixBase<ConfigVector> &
q,
239 const Eigen::MatrixBase<TangentVector> &
v)
const 242 template<
typename Matrix6Like>
243 void calc_aba(JointDataDerived & data,
const Eigen::MatrixBase<Matrix6Like> & I,
const bool update_I)
const 263 template<
typename NewScalar>
266 return cast_joint<NewScalar,Scalar,Options,JointCollectionTpl>(*this);
274 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl,
typename JointDataDerived>
278 return joint_data_generic == joint_data.
derived();
282 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl,
typename JointDataDerived>
286 return joint_data_generic != joint_data.
derived();
289 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl,
typename JointModelDerived>
293 return joint_model_generic == joint_model.
derived();
296 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl,
typename JointModelDerived>
300 return joint_model_generic != joint_model.
derived();
305 #endif // ifndef __pinocchio_joint_generic_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
bool operator==(const JointModelTpl &other) const
int nv(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent space...
std::string shortname() const
bool operator!=(const JointModelTpl &other) const
static std::string classname()
JointDataDerived createData() const
bool isEqual(const JointDataBase< JointDataDerived > &other) const
JointCollection::JointModelVariant JointModelVariant
JointCollection::JointDataVariant JointDataVariant
typedef PINOCCHIO_ALIGNED_STD_VECTOR(JointData) JointDataVector
bool isEqual(const JointModelBase< JointModelDerived > &other) const
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...
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
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...
int nq(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNqVisitor to get the dimension of the joint configuration space...
ConstraintTpl< Eigen::Dynamic, Scalar, Options > Constraint_t
JointCollectionTpl< Scalar, Options > JointCollection
SE3Tpl< Scalar, Options > joint_transform(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataTpl through JointTransformVisitor to get the joint internal transform (transform bet...
JointIndex id(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdVisitor to get the index of the joint in the kinematic chain...
JointDataTpl(const JointDataVariant &jdata_variant)
Motion_t v_accessor() const
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...
bool isEqual(const JointModelTpl &other) const
JointCollection::JointDataVariant JointDataVariant
Constraint_t ConstraintTypeRef
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointTpl< _Scalar, _Options, JointCollectionTpl > JointDerived
JointDataTpl(const JointDataBase< JointDataDerived > &jdata)
bool hasSameIndexes(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel_generic, const JointModelBase< JointModelDerived > &jmodel)
Check whether JointModelTpl<Scalar,...> has the indexes than another JointModelDerived.
JointIndex id_impl() const
bool isEqual(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel_generic, const JointModelBase< JointModelDerived > &jmodel)
Visit a JointModelTpl<Scalar,...> to compare it to JointModelDerived.
Bias_t c_accessor() const
Constraint_t S_accessor() const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointTpl< _Scalar, _Options, JointCollectionTpl > JointDerived
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
bool operator==(const JointDataBase< JointDataDerived > &joint_data, const JointDataTpl< Scalar, Options, JointCollectionTpl > &joint_data_generic)
JointCollectionTpl< _Scalar, _Options > JointCollection
MotionTpl< Scalar, Options > Bias_t
JointCollectionTpl< Scalar, Options > JointCollection
std::string shortname(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointShortnameVisitor to get the shortname of the derived joint model...
#define PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(Joint)
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > D_t
const JointDataVariant & toVariant() const
Transformation_t TansformTypeConstRef
#define PINOCCHIO_JOINT_USE_INDEXES(Joint)
JointModelTpl(const JointModelBase< JointModelDerived > &jmodel)
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > UD_t
bool operator!=(const JointDataBase< JointDataDerived > &joint_data, const JointDataTpl< Scalar, Options, JointCollectionTpl > &joint_data_generic)
JointDataTpl< Scalar, Options, JointCollectionTpl > JointDataDerived
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...
static std::string classname()
JointModelDerived & derived()
JointDataBase< JointDataTpl > Base
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > U_t
std::string shortname() const
Transformation_t M() const
void calc(JointDataDerived &data, const Eigen::MatrixBase< ConfigVector > &q) const
void setIndexes(JointIndex id, int nq, int nv)
Constraint_t ConstraintTypeConstRef
JointModelTpl< NewScalar, Options, JointCollectionTpl > cast() const
Motion_t MotionTypeConstRef
Main pinocchio namespace.
bool operator!=(const JointDataTpl &other) const
MotionTpl< Scalar, Options > Motion_t
JointCollectionDefault::JointDataVariant JointDataVariant
JointTpl< Scalar, Options, JointCollectionTpl > JointDerived
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...
JointDataVariant & toVariant()
void calc(JointDataDerived &data, const Eigen::MatrixBase< ConfigVector > &q, const Eigen::MatrixBase< TangentVector > &v) const
MotionTpl< Scalar, Options > bias(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataTpl through JointBiasVisitor to get the joint bias as a dense motion.
JointModelTpl< NewScalar, Options, JointCollectionTpl > type
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...
D_t Dinv_accessor() const
bool hasSameIndexes(const JointModelBase< JointModelDerived > &other) const
Common traits structure to fully define base classes for CRTP.
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > TangentVector_t
JointModelVariant & toVariant()
SE3Tpl< Scalar, Options > Transformation_t
Transformation_t M_accessor() const
JointModelTpl< Scalar, Options, JointCollectionTpl > JointModelDerived
const JointModelVariant & toVariant() const
UD_t UDinv_accessor() const
JointCollectionDefault::JointModelVariant JointModelVariant
Type of the cast of a class C templated by Scalar and Options, to a new NewScalar type...
JointTpl< Scalar, Options, JointCollectionTpl > JointDerived
Transformation_t TansformTypeRef
JointModelTpl(const JointModelVariant &jmodel_variant)
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...
ConstraintTpl< Eigen::Dynamic, Scalar, Options > constraint_xd(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataVariant through JointConstraintVisitor to get the joint constraint as a dense constr...
bool isEqual(const JointDataTpl &other) const
void calc_aba(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Eigen::MatrixBase< Matrix6Type > &I, const bool update_I)
Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcAbaVisitor to...
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > ConfigVector_t
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...
bool operator==(const JointDataTpl &other) const
#define PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(Joint)