joint-prismatic.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2015-2019 CNRS INRIA
3 // Copyright (c) 2015-2016 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #ifndef __pinocchio_joint_prismatic_hpp__
7 #define __pinocchio_joint_prismatic_hpp__
8 
9 #include "pinocchio/macros.hpp"
10 #include "pinocchio/multibody/joint/joint-base.hpp"
11 #include "pinocchio/multibody/constraint.hpp"
12 #include "pinocchio/spatial/inertia.hpp"
13 #include "pinocchio/spatial/spatial-axis.hpp"
14 #include "pinocchio/utils/axis-label.hpp"
15 
16 namespace pinocchio
17 {
18 
19  template<typename Scalar, int Options, int _axis> struct MotionPrismaticTpl;
20 
21  template<typename Scalar, int Options, int axis>
23  {
25  };
26 
27  template<typename Scalar, int Options, int axis, typename MotionDerived>
29  {
31  };
32 
33  template<typename _Scalar, int _Options, int _axis>
34  struct traits < MotionPrismaticTpl<_Scalar,_Options,_axis> >
35  {
36  typedef _Scalar Scalar;
37  enum { Options = _Options };
38  typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
39  typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
40  typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
41  typedef typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector6) ToVectorConstReturnType;
42  typedef typename PINOCCHIO_EIGEN_REF_TYPE(Vector6) ToVectorReturnType;
43  typedef Vector3 AngularType;
44  typedef Vector3 LinearType;
45  typedef const Vector3 ConstAngularType;
46  typedef const Vector3 ConstLinearType;
47  typedef Matrix6 ActionMatrixType;
48  typedef MotionTpl<Scalar,Options> MotionPlain;
49  typedef MotionPlain PlainReturnType;
50  enum {
51  LINEAR = 0,
52  ANGULAR = 3
53  };
54  }; // struct traits MotionPrismaticTpl
55 
56  template<typename _Scalar, int _Options, int _axis>
57  struct MotionPrismaticTpl
58  : MotionBase < MotionPrismaticTpl<_Scalar,_Options,_axis> >
59  {
60  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
62 
63  enum { axis = _axis };
64 
67 
69  MotionPrismaticTpl(const Scalar & v) : m_v(v) {}
70 
71  inline PlainReturnType plain() const { return Axis() * m_v; }
72 
73  template<typename OtherScalar>
74  MotionPrismaticTpl __mult__(const OtherScalar & alpha) const
75  {
76  return MotionPrismaticTpl(alpha*m_v);
77  }
78 
79  template<typename Derived>
80  void addTo(MotionDense<Derived> & other) const
81  {
82  typedef typename MotionDense<Derived>::Scalar OtherScalar;
83  other.linear()[_axis] += (OtherScalar) m_v;
84  }
85 
86  template<typename MotionDerived>
87  void setTo(MotionDense<MotionDerived> & other) const
88  {
89  for(Eigen::DenseIndex k = 0; k < 3; ++k)
90  other.linear()[k] = k == axis ? m_v : (Scalar)0;
91  other.angular().setZero();
92  }
93 
94  template<typename S2, int O2, typename D2>
95  void se3Action_impl(const SE3Tpl<S2,O2> & m, MotionDense<D2> & v) const
96  {
97  v.angular().setZero();
98  v.linear().noalias() = m_v * (m.rotation().col(axis));
99  }
100 
101  template<typename S2, int O2>
102  MotionPlain se3Action_impl(const SE3Tpl<S2,O2> & m) const
103  {
104  MotionPlain res;
105  se3Action_impl(m,res);
106  return res;
107  }
108 
109  template<typename S2, int O2, typename D2>
111  {
112  // Linear
113  v.linear().noalias() = m_v * (m.rotation().transpose().col(axis));
114 
115  // Angular
116  v.angular().setZero();
117  }
118 
119  template<typename S2, int O2>
120  MotionPlain se3ActionInverse_impl(const SE3Tpl<S2,O2> & m) const
121  {
122  MotionPlain res;
123  se3ActionInverse_impl(m,res);
124  return res;
125  }
126 
127  template<typename M1, typename M2>
128  void motionAction(const MotionDense<M1> & v, MotionDense<M2> & mout) const
129  {
130  // Linear
131  CartesianAxis3::alphaCross(-m_v,v.angular(),mout.linear());
132 
133  // Angular
134  mout.angular().setZero();
135  }
136 
137  template<typename M1>
138  MotionPlain motionAction(const MotionDense<M1> & v) const
139  {
140  MotionPlain res;
141  motionAction(v,res);
142  return res;
143  }
144 
145  Scalar & linearRate() { return m_v; }
146  const Scalar & linearRate() const { return m_v; }
147 
148  bool isEqual_impl(const MotionPrismaticTpl & other) const
149  {
150  return m_v == other.m_v;
151  }
152 
153  protected:
154 
156  }; // struct MotionPrismaticTpl
157 
158  template<typename Scalar, int Options, int axis, typename MotionDerived>
159  typename MotionDerived::MotionPlain
161  const MotionDense<MotionDerived> & m2)
162  {
163  typename MotionDerived::MotionPlain res(m2);
164  res += m1;
165  return res;
166  }
167 
168  template<typename MotionDerived, typename S2, int O2, int axis>
169  EIGEN_STRONG_INLINE
170  typename MotionDerived::MotionPlain
172  {
173  return m2.motionAction(m1);
174  }
175 
176  template<typename Scalar, int Options, int axis> struct TransformPrismaticTpl;
177 
178  template<typename _Scalar, int _Options, int _axis>
179  struct traits< TransformPrismaticTpl<_Scalar,_Options,_axis> >
180  {
181  enum {
182  axis = _axis,
183  Options = _Options,
184  LINEAR = 0,
185  ANGULAR = 3
186  };
187  typedef _Scalar Scalar;
189  typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
190  typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
191  typedef typename Matrix3::IdentityReturnType AngularType;
192  typedef AngularType AngularRef;
193  typedef AngularType ConstAngularRef;
194  typedef Vector3 LinearType;
195  typedef const Vector3 LinearRef;
196  typedef const Vector3 ConstLinearRef;
199  }; // traits TransformPrismaticTpl
200 
201  template<typename Scalar, int Options, int axis>
204 
205  template<typename _Scalar, int _Options, int axis>
206  struct TransformPrismaticTpl : SE3Base< TransformPrismaticTpl<_Scalar,_Options,axis> >
207  {
208  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
210 
213 
215  TransformPrismaticTpl(const Scalar & displacement)
216  : m_displacement(displacement)
217  {}
218 
219  PlainType plain() const
220  {
221  PlainType res(PlainType::Identity());
222  res.rotation().setIdentity();
223  res.translation()[axis] = m_displacement;
224 
225  return res;
226  }
227 
228  operator PlainType() const { return plain(); }
229 
230  template<typename S2, int O2>
232  se3action(const SE3Tpl<S2,O2> & m) const
233  {
235  ReturnType res(m);
236  res.translation()[axis] += m_displacement;
237 
238  return res;
239  }
240 
241  const Scalar & displacement() const { return m_displacement; }
242  Scalar & displacement() { return m_displacement; }
243 
244  ConstLinearRef translation() const { return CartesianAxis3()*displacement(); };
245  AngularType rotation() const { return AngularType(3,3); }
246 
247  bool isEqual(const TransformPrismaticTpl & other) const
248  {
249  return m_displacement == other.m_displacement;
250  }
251 
252  protected:
253 
255  };
256 
257  template<typename Scalar, int Options, int axis> struct ConstraintPrismaticTpl;
258 
259  template<typename _Scalar, int _Options, int axis>
260  struct traits< ConstraintPrismaticTpl<_Scalar,_Options,axis> >
261  {
262  typedef _Scalar Scalar;
263  enum { Options = _Options };
264  enum {
265  LINEAR = 0,
266  ANGULAR = 3
267  };
269  typedef Eigen::Matrix<Scalar,1,1,Options> JointForce;
270  typedef Eigen::Matrix<Scalar,6,1,Options> DenseBase;
271  typedef DenseBase MatrixReturnType;
272  typedef const DenseBase ConstMatrixReturnType;
273  }; // traits ConstraintRevolute
274 
275  template<typename Scalar, int Options, int axis>
277  { typedef Eigen::Matrix<Scalar,6,1,Options> ReturnType; };
278 
279  template<typename Scalar, int Options, int axis, typename MotionDerived>
281  { typedef Eigen::Matrix<Scalar,6,1,Options> ReturnType; };
282 
283  template<typename Scalar, int Options, int axis, typename ForceDerived>
285  { typedef typename ForceDense<ForceDerived>::ConstLinearType::template ConstFixedSegmentReturnType<1>::Type ReturnType; };
286 
287  template<typename Scalar, int Options, int axis, typename ForceSet>
289  { typedef typename Eigen::MatrixBase<ForceSet>::ConstRowXpr ReturnType; };
290 
291  template<typename _Scalar, int _Options, int axis>
293  : ConstraintBase < ConstraintPrismaticTpl <_Scalar,_Options,axis> >
294  {
295  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
297  enum { NV = 1 };
298 
300 
302 
303  template<typename Vector1Like>
304  JointMotion __mult__(const Eigen::MatrixBase<Vector1Like> & v) const
305  {
306  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector1Like,1);
307  assert(v.size() == 1);
308  return JointMotion(v[0]);
309  }
310 
311  template<typename S2, int O2>
313  se3Action(const SE3Tpl<S2,O2> & m) const
314  {
316  MotionRef<DenseBase> v(res);
317  v.linear() = m.rotation().col(axis);
318  v.angular().setZero();
319  return res;
320  }
321 
322  template<typename S2, int O2>
325  {
327  MotionRef<DenseBase> v(res);
328  v.linear() = m.rotation().transpose().col(axis);
329  v.angular().setZero();
330  return res;
331  }
332 
333  int nv_impl() const { return NV; }
334 
336  {
338  TransposeConst(const ConstraintPrismaticTpl & ref) : ref(ref) {}
339 
340  template<typename ForceDerived>
343  { return f.linear().template segment<1>(axis); }
344 
345  /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
346  template<typename Derived>
348  operator*(const Eigen::MatrixBase<Derived> & F )
349  {
350  assert(F.rows()==6);
351  return F.row(LINEAR+axis);
352  }
353 
354  }; // struct TransposeConst
355  TransposeConst transpose() const { return TransposeConst(*this); }
356 
357  /* CRBA joint operators
358  * - ForceSet::Block = ForceSet
359  * - ForceSet operator* (Inertia Y,Constraint S)
360  * - MatrixBase operator* (Constraint::Transpose S, ForceSet::Block)
361  * - SE3::act(ForceSet::Block)
362  */
363  DenseBase matrix_impl() const
364  {
365  DenseBase S;
367  v << Axis();
368  return S;
369  }
370 
371  template<typename MotionDerived>
374  {
376  MotionRef<DenseBase> v(res);
377  v = m.cross(Axis());
378  return res;
379  }
380 
381  bool isEqual(const ConstraintPrismaticTpl &) const { return true; }
382 
383  }; // struct ConstraintPrismaticTpl
384 
385  template<typename S1, int O1,typename S2, int O2, int axis>
387  {
388  typedef Eigen::Matrix<S2,6,1,O2> ReturnType;
389  };
390 
391  /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
392  namespace impl
393  {
394  template<typename S1, int O1, typename S2, int O2>
396  {
400  static inline ReturnType run(const Inertia & Y,
401  const Constraint & /*constraint*/)
402  {
403  ReturnType res;
404 
405  /* Y(:,0) = ( 1,0, 0, 0 , z , -y ) */
406  const S1
407  &m = Y.mass(),
408  &y = Y.lever()[1],
409  &z = Y.lever()[2];
410  res << m, S1(0), S1(0), S1(0), m*z, -m*y;
411 
412  return res;
413  }
414  };
415 
416  template<typename S1, int O1, typename S2, int O2>
418  {
422  static inline ReturnType run(const Inertia & Y,
423  const Constraint & /*constraint*/)
424  {
425  ReturnType res;
426 
427  /* Y(:,1) = ( 0,1, 0, -z , 0 , x) */
428  const S1
429  &m = Y.mass(),
430  &x = Y.lever()[0],
431  &z = Y.lever()[2];
432 
433  res << S1(0), m, S1(0), -m*z, S1(0), m*x;
434 
435  return res;
436  }
437  };
438 
439  template<typename S1, int O1, typename S2, int O2>
441  {
445  static inline ReturnType run(const Inertia & Y,
446  const Constraint & /*constraint*/)
447  {
448  ReturnType res;
449 
450  /* Y(:,2) = ( 0,0, 1, y , -x , 0) */
451  const S1
452  &m = Y.mass(),
453  &x = Y.lever()[0],
454  &y = Y.lever()[1];
455 
456  res << S1(0), S1(0), m, m*y, -m*x, S1(0);
457 
458  return res;
459  }
460  };
461  } // namespace impl
462 
463  template<typename M6Like,typename S2, int O2, int axis>
464  struct MultiplicationOp<Eigen::MatrixBase<M6Like>, ConstraintPrismaticTpl<S2,O2,axis> >
465  {
466  typedef typename M6Like::ConstColXpr ReturnType;
467  };
468 
469  /* [ABA] operator* (Inertia Y,Constraint S) */
470  namespace impl
471  {
472  template<typename M6Like, typename Scalar, int Options, int axis>
473  struct LhsMultiplicationOp<Eigen::MatrixBase<M6Like>, ConstraintPrismaticTpl<Scalar,Options,axis> >
474  {
477  static inline ReturnType run(const Eigen::MatrixBase<M6Like> & Y,
478  const Constraint & /*constraint*/)
479  {
480  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like,6,6);
481  return Y.derived().col(Inertia::LINEAR + axis);
482  }
483  };
484  } // namespace impl
485 
486  template<typename _Scalar, int _Options, int _axis>
488  {
489  typedef _Scalar Scalar;
490 
491  enum
492  {
493  Options = _Options,
494  axis = _axis
495  };
496  };
497 
498  template<typename _Scalar, int _Options, int axis>
499  struct traits< JointPrismaticTpl<_Scalar,_Options,axis> >
500  {
501  enum {
502  NQ = 1,
503  NV = 1
504  };
505  typedef _Scalar Scalar;
506  enum { Options = _Options };
513 
514  // [ABA]
515  typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
516  typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
517  typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
518 
520 
521  typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
522  typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
523  };
524 
525  template<typename Scalar, int Options, int axis>
528 
529  template<typename Scalar, int Options, int axis>
532 
533  template<typename _Scalar, int _Options, int axis>
534  struct JointDataPrismaticTpl : public JointDataBase< JointDataPrismaticTpl<_Scalar,_Options,axis> >
535  {
536  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
540 
541  Constraint_t S;
542  Transformation_t M;
543  Motion_t v;
544  Bias_t c;
545 
546  // [ABA] specific data
547  U_t U;
548  D_t Dinv;
549  UD_t UDinv;
550 
552  : M((Scalar)0)
553  , v((Scalar)0)
554  , U(U_t::Zero())
555  , Dinv(D_t::Zero())
556  , UDinv(UD_t::Zero())
557  {}
558 
559  static std::string classname()
560  {
561  return std::string("JointDataP") + axisLabel<axis>();
562  }
563  std::string shortname() const { return classname(); }
564 
565  }; // struct JointDataPrismaticTpl
566 
567  template<typename NewScalar, typename Scalar, int Options, int axis>
569  {
571  };
572 
573  template<typename _Scalar, int _Options, int axis>
575  : public JointModelBase< JointModelPrismaticTpl<_Scalar,_Options,axis> >
576  {
577  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
579  PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived);
580 
582  using Base::id;
583  using Base::idx_q;
584  using Base::idx_v;
585  using Base::setIndexes;
586 
587  JointDataDerived createData() const { return JointDataDerived(); }
588 
589  template<typename ConfigVector>
590  void calc(JointDataDerived & data,
591  const typename Eigen::MatrixBase<ConfigVector> & qs) const
592  {
593  typedef typename ConfigVector::Scalar Scalar;
594  const Scalar & q = qs[idx_q()];
595  data.M.displacement() = q;
596  }
597 
598  template<typename ConfigVector, typename TangentVector>
599  void calc(JointDataDerived & data,
600  const typename Eigen::MatrixBase<ConfigVector> & qs,
601  const typename Eigen::MatrixBase<TangentVector> & vs) const
602  {
603  calc(data,qs.derived());
604 
605  typedef typename TangentVector::Scalar S2;
606  const S2 & v = vs[idx_v()];
607  data.v.linearRate() = v;
608  }
609 
610  template<typename Matrix6Like>
611  void calc_aba(JointDataDerived & data, const Eigen::MatrixBase<Matrix6Like> & I, const bool update_I) const
612  {
613  data.U = I.col(Inertia::LINEAR + axis);
614  data.Dinv[0] = Scalar(1)/I(Inertia::LINEAR + axis, Inertia::LINEAR + axis);
615  data.UDinv.noalias() = data.U * data.Dinv[0];
616 
617  if (update_I)
618  PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,I) -= data.UDinv * data.U.transpose();
619  }
620 
621  static std::string classname()
622  {
623  return std::string("JointModelP") + axisLabel<axis>();
624  }
625  std::string shortname() const { return classname(); }
626 
628  template<typename NewScalar>
630  {
632  ReturnType res;
633  res.setIndexes(id(),idx_q(),idx_v());
634  return res;
635  }
636 
637  }; // struct JointModelPrismaticTpl
638 
642 
646 
650 
651 } //namespace pinocchio
652 
653 #include <boost/type_traits.hpp>
654 
655 namespace boost
656 {
657  template<typename Scalar, int Options, int axis>
658  struct has_nothrow_constructor< ::pinocchio::JointModelPrismaticTpl<Scalar,Options,axis> >
659  : public integral_constant<bool,true> {};
660 
661  template<typename Scalar, int Options, int axis>
662  struct has_nothrow_copy< ::pinocchio::JointModelPrismaticTpl<Scalar,Options,axis> >
663  : public integral_constant<bool,true> {};
664 
665  template<typename Scalar, int Options, int axis>
666  struct has_nothrow_constructor< ::pinocchio::JointDataPrismaticTpl<Scalar,Options,axis> >
667  : public integral_constant<bool,true> {};
668 
669  template<typename Scalar, int Options, int axis>
670  struct has_nothrow_copy< ::pinocchio::JointDataPrismaticTpl<Scalar,Options,axis> >
671  : public integral_constant<bool,true> {};
672 }
673 
674 #endif // ifndef __pinocchio_joint_prismatic_hpp__
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
ConstraintPrismaticTpl< Scalar, Options, axis > Constraint_t
TransposeConst transpose() const
#define PINOCCHIO_SE3_TYPEDEF_TPL(Derived)
JointModelPrismaticTpl< double, 0, 0 > JointModelPX
Forward declaration of the multiplication operation return type. Should be overloaded, otherwise it will procude a compilation error.
Definition: binary-op.hpp:15
SE3GroupAction< ConstraintPrismaticTpl >::ReturnType se3Action(const SE3Tpl< S2, O2 > &m) const
int NQ
Definition: dpendulum.py:8
axis
traits< TransformPrismaticTpl< Scalar, Options, axis > >::PlainType ReturnType
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
PlainReturnType plain() const
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) 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...
Return type of the Constraint::Transpose * ForceSet operation.
const Scalar & displacement() const
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
JointPrismaticTpl< double, 0, 1 > JointPY
Return type of the ation of a Motion onto an object of type D.
#define MOTION_TYPEDEF_TPL(Derived)
JointDataDerived createData() const
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPrismaticTpl< _Scalar, _Options, axis > JointDerived
SpatialAxis< LINEAR+axis > Axis
ConstLinearRef translation() const
JointModelPrismaticTpl< double, 0, 1 > JointModelPY
void setTo(MotionDense< MotionDerived > &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...
#define PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPrismaticTpl< _Scalar, _Options, axis > JointDerived
MotionAlgebraAction< OtherSpatialType, Derived >::ReturnType cross(const OtherSpatialType &d) const
Definition: motion-base.hpp:72
SE3GroupAction< ConstraintPrismaticTpl >::ReturnType se3ActionInverse(const SE3Tpl< S2, O2 > &m) const
JointDataPrismaticTpl< double, 0, 0 > JointDataPX
JointModelBase< JointModelPrismaticTpl > Base
void addTo(MotionDense< Derived > &other) const
ForceDense< ForceDerived >::ConstLinearType::template ConstFixedSegmentReturnType< 1 >::Type ReturnType
JointModelPrismaticTpl< NewScalar, Options, axis > cast() const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR Constraint_t S
MotionDerived::MotionPlain operator+(const MotionPlanarTpl< Scalar, Options > &m1, const MotionDense< MotionDerived > &m2)
SE3::Scalar Scalar
Definition: conversions.cpp:13
JointModelPrismaticTpl< Scalar, Options, axis > JointModelDerived
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
ConstLinearType linear() const
Return the linear part of the force vector.
Definition: force-base.hpp:42
MotionPlain motionAction(const MotionDense< M1 > &v) const
const Vector3 & lever() const
bool isEqual_impl(const MotionPrismaticTpl &other) const
JointPrismaticTpl< double, 0, 0 > JointPX
ConstLinearType linear() const
Definition: motion-base.hpp:22
bool isEqual(const ConstraintPrismaticTpl &) const
JointDataPrismaticTpl< Scalar, Options, axis > JointDataDerived
#define PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(Joint)
bool isEqual(const TransformPrismaticTpl &other) const
SpatialAxis< axis+LINEAR > Axis
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
JointDataPrismaticTpl< double, 0, 1 > JointDataPY
Axis::CartesianAxis3 CartesianAxis3
TransformPrismaticTpl(const Scalar &displacement)
ConstraintForceSetOp< ConstraintPrismaticTpl, Derived >::ReturnType operator*(const Eigen::MatrixBase< Derived > &F)
SE3GroupAction< TransformPrismaticTpl >::ReturnType se3action(const SE3Tpl< S2, O2 > &m) const
MotionPrismaticTpl __mult__(const OtherScalar &alpha) const
JointMotion __mult__(const Eigen::MatrixBase< Vector1Like > &v) const
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
#define PINOCCHIO_EIGEN_REF_TYPE(D)
Main pinocchio namespace.
Definition: timings.cpp:30
Base class for rigid transformation.
Definition: se3-base.hpp:30
MotionAlgebraAction< ConstraintPrismaticTpl, MotionDerived >::ReturnType motionAction(const MotionDense< MotionDerived > &m) const
res
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...
JointModelPrismaticTpl< double, 0, 2 > JointModelPZ
const Scalar & linearRate() const
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
Common traits structure to fully define base classes for CRTP.
Definition: src/fwd.hpp:44
JointDataPrismaticTpl< double, 0, 2 > JointDataPZ
PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE typedef Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
TransformPrismaticTpl< Scalar, Options, axis > Transformation_t
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
x
— Training
Definition: continuous.py:157
ConstAngularType angular() const
Definition: motion-base.hpp:21
static void motionAction(const MotionDense< MotionDerived > &v, const Eigen::MatrixBase< Mat > &iF, Eigen::MatrixBase< MatRet > const &jF)
Action of a motion on a set of forces, represented by a 6xN matrix whose each column represent a spat...
NV
Definition: dcrba.py:444
Type of the cast of a class C templated by Scalar and Options, to a new NewScalar type...
Definition: src/fwd.hpp:55
MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionPlanarTpl< S2, O2 > &m2)
SpatialAxis< _axis+LINEAR > Axis
Return type of the Constraint::Transpose * Force operation.
MatrixDerived plain(const Eigen::PlainObjectBase< MatrixDerived > &m)
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
ReturnTypeNotDefined ReturnType
JointPrismaticTpl< double, 0, 2 > JointPZ
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType operator*(const InertiaTpl< Scalar, Options > &Y, const ConstraintBase< ConstraintDerived > &constraint)
 .
TransposeConst(const ConstraintPrismaticTpl &ref)
#define PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(Joint)


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:03