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,
42 typename ConfigVectorType>
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,
66 typename ConfigVectorType,
67 typename TangentVectorType>
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,
90 typename TangentVectorType>
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 const std::vector<bool>
167 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
168 inline const std::vector<bool>
180 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
181 inline int idx_q(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
192 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
193 inline int idx_v(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
203 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
204 inline JointIndex id(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
219 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
221 JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel,
JointIndex id,
int q,
int v);
229 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
230 inline std::string
shortname(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
245 template<
typename S,
int O>
class JointCollectionTpl>
246 typename CastType<NewScalar, JointModelTpl<Scalar, Options, JointCollectionTpl>>
::type
247 cast_joint(
const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel);
260 template<
typename S,
int O>
class JointCollectionTpl,
261 typename JointModelDerived>
263 const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel_generic,
264 const JointModelBase<JointModelDerived> & jmodel);
279 template<
typename S,
int O>
class JointCollectionTpl,
280 typename JointModelDerived>
282 const JointModelTpl<Scalar, Options, JointCollectionTpl> & jmodel_generic,
283 const JointModelBase<JointModelDerived> & jmodel);
297 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
298 inline typename JointDataTpl<Scalar, Options, JointCollectionTpl>::ConfigVector_t
299 joint_q(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
309 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
310 inline typename JointDataTpl<Scalar, Options, JointCollectionTpl>::TangentVector_t
311 joint_v(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
321 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
322 inline JointMotionSubspaceTpl<Eigen::Dynamic, Scalar, Options>
333 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
334 inline SE3Tpl<Scalar, Options>
335 joint_transform(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
345 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
346 inline MotionTpl<Scalar, Options>
347 motion(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
357 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
358 inline MotionTpl<Scalar, Options>
359 bias(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
369 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
370 inline Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options>
371 u_inertia(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
381 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
382 inline Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options>
383 dinv_inertia(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
393 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
394 inline Eigen::Matrix<Scalar, 6, Eigen::Dynamic, Options>
395 udinv_inertia(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
405 template<
typename Scalar,
int Options,
template<
typename S,
int O>
class JointCollectionTpl>
406 inline Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Options>
407 stu_inertia(
const JointDataTpl<Scalar, Options, JointCollectionTpl> & jdata);
420 template<
typename S,
int O>
class JointCollectionTpl,
421 typename JointDataDerived>
423 const JointDataTpl<Scalar, Options, JointCollectionTpl> & jmodel_generic,
424 const JointDataBase<JointDataDerived> & jmodel);
432 #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 full model tangent space corre...
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.
ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > createData(const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel)
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.
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...
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.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
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.
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...
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 Fri Nov 1 2024 02:41:44