joint-revolute-unaligned.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_revolute_unaligned_hpp__
7 #define __pinocchio_joint_revolute_unaligned_hpp__
8 
9 #include "pinocchio/fwd.hpp"
10 #include "pinocchio/multibody/joint/joint-base.hpp"
11 #include "pinocchio/multibody/constraint.hpp"
12 #include "pinocchio/spatial/inertia.hpp"
13 #include "pinocchio/math/matrix.hpp"
14 
15 namespace pinocchio
16 {
17 
18  template<typename Scalar, int Options=0> struct MotionRevoluteUnalignedTpl;
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< MotionRevoluteUnalignedTpl<_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 MotionRevoluteUnalignedTpl
55 
56  template<typename _Scalar, int _Options>
58  : MotionBase< MotionRevoluteUnalignedTpl<_Scalar,_Options> >
59  {
60  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
62 
64 
65  template<typename Vector3Like, typename OtherScalar>
66  MotionRevoluteUnalignedTpl(const Eigen::MatrixBase<Vector3Like> & axis,
67  const OtherScalar & w)
68  : m_axis(axis)
69  , m_w(w)
70  {}
71 
72  inline PlainReturnType plain() const
73  {
74  return PlainReturnType(PlainReturnType::Vector3::Zero(),
75  m_axis*m_w);
76  }
77 
78  template<typename OtherScalar>
79  MotionRevoluteUnalignedTpl __mult__(const OtherScalar & alpha) const
80  {
81  return MotionRevoluteUnalignedTpl(m_axis,alpha*m_w);
82  }
83 
84  template<typename MotionDerived>
85  inline void addTo(MotionDense<MotionDerived> & v) const
86  {
87  v.angular() += m_axis*m_w;
88  }
89 
90  template<typename Derived>
91  void setTo(MotionDense<Derived> & other) const
92  {
93  other.linear().setZero();
94  other.angular().noalias() = m_axis*m_w;
95  }
96 
97  template<typename S2, int O2, typename D2>
98  void se3Action_impl(const SE3Tpl<S2,O2> & m, MotionDense<D2> & v) const
99  {
100  // Angular
101  v.angular().noalias() = m_w * m.rotation() * m_axis;
102 
103  // Linear
104  v.linear().noalias() = m.translation().cross(v.angular());
105  }
106 
107  template<typename S2, int O2>
108  MotionPlain se3Action_impl(const SE3Tpl<S2,O2> & m) const
109  {
110  MotionPlain res;
111  se3Action_impl(m,res);
112  return res;
113  }
114 
115  template<typename S2, int O2, typename D2>
117  {
118  // Linear
119  // TODO: use v.angular() as temporary variable
120  Vector3 v3_tmp;
121  v3_tmp.noalias() = m_axis.cross(m.translation());
122  v3_tmp *= m_w;
123  v.linear().noalias() = m.rotation().transpose() * v3_tmp;
124 
125  // Angular
126  v.angular().noalias() = m.rotation().transpose() * m_axis;
127  v.angular() *= m_w;
128  }
129 
130  template<typename S2, int O2>
131  MotionPlain se3ActionInverse_impl(const SE3Tpl<S2,O2> & m) const
132  {
133  MotionPlain res;
134  se3ActionInverse_impl(m,res);
135  return res;
136  }
137 
138  template<typename M1, typename M2>
139  void motionAction(const MotionDense<M1> & v, MotionDense<M2> & mout) const
140  {
141  // Linear
142  mout.linear().noalias() = v.linear().cross(m_axis);
143  mout.linear() *= m_w;
144 
145  // Angular
146  mout.angular().noalias() = v.angular().cross(m_axis);
147  mout.angular() *= m_w;
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  bool isEqual_impl(const MotionRevoluteUnalignedTpl & other) const
159  {
160  return m_axis == other.m_axis && m_w == other.m_w;
161  }
162 
163  const Scalar & angularRate() const { return m_w; }
164  Scalar & angularRate() { return m_w; }
165 
166  const Vector3 & axis() const { return m_axis; }
167  Vector3 & axis() { return m_axis; }
168 
169  protected:
170  Vector3 m_axis;
172 
173  }; // struct MotionRevoluteUnalignedTpl
174 
175  template<typename S1, int O1, typename MotionDerived>
176  inline typename MotionDerived::MotionPlain
178  const MotionDense<MotionDerived> & m2)
179  {
180  typename MotionDerived::MotionPlain res(m2);
181  res += m1;
182  return res;
183  }
184 
185  template<typename MotionDerived, typename S2, int O2>
186  inline typename MotionDerived::MotionPlain
189  {
190  return m2.motionAction(m1);
191  }
192 
193  template<typename Scalar, int Options> struct ConstraintRevoluteUnalignedTpl;
194 
195  template<typename _Scalar, int _Options>
196  struct traits< ConstraintRevoluteUnalignedTpl<_Scalar,_Options> >
197  {
198  typedef _Scalar Scalar;
199  enum { Options = _Options };
200  enum {
201  LINEAR = 0,
202  ANGULAR = 3
203  };
205  typedef Eigen::Matrix<Scalar,1,1,Options> JointForce;
206  typedef Eigen::Matrix<Scalar,6,1,Options> DenseBase;
207  typedef DenseBase MatrixReturnType;
208  typedef const DenseBase ConstMatrixReturnType;
209 
210  typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
211  }; // traits ConstraintRevoluteUnalignedTpl
212 
213  template<typename Scalar, int Options>
215  { typedef Eigen::Matrix<Scalar,6,1,Options> ReturnType; };
216 
217  template<typename Scalar, int Options, typename MotionDerived>
219  { typedef Eigen::Matrix<Scalar,6,1,Options> ReturnType; };
220 
221  template<typename Scalar, int Options, typename ForceDerived>
223  {
225  typedef Eigen::Matrix<typename PINOCCHIO_EIGEN_DOT_PRODUCT_RETURN_TYPE(Vector3,typename ForceDense<ForceDerived>::ConstAngularType),1,1,Options> ReturnType;
226  };
227 
228  template<typename Scalar, int Options, typename ForceSet>
230  {
233  typename Eigen::MatrixBase<const ForceSet>::template NRowsBlockXpr<3>::Type
235  };
236 
237  template<typename _Scalar, int _Options>
239  : ConstraintBase< ConstraintRevoluteUnalignedTpl<_Scalar,_Options> >
240  {
241  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
243 
244  enum { NV = 1 };
245 
247 
249 
250  template<typename Vector3Like>
251  ConstraintRevoluteUnalignedTpl(const Eigen::MatrixBase<Vector3Like> & axis)
252  : m_axis(axis)
253  {}
254 
255  template<typename Vector1Like>
256  JointMotion __mult__(const Eigen::MatrixBase<Vector1Like> & v) const
257  {
258  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector1Like,1);
259  return JointMotion(m_axis,v[0]);
260  }
261 
262  template<typename S1, int O1>
264  se3Action(const SE3Tpl<S1,O1> & m) const
265  {
267 
268  /* X*S = [ R pxR ; 0 R ] [ 0 ; a ] = [ px(Ra) ; Ra ] */
269  ReturnType res;
270  res.template segment<3>(ANGULAR).noalias() = m.rotation() * m_axis;
271  res.template segment<3>(LINEAR).noalias() = m.translation().cross(res.template segment<3>(ANGULAR));
272  return res;
273  }
274 
275  template<typename S1, int O1>
278  {
280 
281  ReturnType res;
282  res.template segment<3>(ANGULAR).noalias() = m.rotation().transpose() * m_axis;
283  res.template segment<3>(LINEAR).noalias() = -m.rotation().transpose() * m.translation().cross(m_axis);
284  return res;
285  }
286 
287  int nv_impl() const { return NV; }
288 
290  {
293 
294  template<typename ForceDerived>
297  {
299  ReturnType res;
300  res[0] = ref.axis().dot(f.angular());
301  return res;
302  }
303 
304  /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
305  template<typename ForceSet>
307  operator*(const Eigen::MatrixBase<ForceSet> & F)
308  {
309  EIGEN_STATIC_ASSERT(ForceSet::RowsAtCompileTime==6,THIS_METHOD_IS_ONLY_FOR_MATRICES_OF_A_SPECIFIC_SIZE)
310  /* Return ax.T * F[3:end,:] */
311  return ref.axis().transpose() * F.template middleRows<3>(ANGULAR);
312  }
313 
314  };
315 
316  TransposeConst transpose() const { return TransposeConst(*this); }
317 
318  /* CRBA joint operators
319  * - ForceSet::Block = ForceSet
320  * - ForceSet operator* (Inertia Y,Constraint S)
321  * - MatrixBase operator* (Constraint::Transpose S, ForceSet::Block)
322  * - SE3::act(ForceSet::Block)
323  */
324  DenseBase matrix_impl() const
325  {
326  DenseBase S;
327  S.template segment<3>(LINEAR).setZero();
328  S.template segment<3>(ANGULAR) = m_axis;
329  return S;
330  }
331 
332  template<typename MotionDerived>
335  {
336  const typename MotionDerived::ConstLinearType v = m.linear();
337  const typename MotionDerived::ConstAngularType w = m.angular();
338 
339  DenseBase res;
340  res.template segment<3>(LINEAR).noalias() = v.cross(m_axis);
341  res.template segment<3>(ANGULAR).noalias() = w.cross(m_axis);
342 
343  return res;
344  }
345 
346  const Vector3 & axis() const { return m_axis; }
347  Vector3 & axis() { return m_axis; }
348 
349  bool isEqual(const ConstraintRevoluteUnalignedTpl & other) const
350  {
351  return m_axis == other.m_axis;
352  }
353 
354  protected:
355 
356  Vector3 m_axis;
357 
358  }; // struct ConstraintRevoluteUnalignedTpl
359 
360  template<typename S1, int O1,typename S2, int O2>
362  {
363  typedef Eigen::Matrix<S2,6,1,O2> ReturnType;
364  };
365 
366  /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
367  namespace impl
368  {
369  template<typename S1, int O1, typename S2, int O2>
371  {
375  static inline ReturnType run(const Inertia & Y,
376  const Constraint & cru)
377  {
378  ReturnType res;
379 
380  /* YS = [ m -mcx ; mcx I-mcxcx ] [ 0 ; w ] = [ mcxw ; Iw -mcxcxw ] */
381  const typename Inertia::Scalar & m = Y.mass();
382  const typename Inertia::Vector3 & c = Y.lever();
383  const typename Inertia::Symmetric3 & I = Y.inertia();
384 
385  res.template segment<3>(Inertia::LINEAR) = -m*c.cross(cru.axis());
386  res.template segment<3>(Inertia::ANGULAR).noalias() = I*cru.axis();
387  res.template segment<3>(Inertia::ANGULAR) += c.cross(res.template segment<3>(Inertia::LINEAR));
388 
389  return res;
390  }
391  };
392  } // namespace impl
393 
394  template<typename M6Like, typename Scalar, int Options>
395  struct MultiplicationOp<Eigen::MatrixBase<M6Like>, ConstraintRevoluteUnalignedTpl<Scalar,Options> >
396  {
397  typedef typename SizeDepType<3>::ColsReturn<M6Like>::ConstType M6LikeCols;
399 
401  typedef typename Constraint::Vector3 Vector3;
403  };
404 
405  /* [ABA] operator* (Inertia Y,Constraint S) */
406  namespace impl
407  {
408  template<typename M6Like, typename Scalar, int Options>
409  struct LhsMultiplicationOp<Eigen::MatrixBase<M6Like>, ConstraintRevoluteUnalignedTpl<Scalar,Options> >
410  {
413 
414  static inline ReturnType run(const Eigen::MatrixBase<M6Like> & Y,
415  const Constraint & cru)
416  {
417  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like,6,6);
418  return Y.derived().template middleCols<3>(Constraint::ANGULAR) * cru.axis();
419  }
420  };
421  } // namespace impl
422 
423  template<typename Scalar, int Options> struct JointRevoluteUnalignedTpl;
424 
425  template<typename _Scalar, int _Options>
426  struct traits< JointRevoluteUnalignedTpl<_Scalar,_Options> >
427  {
428  enum {
429  NQ = 1,
430  NV = 1
431  };
432  typedef _Scalar Scalar;
433  enum { Options = _Options };
440 
441  // [ABA]
442  typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
443  typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
444  typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
445 
447 
448  typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
449  typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
450 
451  };
452 
453  template<typename Scalar, int Options>
456 
457  template<typename Scalar, int Options>
460 
461  template<typename _Scalar, int _Options>
463  : public JointDataBase< JointDataRevoluteUnalignedTpl<_Scalar,_Options> >
464  {
465  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
469 
470  Transformation_t M;
471  Constraint_t S;
472  Motion_t v;
473  Bias_t c;
474 
475  // [ABA] specific data
476  U_t U;
477  D_t Dinv;
478  UD_t UDinv;
479 
481  : M(Transformation_t::Identity())
482  , S(Constraint_t::Vector3::Zero())
483  , v(Constraint_t::Vector3::Zero(),(Scalar)0)
484  , U(U_t::Zero())
485  , Dinv(D_t::Zero())
486  , UDinv(UD_t::Zero())
487  {}
488 
489  template<typename Vector3Like>
490  JointDataRevoluteUnalignedTpl(const Eigen::MatrixBase<Vector3Like> & axis)
491  : M(Transformation_t::Identity())
492  , S(axis)
493  , v(axis,(Scalar)NAN)
494  , U(U_t::Zero())
495  , Dinv(D_t::Zero())
496  , UDinv(UD_t::Zero())
497  {}
498 
499  static std::string classname() { return std::string("JointDataRevoluteUnaligned"); }
500  std::string shortname() const { return classname(); }
501 
502  }; // struct JointDataRevoluteUnalignedTpl
503 
505  template<typename _Scalar, int _Options>
507  : public JointModelBase< JointModelRevoluteUnalignedTpl<_Scalar,_Options> >
508  {
509  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
511  PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived);
512  typedef Eigen::Matrix<Scalar,3,1,_Options> Vector3;
513 
515  using Base::id;
516  using Base::idx_q;
517  using Base::idx_v;
518  using Base::setIndexes;
519 
521 
523  const Scalar & y,
524  const Scalar & z)
525  : axis(x,y,z)
526  {
527  axis.normalize();
528  assert(isUnitary(axis) && "Rotation axis is not unitary");
529  }
530 
531  template<typename Vector3Like>
532  JointModelRevoluteUnalignedTpl(const Eigen::MatrixBase<Vector3Like> & axis)
533  : axis(axis)
534  {
535  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Vector3Like);
536  assert(isUnitary(axis) && "Rotation axis is not unitary");
537  }
538 
539  JointDataDerived createData() const { return JointDataDerived(axis); }
540 
541  using Base::isEqual;
542  bool isEqual(const JointModelRevoluteUnalignedTpl & other) const
543  {
544  return Base::isEqual(other) && axis == other.axis;
545  }
546 
547  template<typename ConfigVector>
548  void calc(JointDataDerived & data,
549  const typename Eigen::MatrixBase<ConfigVector> & qs) const
550  {
551  typedef typename ConfigVector::Scalar OtherScalar;
552  typedef Eigen::AngleAxis<Scalar> AngleAxis;
553 
554  const OtherScalar & q = qs[idx_q()];
555 
556  data.M.rotation(AngleAxis(q,axis).toRotationMatrix());
557  }
558 
559  template<typename ConfigVector, typename TangentVector>
560  void calc(JointDataDerived & data,
561  const typename Eigen::MatrixBase<ConfigVector> & qs,
562  const typename Eigen::MatrixBase<TangentVector> & vs) const
563  {
564  calc(data,qs.derived());
565 
566  data.v.angularRate() = static_cast<Scalar>(vs[idx_v()]);
567  }
568 
569  template<typename Matrix6Like>
570  void calc_aba(JointDataDerived & data, const Eigen::MatrixBase<Matrix6Like> & I, const bool update_I) const
571  {
572  data.U.noalias() = I.template middleCols<3>(Motion::ANGULAR) * axis;
573  data.Dinv[0] = (Scalar)(1)/axis.dot(data.U.template segment<3>(Motion::ANGULAR));
574  data.UDinv.noalias() = data.U * data.Dinv;
575 
576  if (update_I)
577  PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,I) -= data.UDinv * data.U.transpose();
578  }
579 
580  static std::string classname() { return std::string("JointModelRevoluteUnaligned"); }
581  std::string shortname() const { return classname(); }
582 
584  template<typename NewScalar>
586  {
588  ReturnType res(axis.template cast<NewScalar>());
589  res.setIndexes(id(),idx_q(),idx_v());
590  return res;
591  }
592 
593  // data
594 
598  Vector3 axis;
599  }; // struct JointModelRevoluteUnalignedTpl
600 
601 } //namespace pinocchio
602 
603 #include <boost/type_traits.hpp>
604 
605 namespace boost
606 {
607  template<typename Scalar, int Options>
608  struct has_nothrow_constructor< ::pinocchio::JointModelRevoluteUnalignedTpl<Scalar,Options> >
609  : public integral_constant<bool,true> {};
610 
611  template<typename Scalar, int Options>
612  struct has_nothrow_copy< ::pinocchio::JointModelRevoluteUnalignedTpl<Scalar,Options> >
613  : public integral_constant<bool,true> {};
614 
615  template<typename Scalar, int Options>
616  struct has_nothrow_constructor< ::pinocchio::JointDataRevoluteUnalignedTpl<Scalar,Options> >
617  : public integral_constant<bool,true> {};
618 
619  template<typename Scalar, int Options>
620  struct has_nothrow_copy< ::pinocchio::JointDataRevoluteUnalignedTpl<Scalar,Options> >
621  : public integral_constant<bool,true> {};
622 }
623 
624 
625 #endif // ifndef __pinocchio_joint_revolute_unaligned_hpp__
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
c
Definition: ocp.py:61
Forward declaration of the multiplication operation return type. Should be overloaded, otherwise it will procude a compilation error.
Definition: binary-op.hpp:15
int NQ
Definition: dpendulum.py:8
axis
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...
ConstraintForceOp< ConstraintRevoluteUnalignedTpl, ForceDerived >::ReturnType operator*(const ForceDense< ForceDerived > &f) const
Return type of the Constraint::Transpose * ForceSet operation.
MatrixMatrixProduct< Eigen::Transpose< const Vector3 >, typename Eigen::MatrixBase< const ForceSet >::template NRowsBlockXpr< 3 >::Type >::type ReturnType
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
void setTo(MotionDense< Derived > &other) const
void addTo(MotionDense< MotionDerived > &v) const
PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE typedef Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
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 calc_aba(JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
Eigen::Matrix< Scalar, 3, 1, _Options > Vector3
MotionAlgebraAction< ConstraintRevoluteUnalignedTpl, MotionDerived >::ReturnType motionAction(const MotionDense< MotionDerived > &m) const
ConstAngularType angular() const
Return the angular part of the force vector.
Definition: force-base.hpp:35
MotionRevoluteUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis, const OtherScalar &w)
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
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
bool isUnitary(const Eigen::MatrixBase< MatrixLike > &mat, const typename MatrixLike::RealScalar &prec=Eigen::NumTraits< typename MatrixLike::Scalar >::dummy_precision())
Check whether the input matrix is Unitary within the given precision.
MotionDerived::MotionPlain operator+(const MotionPlanarTpl< Scalar, Options > &m1, const MotionDense< MotionDerived > &m2)
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
SE3::Scalar Scalar
Definition: conversions.cpp:13
SE3GroupAction< ConstraintRevoluteUnalignedTpl >::ReturnType se3Action(const SE3Tpl< S1, O1 > &m) const
MotionPlain motionAction(const MotionDense< M1 > &v) const
#define PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
const Symmetric3 & inertia() const
const Vector3 & lever() const
JointModelBase< JointModelRevoluteUnalignedTpl > Base
ConstLinearType linear() const
Definition: motion-base.hpp:22
#define PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(Joint)
SE3GroupAction< ConstraintRevoluteUnalignedTpl >::ReturnType se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
MotionRevoluteUnalignedTpl< double > MotionRevoluteUnaligned
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
bool isEqual_impl(const MotionRevoluteUnalignedTpl &other) const
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
#define PINOCCHIO_EIGEN_REF_TYPE(D)
JointModelRevoluteUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR Transformation_t M
JointModelRevoluteUnalignedTpl(const Scalar &x, const Scalar &y, const Scalar &z)
Main pinocchio namespace.
Definition: timings.cpp:30
Eigen::Matrix< typename PINOCCHIO_EIGEN_DOT_PRODUCT_RETURN_TYPE(Vector3, typename ForceDense< ForceDerived >::ConstAngularType), 1, 1, Options > ReturnType
bool isEqual(const JointModelRevoluteUnalignedTpl &other) 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...
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointRevoluteUnalignedTpl< _Scalar, _Options > JointDerived
Common traits structure to fully define base classes for CRTP.
Definition: src/fwd.hpp:44
Symmetric3Tpl< double, 0 > Symmetric3
JointMotion __mult__(const Eigen::MatrixBase< Vector1Like > &v) const
void toRotationMatrix(const Eigen::MatrixBase< Vector3 > &axis, const Scalar &cos_value, const Scalar &sin_value, const Eigen::MatrixBase< Matrix3 > &res)
Computes a rotation matrix from a vector and values of sin and cos orientations values.
Definition: rotation.hpp:24
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
MotionRevoluteUnalignedTpl __mult__(const OtherScalar &alpha) const
x
— Training
Definition: continuous.py:157
ConstraintForceSetOp< ConstraintRevoluteUnalignedTpl, ForceSet >::ReturnType operator*(const Eigen::MatrixBase< ForceSet > &F)
Eigen::ProductReturnType< M1, M2 >::Type type
Definition: math/matrix.hpp:69
traits< ConstraintRevoluteUnalignedTpl >::Vector3 Vector3
JointModelRevoluteUnalignedTpl< Scalar, Options > JointModelDerived
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
JointModelRevoluteUnalignedTpl< NewScalar, Options > cast() const
w
Definition: ur5x4.py:45
MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionPlanarTpl< S2, O2 > &m2)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointRevoluteUnalignedTpl< _Scalar, _Options > JointDerived
Return type of the Constraint::Transpose * Force operation.
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
JointDataRevoluteUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
ReturnTypeNotDefined ReturnType
ConstraintRevoluteUnalignedTpl(const Eigen::MatrixBase< Vector3Like > &axis)
bool isEqual(const ConstraintRevoluteUnalignedTpl &other) const
#define PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(Joint)


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