pinocchio  2.4.4
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
explog.hpp
1 //
2 // Copyright (c) 2015-2020 CNRS INRIA
3 // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #ifndef __pinocchio_spatial_explog_hpp__
7 #define __pinocchio_spatial_explog_hpp__
8 
9 #include "pinocchio/fwd.hpp"
10 #include "pinocchio/utils/static-if.hpp"
11 #include "pinocchio/math/fwd.hpp"
12 #include "pinocchio/math/sincos.hpp"
13 #include "pinocchio/math/taylor-expansion.hpp"
14 #include "pinocchio/spatial/motion.hpp"
15 #include "pinocchio/spatial/skew.hpp"
16 #include "pinocchio/spatial/se3.hpp"
17 
18 #include <Eigen/Geometry>
19 
20 #include "pinocchio/spatial/log.hpp"
21 
22 namespace pinocchio
23 {
32  template<typename Vector3Like>
33  typename Eigen::Matrix<typename Vector3Like::Scalar,3,3,PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like)::Options>
34  exp3(const Eigen::MatrixBase<Vector3Like> & v)
35  {
36  PINOCCHIO_ASSERT_MATRIX_SPECIFIC_SIZE (Vector3Like, v, 3, 1);
37 
38  typedef typename Vector3Like::Scalar Scalar;
39  typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like) Vector3LikePlain;
40  typedef Eigen::Matrix<Scalar,3,3,Vector3LikePlain::Options> Matrix3;
41 
42  const Scalar t2 = v.squaredNorm();
43 
44  const Scalar t = math::sqrt(t2);
45  Scalar ct,st; SINCOS(t,&st,&ct);
46 
47  const Scalar alpha_vxvx = internal::if_then_else(internal::GT, t, TaylorSeriesExpansion<Scalar>::template precision<3>(),
48  (1 - ct)/t2,
49  Scalar(1)/Scalar(2) - t2/24);
50  const Scalar alpha_vx = internal::if_then_else(internal::GT, t, TaylorSeriesExpansion<Scalar>::template precision<3>(),
51  (st)/t,
52  Scalar(1) - t2/6);
53  Matrix3 res(alpha_vxvx * v * v.transpose());
54  res.coeffRef(0,1) -= alpha_vx * v[2]; res.coeffRef(1,0) += alpha_vx * v[2];
55  res.coeffRef(0,2) += alpha_vx * v[1]; res.coeffRef(2,0) -= alpha_vx * v[1];
56  res.coeffRef(1,2) -= alpha_vx * v[0]; res.coeffRef(2,1) += alpha_vx * v[0];
57 
58  ct = internal::if_then_else(internal::GT, t, TaylorSeriesExpansion<Scalar>::template precision<3>(),
59  ct,
60  Scalar(1) - t2/2);
61  res.diagonal().array() += ct;
62 
63  return res;
64  }
65 
73  template<typename Matrix3Like>
74  Eigen::Matrix<typename Matrix3Like::Scalar,3,1,PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options>
75  log3(const Eigen::MatrixBase<Matrix3Like> & R,
76  typename Matrix3Like::Scalar & theta)
77  {
78  typedef typename Matrix3Like::Scalar Scalar;
79  typedef Eigen::Matrix<Scalar,3,1,
80  PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options> Vector3;
81  Vector3 res;
82  log3_impl<Scalar>::run(R, theta, res);
83  return res;
84  }
85 
94  template<typename Matrix3Like>
95  Eigen::Matrix<typename Matrix3Like::Scalar,3,1,PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like)::Options>
96  log3(const Eigen::MatrixBase<Matrix3Like> & R)
97  {
98  typename Matrix3Like::Scalar theta;
99  return log3(R.derived(),theta);
100  }
101 
110  template<AssignmentOperatorType op, typename Vector3Like, typename Matrix3Like>
111  void Jexp3(const Eigen::MatrixBase<Vector3Like> & r,
112  const Eigen::MatrixBase<Matrix3Like> & Jexp)
113  {
114  PINOCCHIO_ASSERT_MATRIX_SPECIFIC_SIZE (Vector3Like, r , 3, 1);
115  PINOCCHIO_ASSERT_MATRIX_SPECIFIC_SIZE (Matrix3Like, Jexp, 3, 3);
116 
117  Matrix3Like & Jout = PINOCCHIO_EIGEN_CONST_CAST(Matrix3Like,Jexp);
118  typedef typename Matrix3Like::Scalar Scalar;
119 
120  const Scalar n2 = r.squaredNorm();
121  const Scalar n = math::sqrt(n2);
122  const Scalar n_inv = Scalar(1)/n;
123  const Scalar n2_inv = n_inv * n_inv;
124  Scalar cn,sn; SINCOS(n,&sn,&cn);
125 
126  const Scalar a = internal::if_then_else(internal::LT, n, TaylorSeriesExpansion<Scalar>::template precision<3>(),
127  Scalar(1) - n2/Scalar(6),
128  sn*n_inv);
129  const Scalar b = internal::if_then_else(internal::LT, n, TaylorSeriesExpansion<Scalar>::template precision<3>(),
130  - Scalar(1)/Scalar(2) - n2/Scalar(24),
131  - (1-cn)*n2_inv);
132  const Scalar c = internal::if_then_else(internal::LT, n, TaylorSeriesExpansion<Scalar>::template precision<3>(),
133  Scalar(1)/Scalar(6) - n2/Scalar(120),
134  n2_inv * (1 - a));
135 
136  switch(op)
137  {
138  case SETTO:
139  Jout.diagonal().setConstant(a);
140  Jout(0,1) = -b*r[2]; Jout(1,0) = -Jout(0,1);
141  Jout(0,2) = b*r[1]; Jout(2,0) = -Jout(0,2);
142  Jout(1,2) = -b*r[0]; Jout(2,1) = -Jout(1,2);
143  Jout.noalias() += c * r * r.transpose();
144  break;
145  case ADDTO:
146  Jout.diagonal().array() += a;
147  Jout(0,1) += -b*r[2]; Jout(1,0) += b*r[2];
148  Jout(0,2) += b*r[1]; Jout(2,0) += -b*r[1];
149  Jout(1,2) += -b*r[0]; Jout(2,1) += b*r[0];
150  Jout.noalias() += c * r * r.transpose();
151  break;
152  case RMTO:
153  Jout.diagonal().array() -= a;
154  Jout(0,1) -= -b*r[2]; Jout(1,0) -= b*r[2];
155  Jout(0,2) -= b*r[1]; Jout(2,0) -= -b*r[1];
156  Jout(1,2) -= -b*r[0]; Jout(2,1) -= b*r[0];
157  Jout.noalias() -= c * r * r.transpose();
158  break;
159  default:
160  assert(false && "Wrong Op requesed value");
161  break;
162  }
163  }
164 
173  template<typename Vector3Like, typename Matrix3Like>
174  void Jexp3(const Eigen::MatrixBase<Vector3Like> & r,
175  const Eigen::MatrixBase<Matrix3Like> & Jexp)
176  {
177  Jexp3<SETTO>(r, Jexp);
178  }
179 
192  template<typename Scalar, typename Vector3Like, typename Matrix3Like>
193  void Jlog3(const Scalar & theta,
194  const Eigen::MatrixBase<Vector3Like> & log,
195  const Eigen::MatrixBase<Matrix3Like> & Jlog)
196  {
197  Jlog3_impl<Scalar>::run(theta, log,
198  PINOCCHIO_EIGEN_CONST_CAST(Matrix3Like,Jlog));
199  }
200 
213  template<typename Matrix3Like1, typename Matrix3Like2>
214  void Jlog3(const Eigen::MatrixBase<Matrix3Like1> & R,
215  const Eigen::MatrixBase<Matrix3Like2> & Jlog)
216  {
217  typedef typename Matrix3Like1::Scalar Scalar;
218  typedef Eigen::Matrix<Scalar,3,1,PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3Like1)::Options> Vector3;
219 
220  Scalar t;
221  Vector3 w(log3(R,t));
222  Jlog3(t,w,PINOCCHIO_EIGEN_CONST_CAST(Matrix3Like2,Jlog));
223  }
224 
234  template<typename MotionDerived>
237  {
238  typedef typename MotionDerived::Scalar Scalar;
239  enum { Options = PINOCCHIO_EIGEN_PLAIN_TYPE(typename MotionDerived::Vector3)::Options };
240 
241  typedef SE3Tpl<Scalar,Options> SE3;
242 
243  SE3 res;
244  typename SE3::LinearType & trans = res.translation();
245  typename SE3::AngularType & rot = res.rotation();
246 
247  const typename MotionDerived::ConstAngularType & w = nu.angular();
248  const typename MotionDerived::ConstLinearType & v = nu.linear();
249 
250  Scalar alpha_wxv, alpha_v, alpha_w, diagonal_term;
251  const Scalar t2 = w.squaredNorm();
252  const Scalar t = math::sqrt(t2);
253  Scalar ct,st; SINCOS(t,&st,&ct);
254  const Scalar inv_t2 = Scalar(1)/t2;
255 
256  alpha_wxv = internal::if_then_else(internal::LT, t, TaylorSeriesExpansion<Scalar>::template precision<3>(),
257  Scalar(1)/Scalar(2) - t2/24,
258  (Scalar(1) - ct)*inv_t2);
259 
260  alpha_v = internal::if_then_else(internal::LT, t, TaylorSeriesExpansion<Scalar>::template precision<3>(),
261  Scalar(1) - t2/6,
262  (st)/t);
263 
264  alpha_w = internal::if_then_else(internal::LT, t, TaylorSeriesExpansion<Scalar>::template precision<3>(),
265  (Scalar(1)/Scalar(6) - t2/120),
266  (Scalar(1) - alpha_v)*inv_t2);
267 
268  diagonal_term = internal::if_then_else(internal::LT, t, TaylorSeriesExpansion<Scalar>::template precision<3>(),
269  Scalar(1) - t2/2,
270  ct);
271 
272  // Linear
273  trans.noalias() = (alpha_v*v + (alpha_w*w.dot(v))*w + alpha_wxv*w.cross(v));
274 
275  // Rotational
276  rot.noalias() = alpha_wxv * w * w.transpose();
277  rot.coeffRef(0,1) -= alpha_v * w[2]; rot.coeffRef(1,0) += alpha_v * w[2];
278  rot.coeffRef(0,2) += alpha_v * w[1]; rot.coeffRef(2,0) -= alpha_v * w[1];
279  rot.coeffRef(1,2) -= alpha_v * w[0]; rot.coeffRef(2,1) += alpha_v * w[0];
280  rot.diagonal().array() += diagonal_term;
281 
282  return res;
283  }
284 
293  template<typename Vector6Like>
295  exp6(const Eigen::MatrixBase<Vector6Like> & v)
296  {
297  PINOCCHIO_ASSERT_MATRIX_SPECIFIC_SIZE (Vector6Like, v, 6, 1);
298 
299  MotionRef<const Vector6Like> nu(v.derived());
300  return exp6(nu);
301  }
302 
311  template<typename Scalar, int Options>
314  {
316  Motion mout;
317  log6_impl<Scalar>::run(M, mout);
318  return mout;
319  }
320 
329  template<typename Matrix4Like>
331  log6(const Eigen::MatrixBase<Matrix4Like> & M)
332  {
333  PINOCCHIO_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix4Like, M, 4, 4);
334 
335  typedef typename Matrix4Like::Scalar Scalar;
336  enum {Options = Eigen::internal::traits<Matrix4Like>::Options};
338  typedef SE3Tpl<Scalar,Options> SE3;
339 
340  SE3 m(M);
341  Motion mout;
342  log6_impl<Scalar>::run(m, mout);
343  return mout;
344  }
345 
348  template<AssignmentOperatorType op, typename MotionDerived, typename Matrix6Like>
350  const Eigen::MatrixBase<Matrix6Like> & Jexp)
351  {
352  PINOCCHIO_ASSERT_MATRIX_SPECIFIC_SIZE (Matrix6Like, Jexp, 6, 6);
353 
354  typedef typename MotionDerived::Scalar Scalar;
355  typedef typename MotionDerived::Vector3 Vector3;
356  typedef Eigen::Matrix<Scalar, 3, 3, Vector3::Options> Matrix3;
357  Matrix6Like & Jout = PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,Jexp);
358 
359  const typename MotionDerived::ConstLinearType & v = nu.linear();
360  const typename MotionDerived::ConstAngularType & w = nu.angular();
361  const Scalar t2 = w.squaredNorm();
362  const Scalar t = math::sqrt(t2);
363 
364  const Scalar tinv = Scalar(1)/t,
365  t2inv = tinv*tinv;
366  Scalar st,ct; SINCOS (t, &st, &ct);
367  const Scalar inv_2_2ct = Scalar(1)/(Scalar(2)*(Scalar(1)-ct));
368 
369 
370  const Scalar beta = internal::if_then_else(internal::LT, t, TaylorSeriesExpansion<Scalar>::template precision<3>(),
371  Scalar(1)/Scalar(12) + t2/Scalar(720),
372  t2inv - st*tinv*inv_2_2ct);
373 
374  const Scalar beta_dot_over_theta = internal::if_then_else(internal::LT, t, TaylorSeriesExpansion<Scalar>::template precision<3>(),
375  Scalar(1)/Scalar(360),
376  -Scalar(2)*t2inv*t2inv + (Scalar(1) + st*tinv) * t2inv * inv_2_2ct);
377 
378  switch(op)
379  {
380  case SETTO:
381  {
382  Jexp3<SETTO>(w, Jout.template bottomRightCorner<3,3>());
383  Jout.template topLeftCorner<3,3>() = Jout.template bottomRightCorner<3,3>();
384  const Vector3 p = Jout.template topLeftCorner<3,3>().transpose() * v;
385  const Scalar wTp (w.dot (p));
386  const Matrix3 J (alphaSkew(.5, p) +
387  (beta_dot_over_theta*wTp) *w*w.transpose()
388  - (t2*beta_dot_over_theta+Scalar(2)*beta)*p*w.transpose()
389  + wTp * beta * Matrix3::Identity()
390  + beta *w*p.transpose());
391  Jout.template topRightCorner<3,3>().noalias() =
392  - Jout.template topLeftCorner<3,3>() * J;
393  Jout.template bottomLeftCorner<3,3>().setZero();
394  break;
395  }
396  case ADDTO:
397  {
398  Matrix3 Jtmp3;
399  Jexp3<SETTO>(w, Jtmp3);
400  Jout.template bottomRightCorner<3,3>() += Jtmp3;
401  Jout.template topLeftCorner<3,3>() += Jtmp3;
402  const Vector3 p = Jtmp3.transpose() * v;
403  const Scalar wTp (w.dot (p));
404  const Matrix3 J (alphaSkew(.5, p) +
405  (beta_dot_over_theta*wTp) *w*w.transpose()
406  - (t2*beta_dot_over_theta+Scalar(2)*beta)*p*w.transpose()
407  + wTp * beta * Matrix3::Identity()
408  + beta *w*p.transpose());
409  Jout.template topRightCorner<3,3>().noalias() +=
410  - Jtmp3 * J;
411  break;
412  }
413  case RMTO:
414  {
415  Matrix3 Jtmp3;
416  Jexp3<SETTO>(w, Jtmp3);
417  Jout.template bottomRightCorner<3,3>() -= Jtmp3;
418  Jout.template topLeftCorner<3,3>() -= Jtmp3;
419  const Vector3 p = Jtmp3.transpose() * v;
420  const Scalar wTp (w.dot (p));
421  const Matrix3 J (alphaSkew(.5, p) +
422  (beta_dot_over_theta*wTp) *w*w.transpose()
423  - (t2*beta_dot_over_theta+Scalar(2)*beta)*p*w.transpose()
424  + wTp * beta * Matrix3::Identity()
425  + beta *w*p.transpose());
426  Jout.template topRightCorner<3,3>().noalias() -=
427  - Jtmp3 * J;
428  break;
429  }
430  default:
431  assert(false && "Wrong Op requesed value");
432  break;
433  }
434  }
435 
438  template<typename MotionDerived, typename Matrix6Like>
440  const Eigen::MatrixBase<Matrix6Like> & Jexp)
441  {
442  Jexp6<SETTO>(nu, Jexp);
443  }
444 
465  template<typename Scalar, int Options, typename Matrix6Like>
467  const Eigen::MatrixBase<Matrix6Like> & Jlog)
468  {
469  Jlog6_impl<Scalar>::run(M,PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,Jlog));
470  }
471 
472  template<typename Scalar, int Options>
473  template<typename OtherScalar>
475  const SE3Tpl & B,
476  const OtherScalar & alpha)
477  {
478  typedef SE3Tpl<Scalar,Options> ReturnType;
480 
481  Motion dv = log6(A.actInv(B));
482  ReturnType res = A * exp6(alpha*dv);
483  return res;
484  }
485 
486 } // namespace pinocchio
487 
488 #include "pinocchio/spatial/explog-quaternion.hpp"
489 #include "pinocchio/spatial/log.hxx"
490 
491 #endif //#ifndef __pinocchio_spatial_explog_hpp__
void Jexp3(const Eigen::MatrixBase< Vector3Like > &r, const Eigen::MatrixBase< Matrix3Like > &Jexp)
Derivative of .
Definition: explog.hpp:111
Eigen::Matrix< typename Matrix3Like::Scalar, 3, 1, Matrix3Like ::Options > log3(const Eigen::MatrixBase< Matrix3Like > &R, typename Matrix3Like::Scalar &theta)
Same as log3.
Definition: explog.hpp:75
void Jlog3(const Scalar &theta, const Eigen::MatrixBase< Vector3Like > &log, const Eigen::MatrixBase< Matrix3Like > &Jlog)
Derivative of log3.
Definition: explog.hpp:193
Eigen::Matrix< typename Vector3Like::Scalar, 3, 3, Vector3Like ::Options > exp3(const Eigen::MatrixBase< Vector3Like > &v)
Exp: so3 -> SO3.
Definition: explog.hpp:34
void Jlog6(const SE3Tpl< Scalar, Options > &M, const Eigen::MatrixBase< Matrix6Like > &Jlog)
Derivative of log6 where and .
Definition: explog.hpp:466
MotionTpl< Scalar, Options > log6(const SE3Tpl< Scalar, Options > &M)
Log: SE3 -> se3.
Definition: explog.hpp:313
void Jexp6(const MotionDense< MotionDerived > &nu, const Eigen::MatrixBase< Matrix6Like > &Jexp)
Derivative of exp6 Computed as the inverse of Jlog6.
Definition: explog.hpp:349
void SINCOS(const S1 &a, S2 *sa, S3 *ca)
Computes sin/cos values of a given input scalar.
Definition: sincos.hpp:26
Main pinocchio namespace.
Definition: treeview.dox:24
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
SE3Tpl< typename MotionDerived::Scalar, typename MotionDerived::Vector3 ::Options > exp6(const MotionDense< MotionDerived > &nu)
Exp: se3 -> SE3.
Definition: explog.hpp:236
SE3GroupAction< D >::ReturnType actInv(const D &d) const
by = aXb.actInv(ay)
Definition: se3-base.hpp:97
static SE3Tpl Interpolate(const SE3Tpl &A, const SE3Tpl &B, const OtherScalar &alpha)
Linear interpolation on the SE3 manifold.