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,4,4,Options> Matrix4;
41  typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
42  typedef typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector6) ToVectorConstReturnType;
43  typedef typename PINOCCHIO_EIGEN_REF_TYPE(Vector6) ToVectorReturnType;
44  typedef Vector3 AngularType;
45  typedef Vector3 LinearType;
46  typedef const Vector3 ConstAngularType;
47  typedef const Vector3 ConstLinearType;
48  typedef Matrix6 ActionMatrixType;
49  typedef Matrix4 HomogeneousMatrixType;
51  typedef MotionPlain PlainReturnType;
52  enum {
53  LINEAR = 0,
54  ANGULAR = 3
55  };
56  }; // traits MotionTranslationTpl
57 
58  template<typename _Scalar, int _Options>
60  : MotionBase< MotionTranslationTpl<_Scalar,_Options> >
61  {
62  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
63 
65 
67 
68  template<typename Vector3Like>
69  MotionTranslationTpl(const Eigen::MatrixBase<Vector3Like> & v)
70  : m_v(v)
71  {}
72 
74  : m_v(other.m_v)
75  {}
76 
77  Vector3 & operator()() { return m_v; }
78  const Vector3 & operator()() const { return m_v; }
79 
80  inline PlainReturnType plain() const
81  {
82  return PlainReturnType(m_v,PlainReturnType::Vector3::Zero());
83  }
84 
85  bool isEqual_impl(const MotionTranslationTpl & other) const
86  {
87  return m_v == other.m_v;
88  }
89 
91  {
92  m_v = other.m_v;
93  return *this;
94  }
95 
96  template<typename Derived>
97  void addTo(MotionDense<Derived> & other) const
98  {
99  other.linear() += m_v;
100  }
101 
102  template<typename Derived>
103  void setTo(MotionDense<Derived> & other) const
104  {
105  other.linear() = m_v;
106  other.angular().setZero();
107  }
108 
109  template<typename S2, int O2, typename D2>
111  {
112  v.angular().setZero();
113  v.linear().noalias() = m.rotation() * m_v; // TODO: check efficiency
114  }
115 
116  template<typename S2, int O2>
117  MotionPlain se3Action_impl(const SE3Tpl<S2,O2> & m) const
118  {
119  MotionPlain res;
120  se3Action_impl(m,res);
121  return res;
122  }
123 
124  template<typename S2, int O2, typename D2>
126  {
127  // Linear
128  v.linear().noalias() = m.rotation().transpose() * m_v;
129 
130  // Angular
131  v.angular().setZero();
132  }
133 
134  template<typename S2, int O2>
135  MotionPlain se3ActionInverse_impl(const SE3Tpl<S2,O2> & m) const
136  {
137  MotionPlain res;
138  se3ActionInverse_impl(m,res);
139  return res;
140  }
141 
142  template<typename M1, typename M2>
143  void motionAction(const MotionDense<M1> & v, MotionDense<M2> & mout) const
144  {
145  // Linear
146  mout.linear().noalias() = v.angular().cross(m_v);
147 
148  // Angular
149  mout.angular().setZero();
150  }
151 
152  template<typename M1>
153  MotionPlain motionAction(const MotionDense<M1> & v) const
154  {
155  MotionPlain res;
156  motionAction(v,res);
157  return res;
158  }
159 
160  const Vector3 & linear() const { return m_v; }
161  Vector3 & linear() { return m_v; }
162 
163  protected:
164 
165  Vector3 m_v;
166 
167  }; // struct MotionTranslationTpl
168 
169  template<typename S1, int O1, typename MotionDerived>
170  inline typename MotionDerived::MotionPlain
172  const MotionDense<MotionDerived> & m2)
173  {
174  return typename MotionDerived::MotionPlain(m2.linear() + m1.linear(), m2.angular());
175  }
176 
177  template<typename Scalar, int Options> struct TransformTranslationTpl;
178 
179  template<typename _Scalar, int _Options>
180  struct traits< TransformTranslationTpl<_Scalar,_Options> >
181  {
182  enum {
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 LinearType & LinearRef;
196  typedef const LinearType & ConstLinearRef;
199  }; // traits TransformTranslationTpl
200 
201  template<typename Scalar, int Options>
204 
205  template<typename _Scalar, int _Options>
207  : SE3Base< TransformTranslationTpl<_Scalar,_Options> >
208  {
209  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
212 
214 
215  template<typename Vector3Like>
216  TransformTranslationTpl(const Eigen::MatrixBase<Vector3Like> & translation)
217  : m_translation(translation)
218  {}
219 
220  PlainType plain() const
221  {
222  PlainType res(PlainType::Identity());
223  res.rotation().setIdentity();
224  res.translation() = translation();
225 
226  return res;
227  }
228 
229  operator PlainType() const { return plain(); }
230 
231  template<typename S2, int O2>
233  se3action(const SE3Tpl<S2,O2> & m) const
234  {
236  ReturnType res(m);
237  res.translation() += translation();
238 
239  return res;
240  }
241 
242  ConstLinearRef translation() const { return m_translation; }
243  LinearRef translation() { return m_translation; }
244 
245  AngularType rotation() const { return AngularType(3,3); }
246 
247  bool isEqual(const TransformTranslationTpl & other) const
248  {
249  return m_translation == other.m_translation;
250  }
251 
252  protected:
253 
254  LinearType m_translation;
255  };
256 
257  template<typename Scalar, int Options> struct ConstraintTranslationTpl;
258 
259  template<typename _Scalar, int _Options>
260  struct traits< ConstraintTranslationTpl<_Scalar,_Options> >
261  {
262  typedef _Scalar Scalar;
263 
264  enum { Options = _Options };
265  enum { LINEAR = 0, ANGULAR = 3 };
266 
268  typedef Eigen::Matrix<Scalar,3,1,Options> JointForce;
269  typedef Eigen::Matrix<Scalar,6,3,Options> DenseBase;
270 
271  typedef DenseBase MatrixReturnType;
272  typedef const DenseBase ConstMatrixReturnType;
273  }; // traits ConstraintTranslationTpl
274 
275  template<typename _Scalar, int _Options>
277  : ConstraintBase< ConstraintTranslationTpl<_Scalar,_Options> >
278  {
279  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
280 
282 
283  enum { NV = 3 };
284 
286 
287 // template<typename S1, int O1>
288 // Motion operator*(const MotionTranslationTpl<S1,O1> & vj) const
289 // { return Motion(vj(), Motion::Vector3::Zero()); }
290 
291  template<typename Vector3Like>
292  JointMotion __mult__(const Eigen::MatrixBase<Vector3Like> & v) const
293  {
294  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
295  return JointMotion(v);
296  }
297 
298  int nv_impl() const { return NV; }
299 
301  {
304 
305  template<typename Derived>
308  {
309  return phi.linear();
310  }
311 
312  /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
313  template<typename MatrixDerived>
314  const typename SizeDepType<3>::RowsReturn<MatrixDerived>::ConstType
315  operator*(const Eigen::MatrixBase<MatrixDerived> & F) const
316  {
317  assert(F.rows()==6);
318  return F.derived().template middleRows<3>(LINEAR);
319  }
320 
321  }; // struct ConstraintTranspose
322 
324 
325  DenseBase matrix_impl() const
326  {
327  DenseBase S;
328  S.template middleRows<3>(LINEAR).setIdentity();
329  S.template middleRows<3>(ANGULAR).setZero();
330  return S;
331  }
332 
333  template<typename S1, int O1>
334  Eigen::Matrix<S1,6,3,O1> se3Action(const SE3Tpl<S1,O1> & m) const
335  {
336  Eigen::Matrix<S1,6,3,O1> M;
337  M.template middleRows<3>(LINEAR) = m.rotation();
338  M.template middleRows<3>(ANGULAR).setZero();
339 
340  return M;
341  }
342 
343  template<typename S1, int O1>
344  Eigen::Matrix<S1,6,3,O1> se3ActionInverse(const SE3Tpl<S1,O1> & m) const
345  {
346  Eigen::Matrix<S1,6,3,O1> M;
347  M.template middleRows<3>(LINEAR) = m.rotation().transpose();
348  M.template middleRows<3>(ANGULAR).setZero();
349 
350  return M;
351  }
352 
353  template<typename MotionDerived>
354  DenseBase motionAction(const MotionDense<MotionDerived> & m) const
355  {
356  const typename MotionDerived::ConstAngularType w = m.angular();
357 
358  DenseBase res;
359  skew(w,res.template middleRows<3>(LINEAR));
360  res.template middleRows<3>(ANGULAR).setZero();
361 
362  return res;
363  }
364 
365  bool isEqual(const ConstraintTranslationTpl &) const { return true; }
366 
367  }; // struct ConstraintTranslationTpl
368 
369  template<typename MotionDerived, typename S2, int O2>
370  inline typename MotionDerived::MotionPlain
372  const MotionTranslationTpl<S2,O2> & m2)
373  {
374  return m2.motionAction(m1);
375  }
376 
377  /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
378  template<typename S1, int O1, typename S2, int O2>
379  inline Eigen::Matrix<S2,6,3,O2>
382  {
383  typedef ConstraintTranslationTpl<S2,O2> Constraint;
384  Eigen::Matrix<S2,6,3,O2> M;
385  alphaSkew(Y.mass(),Y.lever(),M.template middleRows<3>(Constraint::ANGULAR));
386  M.template middleRows<3>(Constraint::LINEAR).setZero();
387  M.template middleRows<3>(Constraint::LINEAR).diagonal().fill(Y.mass ());
388 
389  return M;
390  }
391 
392  /* [ABA] Y*S operator*/
393  template<typename M6Like, typename S2, int O2>
394  inline const typename SizeDepType<3>::ColsReturn<M6Like>::ConstType
395  operator*(const Eigen::MatrixBase<M6Like> & Y,
397  {
398  typedef ConstraintTranslationTpl<S2,O2> Constraint;
399  return Y.derived().template middleCols<3>(Constraint::LINEAR);
400  }
401 
402  template<typename S1, int O1>
404  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
405 
406  template<typename S1, int O1, typename MotionDerived>
407  struct MotionAlgebraAction< ConstraintTranslationTpl<S1,O1>,MotionDerived >
408  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
409 
410  template<typename Scalar, int Options> struct JointTranslationTpl;
411 
412  template<typename _Scalar, int _Options>
413  struct traits< JointTranslationTpl<_Scalar,_Options> >
414  {
415  enum {
416  NQ = 3,
417  NV = 3
418  };
419  typedef _Scalar Scalar;
420  enum { Options = _Options };
427 
428  // [ABA]
429  typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
430  typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
431  typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
432 
434 
435  typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
436  typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
437  }; // traits JointTranslationTpl
438 
439  template<typename Scalar, int Options>
442 
443  template<typename Scalar, int Options>
446 
447  template<typename _Scalar, int _Options>
449  : public JointDataBase< JointDataTranslationTpl<_Scalar,_Options> >
450  {
451  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
452 
456 
457  Constraint_t S;
458  Transformation_t M;
459  Motion_t v;
460  Bias_t c;
461 
462  // [ABA] specific data
463  U_t U;
464  D_t Dinv;
465  UD_t UDinv;
466 
468  : M(Transformation_t::Vector3::Zero())
469  , v(Motion_t::Vector3::Zero())
470  , U(U_t::Zero())
471  , Dinv(D_t::Zero())
472  , UDinv(UD_t::Zero())
473  {}
474 
475  static std::string classname() { return std::string("JointDataTranslation"); }
476  std::string shortname() const { return classname(); }
477  }; // struct JointDataTranslationTpl
478 
480  template<typename _Scalar, int _Options>
482  : public JointModelBase< JointModelTranslationTpl<_Scalar,_Options> >
483  {
484  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
485 
487  PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived);
488 
490  using Base::id;
491  using Base::idx_q;
492  using Base::idx_v;
493  using Base::setIndexes;
494 
495  JointDataDerived createData() const { return JointDataDerived(); }
496 
497  const std::vector<bool> hasConfigurationLimit() const
498  {
499  return {true, true, true};
500  }
501 
502  const std::vector<bool> hasConfigurationLimitInTangent() const
503  {
504  return {true, true, true};
505  }
506 
507  template<typename ConfigVector>
508  void calc(JointDataDerived & data,
509  const typename Eigen::MatrixBase<ConfigVector> & qs) const
510  {
511  data.M.translation() = this->jointConfigSelector(qs);
512  }
513 
514  template<typename ConfigVector, typename TangentVector>
515  void calc(JointDataDerived & data,
516  const typename Eigen::MatrixBase<ConfigVector> & qs,
517  const typename Eigen::MatrixBase<TangentVector> & vs) const
518  {
519  calc(data,qs.derived());
520 
521  data.v.linear() = this->jointVelocitySelector(vs);
522  }
523 
524  template<typename Matrix6Like>
525  void calc_aba(JointDataDerived & data,
526  const Eigen::MatrixBase<Matrix6Like> & I,
527  const bool update_I) const
528  {
529  data.U = I.template middleCols<3>(Inertia::LINEAR);
530 
531  // compute inverse
532 // data.Dinv.setIdentity();
533 // data.U.template middleRows<3>(Inertia::LINEAR).llt().solveInPlace(data.Dinv);
534  internal::PerformStYSInversion<Scalar>::run(data.U.template middleRows<3>(Inertia::LINEAR),data.Dinv);
535 
536  data.UDinv.template middleRows<3>(Inertia::LINEAR).setIdentity(); // can be put in data constructor
537  data.UDinv.template middleRows<3>(Inertia::ANGULAR).noalias() = data.U.template middleRows<3>(Inertia::ANGULAR) * data.Dinv;
538 
539  if (update_I)
540  {
541  Matrix6Like & I_ = PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,I);
542  I_.template block<3,3>(Inertia::ANGULAR,Inertia::ANGULAR)
543  -= data.UDinv.template middleRows<3>(Inertia::ANGULAR) * I_.template block<3,3>(Inertia::LINEAR, Inertia::ANGULAR);
544  I_.template middleCols<3>(Inertia::LINEAR).setZero();
545  I_.template block<3,3>(Inertia::LINEAR,Inertia::ANGULAR).setZero();
546  }
547  }
548 
549  static std::string classname() { return std::string("JointModelTranslation"); }
550  std::string shortname() const { return classname(); }
551 
553  template<typename NewScalar>
555  {
557  ReturnType res;
558  res.setIndexes(id(),idx_q(),idx_v());
559  return res;
560  }
561 
562  }; // struct JointModelTranslationTpl
563 
564 } // namespace pinocchio
565 
566 #include <boost/type_traits.hpp>
567 
568 namespace boost
569 {
570  template<typename Scalar, int Options>
571  struct has_nothrow_constructor< ::pinocchio::JointModelTranslationTpl<Scalar,Options> >
572  : public integral_constant<bool,true> {};
573 
574  template<typename Scalar, int Options>
575  struct has_nothrow_copy< ::pinocchio::JointModelTranslationTpl<Scalar,Options> >
576  : public integral_constant<bool,true> {};
577 
578  template<typename Scalar, int Options>
579  struct has_nothrow_constructor< ::pinocchio::JointDataTranslationTpl<Scalar,Options> >
580  : public integral_constant<bool,true> {};
581 
582  template<typename Scalar, int Options>
583  struct has_nothrow_copy< ::pinocchio::JointDataTranslationTpl<Scalar,Options> >
584  : public integral_constant<bool,true> {};
585 }
586 
587 #endif // ifndef __pinocchio_joint_translation_hpp__
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
#define PINOCCHIO_SE3_TYPEDEF_TPL(Derived)
ConstraintTranspose transpose() const
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
const SizeDepType< 3 >::RowsReturn< MatrixDerived >::ConstType operator*(const Eigen::MatrixBase< MatrixDerived > &F) const
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) 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...
const std::vector< bool > hasConfigurationLimitInTangent() const
const Vector3 & operator()() const
Return type of the ation of a Motion onto an object of type D.
#define MOTION_TYPEDEF_TPL(Derived)
JointDataTranslationTpl< Scalar, Options > JointDataDerived
bool isEqual_impl(const MotionTranslationTpl &other) const
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
const Vector3 & lever() 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
MotionPlain motionAction(const MotionDense< M1 > &v) const
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
ConstraintTranspose(const ConstraintTranslationTpl &ref)
void addTo(MotionDense< Derived > &other) const
ConstLinearType linear() const
Definition: motion-base.hpp:22
#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
ConstAngularType angular() const
Definition: motion-base.hpp:21
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
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
Eigen::Matrix< S1, 6, 3, O1 > se3Action(const SE3Tpl< S1, O1 > &m) const
traits< TransformTranslationTpl >::Vector3 Vector3
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
bool isEqual(const ConstraintTranslationTpl &) const
#define PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(Joint)
traits< PlainType >::HomogeneousMatrixType HomogeneousMatrixType
Eigen::Matrix< S1, 6, 3, O1 > se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
static EIGEN_STRONG_INLINE void run(const Eigen::MatrixBase< M1 > &StYS, const Eigen::MatrixBase< M2 > &Dinv)
JointMotion __mult__(const Eigen::MatrixBase< Vector3Like > &v) const
ConstraintTranslationTpl< Scalar, Options > Constraint_t
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
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
ConstLinearType linear() const
Return the linear part of the force vector.
Definition: force-base.hpp:42
#define PINOCCHIO_EIGEN_REF_TYPE(D)
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
void setTo(MotionDense< Derived > &other) const
Main pinocchio namespace.
Definition: timings.cpp:28
Base class for rigid transformation.
Definition: se3-base.hpp:30
JointModelTranslationTpl< NewScalar, Options > cast() const
const std::vector< bool > hasConfigurationLimit() 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...
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 setZero(std::vector< MatType, Eigen::aligned_allocator< MatType > > &Ms)
DenseBase motionAction(const MotionDense< MotionDerived > &m) const
Common traits structure to fully define base classes for CRTP.
Definition: src/fwd.hpp:44
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)
MotionTranslationTpl & operator=(const MotionTranslationTpl &other)
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
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()
MatrixDerived plain(const Eigen::PlainObjectBase< MatrixDerived > &m)
SE3GroupAction< TransformTranslationTpl >::ReturnType se3action(const SE3Tpl< S2, O2 > &m) const
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)


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