joint-basic-visitors.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2016,2018 CNRS
3 //
4 
5 #ifndef __pinocchio_joint_basic_visitors_hpp__
6 #define __pinocchio_joint_basic_visitors_hpp__
7 
8 #include "pinocchio/multibody/joint/fwd.hpp"
9 
10 namespace pinocchio
11 {
12 
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);
25 
26 
38  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl, typename ConfigVectorType>
39  inline void calc_zero_order(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel,
40  JointDataTpl<Scalar,Options,JointCollectionTpl> & jdata,
41  const Eigen::MatrixBase<ConfigVectorType> & q);
42 
56  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType>
57  inline void calc_first_order(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel,
58  JointDataTpl<Scalar,Options,JointCollectionTpl> & jdata,
59  const Eigen::MatrixBase<ConfigVectorType> & q,
60  const Eigen::MatrixBase<TangentVectorType> & v);
61 
62 
74  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl, typename Matrix6Type>
75  inline void calc_aba(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel,
76  JointDataTpl<Scalar,Options,JointCollectionTpl> & jdata,
77  const Eigen::MatrixBase<Matrix6Type> & I,
78  const bool update_I);
79 
88  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
89  inline int nv(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel);
90 
91 
92 
101  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
102  inline int nq(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel);
103 
104 
113  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
114  inline const std::vector<bool> hasConfigurationLimit(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel);
115 
116 
125  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
126  inline const std::vector<bool> hasConfigurationLimitInTangent(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel);
127 
128 
138  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
139  inline int idx_q(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel);
140 
141 
151  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
152  inline int idx_v(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel);
153 
154 
162  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
163  inline JointIndex id(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel);
164 
176  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
177  inline void setIndexes(JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel, JointIndex id, int q,int v);
178 
179 
185  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
186  inline std::string shortname(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel);
187 
197  template<typename NewScalar, typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
198  typename CastType< NewScalar,JointModelTpl<Scalar,Options,JointCollectionTpl> >::type
199  cast_joint(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel);
200 
209  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl, typename JointModelDerived>
210  bool isEqual(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel_generic,
211  const JointModelBase<JointModelDerived> & jmodel);
212 
213 
222  template<typename NewScalar, typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl, typename JointModelDerived>
223  bool hasSameIndexes(const JointModelTpl<Scalar,Options,JointCollectionTpl> & jmodel_generic,
224  const JointModelBase<JointModelDerived> & jmodel);
225 
226 
227  //
228  // Visitors on JointDatas
229  //
230 
231 
240  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
241  inline ConstraintTpl<Eigen::Dynamic,Scalar,Options>
242  constraint_xd(const JointDataTpl<Scalar,Options,JointCollectionTpl> & jdata);
243 
252  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
253  inline SE3Tpl<Scalar,Options>
254  joint_transform(const JointDataTpl<Scalar,Options,JointCollectionTpl> & jdata);
255 
264  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
265  inline MotionTpl<Scalar,Options>
266  motion(const JointDataTpl<Scalar,Options,JointCollectionTpl> & jdata);
267 
276  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
277  inline MotionTpl<Scalar,Options>
278  bias(const JointDataTpl<Scalar,Options,JointCollectionTpl> & jdata);
279 
288  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
289  inline Eigen::Matrix<Scalar,6,Eigen::Dynamic,Options>
290  u_inertia(const JointDataTpl<Scalar,Options,JointCollectionTpl> & jdata);
291 
300  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
301  inline Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic,Options>
302  dinv_inertia(const JointDataTpl<Scalar,Options,JointCollectionTpl> & jdata);
303 
312  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl>
313  inline Eigen::Matrix<Scalar,6,Eigen::Dynamic,Options>
314  udinv_inertia(const JointDataTpl<Scalar,Options,JointCollectionTpl> & jdata);
315 
324  template<typename Scalar, int Options, template<typename S, int O> class JointCollectionTpl, typename JointDataDerived>
325  bool isEqual(const JointDataTpl<Scalar,Options,JointCollectionTpl> & jmodel_generic,
326  const JointDataBase<JointDataDerived> & jmodel);
327 
328 } // namespace pinocchio
329 
330 
331 /* --- Details -------------------------------------------------------------------- */
332 // Included later
333 // #include "pinocchio/multibody/joint/joint-basic-visitors.hxx"
334 
335 
336 #endif // ifndef __pinocchio_joint_basic_visitors_hpp__
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
int nv(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointNvVisitor to get the dimension of the joint tangent space...
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...
JointDataTpl< Scalar, Options, JointCollectionTpl > createData(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through CreateData visitor to create a JointDataTpl.
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...
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...
const std::vector< bool > hasConfigurationLimitInTangent(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointConfigurationLimitInTangentVisitor to get the configurations limit...
bool hasSameIndexes(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel_generic, const JointModelBase< JointModelDerived > &jmodel)
Check whether JointModelTpl<Scalar,...> has the indexes than another JointModelDerived.
bool isEqual(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel_generic, const JointModelBase< JointModelDerived > &jmodel)
Visit a JointModelTpl<Scalar,...> to compare it to JointModelDerived.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
std::string shortname(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointShortnameVisitor to get the shortname of the derived joint model...
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...
Main pinocchio namespace.
Definition: timings.cpp:28
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 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...
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 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...
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...
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...
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...


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:30