pinocchio  3.3.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
liegroup-base.hpp
1 //
2 // Copyright (c) 2016-2020 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_multibody_liegroup_liegroup_operation_base_hpp__
6 #define __pinocchio_multibody_liegroup_liegroup_operation_base_hpp__
7 
8 #include "pinocchio/multibody/liegroup/fwd.hpp"
9 
10 #include <limits>
11 
12 namespace pinocchio
13 {
14 #ifdef PINOCCHIO_WITH_CXX11_SUPPORT
15  constexpr int SELF = 0;
16 #else
17  enum
18  {
19  SELF = 0
20  };
21 #endif
22 
23 #define PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE_GENERIC(Derived, TYPENAME) \
24  typedef LieGroupBase<Derived> Base; \
25  typedef TYPENAME Base::Index Index; \
26  typedef TYPENAME traits<Derived>::Scalar Scalar; \
27  enum \
28  { \
29  Options = traits<Derived>::Options, \
30  NQ = Base::NQ, \
31  NV = Base::NV \
32  }; \
33  typedef TYPENAME Base::ConfigVector_t ConfigVector_t; \
34  typedef TYPENAME Base::TangentVector_t TangentVector_t; \
35  typedef TYPENAME Base::JacobianMatrix_t JacobianMatrix_t
36 
37 #define PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE(Derived) \
38  PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE_GENERIC(Derived, PINOCCHIO_MACRO_EMPTY_ARG)
39 
40 #define PINOCCHIO_LIE_GROUP_TPL_PUBLIC_INTERFACE(Derived) \
41  PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE_GENERIC(Derived, typename)
42 
43  template<typename Derived>
44  struct LieGroupBase
45  {
46  typedef Derived LieGroupDerived;
47  typedef int Index;
48  typedef typename traits<LieGroupDerived>::Scalar Scalar;
49  enum
50  {
54  };
55 
56  typedef Eigen::Matrix<Scalar, NQ, 1, Options> ConfigVector_t;
57  typedef Eigen::Matrix<Scalar, NV, 1, Options> TangentVector_t;
58  typedef Eigen::Matrix<Scalar, NV, NV, Options> JacobianMatrix_t;
59 
62 
72  template<class ConfigIn_t, class Tangent_t, class ConfigOut_t>
73  void integrate(
74  const Eigen::MatrixBase<ConfigIn_t> & q,
75  const Eigen::MatrixBase<Tangent_t> & v,
76  const Eigen::MatrixBase<ConfigOut_t> & qout) const;
77 
92  template<class Config_t, class Jacobian_t>
94  const Eigen::MatrixBase<Config_t> & q, const Eigen::MatrixBase<Jacobian_t> & J) const;
95 
111  template<ArgumentPosition arg, class Config_t, class Tangent_t, class JacobianOut_t>
113  const Eigen::MatrixBase<Config_t> & q,
114  const Eigen::MatrixBase<Tangent_t> & v,
115  const Eigen::MatrixBase<JacobianOut_t> & J,
116  AssignmentOperatorType op = SETTO) const
117  {
118  PINOCCHIO_STATIC_ASSERT(arg == ARG0 || arg == ARG1, arg_SHOULD_BE_ARG0_OR_ARG1);
119  return dIntegrate(
120  q.derived(), v.derived(), PINOCCHIO_EIGEN_CONST_CAST(JacobianOut_t, J), arg, op);
121  }
122 
138  template<class Config_t, class Tangent_t, class JacobianOut_t>
140  const Eigen::MatrixBase<Config_t> & q,
141  const Eigen::MatrixBase<Tangent_t> & v,
142  const Eigen::MatrixBase<JacobianOut_t> & J,
143  const ArgumentPosition arg,
144  const AssignmentOperatorType op = SETTO) const;
145 
159  template<class Config_t, class Tangent_t, class JacobianOut_t>
161  const Eigen::MatrixBase<Config_t> & q,
162  const Eigen::MatrixBase<Tangent_t> & v,
163  const Eigen::MatrixBase<JacobianOut_t> & J,
164  const AssignmentOperatorType op = SETTO) const;
165 
166  template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
167  void dIntegrate_dq(
168  const Eigen::MatrixBase<Config_t> & q,
169  const Eigen::MatrixBase<Tangent_t> & v,
170  const Eigen::MatrixBase<JacobianIn_t> & Jin,
171  int self,
172  const Eigen::MatrixBase<JacobianOut_t> & Jout,
173  const AssignmentOperatorType op = SETTO) const;
174 
175  template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
176  void dIntegrate_dq(
177  const Eigen::MatrixBase<Config_t> & q,
178  const Eigen::MatrixBase<Tangent_t> & v,
179  int self,
180  const Eigen::MatrixBase<JacobianIn_t> & Jin,
181  const Eigen::MatrixBase<JacobianOut_t> & Jout,
182  const AssignmentOperatorType op = SETTO) const;
183 
197  template<class Config_t, class Tangent_t, class JacobianOut_t>
199  const Eigen::MatrixBase<Config_t> & q,
200  const Eigen::MatrixBase<Tangent_t> & v,
201  const Eigen::MatrixBase<JacobianOut_t> & J,
202  const AssignmentOperatorType op = SETTO) const;
203 
204  template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
205  void dIntegrate_dv(
206  const Eigen::MatrixBase<Config_t> & q,
207  const Eigen::MatrixBase<Tangent_t> & v,
208  int self,
209  const Eigen::MatrixBase<JacobianIn_t> & Jin,
210  const Eigen::MatrixBase<JacobianOut_t> & Jout,
211  const AssignmentOperatorType op = SETTO) const;
212 
213  template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
214  void dIntegrate_dv(
215  const Eigen::MatrixBase<Config_t> & q,
216  const Eigen::MatrixBase<Tangent_t> & v,
217  const Eigen::MatrixBase<JacobianIn_t> & Jin,
218  int self,
219  const Eigen::MatrixBase<JacobianOut_t> & Jout,
220  const AssignmentOperatorType op = SETTO) const;
221 
247  template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
249  const Eigen::MatrixBase<Config_t> & q,
250  const Eigen::MatrixBase<Tangent_t> & v,
251  const Eigen::MatrixBase<JacobianIn_t> & Jin,
252  const Eigen::MatrixBase<JacobianOut_t> & Jout,
253  const ArgumentPosition arg) const;
254 
277  template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
279  const Eigen::MatrixBase<Config_t> & q,
280  const Eigen::MatrixBase<Tangent_t> & v,
281  const Eigen::MatrixBase<JacobianIn_t> & Jin,
282  const Eigen::MatrixBase<JacobianOut_t> & Jout) const;
305  template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
307  const Eigen::MatrixBase<Config_t> & q,
308  const Eigen::MatrixBase<Tangent_t> & v,
309  const Eigen::MatrixBase<JacobianIn_t> & Jin,
310  const Eigen::MatrixBase<JacobianOut_t> & Jout) const;
311 
334  template<class Config_t, class Tangent_t, class Jacobian_t>
336  const Eigen::MatrixBase<Config_t> & q,
337  const Eigen::MatrixBase<Tangent_t> & v,
338  const Eigen::MatrixBase<Jacobian_t> & J,
339  const ArgumentPosition arg) const;
340 
362  template<class Config_t, class Tangent_t, class Jacobian_t>
364  const Eigen::MatrixBase<Config_t> & q,
365  const Eigen::MatrixBase<Tangent_t> & v,
366  const Eigen::MatrixBase<Jacobian_t> & J) const;
388  template<class Config_t, class Tangent_t, class Jacobian_t>
390  const Eigen::MatrixBase<Config_t> & q,
391  const Eigen::MatrixBase<Tangent_t> & v,
392  const Eigen::MatrixBase<Jacobian_t> & J) const;
393 
403  template<class ConfigL_t, class ConfigR_t, class ConfigOut_t>
405  const Eigen::MatrixBase<ConfigL_t> & q0,
406  const Eigen::MatrixBase<ConfigR_t> & q1,
407  const Scalar & u,
408  const Eigen::MatrixBase<ConfigOut_t> & qout) const;
409 
420  template<class Config_t>
421  void normalize(const Eigen::MatrixBase<Config_t> & qout) const;
422 
431  template<class Config_t>
433  const Eigen::MatrixBase<Config_t> & qin,
434  const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const;
435 
444  template<class Config_t>
445  void random(const Eigen::MatrixBase<Config_t> & qout) const;
446 
456  template<class ConfigL_t, class ConfigR_t, class ConfigOut_t>
458  const Eigen::MatrixBase<ConfigL_t> & lower_pos_limit,
459  const Eigen::MatrixBase<ConfigR_t> & upper_pos_limit,
460  const Eigen::MatrixBase<ConfigOut_t> & qout) const;
461 
477  template<class ConfigL_t, class ConfigR_t, class Tangent_t>
479  const Eigen::MatrixBase<ConfigL_t> & q0,
480  const Eigen::MatrixBase<ConfigR_t> & q1,
481  const Eigen::MatrixBase<Tangent_t> & v) const;
482 
504  template<ArgumentPosition arg, class ConfigL_t, class ConfigR_t, class JacobianOut_t>
506  const Eigen::MatrixBase<ConfigL_t> & q0,
507  const Eigen::MatrixBase<ConfigR_t> & q1,
508  const Eigen::MatrixBase<JacobianOut_t> & J) const;
509 
521  template<class ConfigL_t, class ConfigR_t, class JacobianOut_t>
523  const Eigen::MatrixBase<ConfigL_t> & q0,
524  const Eigen::MatrixBase<ConfigR_t> & q1,
525  const Eigen::MatrixBase<JacobianOut_t> & J,
526  const ArgumentPosition arg) const;
527 
528  template<
529  ArgumentPosition arg,
530  class ConfigL_t,
531  class ConfigR_t,
532  class JacobianIn_t,
533  class JacobianOut_t>
534  void dDifference(
535  const Eigen::MatrixBase<ConfigL_t> & q0,
536  const Eigen::MatrixBase<ConfigR_t> & q1,
537  const Eigen::MatrixBase<JacobianIn_t> & Jin,
538  int self,
539  const Eigen::MatrixBase<JacobianOut_t> & Jout,
540  const AssignmentOperatorType op = SETTO) const;
541 
542  template<
543  ArgumentPosition arg,
544  class ConfigL_t,
545  class ConfigR_t,
546  class JacobianIn_t,
547  class JacobianOut_t>
548  void dDifference(
549  const Eigen::MatrixBase<ConfigL_t> & q0,
550  const Eigen::MatrixBase<ConfigR_t> & q1,
551  int self,
552  const Eigen::MatrixBase<JacobianIn_t> & Jin,
553  const Eigen::MatrixBase<JacobianOut_t> & Jout,
554  const AssignmentOperatorType op = SETTO) const;
555 
564  template<class ConfigL_t, class ConfigR_t>
566  const Eigen::MatrixBase<ConfigL_t> & q0, const Eigen::MatrixBase<ConfigR_t> & q1) const;
567 
576  template<class ConfigL_t, class ConfigR_t>
577  Scalar distance(
578  const Eigen::MatrixBase<ConfigL_t> & q0, const Eigen::MatrixBase<ConfigR_t> & q1) const;
579 
589  template<class ConfigL_t, class ConfigR_t>
591  const Eigen::MatrixBase<ConfigL_t> & q0,
592  const Eigen::MatrixBase<ConfigR_t> & q1,
593  const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const;
594 
595  bool operator==(const LieGroupBase & other) const
596  {
597  return derived().isEqual_impl(other.derived());
598  }
599 
600  bool operator!=(const LieGroupBase & other) const
601  {
602  return derived().isDifferent_impl(other.derived());
603  }
605 
608 
609  template<class Config_t, class Tangent_t>
610  ConfigVector_t
611  integrate(const Eigen::MatrixBase<Config_t> & q, const Eigen::MatrixBase<Tangent_t> & v) const;
612 
613  template<class ConfigL_t, class ConfigR_t>
614  ConfigVector_t interpolate(
615  const Eigen::MatrixBase<ConfigL_t> & q0,
616  const Eigen::MatrixBase<ConfigR_t> & q1,
617  const Scalar & u) const;
618 
619  ConfigVector_t random() const;
620 
621  template<class ConfigL_t, class ConfigR_t>
622  ConfigVector_t randomConfiguration(
623  const Eigen::MatrixBase<ConfigL_t> & lower_pos_limit,
624  const Eigen::MatrixBase<ConfigR_t> & upper_pos_limit) const;
625 
626  template<class ConfigL_t, class ConfigR_t>
627  TangentVector_t difference(
628  const Eigen::MatrixBase<ConfigL_t> & q0, const Eigen::MatrixBase<ConfigR_t> & q1) const;
630 
633 
634  template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
635  void dIntegrate_product_impl(
636  const Config_t & q,
637  const Tangent_t & v,
638  const JacobianIn_t & Jin,
639  JacobianOut_t & Jout,
640  bool dIntegrateOnTheLeft,
641  const ArgumentPosition arg,
642  const AssignmentOperatorType op) const;
643 
644  template<
645  ArgumentPosition arg,
646  class ConfigL_t,
647  class ConfigR_t,
648  class JacobianIn_t,
649  class JacobianOut_t>
650  void dDifference_product_impl(
651  const ConfigL_t & q0,
652  const ConfigR_t & q1,
653  const JacobianIn_t & Jin,
654  JacobianOut_t & Jout,
655  bool dDifferenceOnTheLeft,
656  const AssignmentOperatorType op) const;
657 
658  template<class ConfigL_t, class ConfigR_t, class ConfigOut_t>
659  void interpolate_impl(
660  const Eigen::MatrixBase<ConfigL_t> & q0,
661  const Eigen::MatrixBase<ConfigR_t> & q1,
662  const Scalar & u,
663  const Eigen::MatrixBase<ConfigOut_t> & qout) const;
664 
665  template<class Config_t>
666  void normalize_impl(const Eigen::MatrixBase<Config_t> & qout) const;
667 
668  template<class Config_t>
669  bool isNormalized_impl(
670  const Eigen::MatrixBase<Config_t> & qin,
671  const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const;
672 
673  template<class ConfigL_t, class ConfigR_t>
674  Scalar squaredDistance_impl(
675  const Eigen::MatrixBase<ConfigL_t> & q0, const Eigen::MatrixBase<ConfigR_t> & q1) const;
676 
677  template<class ConfigL_t, class ConfigR_t>
678  bool isSameConfiguration_impl(
679  const Eigen::MatrixBase<ConfigL_t> & q0,
680  const Eigen::MatrixBase<ConfigR_t> & q1,
681  const Scalar & prec) const;
682 
685  bool isEqual_impl(const LieGroupBase & /*other*/) const
686  {
687  return true;
688  }
689  bool isDifferent_impl(const LieGroupBase & other) const
690  {
691  return !derived().isEqual_impl(other.derived());
692  }
693 
698  Index nq() const;
700  Index nv() const;
702  ConfigVector_t neutral() const;
703 
705  std::string name() const;
706 
707  Derived & derived()
708  {
709  return static_cast<Derived &>(*this);
710  }
711 
712  const Derived & derived() const
713  {
714  return static_cast<const Derived &>(*this);
715  }
717 
718  protected:
723  {
724  }
725 
729  LieGroupBase(const LieGroupBase & /*clone*/)
730  {
731  }
732 
736  LieGroupBase & operator=(const LieGroupBase & /*other*/)
737  {
738  return *this;
739  }
740 
741  // C++11
742  // LieGroupBase(const LieGroupBase &) = delete;
743  // LieGroupBase& operator=(const LieGroupBase & /*x*/) = delete;
744  }; // struct LieGroupBase
745 
746 } // namespace pinocchio
747 
748 #include "pinocchio/multibody/liegroup/liegroup-base.hxx"
749 
750 #endif // ifndef __pinocchio_multibody_liegroup_liegroup_operation_base_hpp__
Main pinocchio namespace.
Definition: treeview.dox:11
ArgumentPosition
Argument position. Used as template parameter to refer to an argument.
Definition: fwd.hpp:122
void random(const Eigen::MatrixBase< Config_t > &qout) const
Generate a random joint configuration, normalizing quaternions when necessary.
void interpolate(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &u, const Eigen::MatrixBase< ConfigOut_t > &qout) const
Interpolation between two joint's configurations.
std::string name() const
Get name of instance.
void integrate(const Eigen::MatrixBase< ConfigIn_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< ConfigOut_t > &qout) const
Integrate a joint's configuration with a tangent vector during one unit time duration.
Index nv() const
Get dimension of Lie Group tangent space.
void dIntegrateTransport(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout, const ArgumentPosition arg) const
Transport a matrix from the terminal to the initial tangent space of the integrate operation,...
void dIntegrateTransport_dq(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< Jacobian_t > &J) const
Transport in place a matrix from the terminal to the initial tangent space of the integrate operation...
bool isEqual_impl(const LieGroupBase &) const
Default equality check. By default, two LieGroupBase of same type are considered equal.
void dIntegrateTransport_dv(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout) const
Transport a matrix from the terminal to the initial tangent space of the integrate operation,...
void normalize(const Eigen::MatrixBase< Config_t > &qout) const
Normalize the joint configuration given as input. For instance, the quaternion must be unitary.
LieGroupBase(const LieGroupBase &)
void dIntegrateTransport_dq(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianIn_t > &Jin, const Eigen::MatrixBase< JacobianOut_t > &Jout) const
Transport a matrix from the terminal to the initial tangent space of the integrate operation,...
Scalar distance(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const
Distance between two configurations of the joint.
void dIntegrate_dq(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, const AssignmentOperatorType op=SETTO) const
Computes the Jacobian of a small variation of the configuration vector into tangent space at identity...
Scalar squaredDistance(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const
Squared distance between two joint configurations.
void dIntegrateTransport(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< Jacobian_t > &J, const ArgumentPosition arg) const
Transport in place a matrix from the terminal to the initial tangent space of the integrate operation...
LieGroupBase & operator=(const LieGroupBase &)
void dDifference(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianOut_t > &J) const
Computes the Jacobian of the difference operation with respect to q0 or q1.
void dDifference(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< JacobianOut_t > &J, const ArgumentPosition arg) const
Computes the Jacobian of the difference operation with respect to q0 or q1.
void dIntegrateTransport_dv(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< Jacobian_t > &J) const
Transport in place a matrix from the terminal to the initial tangent space of the integrate operation...
ConfigVector_t neutral() const
Get neutral element as a vector.
void dIntegrate_dv(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, const AssignmentOperatorType op=SETTO) const
Computes the Jacobian of a small variation of the tangent vector into tangent space at identity.
void dIntegrate(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, const ArgumentPosition arg, const AssignmentOperatorType op=SETTO) const
Computes the Jacobian of a small variation of the configuration vector or the tangent vector into tan...
bool isSameConfiguration(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Check if two configurations are equivalent within the given precision.
void difference(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Eigen::MatrixBase< Tangent_t > &v) const
Computes the tangent vector that must be integrated during one unit time to go from q0 to q1.
void randomConfiguration(const Eigen::MatrixBase< ConfigL_t > &lower_pos_limit, const Eigen::MatrixBase< ConfigR_t > &upper_pos_limit, const Eigen::MatrixBase< ConfigOut_t > &qout) const
Generate a configuration vector uniformly sampled among provided limits.
void dIntegrate(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< JacobianOut_t > &J, AssignmentOperatorType op=SETTO) const
Computes the Jacobian of a small variation of the configuration vector or the tangent vector into tan...
bool isNormalized(const Eigen::MatrixBase< Config_t > &qin, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Check whether the input joint configuration is normalized. For instance, the quaternion must be unita...
void integrateCoeffWiseJacobian(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Jacobian_t > &J) const
Computes the Jacobian of the integrate operator around zero.
Common traits structure to fully define base classes for CRTP.
Definition: fwd.hpp:72