pinocchio  UNKNOWN
joint-spherical.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_spherical_hpp__
20 #define __se3_joint_spherical_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/inertia.hpp"
27 #include "pinocchio/spatial/skew.hpp"
28 
29 namespace se3
30 {
31 
32  template<typename Scalar, int Options> struct MotionSpherical;
33 
34  template<typename _Scalar, int _Options>
35  struct traits< MotionSpherical<_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 MotionSpherical
55 
56  template<typename _Scalar, int _Options>
57  struct MotionSpherical : MotionBase< MotionSpherical<_Scalar,_Options> >
58  {
59  MOTION_TYPEDEF_TPL(MotionSpherical);
60 
61  MotionSpherical() : w (Motion::Vector3(NAN, NAN, NAN)) {}
62  MotionSpherical(const Motion::Vector3 & w) : w (w) {}
63 
64  Vector3 & operator() () { return w; }
65  const Vector3 & operator() () const { return w; }
66 
67  operator MotionPlain() const
68  {
69  return MotionPlain(MotionPlain::Vector3::Zero(), w);
70  }
71 
72  template<typename MotionDerived>
73  void addTo(MotionDense<MotionDerived> & v) const
74  {
75  v.angular() += w;
76  }
77 
78  Vector3 w;
79  }; // struct MotionSpherical
80 
81  template<typename S1, int O1, typename MotionDerived>
82  inline typename MotionDerived::MotionPlain
83  operator+(const MotionSpherical<S1,O1> & m1, const MotionDense<MotionDerived> & m2)
84  {
85  return typename MotionDerived::MotionPlain(m2.linear(),m2.angular() + m1.w);
86  }
87 
88  template<typename Scalar, int Options> struct ConstraintSphericalTpl;
89 
90  template<typename _Scalar, int _Options>
91  struct traits< ConstraintSphericalTpl<_Scalar,_Options> >
92  {
93  typedef _Scalar Scalar;
94  enum { Options = _Options };
95  typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
96  typedef Eigen::Matrix<Scalar,4,1,Options> Vector4;
97  typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
98  typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
99  typedef Eigen::Matrix<Scalar,4,4,Options> Matrix4;
100  typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
101  typedef Matrix3 Angular_t;
102  typedef Vector3 Linear_t;
103  typedef const Matrix3 ConstAngular_t;
104  typedef const Vector3 ConstLinear_t;
105  typedef Matrix6 ActionMatrix_t;
106  typedef Eigen::Quaternion<Scalar,Options> Quaternion_t;
107  typedef SE3Tpl<Scalar,Options> SE3;
111  enum {
112  LINEAR = 0,
113  ANGULAR = 3
114  };
115  typedef Eigen::Matrix<Scalar,3,1,Options> JointMotion;
116  typedef Eigen::Matrix<Scalar,3,1,Options> JointForce;
117  typedef Eigen::Matrix<Scalar,6,3,Options> DenseBase;
118  typedef DenseBase MatrixReturnType;
119  typedef const DenseBase ConstMatrixReturnType;
120  }; // struct traits struct ConstraintSphericalTpl
121 
122  template<typename _Scalar, int _Options>
123  struct ConstraintSphericalTpl : public ConstraintBase< ConstraintSphericalTpl<_Scalar,_Options> >
124  {
125  SPATIAL_TYPEDEF_TEMPLATE(ConstraintSphericalTpl);
126  enum { NV = 3 };
127  typedef typename traits<ConstraintSphericalTpl>::JointMotion JointMotion;
128  typedef typename traits<ConstraintSphericalTpl>::JointForce JointForce;
129  typedef typename traits<ConstraintSphericalTpl>::DenseBase DenseBase;
130 
131  int nv_impl() const { return NV; }
132 
134  {
135  template<typename Derived>
137  operator* (const ForceDense<Derived> & phi)
138  { return phi.angular(); }
139 
140  /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
141  template<typename MatrixDerived>
142  const typename SizeDepType<3>::RowsReturn<MatrixDerived>::ConstType
143  operator*(const Eigen::MatrixBase<MatrixDerived> & F) const
144  {
145  assert(F.rows()==6);
146  return F.derived().template middleRows<3>(Inertia::ANGULAR);
147  }
148  };
149 
150  TransposeConst transpose() const { return TransposeConst(); }
151 
152  DenseBase matrix_impl() const
153  {
154  DenseBase S;
155  S.template block <3,3>(LINEAR,0).setZero();
156  S.template block <3,3>(ANGULAR,0).setIdentity();
157  return S;
158  }
159 
160  template<typename S1, int O1>
161  Eigen::Matrix<S1,6,3,O1> se3Action(const SE3Tpl<S1,O1> & m) const
162  {
163  Eigen::Matrix<S1,6,3,O1> X_subspace;
164  cross(m.translation(),m.rotation(),X_subspace.template block<3,3>(LINEAR,0));
165  X_subspace.template block<3,3>(ANGULAR,0) = m.rotation();
166 
167  return X_subspace;
168  }
169 
170  template<typename MotionDerived>
171  DenseBase motionAction(const MotionDense<MotionDerived> & m) const
172  {
173  const typename MotionDerived::ConstLinearType v = m.linear();
174  const typename MotionDerived::ConstAngularType w = m.angular();
175 
176  DenseBase res;
177  skew(v,res.template middleRows<3>(LINEAR));
178  skew(w,res.template middleRows<3>(ANGULAR));
179 
180  return res;
181  }
182 
183  }; // struct ConstraintSphericalTpl
184 
185 
186  template<typename Scalar, int Options, typename Vector3Like>
188  operator*(const ConstraintSphericalTpl<Scalar,Options> &,
189  const Eigen::MatrixBase<Vector3Like>& v)
190  {
191  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
193  }
194 
195  template<typename MotionDerived, typename S2, int O2>
196  inline typename MotionDerived::MotionPlain
197  operator^(const MotionDense<MotionDerived> & m1,
198  const MotionSpherical<S2,O2> & m2)
199  {
200  return typename MotionDerived::MotionPlain(m1.template linear().cross(m2.w),
201  m1.template angular().cross(m2.w));
202  }
203 
204  /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
205  template<typename S1, int O1, typename S2, int O2>
206  inline Eigen::Matrix<S2,6,3,O2>
207  operator*(const InertiaTpl<S1,O1> & Y,
209  {
210  typedef InertiaTpl<S1,O1> Inertia;
211  Eigen::Matrix<S2,6,3,O2> M;
212  // M.block <3,3> (Inertia::LINEAR, 0) = - Y.mass () * skew(Y.lever ());
213  M.template block<3,3>(Inertia::LINEAR,0) = alphaSkew(-Y.mass(), Y.lever());
214  M.template block<3,3>(Inertia::ANGULAR,0) = (Y.inertia() - Symmetric3::AlphaSkewSquare(Y.mass(), Y.lever())).matrix();
215  return M;
216  }
217 
218  /* [ABA] Y*S operator*/
219  template<typename M6Like, typename S2, int O2>
220  inline typename SizeDepType<3>::ColsReturn<M6Like>::ConstType
221  operator*(const Eigen::MatrixBase<M6Like> & Y,
223  {
224  typedef ConstraintSphericalTpl<S2,O2> Constraint;
225  return Y.derived().template middleCols<3>(Constraint::ANGULAR);
226  }
227 
228  namespace internal
229  {
230  template<typename S1, int O1>
231  struct SE3GroupAction< ConstraintSphericalTpl<S1,O1> >
232  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
233 
234  template<typename S1, int O1, typename MotionDerived>
235  struct MotionAlgebraAction< ConstraintSphericalTpl<S1,O1>,MotionDerived >
236  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
237  }
238 
239  template<typename Scalar, int Options> struct JointSphericalTpl;
240 
241  template<typename _Scalar, int _Options>
242  struct traits< JointSphericalTpl<_Scalar,_Options> >
243  {
244  enum {
245  NQ = 4,
246  NV = 3
247  };
248  typedef _Scalar Scalar;
249  enum { Options = _Options };
255  typedef BiasZero Bias_t;
256  typedef Eigen::Matrix<Scalar,6,NV,Options> F_t;
257 
258  // [ABA]
259  typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
260  typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
261  typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
262 
263  typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
264  typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
265  };
266 
267  template<typename Scalar, int Options>
268  struct traits< JointDataSphericalTpl<Scalar,Options> >
270 
271  template<typename Scalar, int Options>
272  struct traits< JointModelSphericalTpl<Scalar,Options> >
274 
275  template<typename _Scalar, int _Options>
276  struct JointDataSphericalTpl : public JointDataBase< JointDataSphericalTpl<_Scalar,_Options> >
277  {
279  SE3_JOINT_TYPEDEF_TEMPLATE;
280 
281  Constraint_t S;
282  Transformation_t M;
283  Motion_t v;
284  Bias_t c;
285 
286  F_t F;
287 
288  // [ABA] specific data
289  U_t U;
290  D_t Dinv;
291  UD_t UDinv;
292 
293  JointDataSphericalTpl () : M(1), U(), Dinv(), UDinv() {}
294 
295  }; // struct JointDataSphericalTpl
296 
297  template<typename _Scalar, int _Options>
298  struct JointModelSphericalTpl : public JointModelBase< JointModelSphericalTpl<_Scalar,_Options> >
299  {
301  SE3_JOINT_TYPEDEF_TEMPLATE;
302 
307 
308  JointDataDerived createData() const { return JointDataDerived(); }
309 
310  template<typename ConfigVectorLike>
311  inline void forwardKinematics(Transformation_t & M, const Eigen::MatrixBase<ConfigVectorLike> & q_joint) const
312  {
313  EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t,ConfigVectorLike);
314  typedef typename Eigen::Quaternion<typename ConfigVectorLike::Scalar,EIGEN_PLAIN_TYPE(ConfigVectorLike)::Options> Quaternion;
315  typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
316 
317  ConstQuaternionMap quat(q_joint.derived().data());
318  //assert(std::fabs(quat.coeffs().squaredNorm()-1.) <= sqrt(Eigen::NumTraits<typename V::Scalar>::epsilon())); TODO: check validity of the rhs precision
319  assert(std::fabs(quat.coeffs().squaredNorm()-1.) <= 1e-4);
320 
321  M.rotation(quat.matrix());
322  M.translation().setZero();
323  }
324 
325  template<typename ConfigVector>
326  void calc(JointDataDerived & data,
327  const typename Eigen::MatrixBase<ConfigVector> & qs) const
328  {
329  EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t,ConfigVector);
330  typedef typename Eigen::Quaternion<typename ConfigVector::Scalar,ConfigVector::Options> Quaternion;
331  typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
332 
333  typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type & q = qs.template segment<NQ>(idx_q());
334 
335  ConstQuaternionMap quat(q.data());
336  data.M.rotation(quat.matrix());
337  }
338 
339  template<typename ConfigVector, typename TangentVector>
340  void calc(JointDataDerived & data,
341  const typename Eigen::MatrixBase<ConfigVector> & qs,
342  const typename Eigen::MatrixBase<TangentVector> & vs) const
343  {
344  EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(TangentVector_t,TangentVector);
345  calc(data,qs.derived());
346 
347  data.v() = vs.template segment<NV>(idx_v());
348  }
349 
350  template<typename S2, int O2>
351  void calc_aba(JointDataDerived & data, Eigen::Matrix<S2,6,6,O2> & I, const bool update_I) const
352  {
353  data.U = I.template block<6,3>(0,Inertia::ANGULAR);
354  data.Dinv = I.template block<3,3>(Inertia::ANGULAR,Inertia::ANGULAR).inverse();
355  data.UDinv.template middleRows<3>(Inertia::ANGULAR).setIdentity(); // can be put in data constructor
356  data.UDinv.template middleRows<3>(Inertia::LINEAR) = data.U.template block<3,3>(Inertia::LINEAR, 0) * data.Dinv;
357 
358  if (update_I)
359  {
360  I.template block<3,3>(Inertia::LINEAR,Inertia::LINEAR)
361  -= data.UDinv.template middleRows<3>(Inertia::LINEAR) * I.template block<3,3> (Inertia::ANGULAR, Inertia::LINEAR);
362  I.template block<6,3>(0,Inertia::ANGULAR).setZero();
363  I.template block<3,3>(Inertia::ANGULAR,Inertia::LINEAR).setZero();
364  }
365  }
366 
367  Scalar finiteDifferenceIncrement() const
368  {
369  using std::sqrt;
370  return 2.*sqrt(sqrt(Eigen::NumTraits<Scalar>::epsilon()));
371  }
372 
373  static std::string classname() { return std::string("JointModelSpherical"); }
374  std::string shortname() const { return classname(); }
375 
376  }; // struct JointModelSphericalTpl
377 
378 } // namespace se3
379 
380 #endif // ifndef __se3_joint_spherical_hpp__
JointDataVariant createData(const JointModelVariant &jmodel)
Visit a JointModelVariant through CreateData visitor to create a JointDataVariant.
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:116
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...
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:34
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...
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:203