pinocchio  UNKNOWN
joint-planar.hpp
1 //
2 // Copyright (c) 2015-2018 CNRS
3 // Copyright (c) 2015-2016 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 // This file is part of Pinocchio
6 // Pinocchio is free software: you can redistribute it
7 // and/or modify it under the terms of the GNU Lesser General Public
8 // License as published by the Free Software Foundation, either version
9 // 3 of the License, or (at your option) any later version.
10 //
11 // Pinocchio is distributed in the hope that it will be
12 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
13 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
14 // General Lesser Public License for more details. You should have
15 // received a copy of the GNU Lesser General Public License along with
16 // Pinocchio If not, see
17 // <http://www.gnu.org/licenses/>.
18 
19 #ifndef __se3_joint_planar_hpp__
20 #define __se3_joint_planar_hpp__
21 
22 #include "pinocchio/macros.hpp"
23 #include "pinocchio/multibody/joint/joint-base.hpp"
24 #include "pinocchio/multibody/constraint.hpp"
25 #include "pinocchio/math/sincos.hpp"
26 #include "pinocchio/spatial/motion.hpp"
27 #include "pinocchio/spatial/inertia.hpp"
28 
29 namespace se3
30 {
31 
32  template<typename Scalar, int Options = 0> struct MotionPlanarTpl;
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 EIGEN_REF_CONSTTYPE(Vector6) ToVectorConstReturnType;
43  typedef typename 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;
50  enum {
51  LINEAR = 0,
52  ANGULAR = 3
53  };
54  }; // traits MotionPlanarTpl
55 
56  template<typename _Scalar, int _Options>
57  struct MotionPlanarTpl : MotionBase< MotionPlanarTpl<_Scalar,_Options> >
58  {
59  MOTION_TYPEDEF_TPL(MotionPlanarTpl);
60 
61  MotionPlanarTpl () : m_x_dot(NAN), m_y_dot(NAN), m_theta_dot(NAN) {}
62 
63  MotionPlanarTpl (Scalar x_dot, Scalar y_dot, Scalar theta_dot)
64  : m_x_dot(x_dot), m_y_dot(y_dot), m_theta_dot(theta_dot)
65  {}
66 
67  operator MotionPlain() const
68  {
69  return MotionPlain(typename MotionPlain::Vector3(m_x_dot,m_y_dot,Scalar(0)),
70  typename MotionPlain::Vector3(Scalar(0),Scalar(0),m_theta_dot));
71  }
72 
73  template<typename Derived>
74  void addTo(MotionDense<Derived> & v) const
75  {
76  v.linear()[0] += m_x_dot;
77  v.linear()[1] += m_y_dot;
78  v.angular()[2] += m_theta_dot;
79  }
80 
81  // data
82  Scalar m_x_dot;
83  Scalar m_y_dot;
84  Scalar m_theta_dot;
85 
86  }; // struct MotionPlanarTpl
87 
88  template<typename Scalar, int Options, typename MotionDerived>
89  inline typename MotionDerived::MotionPlain
90  operator+(const MotionPlanarTpl<Scalar,Options> & m1, const MotionDense<MotionDerived> & m2)
91  {
92  typename MotionDerived::MotionPlain result(m2);
93  result.linear()[0] += m1.m_x_dot;
94  result.linear()[1] += m1.m_y_dot;
95 
96  result.angular()[2] += m1.m_theta_dot;
97 
98  return result;
99  }
100 
101  template<typename Scalar, int Options> struct ConstraintPlanarTpl;
102 
103  template<typename _Scalar, int _Options>
104  struct traits< ConstraintPlanarTpl<_Scalar,_Options> >
105  {
106  typedef _Scalar Scalar;
107  enum { Options = _Options };
108  typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
109  typedef Eigen::Matrix<Scalar,4,1,Options> Vector4;
110  typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
111  typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
112  typedef Eigen::Matrix<Scalar,4,4,Options> Matrix4;
113  typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
114  typedef Matrix3 Angular_t;
115  typedef Vector3 Linear_t;
116  typedef const Matrix3 ConstAngular_t;
117  typedef const Vector3 ConstLinear_t;
118  typedef Matrix6 ActionMatrix_t;
119  typedef Eigen::Quaternion<Scalar,Options> Quaternion_t;
120  typedef SE3Tpl<Scalar,Options> SE3;
124  enum {
125  LINEAR = 0,
126  ANGULAR = 3
127  };
128  typedef Eigen::Matrix<Scalar,3,1,Options> JointMotion;
129  typedef Eigen::Matrix<Scalar,3,1,Options> JointForce;
130  typedef Eigen::Matrix<Scalar,6,3,Options> DenseBase;
131  typedef DenseBase MatrixReturnType;
132  typedef const DenseBase ConstMatrixReturnType;
133  }; // struct traits ConstraintPlanarTpl
134 
135  template<typename _Scalar, int _Options>
136  struct ConstraintPlanarTpl : ConstraintBase< ConstraintPlanarTpl<_Scalar,_Options> >
137  {
138 
139  SPATIAL_TYPEDEF_TEMPLATE(ConstraintPlanarTpl);
140  enum { NV = 3, Options = 0 }; // to check
141  typedef typename traits<ConstraintPlanarTpl>::JointMotion JointMotion;
142  typedef typename traits<ConstraintPlanarTpl>::JointForce JointForce;
143  typedef typename traits<ConstraintPlanarTpl>::DenseBase DenseBase;
144 
145  template<typename S1, int O1>
147  operator*(const MotionPlanarTpl<S1,O1> & vj) const
148  { return vj; }
149 
150  int nv_impl() const { return NV; }
151 
153  {
154  const ConstraintPlanarTpl & ref;
155  ConstraintTranspose(const ConstraintPlanarTpl & ref) : ref(ref) {}
156 
157  template<typename Derived>
158  typename ForceDense<Derived>::Vector3 operator* (const ForceDense<Derived> & phi)
159  {
160  typedef typename ForceDense<Derived>::Vector3 Vector3;
161  return Vector3(phi.linear()[0], phi.linear()[1], phi.angular()[2]);
162  }
163 
164  /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
165  template<typename Derived>
166  friend typename Eigen::Matrix <typename Eigen::MatrixBase<Derived>::Scalar, 3, Derived::ColsAtCompileTime>
167  operator*(const ConstraintTranspose &, const Eigen::MatrixBase<Derived> & F)
168  {
169  typedef typename Eigen::MatrixBase<Derived>::Scalar Scalar;
170  typedef Eigen::Matrix<Scalar, 3, Derived::ColsAtCompileTime> MatrixReturnType;
171  assert(F.rows()==6);
172 
173  MatrixReturnType result(3, F.cols ());
174  result.template topRows<2>() = F.template topRows<2>();
175  result.template bottomRows<1>() = F.template bottomRows<1>();
176  return result;
177  }
178 
179  }; // struct ConstraintTranspose
180 
181  ConstraintTranspose transpose () const { return ConstraintTranspose(*this); }
182 
183  DenseBase matrix_impl() const
184  {
185  DenseBase S;
186  S.template block<3,3>(Inertia::LINEAR, 0).setZero ();
187  S.template block<3,3>(Inertia::ANGULAR, 0).setZero ();
188  S(Inertia::LINEAR + 0,0) = Scalar(1);
189  S(Inertia::LINEAR + 1,1) = Scalar(1);
190  S(Inertia::ANGULAR + 2,2) = Scalar(1);
191  return S;
192  }
193 
194  template<typename S1, int O1>
195  DenseBase se3Action(const SE3Tpl<S1,O1> & m) const
196  {
197  DenseBase X_subspace;
198  X_subspace.template block <3,2>(Motion::LINEAR, 0) = m.rotation ().template leftCols <2> ();
199  X_subspace.template block <3,1>(Motion::LINEAR, 2) = m.translation().cross(m.rotation ().template rightCols<1>());
200 
201  X_subspace.template block <3,2>(Motion::ANGULAR, 0).setZero ();
202  X_subspace.template block <3,1>(Motion::ANGULAR, 2) = m.rotation ().template rightCols<1>();
203 
204  return X_subspace;
205  }
206 
207  template<typename MotionDerived>
208  DenseBase motionAction(const MotionDense<MotionDerived> & m) const
209  {
210  const typename MotionDerived::ConstLinearType v = m.linear();
211  const typename MotionDerived::ConstAngularType w = m.angular();
212  DenseBase res(DenseBase::Zero());
213 
214  res(0,1) = -w[2]; res(0,2) = v[1];
215  res(1,0) = w[2]; res(1,2) = -v[0];
216  res(2,0) = -w[1]; res(2,1) = w[0];
217  res(3,2) = w[1];
218  res(4,2) = -w[0];
219 
220  return res;
221  }
222  }; // struct ConstraintPlanarTpl
223 
224  template<typename Scalar, int Options, typename MatrixDerived>
225  MotionTpl<Scalar,Options> operator* (const ConstraintPlanarTpl<Scalar,Options> &, const Eigen::MatrixBase<MatrixDerived> & v)
226  {
227  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(MatrixDerived,3);
228 
229  typedef MotionTpl<Scalar,Options> ReturnType;
230  ReturnType result(ReturnType::Zero());
231  result.linear().template head<2> () = v.template topRows<2>();
232  result.angular().template tail<1> () = v.template bottomRows<1>();
233  return result;
234  }
235 
236  template<typename MotionDerived, typename S2, int O2>
237  inline typename MotionDerived::MotionPlain operator^ (const MotionDense<MotionDerived> & m1, const MotionPlanarTpl<S2,O2> & m2)
238  {
239  typename MotionDerived::MotionPlain result;
240  typedef typename MotionDerived::Scalar Scalar;
241 
242  const typename MotionDerived::ConstLinearType & m1_t = m1.linear();
243  const typename MotionDerived::ConstAngularType & m1_w = m1.angular();
244 
245  result.angular()
246  << m1_w(1) * m2.m_theta_dot
247  , - m1_w(0) * m2.m_theta_dot
248  , Scalar(0);
249 
250  result.linear()
251  << m1_t(1) * m2.m_theta_dot - m1_w(2) * m2.m_y_dot
252  , - m1_t(0) * m2.m_theta_dot + m1_w(2) * m2.m_x_dot
253  , m1_w(0) * m2.m_y_dot - m1_w(1) * m2.m_x_dot;
254 
255  return result;
256  }
257 
258  /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
259  template<typename S1, int O1, typename S2, int O2>
260  inline typename Eigen::Matrix<S1,6,3,O1>
261  operator*(const InertiaTpl<S1,O1> & Y, const ConstraintPlanarTpl<S2,O2> &)
262  {
263  typedef InertiaTpl<S1,O1> Inertia;
264  typedef typename Inertia::Scalar Scalar;
265  typedef Eigen::Matrix<S1,6,3,O1> ReturnType;
266 
267  ReturnType M;
268  const Scalar mass = Y.mass();
269  const typename Inertia::Vector3 & com = Y.lever();
270  const typename Inertia::Symmetric3 & inertia = Y.inertia();
271 
272  M.template topLeftCorner<3,3>().setZero();
273  M.template topLeftCorner<2,2>().diagonal().fill(mass);
274 
275  const typename Inertia::Vector3 mc(mass * com);
276  M.template rightCols<1>().template head<2>() << -mc(1), mc(0);
277 
278  M.template bottomLeftCorner<3,2>() << 0., -mc(2), mc(2), 0., -mc(1), mc(0);
279  M.template rightCols<1>().template tail<3>() = inertia.data().template tail<3>();
280  M.template rightCols<1>()[3] -= mc(0)*com(2);
281  M.template rightCols<1>()[4] -= mc(1)*com(2);
282  M.template rightCols<1>()[5] += mass*(com(0)*com(0) + com(1)*com(1));
283 
284  return M;
285  }
286 
287  /* [ABA] Y*S operator (Inertia Y,Constraint S) */
288  // inline Eigen::Matrix<double,6,1>
289 
290  template<typename M6Like, typename S2, int O2>
291  inline Eigen::Matrix<S2,6,3,O2>
292  operator*(const Eigen::MatrixBase<M6Like> & Y,
294  {
295  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like,6,6);
296  typedef Eigen::Matrix<S2,6,3,O2> Matrix63;
297 
298  Matrix63 IS;
299  IS.template leftCols<2>() = Y.template leftCols<2>();
300  IS.template rightCols<1>() = Y.template rightCols<1>();
301 
302  return IS;
303  }
304 
305  namespace internal
306  {
307  template<typename S1, int O1>
308  struct SE3GroupAction< ConstraintPlanarTpl<S1,O1> >
309  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
310 
311  template<typename S1, int O1, typename MotionDerived>
312  struct MotionAlgebraAction< ConstraintPlanarTpl<S1,O1>,MotionDerived >
313  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
314  }
315 
316  template<typename Scalar, int Options> struct JointPlanarTpl;
317 
318  template<typename _Scalar, int _Options>
319  struct traits< JointPlanarTpl<_Scalar,_Options> >
320  {
321  enum {
322  NQ = 4,
323  NV = 3
324  };
325  enum { Options = _Options };
326  typedef _Scalar Scalar;
330  typedef SE3 Transformation_t;
332  typedef BiasZero Bias_t;
333  typedef Eigen::Matrix<Scalar,6,NV,Options> F_t;
334 
335  // [ABA]
336  typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
337  typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
338  typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
339 
340  typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
341  typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
342  };
343 
344  template<typename Scalar, int Options>
346  template<typename Scalar, int Options>
348 
349  template<typename _Scalar, int _Options>
350  struct JointDataPlanarTpl : public JointDataBase< JointDataPlanarTpl<_Scalar,_Options> >
351  {
353  SE3_JOINT_TYPEDEF_TEMPLATE;
354 
355  Constraint_t S;
356  Transformation_t M;
357  Motion_t v;
358  Bias_t c;
359 
360  F_t F; // TODO if not used anymore, clean F_t
361 
362  // [ABA] specific data
363  U_t U;
364  D_t Dinv;
365  UD_t UDinv;
366 
367  JointDataPlanarTpl () : M(1), U(), Dinv(), UDinv() {}
368 
369  }; // struct JointDataPlanarTpl
370 
371  template<typename _Scalar, int _Options>
372  struct JointModelPlanarTpl : public JointModelBase< JointModelPlanarTpl<_Scalar,_Options> >
373  {
375  SE3_JOINT_TYPEDEF_TEMPLATE;
376 
381 
382  JointDataDerived createData() const { return JointDataDerived(); }
383 
384  template<typename V>
385  inline void forwardKinematics(Transformation_t & M, const Eigen::MatrixBase<V> & q_joint) const
386  {
387  EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t,V);
388 
389  const double& c_theta = q_joint(2),
390  s_theta = q_joint(3);
391 
392  M.rotation().template topLeftCorner<2,2>() << c_theta, -s_theta, s_theta, c_theta;
393  M.translation().template head<2>() = q_joint.template head<2>();
394  }
395 
396  template<typename ConfigVector>
397  void calc(JointDataDerived & data,
398  const typename Eigen::MatrixBase<ConfigVector> & qs) const
399  {
400  EIGEN_STATIC_ASSERT_VECTOR_ONLY(ConfigVector);
401 
402  typedef typename ConfigVector::Scalar Scalar;
403  typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type & q = qs.template segment<NQ>(idx_q());
404 
405  const Scalar
406  &c_theta = q(2),
407  &s_theta = q(3);
408 
409  data.M.rotation().template topLeftCorner<2,2>() << c_theta, -s_theta, s_theta, c_theta;
410  data.M.translation().template head<2>() = q.template head<2>();
411 
412  }
413 
414  template<typename ConfigVector, typename TangentVector>
415  void calc(JointDataDerived & data,
416  const typename Eigen::MatrixBase<ConfigVector> & qs,
417  const typename Eigen::MatrixBase<TangentVector> & vs) const
418  {
419  EIGEN_STATIC_ASSERT_VECTOR_ONLY(TangentVector);
420  calc(data,qs.derived());
421 
422  typename TangentVector::template ConstFixedSegmentReturnType<NV>::Type & q_dot = vs.template segment<NV>(idx_v ());
423 
424  data.v.m_x_dot = q_dot(0);
425  data.v.m_y_dot = q_dot(1);
426  data.v.m_theta_dot = q_dot(2);
427  }
428 
429  template<typename S2, int O2>
430  void calc_aba(JointDataDerived & data, Eigen::Matrix<S2,6,6,O2> & I, const bool update_I) const
431  {
432  data.U.template leftCols<2>() = I.template leftCols<2>();
433  data.U.template rightCols<1>() = I.template rightCols<1>();
434  Eigen::Matrix<S2,3,3,O2> tmp;
435  tmp.template leftCols<2>() = data.U.template topRows<2>().transpose();
436  tmp.template rightCols<1>() = data.U.template bottomRows<1>();
437  data.Dinv = tmp.inverse();
438  data.UDinv.noalias() = data.U * data.Dinv;
439 
440  if (update_I)
441  I -= data.UDinv * data.U.transpose();
442  }
443 
444  Scalar finiteDifferenceIncrement() const
445  {
446  using std::sqrt;
447  return 2.*sqrt(sqrt(Eigen::NumTraits<Scalar>::epsilon()));
448  }
449 
450  static std::string classname() { return std::string("JointModelPlanar");}
451  std::string shortname() const { return classname(); }
452 
453  }; // struct JointModelPlanarTpl
454 
455 } // namespace se3
456 
457 #endif // ifndef __se3_joint_planar_hpp__
JointDataVariant createData(const JointModelVariant &jmodel)
Visit a JointModelVariant through CreateData visitor to create a JointDataVariant.
ConstAngularType angular() const
Return the angular part of the force vector.
Definition: force-base.hpp:53
void calc_aba(const JointModelVariant &jmodel, JointDataVariant &jdata, Inertia::Matrix6 &I, const bool update_I)
Visit a JointDataVariant and the corresponding JointModelVariant through JointCalcAbaVisitor to...
ConstLinearType linear() const
Return the linear part of the force vector.
Definition: force-base.hpp:60
std::string shortname(const JointModelVariant &jmodel)
Visit a JointModelVariant through JointShortnameVisitor to get the shortname of the derived joint mod...
int idx_q(const JointModelVariant &jmodel)
Visit a JointModelVariant through JointIdxQVisitor to get the index in the full model configuration s...
Eigen::VectorXd finiteDifferenceIncrement(const Model &model)
Computes the finite difference increments for each degree of freedom according to the current joint c...
void forwardKinematics(const Model &model, Data &data, const Eigen::VectorXd &q)
Update the joint placements according to the current joint configuration.
Definition: kinematics.hxx:106
int idx_v(const JointModelVariant &jmodel)
Visit a JointModelVariant through JointIdxVVisitor to get the index in the full model tangent space c...