joint-translation.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_translation_hpp__
7 #define __pinocchio_joint_translation_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/skew.hpp"
14 
15 namespace pinocchio
16 {
17 
18  template<typename Scalar, int Options=0> struct MotionTranslationTpl;
20 
21  template<typename Scalar, int Options>
23  {
25  };
26 
27  template<typename Scalar, int Options, typename MotionDerived>
29  {
31  };
32 
33  template<typename _Scalar, int _Options>
34  struct traits< MotionTranslationTpl<_Scalar,_Options> >
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  }; // traits MotionTranslationTpl
55 
56  template<typename _Scalar, int _Options>
58  : MotionBase< MotionTranslationTpl<_Scalar,_Options> >
59  {
60  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
61 
63 
65 
66  template<typename Vector3Like>
67  MotionTranslationTpl(const Eigen::MatrixBase<Vector3Like> & v)
68  : m_v(v)
69  {}
70 
72  : m_v(other.m_v)
73  {}
74 
75  Vector3 & operator()() { return m_v; }
76  const Vector3 & operator()() const { return m_v; }
77 
78  inline PlainReturnType plain() const
79  {
80  return PlainReturnType(m_v,PlainReturnType::Vector3::Zero());
81  }
82 
83  bool isEqual_impl(const MotionTranslationTpl & other) const
84  {
85  return m_v == other.m_v;
86  }
87 
89  {
90  m_v = other.m_v;
91  return *this;
92  }
93 
94  template<typename Derived>
95  void addTo(MotionDense<Derived> & other) const
96  {
97  other.linear() += m_v;
98  }
99 
100  template<typename Derived>
101  void setTo(MotionDense<Derived> & other) const
102  {
103  other.linear() = m_v;
104  other.angular().setZero();
105  }
106 
107  template<typename S2, int O2, typename D2>
109  {
110  v.angular().setZero();
111  v.linear().noalias() = m.rotation() * m_v; // TODO: check efficiency
112  }
113 
114  template<typename S2, int O2>
115  MotionPlain se3Action_impl(const SE3Tpl<S2,O2> & m) const
116  {
117  MotionPlain res;
118  se3Action_impl(m,res);
119  return res;
120  }
121 
122  template<typename S2, int O2, typename D2>
124  {
125  // Linear
126  v.linear().noalias() = m.rotation().transpose() * m_v;
127 
128  // Angular
129  v.angular().setZero();
130  }
131 
132  template<typename S2, int O2>
133  MotionPlain se3ActionInverse_impl(const SE3Tpl<S2,O2> & m) const
134  {
135  MotionPlain res;
136  se3ActionInverse_impl(m,res);
137  return res;
138  }
139 
140  template<typename M1, typename M2>
141  void motionAction(const MotionDense<M1> & v, MotionDense<M2> & mout) const
142  {
143  // Linear
144  mout.linear().noalias() = v.angular().cross(m_v);
145 
146  // Angular
147  mout.angular().setZero();
148  }
149 
150  template<typename M1>
151  MotionPlain motionAction(const MotionDense<M1> & v) const
152  {
153  MotionPlain res;
154  motionAction(v,res);
155  return res;
156  }
157 
158  const Vector3 & linear() const { return m_v; }
159  Vector3 & linear() { return m_v; }
160 
161  protected:
162 
163  Vector3 m_v;
164 
165  }; // struct MotionTranslationTpl
166 
167  template<typename S1, int O1, typename MotionDerived>
168  inline typename MotionDerived::MotionPlain
170  const MotionDense<MotionDerived> & m2)
171  {
172  return typename MotionDerived::MotionPlain(m2.linear() + m1.linear(), m2.angular());
173  }
174 
175  template<typename Scalar, int Options> struct TransformTranslationTpl;
176 
177  template<typename _Scalar, int _Options>
178  struct traits< TransformTranslationTpl<_Scalar,_Options> >
179  {
180  enum {
181  Options = _Options,
182  LINEAR = 0,
183  ANGULAR = 3
184  };
185  typedef _Scalar Scalar;
187  typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
188  typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
189  typedef typename Matrix3::IdentityReturnType AngularType;
190  typedef AngularType AngularRef;
191  typedef AngularType ConstAngularRef;
192  typedef Vector3 LinearType;
193  typedef LinearType & LinearRef;
194  typedef const LinearType & ConstLinearRef;
197  }; // traits TransformTranslationTpl
198 
199  template<typename Scalar, int Options>
202 
203  template<typename _Scalar, int _Options>
205  : SE3Base< TransformTranslationTpl<_Scalar,_Options> >
206  {
207  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
210 
212 
213  template<typename Vector3Like>
214  TransformTranslationTpl(const Eigen::MatrixBase<Vector3Like> & translation)
215  : m_translation(translation)
216  {}
217 
218  PlainType plain() const
219  {
220  PlainType res(PlainType::Identity());
221  res.rotation().setIdentity();
222  res.translation() = translation();
223 
224  return res;
225  }
226 
227  operator PlainType() const { return plain(); }
228 
229  template<typename S2, int O2>
231  se3action(const SE3Tpl<S2,O2> & m) const
232  {
234  ReturnType res(m);
235  res.translation() += translation();
236 
237  return res;
238  }
239 
240  ConstLinearRef translation() const { return m_translation; }
241  LinearRef translation() { return m_translation; }
242 
243  AngularType rotation() const { return AngularType(3,3); }
244 
245  bool isEqual(const TransformTranslationTpl & other) const
246  {
247  return m_translation == other.m_translation;
248  }
249 
250  protected:
251 
252  LinearType m_translation;
253  };
254 
255  template<typename Scalar, int Options> struct ConstraintTranslationTpl;
256 
257  template<typename _Scalar, int _Options>
258  struct traits< ConstraintTranslationTpl<_Scalar,_Options> >
259  {
260  typedef _Scalar Scalar;
261 
262  enum { Options = _Options };
263  enum { LINEAR = 0, ANGULAR = 3 };
264 
266  typedef Eigen::Matrix<Scalar,3,1,Options> JointForce;
267  typedef Eigen::Matrix<Scalar,6,3,Options> DenseBase;
268 
269  typedef DenseBase MatrixReturnType;
270  typedef const DenseBase ConstMatrixReturnType;
271  }; // traits ConstraintTranslationTpl
272 
273  template<typename _Scalar, int _Options>
275  : ConstraintBase< ConstraintTranslationTpl<_Scalar,_Options> >
276  {
277  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
278 
280 
281  enum { NV = 3 };
282 
284 
285 // template<typename S1, int O1>
286 // Motion operator*(const MotionTranslationTpl<S1,O1> & vj) const
287 // { return Motion(vj(), Motion::Vector3::Zero()); }
288 
289  template<typename Vector3Like>
290  JointMotion __mult__(const Eigen::MatrixBase<Vector3Like> & v) const
291  {
292  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
293  return JointMotion(v);
294  }
295 
296  int nv_impl() const { return NV; }
297 
299  {
302 
303  template<typename Derived>
306  {
307  return phi.linear();
308  }
309 
310  /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
311  template<typename MatrixDerived>
312  const typename SizeDepType<3>::RowsReturn<MatrixDerived>::ConstType
313  operator*(const Eigen::MatrixBase<MatrixDerived> & F) const
314  {
315  assert(F.rows()==6);
316  return F.derived().template middleRows<3>(LINEAR);
317  }
318 
319  }; // struct ConstraintTranspose
320 
322 
323  DenseBase matrix_impl() const
324  {
325  DenseBase S;
326  S.template middleRows<3>(LINEAR).setIdentity();
327  S.template middleRows<3>(ANGULAR).setZero();
328  return S;
329  }
330 
331  template<typename S1, int O1>
332  Eigen::Matrix<S1,6,3,O1> se3Action(const SE3Tpl<S1,O1> & m) const
333  {
334  Eigen::Matrix<S1,6,3,O1> M;
335  M.template middleRows<3>(LINEAR) = m.rotation();
336  M.template middleRows<3>(ANGULAR).setZero();
337 
338  return M;
339  }
340 
341  template<typename S1, int O1>
342  Eigen::Matrix<S1,6,3,O1> se3ActionInverse(const SE3Tpl<S1,O1> & m) const
343  {
344  Eigen::Matrix<S1,6,3,O1> M;
345  M.template middleRows<3>(LINEAR) = m.rotation().transpose();
346  M.template middleRows<3>(ANGULAR).setZero();
347 
348  return M;
349  }
350 
351  template<typename MotionDerived>
352  DenseBase motionAction(const MotionDense<MotionDerived> & m) const
353  {
354  const typename MotionDerived::ConstAngularType w = m.angular();
355 
356  DenseBase res;
357  skew(w,res.template middleRows<3>(LINEAR));
358  res.template middleRows<3>(ANGULAR).setZero();
359 
360  return res;
361  }
362 
363  bool isEqual(const ConstraintTranslationTpl &) const { return true; }
364 
365  }; // struct ConstraintTranslationTpl
366 
367  template<typename MotionDerived, typename S2, int O2>
368  inline typename MotionDerived::MotionPlain
370  const MotionTranslationTpl<S2,O2> & m2)
371  {
372  return m2.motionAction(m1);
373  }
374 
375  /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
376  template<typename S1, int O1, typename S2, int O2>
377  inline Eigen::Matrix<S2,6,3,O2>
380  {
381  typedef ConstraintTranslationTpl<S2,O2> Constraint;
382  Eigen::Matrix<S2,6,3,O2> M;
383  alphaSkew(Y.mass(),Y.lever(),M.template middleRows<3>(Constraint::ANGULAR));
384  M.template middleRows<3>(Constraint::LINEAR).setZero();
385  M.template middleRows<3>(Constraint::LINEAR).diagonal().fill(Y.mass ());
386 
387  return M;
388  }
389 
390  /* [ABA] Y*S operator*/
391  template<typename M6Like, typename S2, int O2>
392  inline const typename SizeDepType<3>::ColsReturn<M6Like>::ConstType
393  operator*(const Eigen::MatrixBase<M6Like> & Y,
395  {
396  typedef ConstraintTranslationTpl<S2,O2> Constraint;
397  return Y.derived().template middleCols<3>(Constraint::LINEAR);
398  }
399 
400  template<typename S1, int O1>
402  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
403 
404  template<typename S1, int O1, typename MotionDerived>
405  struct MotionAlgebraAction< ConstraintTranslationTpl<S1,O1>,MotionDerived >
406  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
407 
408  template<typename Scalar, int Options> struct JointTranslationTpl;
409 
410  template<typename _Scalar, int _Options>
411  struct traits< JointTranslationTpl<_Scalar,_Options> >
412  {
413  enum {
414  NQ = 3,
415  NV = 3
416  };
417  typedef _Scalar Scalar;
418  enum { Options = _Options };
425 
426  // [ABA]
427  typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
428  typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
429  typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
430 
432 
433  typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
434  typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
435  }; // traits JointTranslationTpl
436 
437  template<typename Scalar, int Options>
440 
441  template<typename Scalar, int Options>
444 
445  template<typename _Scalar, int _Options>
447  : public JointDataBase< JointDataTranslationTpl<_Scalar,_Options> >
448  {
449  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
450 
454 
455  Constraint_t S;
456  Transformation_t M;
457  Motion_t v;
458  Bias_t c;
459 
460  // [ABA] specific data
461  U_t U;
462  D_t Dinv;
463  UD_t UDinv;
464 
466  : M(Transformation_t::Vector3::Zero())
467  , v(Motion_t::Vector3::Zero())
468  , U(U_t::Zero())
469  , Dinv(D_t::Zero())
470  , UDinv(UD_t::Zero())
471  {}
472 
473  static std::string classname() { return std::string("JointDataTranslation"); }
474  std::string shortname() const { return classname(); }
475  }; // struct JointDataTranslationTpl
476 
478  template<typename _Scalar, int _Options>
480  : public JointModelBase< JointModelTranslationTpl<_Scalar,_Options> >
481  {
482  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
483 
485  PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived);
486 
488  using Base::id;
489  using Base::idx_q;
490  using Base::idx_v;
491  using Base::setIndexes;
492 
493  JointDataDerived createData() const { return JointDataDerived(); }
494 
495  template<typename ConfigVector>
496  void calc(JointDataDerived & data,
497  const typename Eigen::MatrixBase<ConfigVector> & qs) const
498  {
499  data.M.translation() = this->jointConfigSelector(qs);
500  }
501 
502  template<typename ConfigVector, typename TangentVector>
503  void calc(JointDataDerived & data,
504  const typename Eigen::MatrixBase<ConfigVector> & qs,
505  const typename Eigen::MatrixBase<TangentVector> & vs) const
506  {
507  calc(data,qs.derived());
508 
509  data.v.linear() = this->jointVelocitySelector(vs);
510  }
511 
512  template<typename Matrix6Like>
513  void calc_aba(JointDataDerived & data,
514  const Eigen::MatrixBase<Matrix6Like> & I,
515  const bool update_I) const
516  {
517  data.U = I.template middleCols<3>(Inertia::LINEAR);
518 
519  // compute inverse
520 // data.Dinv.setIdentity();
521 // data.U.template middleRows<3>(Inertia::LINEAR).llt().solveInPlace(data.Dinv);
522  internal::PerformStYSInversion<Scalar>::run(data.U.template middleRows<3>(Inertia::LINEAR),data.Dinv);
523 
524  data.UDinv.template middleRows<3>(Inertia::LINEAR).setIdentity(); // can be put in data constructor
525  data.UDinv.template middleRows<3>(Inertia::ANGULAR).noalias() = data.U.template middleRows<3>(Inertia::ANGULAR) * data.Dinv;
526 
527  if (update_I)
528  {
529  Matrix6Like & I_ = PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,I);
530  I_.template block<3,3>(Inertia::ANGULAR,Inertia::ANGULAR)
531  -= data.UDinv.template middleRows<3>(Inertia::ANGULAR) * I_.template block<3,3>(Inertia::LINEAR, Inertia::ANGULAR);
532  I_.template middleCols<3>(Inertia::LINEAR).setZero();
533  I_.template block<3,3>(Inertia::LINEAR,Inertia::ANGULAR).setZero();
534  }
535  }
536 
537  static std::string classname() { return std::string("JointModelTranslation"); }
538  std::string shortname() const { return classname(); }
539 
541  template<typename NewScalar>
543  {
545  ReturnType res;
546  res.setIndexes(id(),idx_q(),idx_v());
547  return res;
548  }
549 
550  }; // struct JointModelTranslationTpl
551 
552 } // namespace pinocchio
553 
554 #include <boost/type_traits.hpp>
555 
556 namespace boost
557 {
558  template<typename Scalar, int Options>
559  struct has_nothrow_constructor< ::pinocchio::JointModelTranslationTpl<Scalar,Options> >
560  : public integral_constant<bool,true> {};
561 
562  template<typename Scalar, int Options>
563  struct has_nothrow_copy< ::pinocchio::JointModelTranslationTpl<Scalar,Options> >
564  : public integral_constant<bool,true> {};
565 
566  template<typename Scalar, int Options>
567  struct has_nothrow_constructor< ::pinocchio::JointDataTranslationTpl<Scalar,Options> >
568  : public integral_constant<bool,true> {};
569 
570  template<typename Scalar, int Options>
571  struct has_nothrow_copy< ::pinocchio::JointDataTranslationTpl<Scalar,Options> >
572  : public integral_constant<bool,true> {};
573 }
574 
575 #endif // ifndef __pinocchio_joint_translation_hpp__
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
#define PINOCCHIO_SE3_TYPEDEF_TPL(Derived)
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
traits< TransformTranslationTpl< Scalar, Options > >::PlainType ReturnType
int NQ
Definition: dpendulum.py:8
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...
Eigen::Matrix< S1, 6, 3, O1 > se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
Return type of the ation of a Motion onto an object of type D.
#define MOTION_TYPEDEF_TPL(Derived)
JointDataTranslationTpl< Scalar, Options > JointDataDerived
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
void addTo(MotionDense< Derived > &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
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
const Vector3 & operator()() const
PlainReturnType plain() const
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
ConstraintTranspose(const ConstraintTranslationTpl &ref)
ConstraintTranspose transpose() const
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
MotionDerived::MotionPlain operator+(const MotionPlanarTpl< Scalar, Options > &m1, const MotionDense< MotionDerived > &m2)
JointModelTranslationTpl< Scalar, Options > JointModelDerived
SE3::Scalar Scalar
Definition: conversions.cpp:13
TransformTranslationTpl< Scalar, Options > Transformation_t
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR Constraint_t S
#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
PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE typedef Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointTranslationTpl< _Scalar, _Options > JointDerived
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
const Vector3 & lever() const
traits< TransformTranslationTpl >::Vector3 Vector3
ConstLinearType linear() const
Definition: motion-base.hpp:22
#define PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(Joint)
const SizeDepType< 3 >::RowsReturn< MatrixDerived >::ConstType operator*(const Eigen::MatrixBase< MatrixDerived > &F) const
traits< PlainType >::HomogeneousMatrixType HomogeneousMatrixType
static EIGEN_STRONG_INLINE void run(const Eigen::MatrixBase< M1 > &StYS, const Eigen::MatrixBase< M2 > &Dinv)
JointDataDerived createData() const
ConstraintTranslationTpl< Scalar, Options > Constraint_t
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
JointMotion __mult__(const Eigen::MatrixBase< Vector3Like > &v) const
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
MotionTranslationTpl(const Eigen::MatrixBase< Vector3Like > &v)
MotionTranslationTpl< double > MotionTranslation
JointModelTranslationTpl< NewScalar, Options > cast() const
#define PINOCCHIO_EIGEN_REF_TYPE(D)
bool isEqual(const ConstraintTranslationTpl &) const
Main pinocchio namespace.
Definition: timings.cpp:30
Base class for rigid transformation.
Definition: se3-base.hpp:30
void setTo(MotionDense< Derived > &other) const
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &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...
bool isEqual_impl(const MotionTranslationTpl &other) const
void alphaSkew(const Scalar alpha, const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector multiplied by a given scalar. i.e. the antisymmetric matrix representation of the cross product operator ( )
Definition: skew.hpp:124
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
SE3GroupAction< TransformTranslationTpl >::ReturnType se3action(const SE3Tpl< S2, O2 > &m) const
Common traits structure to fully define base classes for CRTP.
Definition: src/fwd.hpp:44
DenseBase motionAction(const MotionDense< MotionDerived > &m) const
Eigen::Matrix< S1, 6, 3, O1 > se3Action(const SE3Tpl< S1, O1 > &m) const
bool isEqual(const TransformTranslationTpl &other) const
JointModelBase< JointModelTranslationTpl > Base
void skew(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector, i.e. the antisymmetric matrix representation o...
Definition: skew.hpp:21
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
MotionTranslationTpl & operator=(const MotionTranslationTpl &other)
ConstAngularType angular() const
Definition: motion-base.hpp:21
M
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
TransformTranslationTpl(const Eigen::MatrixBase< Vector3Like > &translation)
w
Definition: ur5x4.py:45
MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionPlanarTpl< S2, O2 > &m2)
MotionTranslationTpl(const MotionTranslationTpl &other)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Derived & derived()
const Vector3 & linear() const
MatrixDerived plain(const Eigen::PlainObjectBase< MatrixDerived > &m)
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType operator*(const InertiaTpl< Scalar, Options > &Y, const ConstraintBase< ConstraintDerived > &constraint)
 .
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointTranslationTpl< _Scalar, _Options > JointDerived
#define PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(Joint)
MotionPlain motionAction(const MotionDense< M1 > &v) const


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