Go to the documentation of this file.
5 #ifndef __pinocchio_multibody_joint_basic_visitors_hpp__
6 #define __pinocchio_multibody_joint_basic_visitors_hpp__
22 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
23 inline JointDataTpl<Scalar, Options, JointCollectionTpl>
24 createData(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
41 template<
typename S,
int O>
class JointCollectionTpl,
44 const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel,
45 JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata,
46 const Eigen::MatrixBase<ConfigVectorType> &
q);
65 template<
typename S,
int O>
class JointCollectionTpl,
69 const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel,
70 JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata,
71 const Eigen::MatrixBase<ConfigVectorType> &
q,
72 const Eigen::MatrixBase<TangentVectorType> &
v);
89 template<
typename S,
int O>
class JointCollectionTpl,
92 const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel,
93 JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata,
95 const Eigen::MatrixBase<TangentVectorType> &
v);
115 template<
typename S,
int O>
class JointCollectionTpl,
117 typename Matrix6Type>
119 const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel,
120 JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata,
121 const Eigen::MatrixBase<VectorLike> & armature,
122 const Eigen::MatrixBase<Matrix6Type> & I,
123 const bool update_I);
133 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
134 inline int nv(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
144 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
145 inline int nq(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
155 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
156 inline int nvExtended(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
166 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
167 inline const std::vector<bool>
178 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
179 inline const std::vector<bool>
191 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
192 inline int idx_q(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
203 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
204 inline int idx_v(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
215 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
216 inline int idx_vExtended(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
226 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
227 inline JointIndex id(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
244 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
246 JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel,
265 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
267 JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel,
JointIndex id,
int q,
int v);
275 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
276 inline std::string
shortname(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
291 template<
typename S,
int O>
class JointCollectionTpl>
292 typename CastType<NewScalar, JointModelTpl<Scalar, Options, JointCollectionTpl>>
::type
293 cast_joint(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
306 template<
typename S,
int O>
class JointCollectionTpl,
307 typename JointModelDerived>
309 const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel_generic,
310 const JointModelBase<JointModelDerived> & jmodel);
325 template<
typename S,
int O>
class JointCollectionTpl,
326 typename JointModelDerived>
328 const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel_generic,
329 const JointModelBase<JointModelDerived> & jmodel);
343 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
344 inline typename JointDataTpl<Scalar, Options, JointCollectionTpl>::ConfigVector_t
345 joint_q(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
355 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
356 inline typename JointDataTpl<Scalar, Options, JointCollectionTpl>::TangentVector_t
357 joint_v(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
367 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
368 inline JointMotionSubspaceTpl<Eigen::Dynamic, Scalar, Options>
379 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
380 inline SE3Tpl<Scalar, Options>
381 joint_transform(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
391 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
392 inline MotionTpl<Scalar, Options>
393 motion(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
403 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
404 inline MotionTpl<Scalar, Options>
405 bias(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
415 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
416 inline Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options>
417 u_inertia(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
427 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
428 inline Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options>
429 dinv_inertia(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
439 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
440 inline Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options>
441 udinv_inertia(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
451 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
452 inline Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options>
453 stu_inertia(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
466 template<
typename S,
int O>
class JointCollectionTpl,
467 typename JointDataDerived>
469 const JointDataTpl<Scalar, Options, JointCollectionTpl> & jmodel_generic,
470 const JointDataBase<JointDataDerived> & jmodel);
490 template<
typename S,
int O>
class JointCollectionTpl,
491 typename ConfigVectorIn,
492 typename ConfigVectorOut>
494 const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel,
495 const Eigen::MatrixBase<ConfigVectorIn> & qIn,
498 const Eigen::MatrixBase<ConfigVectorOut> & qOut);
516 template<
typename S,
int O>
class JointCollectionTpl,
518 typename ExpressionType>
520 JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata, ForceType F, ExpressionType R);
528 #endif // ifndef __pinocchio_multibody_joint_basic_visitors_hpp__
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.
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 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.
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, 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...
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 > motion(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataTpl through JointMotionVisitor to get the joint internal motion as a dense motion.
const std::vector< bool > hasConfigurationLimitInTangent(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointConfigurationLimitInTangentVisitor to get the configurations limit...
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.
std::string shortname(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointShortnameVisitor to get the shortname of the derived joint model.
void configVectorAffineTransform(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, const Eigen::MatrixBase< ConfigVectorIn > &qIn, const Scalar &scaling, const Scalar &offset, const Eigen::MatrixBase< ConfigVectorOut > &qOut)
Apply the correct affine transform, on a joint configuration, depending on the joint type.
ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > createData(const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel)
Model::ConfigVectorType ConfigVectorType
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.
CastType< NewScalar, JointModelTpl< Scalar, Options, JointCollectionTpl > >::type cast_joint(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl<Scalar,...> to cast it into JointModelTpl<NewScalar,...>
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.
Model::TangentVectorType TangentVectorType
int nvExtended(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNvExtendVisitor to get the dimension of the joint extended tangent...
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
MotionTpl< Scalar, Options > bias(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataTpl through JointBiasVisitor to get the joint bias as a dense motion.
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...
bool isEqual(const ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > &cdata_generic, const ConstraintDataBase< ConstraintDataDerived > &cdata)
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...
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::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...
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...
void applyConstraintOnForceVisitor(JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, ForceType F, ExpressionType R)
Apply joint constraint (motion subspace) on a force.
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...
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Wed Apr 16 2025 02:41:47