joint-spherical.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_spherical_hpp__
7 #define __pinocchio_joint_spherical_hpp__
8 
9 #include "pinocchio/macros.hpp"
10 #include "pinocchio/multibody/joint/joint-base.hpp"
11 #include "pinocchio/multibody/constraint.hpp"
12 #include "pinocchio/math/sincos.hpp"
13 #include "pinocchio/spatial/inertia.hpp"
14 #include "pinocchio/spatial/skew.hpp"
15 
16 namespace pinocchio
17 {
18 
19  template<typename Scalar, int Options = 0> struct MotionSphericalTpl;
21 
22  template<typename Scalar, int Options>
24  {
26  };
27 
28  template<typename Scalar, int Options, typename MotionDerived>
30  {
32  };
33 
34  template<typename _Scalar, int _Options>
35  struct traits< MotionSphericalTpl<_Scalar,_Options> >
36  {
37  typedef _Scalar Scalar;
38  enum { Options = _Options };
39  typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
40  typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
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 MotionTpl<Scalar,Options> MotionPlain;
50  typedef MotionPlain PlainReturnType;
51  enum {
52  LINEAR = 0,
53  ANGULAR = 3
54  };
55  }; // traits MotionSphericalTpl
56 
57  template<typename _Scalar, int _Options>
58  struct MotionSphericalTpl
59  : MotionBase< MotionSphericalTpl<_Scalar,_Options> >
60  {
61  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
62 
64 
66 
67  template<typename Vector3Like>
68  MotionSphericalTpl(const Eigen::MatrixBase<Vector3Like> & w)
69  : m_w(w)
70  {}
71 
72  Vector3 & operator() () { return m_w; }
73  const Vector3 & operator() () const { return m_w; }
74 
75  inline PlainReturnType plain() const
76  {
77  return PlainReturnType(PlainReturnType::Vector3::Zero(), m_w);
78  }
79 
80  template<typename MotionDerived>
81  void addTo(MotionDense<MotionDerived> & other) const
82  {
83  other.angular() += m_w;
84  }
85 
86  template<typename Derived>
87  void setTo(MotionDense<Derived> & other) const
88  {
89  other.linear().setZero();
90  other.angular() = m_w;
91  }
92 
94  {
95  return MotionSphericalTpl(m_w + other.m_w);
96  }
97 
98  bool isEqual_impl(const MotionSphericalTpl & other) const
99  {
100  return m_w == other.m_w;
101  }
102 
103  template<typename MotionDerived>
104  bool isEqual_impl(const MotionDense<MotionDerived> & other) const
105  {
106  return other.angular() == m_w && other.linear().isZero(0);
107  }
108 
109  template<typename S2, int O2, typename D2>
111  {
112  // Angular
113  v.angular().noalias() = m.rotation() * m_w;
114 
115  // Linear
116  v.linear().noalias() = m.translation().cross(v.angular());
117  }
118 
119  template<typename S2, int O2>
120  MotionPlain se3Action_impl(const SE3Tpl<S2,O2> & m) const
121  {
122  MotionPlain res;
123  se3Action_impl(m,res);
124  return res;
125  }
126 
127  template<typename S2, int O2, typename D2>
129  {
130  // Linear
131  // TODO: use v.angular() as temporary variable
132  Vector3 v3_tmp;
133  v3_tmp.noalias() = m_w.cross(m.translation());
134  v.linear().noalias() = m.rotation().transpose() * v3_tmp;
135 
136  // Angular
137  v.angular().noalias() = m.rotation().transpose() * m_w;
138  }
139 
140  template<typename S2, int O2>
141  MotionPlain se3ActionInverse_impl(const SE3Tpl<S2,O2> & m) const
142  {
143  MotionPlain res;
144  se3ActionInverse_impl(m,res);
145  return res;
146  }
147 
148  template<typename M1, typename M2>
149  void motionAction(const MotionDense<M1> & v, MotionDense<M2> & mout) const
150  {
151  // Linear
152  mout.linear().noalias() = v.linear().cross(m_w);
153 
154  // Angular
155  mout.angular().noalias() = v.angular().cross(m_w);
156  }
157 
158  template<typename M1>
159  MotionPlain motionAction(const MotionDense<M1> & v) const
160  {
161  MotionPlain res;
162  motionAction(v,res);
163  return res;
164  }
165 
166  const Vector3 & angular() const { return m_w; }
167  Vector3 & angular() { return m_w; }
168 
169  protected:
170 
171  Vector3 m_w;
172  }; // struct MotionSphericalTpl
173 
174  template<typename S1, int O1, typename MotionDerived>
175  inline typename MotionDerived::MotionPlain
177  {
178  return typename MotionDerived::MotionPlain(m2.linear(),m2.angular() + m1.angular());
179  }
180 
181  template<typename Scalar, int Options> struct ConstraintSphericalTpl;
182 
183  template<typename _Scalar, int _Options>
184  struct traits< ConstraintSphericalTpl<_Scalar,_Options> >
185  {
186  typedef _Scalar Scalar;
187  enum { Options = _Options };
188  enum {
189  LINEAR = 0,
190  ANGULAR = 3
191  };
193  typedef Eigen::Matrix<Scalar,3,1,Options> JointForce;
194  typedef Eigen::Matrix<Scalar,6,3,Options> DenseBase;
195  typedef DenseBase MatrixReturnType;
196  typedef const DenseBase ConstMatrixReturnType;
197  }; // struct traits struct ConstraintSphericalTpl
198 
199  template<typename _Scalar, int _Options>
201  : public ConstraintBase< ConstraintSphericalTpl<_Scalar,_Options> >
202  {
203  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
204 
206 
208 
209  enum { NV = 3 };
210 
211  int nv_impl() const { return NV; }
212 
213  template<typename Vector3Like>
214  JointMotion __mult__(const Eigen::MatrixBase<Vector3Like> & w) const
215  {
216  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
217  return JointMotion(w);
218  }
219 
221  {
222  template<typename Derived>
225  { return phi.angular(); }
226 
227  /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
228  template<typename MatrixDerived>
229  const typename SizeDepType<3>::RowsReturn<MatrixDerived>::ConstType
230  operator*(const Eigen::MatrixBase<MatrixDerived> & F) const
231  {
232  assert(F.rows()==6);
233  return F.derived().template middleRows<3>(Inertia::ANGULAR);
234  }
235  };
236 
238 
239  DenseBase matrix_impl() const
240  {
241  DenseBase S;
242  S.template block <3,3>(LINEAR,0).setZero();
243  S.template block <3,3>(ANGULAR,0).setIdentity();
244  return S;
245  }
246 
247  template<typename S1, int O1>
248  Eigen::Matrix<S1,6,3,O1> se3Action(const SE3Tpl<S1,O1> & m) const
249  {
250  Eigen::Matrix<S1,6,3,O1> X_subspace;
251  cross(m.translation(),m.rotation(),X_subspace.template middleRows<3>(LINEAR));
252  X_subspace.template middleRows<3>(ANGULAR) = m.rotation();
253 
254  return X_subspace;
255  }
256 
257  template<typename S1, int O1>
258  Eigen::Matrix<S1,6,3,O1> se3ActionInverse(const SE3Tpl<S1,O1> & m) const
259  {
260  Eigen::Matrix<S1,6,3,O1> X_subspace;
261  AxisX::cross(m.translation(),X_subspace.template middleRows<3>(ANGULAR).col(0));
262  AxisY::cross(m.translation(),X_subspace.template middleRows<3>(ANGULAR).col(1));
263  AxisZ::cross(m.translation(),X_subspace.template middleRows<3>(ANGULAR).col(2));
264 
265  X_subspace.template middleRows<3>(LINEAR).noalias()
266  = m.rotation().transpose() * X_subspace.template middleRows<3>(ANGULAR);
267  X_subspace.template middleRows<3>(ANGULAR) = m.rotation().transpose();
268 
269  return X_subspace;
270  }
271 
272  template<typename MotionDerived>
273  DenseBase motionAction(const MotionDense<MotionDerived> & m) const
274  {
275  const typename MotionDerived::ConstLinearType v = m.linear();
276  const typename MotionDerived::ConstAngularType w = m.angular();
277 
278  DenseBase res;
279  skew(v,res.template middleRows<3>(LINEAR));
280  skew(w,res.template middleRows<3>(ANGULAR));
281 
282  return res;
283  }
284 
285  bool isEqual(const ConstraintSphericalTpl &) const { return true; }
286 
287  }; // struct ConstraintSphericalTpl
288 
289  template<typename MotionDerived, typename S2, int O2>
290  inline typename MotionDerived::MotionPlain
292  const MotionSphericalTpl<S2,O2> & m2)
293  {
294  return m2.motionAction(m1);
295  }
296 
297  /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
298  template<typename S1, int O1, typename S2, int O2>
299  inline Eigen::Matrix<S2,6,3,O2>
302  {
303  typedef InertiaTpl<S1,O1> Inertia;
304  typedef typename Inertia::Symmetric3 Symmetric3;
305  Eigen::Matrix<S2,6,3,O2> M;
306  // M.block <3,3> (Inertia::LINEAR, 0) = - Y.mass () * skew(Y.lever ());
307  M.template block<3,3>(Inertia::LINEAR,0) = alphaSkew(-Y.mass(), Y.lever());
308  M.template block<3,3>(Inertia::ANGULAR,0) = (Y.inertia() - typename Symmetric3::AlphaSkewSquare(Y.mass(), Y.lever())).matrix();
309  return M;
310  }
311 
312  /* [ABA] Y*S operator*/
313  template<typename M6Like, typename S2, int O2>
314  inline typename SizeDepType<3>::ColsReturn<M6Like>::ConstType
315  operator*(const Eigen::MatrixBase<M6Like> & Y,
317  {
318  typedef ConstraintSphericalTpl<S2,O2> Constraint;
319  return Y.derived().template middleCols<3>(Constraint::ANGULAR);
320  }
321 
322  template<typename S1, int O1>
324  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
325 
326  template<typename S1, int O1, typename MotionDerived>
327  struct MotionAlgebraAction< ConstraintSphericalTpl<S1,O1>,MotionDerived >
328  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
329 
330  template<typename Scalar, int Options> struct JointSphericalTpl;
331 
332  template<typename _Scalar, int _Options>
333  struct traits< JointSphericalTpl<_Scalar,_Options> >
334  {
335  enum {
336  NQ = 4,
337  NV = 3
338  };
339  typedef _Scalar Scalar;
340  enum { Options = _Options };
347 
348  // [ABA]
349  typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
350  typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
351  typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
352 
354 
355  typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
356  typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
357  };
358 
359  template<typename Scalar, int Options>
362 
363  template<typename Scalar, int Options>
366 
367  template<typename _Scalar, int _Options>
368  struct JointDataSphericalTpl : public JointDataBase< JointDataSphericalTpl<_Scalar,_Options> >
369  {
370  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
371 
375 
376  Constraint_t S;
377  Transformation_t M;
378  Motion_t v;
379  Bias_t c;
380 
381  // [ABA] specific data
382  U_t U;
383  D_t Dinv;
384  UD_t UDinv;
385 
387  : M(Transformation_t::Identity())
388  , v(Motion_t::Vector3::Zero())
389  , U(U_t::Zero())
390  , Dinv(D_t::Zero())
391  , UDinv(UD_t::Zero())
392  {}
393 
394  static std::string classname() { return std::string("JointDataSpherical"); }
395  std::string shortname() const { return classname(); }
396 
397  }; // struct JointDataSphericalTpl
398 
400  template<typename _Scalar, int _Options>
402  : public JointModelBase< JointModelSphericalTpl<_Scalar,_Options> >
403  {
404  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
405 
407  PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived);
408 
410  using Base::id;
411  using Base::idx_q;
412  using Base::idx_v;
413  using Base::setIndexes;
414 
415  JointDataDerived createData() const { return JointDataDerived(); }
416 
417  template<typename ConfigVectorLike>
418  inline void forwardKinematics(Transformation_t & M, const Eigen::MatrixBase<ConfigVectorLike> & q_joint) const
419  {
420  typedef typename ConfigVectorLike::Scalar Scalar;
421  EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t,ConfigVectorLike);
422  typedef typename Eigen::Quaternion<Scalar,PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorLike)::Options> Quaternion;
423  typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
424 
425  ConstQuaternionMap quat(q_joint.derived().data());
426  //assert(math::fabs(quat.coeffs().squaredNorm()-1.) <= sqrt(Eigen::NumTraits<typename V::Scalar>::epsilon())); TODO: check validity of the rhs precision
427  assert(math::fabs(static_cast<Scalar>(quat.coeffs().squaredNorm()-1)) <= 1e-4);
428 
429  M.rotation(quat.matrix());
430  M.translation().setZero();
431  }
432 
433  template<typename QuaternionDerived>
434  void calc(JointDataDerived & data,
435  const typename Eigen::QuaternionBase<QuaternionDerived> & quat) const
436  {
437  data.M.rotation(quat.matrix());
438  }
439 
440  template<typename ConfigVector>
441  EIGEN_DONT_INLINE
442  void calc(JointDataDerived & data,
443  const typename Eigen::PlainObjectBase<ConfigVector> & qs) const
444  {
445  typedef typename Eigen::Quaternion<typename ConfigVector::Scalar,ConfigVector::Options> Quaternion;
446  typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
447 
448  ConstQuaternionMap quat(qs.template segment<NQ>(idx_q()).data());
449  calc(data,quat);
450  }
451 
452  template<typename ConfigVector>
453  EIGEN_DONT_INLINE
454  void calc(JointDataDerived & data,
455  const typename Eigen::MatrixBase<ConfigVector> & qs) const
456  {
457  typedef typename Eigen::Quaternion<Scalar,Options> Quaternion;
458 
459  const Quaternion quat(qs.template segment<NQ>(idx_q()));
460  calc(data,quat);
461  }
462 
463  template<typename ConfigVector, typename TangentVector>
464  void calc(JointDataDerived & data,
465  const typename Eigen::MatrixBase<ConfigVector> & qs,
466  const typename Eigen::MatrixBase<TangentVector> & vs) const
467  {
468  calc(data,qs.derived());
469 
470  data.v.angular() = vs.template segment<NV>(idx_v());
471  }
472 
473  template<typename Matrix6Like>
474  void calc_aba(JointDataDerived & data,
475  const Eigen::MatrixBase<Matrix6Like> & I,
476  const bool update_I) const
477  {
478  data.U = I.template block<6,3>(0,Inertia::ANGULAR);
479 
480  // compute inverse
481 // data.Dinv.setIdentity();
482 // data.U.template middleRows<3>(Inertia::ANGULAR).llt().solveInPlace(data.Dinv);
483  internal::PerformStYSInversion<Scalar>::run(data.U.template middleRows<3>(Inertia::ANGULAR),data.Dinv);
484 
485  data.UDinv.template middleRows<3>(Inertia::ANGULAR).setIdentity(); // can be put in data constructor
486  data.UDinv.template middleRows<3>(Inertia::LINEAR).noalias() = data.U.template block<3,3>(Inertia::LINEAR, 0) * data.Dinv;
487 
488  if (update_I)
489  {
490  Matrix6Like & I_ = PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,I);
491  I_.template block<3,3>(Inertia::LINEAR,Inertia::LINEAR)
492  -= data.UDinv.template middleRows<3>(Inertia::LINEAR) * I_.template block<3,3> (Inertia::ANGULAR, Inertia::LINEAR);
493  I_.template block<6,3>(0,Inertia::ANGULAR).setZero();
494  I_.template block<3,3>(Inertia::ANGULAR,Inertia::LINEAR).setZero();
495  }
496  }
497 
498  static std::string classname() { return std::string("JointModelSpherical"); }
499  std::string shortname() const { return classname(); }
500 
502  template<typename NewScalar>
504  {
506  ReturnType res;
507  res.setIndexes(id(),idx_q(),idx_v());
508  return res;
509  }
510 
511  }; // struct JointModelSphericalTpl
512 
513 } // namespace pinocchio
514 
515 #include <boost/type_traits.hpp>
516 
517 namespace boost
518 {
519  template<typename Scalar, int Options>
520  struct has_nothrow_constructor< ::pinocchio::JointModelSphericalTpl<Scalar,Options> >
521  : public integral_constant<bool,true> {};
522 
523  template<typename Scalar, int Options>
524  struct has_nothrow_copy< ::pinocchio::JointModelSphericalTpl<Scalar,Options> >
525  : public integral_constant<bool,true> {};
526 
527  template<typename Scalar, int Options>
528  struct has_nothrow_constructor< ::pinocchio::JointDataSphericalTpl<Scalar,Options> >
529  : public integral_constant<bool,true> {};
530 
531  template<typename Scalar, int Options>
532  struct has_nothrow_copy< ::pinocchio::JointDataSphericalTpl<Scalar,Options> >
533  : public integral_constant<bool,true> {};
534 }
535 
536 #endif // ifndef __pinocchio_joint_spherical_hpp__
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
InertiaTpl< double, 0 > Inertia
void setTo(MotionDense< Derived > &other) const
void calc(JointDataDerived &data, const typename Eigen::QuaternionBase< QuaternionDerived > &quat) const
EIGEN_DONT_INLINE void calc(JointDataDerived &data, const typename Eigen::PlainObjectBase< ConfigVector > &qs) const
int NQ
Definition: dpendulum.py:8
JointModelSphericalTpl< NewScalar, Options > cast() const
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
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...
MotionSphericalTpl(const Eigen::MatrixBase< Vector3Like > &w)
JointModelBase< JointModelSphericalTpl > Base
Return type of the ation of a Motion onto an object of type D.
#define MOTION_TYPEDEF_TPL(Derived)
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
bool isEqual(const ConstraintSphericalTpl &) const
EIGEN_DONT_INLINE void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
const Vector3 & angular() 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
JointMotion __mult__(const Eigen::MatrixBase< Vector3Like > &w) const
PlainReturnType plain() const
ConstAngularType angular() const
Return the angular part of the force vector.
Definition: force-base.hpp:35
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
void forwardKinematics(Transformation_t &M, const Eigen::MatrixBase< ConfigVectorLike > &q_joint) const
JointModelSphericalTpl< Scalar, Options > JointModelDerived
#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)
SE3::Scalar Scalar
Definition: conversions.cpp:13
MotionPlain motionAction(const MotionDense< M1 > &v) const
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
Eigen::Matrix< S1, 6, 3, O1 > se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
MotionSphericalTpl __plus__(const MotionSphericalTpl &other) const
const Symmetric3 & inertia() const
const Vector3 & lever() const
bool isEqual_impl(const MotionSphericalTpl &other) const
const SizeDepType< 3 >::RowsReturn< MatrixDerived >::ConstType operator*(const Eigen::MatrixBase< MatrixDerived > &F) const
ConstLinearType linear() const
Definition: motion-base.hpp:22
void cross(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3xIn > &Min, const Eigen::MatrixBase< Matrix3xOut > &Mout)
Applies the cross product onto the columns of M.
Definition: skew.hpp:211
#define PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(Joint)
MotionSphericalTpl< double > MotionSpherical
static EIGEN_STRONG_INLINE void run(const Eigen::MatrixBase< M1 > &StYS, const Eigen::MatrixBase< M2 > &Dinv)
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
DenseBase motionAction(const MotionDense< MotionDerived > &m) const
static void cross(const Eigen::MatrixBase< V3_in > &vin, const Eigen::MatrixBase< V3_out > &vout)
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
quat
TransposeConst transpose() const
PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE typedef Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
#define PINOCCHIO_EIGEN_REF_TYPE(D)
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR Constraint_t S
Main pinocchio namespace.
Definition: timings.cpp:30
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
JointDataDerived createData() const
Common traits structure to fully define base classes for CRTP.
Definition: src/fwd.hpp:44
Symmetric3Tpl< double, 0 > Symmetric3
bool isEqual_impl(const MotionDense< MotionDerived > &other) const
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
JointDataSphericalTpl< Scalar, Options > JointDataDerived
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)
ConstraintSphericalTpl< Scalar, Options > Constraint_t
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...
Eigen::Matrix< S1, 6, 3, O1 > se3Action(const SE3Tpl< S1, O1 > &m) const
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
NV
Definition: dcrba.py:444
w
Definition: ur5x4.py:45
MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionPlanarTpl< S2, O2 > &m2)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Derived & derived()
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointSphericalTpl< _Scalar, _Options > JointDerived
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType operator*(const InertiaTpl< Scalar, Options > &Y, const ConstraintBase< ConstraintDerived > &constraint)
 .
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointSphericalTpl< _Scalar, _Options > JointDerived
void addTo(MotionDense< MotionDerived > &other) const
#define PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(Joint)


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