joint-planar.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_planar_hpp__
7 #define __pinocchio_joint_planar_hpp__
8 
9 #include "pinocchio/macros.hpp"
10 #include "pinocchio/multibody/joint/joint-base.hpp"
11 #include "pinocchio/spatial/cartesian-axis.hpp"
12 #include "pinocchio/multibody/constraint.hpp"
13 #include "pinocchio/spatial/motion.hpp"
14 #include "pinocchio/spatial/inertia.hpp"
15 
16 namespace pinocchio
17 {
18 
19  template<typename Scalar, int Options = 0> struct MotionPlanarTpl;
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< MotionPlanarTpl<_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 MotionPlanarTpl
56 
57  template<typename _Scalar, int _Options>
58  struct MotionPlanarTpl
59  : MotionBase< MotionPlanarTpl<_Scalar,_Options> >
60  {
61  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
63 
65 
67 
68  MotionPlanarTpl(const Scalar & x_dot, const Scalar & y_dot,
69  const Scalar & theta_dot)
70  {
71  m_data << x_dot, y_dot, theta_dot;
72  }
73 
74  template<typename Vector3Like>
75  MotionPlanarTpl(const Eigen::MatrixBase<Vector3Like> & vj)
76  : m_data(vj)
77  {
78  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
79  }
80 
81  inline PlainReturnType plain() const
82  {
83  return PlainReturnType(typename PlainReturnType::Vector3(vx(),vy(),Scalar(0)),
84  typename PlainReturnType::Vector3(Scalar(0),Scalar(0),wz()));
85  }
86 
87  template<typename Derived>
88  void addTo(MotionDense<Derived> & other) const
89  {
90  other.linear()[0] += vx();
91  other.linear()[1] += vy();
92  other.angular()[2] += wz();
93  }
94 
95  template<typename MotionDerived>
96  void setTo(MotionDense<MotionDerived> & other) const
97  {
98  other.linear() << vx(), vy(), (Scalar)0;
99  other.angular() << (Scalar)0, (Scalar)0, wz();
100  }
101 
102  template<typename S2, int O2, typename D2>
104  {
105  v.angular().noalias() = m.rotation().col(2) * wz();
106  v.linear().noalias() = m.rotation().template leftCols<2>() * m_data.template head<2>();
107  v.linear() += m.translation().cross(v.angular());
108  }
109 
110  template<typename S2, int O2>
111  MotionPlain se3Action_impl(const SE3Tpl<S2,O2> & m) const
112  {
113  MotionPlain res;
114  se3Action_impl(m,res);
115  return res;
116  }
117 
118  template<typename S2, int O2, typename D2>
120  {
121  // Linear
122  // TODO: use v.angular() as temporary variable
123  Vector3 v3_tmp;
124  AxisZ::alphaCross(wz(),m.translation(),v3_tmp);
125  v3_tmp[0] += vx(); v3_tmp[1] += vy();
126  v.linear().noalias() = m.rotation().transpose() * v3_tmp;
127 
128  // Angular
129  v.angular().noalias() = m.rotation().transpose().col(2) * wz();
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  AxisZ::alphaCross(-wz(),v.linear(),mout.linear());
145 
146  typename M1::ConstAngularType w_in = v.angular();
147  typename M2::LinearType v_out = mout.linear();
148 
149  v_out[0] -= w_in[2] * vy();
150  v_out[1] += w_in[2] * vx();
151  v_out[2] += -w_in[1] * vx() + w_in[0] * vy() ;
152 
153  // Angular
154  AxisZ::alphaCross(-wz(),v.angular(),mout.angular());
155  }
156 
157  template<typename M1>
158  MotionPlain motionAction(const MotionDense<M1> & v) const
159  {
160  MotionPlain res;
161  motionAction(v,res);
162  return res;
163  }
164 
165  const Scalar & vx() const { return m_data[0]; }
166  Scalar & vx() { return m_data[0]; }
167 
168  const Scalar & vy() const { return m_data[1]; }
169  Scalar & vy() { return m_data[1]; }
170 
171  const Scalar & wz() const { return m_data[2]; }
172  Scalar & wz() { return m_data[2]; }
173 
174  const Vector3 & data() const { return m_data; }
175  Vector3 & data() { return m_data; }
176 
177  bool isEqual_impl(const MotionPlanarTpl & other) const
178  {
179  return m_data == other.m_data;
180  }
181 
182  protected:
183 
184  Vector3 m_data;
185 
186  }; // struct MotionPlanarTpl
187 
188  template<typename Scalar, int Options, typename MotionDerived>
189  inline typename MotionDerived::MotionPlain
191  {
192  typename MotionDerived::MotionPlain result(m2);
193  result.linear()[0] += m1.vx();
194  result.linear()[1] += m1.vy();
195 
196  result.angular()[2] += m1.wz();
197 
198  return result;
199  }
200 
201  template<typename Scalar, int Options> struct ConstraintPlanarTpl;
202 
203  template<typename _Scalar, int _Options>
204  struct traits< ConstraintPlanarTpl<_Scalar,_Options> >
205  {
206  typedef _Scalar Scalar;
207  enum { Options = _Options };
208  enum {
209  LINEAR = 0,
210  ANGULAR = 3
211  };
213  typedef Eigen::Matrix<Scalar,3,1,Options> JointForce;
214  typedef Eigen::Matrix<Scalar,6,3,Options> DenseBase;
215  typedef DenseBase MatrixReturnType;
216  typedef const DenseBase ConstMatrixReturnType;
217  }; // struct traits ConstraintPlanarTpl
218 
219  template<typename _Scalar, int _Options>
220  struct ConstraintPlanarTpl
221  : ConstraintBase< ConstraintPlanarTpl<_Scalar,_Options> >
222  {
223  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
225 
226  enum { NV = 3 };
227 
229 
230  template<typename Vector3Like>
231  JointMotion __mult__(const Eigen::MatrixBase<Vector3Like> & vj) const
232  {
233  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
234  return JointMotion(vj);
235  }
236 
237  int nv_impl() const { return NV; }
238 
240  {
242  ConstraintTranspose(const ConstraintPlanarTpl & ref) : ref(ref) {}
243 
244  template<typename Derived>
246  {
247  typedef typename ForceDense<Derived>::Vector3 Vector3;
248  return Vector3(phi.linear()[0], phi.linear()[1], phi.angular()[2]);
249  }
250 
251  /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
252  template<typename Derived>
253  friend typename Eigen::Matrix <typename Eigen::MatrixBase<Derived>::Scalar, 3, Derived::ColsAtCompileTime>
254  operator*(const ConstraintTranspose &, const Eigen::MatrixBase<Derived> & F)
255  {
257  typedef Eigen::Matrix<Scalar, 3, Derived::ColsAtCompileTime> MatrixReturnType;
258  assert(F.rows()==6);
259 
260  MatrixReturnType result(3, F.cols ());
261  result.template topRows<2>() = F.template topRows<2>();
262  result.template bottomRows<1>() = F.template bottomRows<1>();
263  return result;
264  }
265 
266  }; // struct ConstraintTranspose
267 
269 
270  DenseBase matrix_impl() const
271  {
272  DenseBase S;
273  S.template block<3,3>(Inertia::LINEAR, 0).setZero ();
274  S.template block<3,3>(Inertia::ANGULAR, 0).setZero ();
275  S(Inertia::LINEAR + 0,0) = Scalar(1);
276  S(Inertia::LINEAR + 1,1) = Scalar(1);
277  S(Inertia::ANGULAR + 2,2) = Scalar(1);
278  return S;
279  }
280 
281  template<typename S1, int O1>
282  DenseBase se3Action(const SE3Tpl<S1,O1> & m) const
283  {
284  DenseBase X_subspace;
285 
286  // LINEAR
287  X_subspace.template block <3,2>(Motion::LINEAR, 0) = m.rotation ().template leftCols <2> ();
288  X_subspace.template block <3,1>(Motion::LINEAR, 2).noalias()
289  = m.translation().cross(m.rotation ().template rightCols<1>());
290 
291  // ANGULAR
292  X_subspace.template block <3,2>(Motion::ANGULAR, 0).setZero ();
293  X_subspace.template block <3,1>(Motion::ANGULAR, 2) = m.rotation ().template rightCols<1>();
294 
295  return X_subspace;
296  }
297 
298  template<typename S1, int O1>
299  DenseBase se3ActionInverse(const SE3Tpl<S1,O1> & m) const
300  {
301  DenseBase X_subspace;
302 
303  // LINEAR
304  X_subspace.template block <3,2>(Motion::LINEAR, 0) = m.rotation().transpose().template leftCols <2>();
305  X_subspace.template block <3,1>(Motion::ANGULAR,2).noalias() = m.rotation().transpose() * m.translation(); // tmp variable
306  X_subspace.template block <3,1>(Motion::LINEAR, 2).noalias() = -X_subspace.template block <3,1>(Motion::ANGULAR,2).cross(m.rotation().transpose().template rightCols<1>());
307 
308  // ANGULAR
309  X_subspace.template block <3,2>(Motion::ANGULAR, 0).setZero();
310  X_subspace.template block <3,1>(Motion::ANGULAR, 2) = m.rotation().transpose().template rightCols<1>();
311 
312  return X_subspace;
313  }
314 
315  template<typename MotionDerived>
316  DenseBase motionAction(const MotionDense<MotionDerived> & m) const
317  {
318  const typename MotionDerived::ConstLinearType v = m.linear();
319  const typename MotionDerived::ConstAngularType w = m.angular();
320  DenseBase res(DenseBase::Zero());
321 
322  res(0,1) = -w[2]; res(0,2) = v[1];
323  res(1,0) = w[2]; res(1,2) = -v[0];
324  res(2,0) = -w[1]; res(2,1) = w[0];
325  res(3,2) = w[1];
326  res(4,2) = -w[0];
327 
328  return res;
329  }
330 
331  bool isEqual(const ConstraintPlanarTpl &) const { return true; }
332 
333  }; // struct ConstraintPlanarTpl
334 
335  template<typename MotionDerived, typename S2, int O2>
336  inline typename MotionDerived::MotionPlain
338  {
339  return m2.motionAction(m1);
340  }
341 
342  /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
343  template<typename S1, int O1, typename S2, int O2>
344  inline typename Eigen::Matrix<S1,6,3,O1>
346  {
347  typedef InertiaTpl<S1,O1> Inertia;
348  typedef typename Inertia::Scalar Scalar;
349  typedef Eigen::Matrix<S1,6,3,O1> ReturnType;
350 
351  ReturnType M;
352  const Scalar mass = Y.mass();
353  const typename Inertia::Vector3 & com = Y.lever();
354  const typename Inertia::Symmetric3 & inertia = Y.inertia();
355 
356  M.template topLeftCorner<3,3>().setZero();
357  M.template topLeftCorner<2,2>().diagonal().fill(mass);
358 
359  const typename Inertia::Vector3 mc(mass * com);
360  M.template rightCols<1>().template head<2>() << -mc(1), mc(0);
361 
362  M.template bottomLeftCorner<3,2>() << (Scalar)0, -mc(2), mc(2), (Scalar)0, -mc(1), mc(0);
363  M.template rightCols<1>().template tail<3>() = inertia.data().template tail<3>();
364  M.template rightCols<1>()[3] -= mc(0)*com(2);
365  M.template rightCols<1>()[4] -= mc(1)*com(2);
366  M.template rightCols<1>()[5] += mass*(com(0)*com(0) + com(1)*com(1));
367 
368  return M;
369  }
370 
371  /* [ABA] Y*S operator (Inertia Y,Constraint S) */
372  // inline Eigen::Matrix<double,6,1>
373 
374  template<typename M6Like, typename S2, int O2>
375  inline Eigen::Matrix<S2,6,3,O2>
376  operator*(const Eigen::MatrixBase<M6Like> & Y,
378  {
379  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like,6,6);
380  typedef Eigen::Matrix<S2,6,3,O2> Matrix63;
381 
382  Matrix63 IS;
383  IS.template leftCols<2>() = Y.template leftCols<2>();
384  IS.template rightCols<1>() = Y.template rightCols<1>();
385 
386  return IS;
387  }
388 
389  template<typename S1, int O1>
391  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
392 
393  template<typename S1, int O1, typename MotionDerived>
394  struct MotionAlgebraAction< ConstraintPlanarTpl<S1,O1>,MotionDerived >
395  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
396 
397  template<typename Scalar, int Options> struct JointPlanarTpl;
398 
399  template<typename _Scalar, int _Options>
400  struct traits< JointPlanarTpl<_Scalar,_Options> >
401  {
402  enum {
403  NQ = 4,
404  NV = 3
405  };
406  enum { Options = _Options };
407  typedef _Scalar Scalar;
414 
415  // [ABA]
416  typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
417  typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
418  typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
419 
421 
422  typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
423  typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
424  };
425 
426  template<typename Scalar, int Options>
428  template<typename Scalar, int Options>
430 
431  template<typename _Scalar, int _Options>
432  struct JointDataPlanarTpl : public JointDataBase< JointDataPlanarTpl<_Scalar,_Options> >
433  {
434  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
438 
439  Constraint_t S;
440  Transformation_t M;
441  Motion_t v;
442  Bias_t c;
443 
444  // [ABA] specific data
445  U_t U;
446  D_t Dinv;
447  UD_t UDinv;
448 
449  D_t StU;
450 
452  : M(Transformation_t::Identity())
453  , v(Motion_t::Vector3::Zero())
454  , U(U_t::Zero())
455  , Dinv(D_t::Zero())
456  , UDinv(UD_t::Zero())
457  {}
458 
459  static std::string classname() { return std::string("JointDataPlanar"); }
460  std::string shortname() const { return classname(); }
461 
462  }; // struct JointDataPlanarTpl
463 
465  template<typename _Scalar, int _Options>
466  struct JointModelPlanarTpl
467  : public JointModelBase< JointModelPlanarTpl<_Scalar,_Options> >
468  {
469  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
471  PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived);
472 
474  using Base::id;
475  using Base::idx_q;
476  using Base::idx_v;
477  using Base::setIndexes;
478 
479  JointDataDerived createData() const { return JointDataDerived(); }
480 
481  template<typename ConfigVector>
482  inline void forwardKinematics(Transformation_t & M, const Eigen::MatrixBase<ConfigVector> & q_joint) const
483  {
484  const Scalar
485  & c_theta = q_joint(2),
486  & s_theta = q_joint(3);
487 
488  M.rotation().template topLeftCorner<2,2>() << c_theta, -s_theta, s_theta, c_theta;
489  M.translation().template head<2>() = q_joint.template head<2>();
490  }
491 
492  template<typename ConfigVector>
493  void calc(JointDataDerived & data,
494  const typename Eigen::MatrixBase<ConfigVector> & qs) const
495  {
496  typedef typename ConfigVector::Scalar Scalar;
497  typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type & q = qs.template segment<NQ>(idx_q());
498 
499  const Scalar
500  &c_theta = q(2),
501  &s_theta = q(3);
502 
503  data.M.rotation().template topLeftCorner<2,2>() << c_theta, -s_theta, s_theta, c_theta;
504  data.M.translation().template head<2>() = q.template head<2>();
505 
506  }
507 
508  template<typename ConfigVector, typename TangentVector>
509  void calc(JointDataDerived & data,
510  const typename Eigen::MatrixBase<ConfigVector> & qs,
511  const typename Eigen::MatrixBase<TangentVector> & vs) const
512  {
513  calc(data,qs.derived());
514 
515  typename TangentVector::template ConstFixedSegmentReturnType<NV>::Type & q_dot = vs.template segment<NV>(idx_v ());
516 
517  data.v.vx() = q_dot(0);
518  data.v.vy() = q_dot(1);
519  data.v.wz() = q_dot(2);
520  }
521 
522  template<typename Matrix6Like>
523  void calc_aba(JointDataDerived & data,
524  const Eigen::MatrixBase<Matrix6Like> & I,
525  const bool update_I) const
526  {
527  data.U.template leftCols<2>() = I.template leftCols<2>();
528  data.U.template rightCols<1>() = I.template rightCols<1>();
529 
530  data.StU.template leftCols<2>() = data.U.template topRows<2>().transpose();
531  data.StU.template rightCols<1>() = data.U.template bottomRows<1>();
532 
533  // compute inverse
534 // data.Dinv.setIdentity();
535 // data.StU.llt().solveInPlace(data.Dinv);
537 
538  data.UDinv.noalias() = data.U * data.Dinv;
539 
540  if(update_I)
541  PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,I).noalias() -= data.UDinv * data.U.transpose();
542  }
543 
544  static std::string classname() { return std::string("JointModelPlanar");}
545  std::string shortname() const { return classname(); }
546 
548  template<typename NewScalar>
550  {
552  ReturnType res;
553  res.setIndexes(id(),idx_q(),idx_v());
554  return res;
555  }
556 
557  }; // struct JointModelPlanarTpl
558 
559 } // namespace pinocchio
560 
561 #include <boost/type_traits.hpp>
562 
563 namespace boost
564 {
565  template<typename Scalar, int Options>
566  struct has_nothrow_constructor< ::pinocchio::JointModelPlanarTpl<Scalar,Options> >
567  : public integral_constant<bool,true> {};
568 
569  template<typename Scalar, int Options>
570  struct has_nothrow_copy< ::pinocchio::JointModelPlanarTpl<Scalar,Options> >
571  : public integral_constant<bool,true> {};
572 
573  template<typename Scalar, int Options>
574  struct has_nothrow_constructor< ::pinocchio::JointDataPlanarTpl<Scalar,Options> >
575  : public integral_constant<bool,true> {};
576 
577  template<typename Scalar, int Options>
578  struct has_nothrow_copy< ::pinocchio::JointDataPlanarTpl<Scalar,Options> >
579  : public integral_constant<bool,true> {};
580 }
581 
582 #endif // ifndef __pinocchio_joint_planar_hpp__
PlainReturnType plain() const
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
InertiaTpl< double, 0 > Inertia
bool isEqual(const ConstraintPlanarTpl &) const
MotionPlain se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m) const
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...
PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR Constraint_t S
Eigen::Matrix< Scalar, NV, NV, Options > D_t
Eigen::Matrix< Scalar, 6, 1, Options > Vector6
Return type of the ation of a Motion onto an object of type D.
#define MOTION_TYPEDEF_TPL(Derived)
JointDataPlanarTpl< Scalar, Options > JointDataDerived
JointModelPlanarTpl< Scalar, Options > JointModelDerived
PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like) operator*(const Eigen
JointModelPlanarTpl< NewScalar, Options > cast() const
void calc_aba(JointDataDerived &data, const Eigen::MatrixBase< Matrix6Like > &I, const bool update_I) const
friend Eigen::Matrix< typename Eigen::MatrixBase< Derived >::Scalar, 3, Derived::ColsAtCompileTime > operator*(const ConstraintTranspose &, const Eigen::MatrixBase< Derived > &F)
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
DenseBase se3Action(const SE3Tpl< S1, O1 > &m) const
DenseBase matrix_impl() const
static void alphaCross(const Scalar &s, const Eigen::MatrixBase< V3_in > &vin, const Eigen::MatrixBase< V3_out > &vout)
void se3Action_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
ConstraintPlanarTpl< Scalar, Options > Constraint_t
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs, const typename Eigen::MatrixBase< TangentVector > &vs) const
static std::string classname()
ConstAngularType angular() const
Return the angular part of the force vector.
Definition: force-base.hpp:35
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
MotionPlain se3Action_impl(const SE3Tpl< S2, O2 > &m) const
MotionDerived::MotionPlain operator+(const MotionPlanarTpl< Scalar, Options > &m1, const MotionDense< MotionDerived > &m2)
SE3::Scalar Scalar
Definition: conversions.cpp:13
Eigen::Matrix< Scalar, 6, 6, Options > Matrix6
const Scalar & vx() 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
const Symmetric3 & inertia() const
const Vector3 & lever() const
bool isEqual_impl(const MotionPlanarTpl &other) const
JointDataDerived createData() 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
static std::string classname()
void forwardKinematics(Transformation_t &M, const Eigen::MatrixBase< ConfigVector > &q_joint) const
#define PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(Joint)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPlanarTpl< _Scalar, _Options > JointDerived
std::string shortname() const
ConstraintTranspose(const ConstraintPlanarTpl &ref)
static EIGEN_STRONG_INLINE void run(const Eigen::MatrixBase< M1 > &StYS, const Eigen::MatrixBase< M2 > &Dinv)
void calc(JointDataDerived &data, const typename Eigen::MatrixBase< ConfigVector > &qs) const
JointMotion __mult__(const Eigen::MatrixBase< Vector3Like > &vj) const
void motionAction(const MotionDense< M1 > &v, MotionDense< M2 > &mout) const
PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl)
void addTo(MotionDense< Derived > &other) const
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
MotionPlanarTpl(const Eigen::MatrixBase< Vector3Like > &vj)
#define PINOCCHIO_EIGEN_REF_TYPE(D)
MotionPlanarTpl(const Scalar &x_dot, const Scalar &y_dot, const Scalar &theta_dot)
ConstraintTranspose transpose() const
Main pinocchio namespace.
Definition: timings.cpp:30
DenseBase 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...
DenseBase se3ActionInverse(const SE3Tpl< S1, O1 > &m) const
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
JointModelBase< JointModelPlanarTpl > Base
std::string shortname() const
Common traits structure to fully define base classes for CRTP.
Definition: src/fwd.hpp:44
Symmetric3Tpl< double, 0 > Symmetric3
MotionPlanarTpl< double > MotionPlanar
#define PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(DERIVED)
const Scalar & vy() const
const Vector3 & data() const
ConstAngularType angular() const
Definition: motion-base.hpp:21
const Scalar & wz() 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...
void setTo(MotionDense< MotionDerived > &other) const
void se3ActionInverse_impl(const SE3Tpl< S2, O2 > &m, MotionDense< D2 > &v) const
NV
Definition: dcrba.py:444
CartesianAxis< 2 > AxisZ
w
Definition: ur5x4.py:45
Eigen::Matrix< Scalar, 6, NV, Options > UD_t
MotionDerived::MotionPlain operator^(const MotionDense< MotionDerived > &m1, const MotionPlanarTpl< S2, O2 > &m2)
MotionPlain motionAction(const MotionDense< M1 > &v) const
PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE typedef Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
MultiplicationOp< InertiaTpl< Scalar, Options >, ConstraintDerived >::ReturnType operator*(const InertiaTpl< Scalar, Options > &Y, const ConstraintBase< ConstraintDerived > &constraint)
 .
Eigen::Matrix< Scalar, 6, NV, Options > U_t
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef JointPlanarTpl< _Scalar, _Options > JointDerived
#define PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(Joint)


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