liegroup-base.hpp
Go to the documentation of this file.
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 { SELF = 0 };
18 #endif
19 
20 #define PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE_GENERIC(Derived,TYPENAME) \
21  typedef LieGroupBase<Derived> Base; \
22  typedef TYPENAME Base::Index Index; \
23  typedef TYPENAME traits<Derived>::Scalar Scalar; \
24  enum { \
25  Options = traits<Derived>::Options, \
26  NQ = Base::NQ, \
27  NV = Base::NV \
28  }; \
29  typedef TYPENAME Base::ConfigVector_t ConfigVector_t; \
30  typedef TYPENAME Base::TangentVector_t TangentVector_t; \
31  typedef TYPENAME Base::JacobianMatrix_t JacobianMatrix_t
32 
33 #define PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE(Derived) \
34 PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE_GENERIC(Derived,PINOCCHIO_MACRO_EMPTY_ARG)
35 
36 #define PINOCCHIO_LIE_GROUP_TPL_PUBLIC_INTERFACE(Derived) \
37 PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE_GENERIC(Derived,typename)
38 
39  template<typename Derived>
40  struct LieGroupBase
41  {
42  typedef Derived LieGroupDerived;
43  typedef int Index;
45  enum
46  {
50  };
51 
52  typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
53  typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
54  typedef Eigen::Matrix<Scalar,NV,NV,Options> JacobianMatrix_t;
55 
58 
67  template <class ConfigIn_t, class Tangent_t, class ConfigOut_t>
68  void integrate(const Eigen::MatrixBase<ConfigIn_t> & q,
69  const Eigen::MatrixBase<Tangent_t> & v,
70  const Eigen::MatrixBase<ConfigOut_t> & qout) const;
71 
84  template<class Config_t, class Jacobian_t>
85  void integrateCoeffWiseJacobian(const Eigen::MatrixBase<Config_t > & q,
86  const Eigen::MatrixBase<Jacobian_t> & J) const;
87 
101  template <ArgumentPosition arg, class Config_t, class Tangent_t, class JacobianOut_t>
102  void dIntegrate(const Eigen::MatrixBase<Config_t > & q,
103  const Eigen::MatrixBase<Tangent_t> & v,
104  const Eigen::MatrixBase<JacobianOut_t> & J,
105  AssignmentOperatorType op = SETTO) const
106  {
107  PINOCCHIO_STATIC_ASSERT(arg==ARG0||arg==ARG1, arg_SHOULD_BE_ARG0_OR_ARG1);
108  return dIntegrate(q.derived(),v.derived(),PINOCCHIO_EIGEN_CONST_CAST(JacobianOut_t,J),arg,op);
109  }
110 
124  template<class Config_t, class Tangent_t, class JacobianOut_t>
125  void dIntegrate(const Eigen::MatrixBase<Config_t > & q,
126  const Eigen::MatrixBase<Tangent_t> & v,
127  const Eigen::MatrixBase<JacobianOut_t> & J,
128  const ArgumentPosition arg,
129  const AssignmentOperatorType op = SETTO) const;
130 
143  template <class Config_t, class Tangent_t, class JacobianOut_t>
144  void dIntegrate_dq(const Eigen::MatrixBase<Config_t > & q,
145  const Eigen::MatrixBase<Tangent_t> & v,
146  const Eigen::MatrixBase<JacobianOut_t> & J,
147  const AssignmentOperatorType op = SETTO) const;
148 
149  template <class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
150  void dIntegrate_dq(const Eigen::MatrixBase<Config_t > & q,
151  const Eigen::MatrixBase<Tangent_t> & v,
152  const Eigen::MatrixBase<JacobianIn_t> & Jin,
153  int self,
154  const Eigen::MatrixBase<JacobianOut_t> & Jout,
155  const AssignmentOperatorType op = SETTO) const;
156 
157  template <class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
158  void dIntegrate_dq(const Eigen::MatrixBase<Config_t > & q,
159  const Eigen::MatrixBase<Tangent_t> & v,
160  int self,
161  const Eigen::MatrixBase<JacobianIn_t> & Jin,
162  const Eigen::MatrixBase<JacobianOut_t> & Jout,
163  const AssignmentOperatorType op = SETTO) const;
164 
177  template <class Config_t, class Tangent_t, class JacobianOut_t>
178  void dIntegrate_dv(const Eigen::MatrixBase<Config_t > & q,
179  const Eigen::MatrixBase<Tangent_t> & v,
180  const Eigen::MatrixBase<JacobianOut_t> & J,
181  const AssignmentOperatorType op = SETTO) const;
182 
183  template <class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
184  void dIntegrate_dv(const Eigen::MatrixBase<Config_t > & q,
185  const Eigen::MatrixBase<Tangent_t> & v,
186  int self,
187  const Eigen::MatrixBase<JacobianIn_t> & Jin,
188  const Eigen::MatrixBase<JacobianOut_t> & Jout,
189  const AssignmentOperatorType op = SETTO) const;
190 
191  template <class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
192  void dIntegrate_dv(const Eigen::MatrixBase<Config_t > & q,
193  const Eigen::MatrixBase<Tangent_t> & v,
194  const Eigen::MatrixBase<JacobianIn_t> & Jin,
195  int self,
196  const Eigen::MatrixBase<JacobianOut_t> & Jout,
197  const AssignmentOperatorType op = SETTO) const;
198 
219  template<class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
220  void dIntegrateTransport(const Eigen::MatrixBase<Config_t > & q,
221  const Eigen::MatrixBase<Tangent_t> & v,
222  const Eigen::MatrixBase<JacobianIn_t> & Jin,
223  const Eigen::MatrixBase<JacobianOut_t> & Jout,
224  const ArgumentPosition arg) const;
225 
244  template <class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
245  void dIntegrateTransport_dq(const Eigen::MatrixBase<Config_t > & q,
246  const Eigen::MatrixBase<Tangent_t> & v,
247  const Eigen::MatrixBase<JacobianIn_t> & Jin,
248  const Eigen::MatrixBase<JacobianOut_t> & Jout) const;
267  template <class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
268  void dIntegrateTransport_dv(const Eigen::MatrixBase<Config_t > & q,
269  const Eigen::MatrixBase<Tangent_t> & v,
270  const Eigen::MatrixBase<JacobianIn_t> & Jin,
271  const Eigen::MatrixBase<JacobianOut_t> & Jout) const;
272 
273 
291  template<class Config_t, class Tangent_t, class Jacobian_t>
292  void dIntegrateTransport(const Eigen::MatrixBase<Config_t > & q,
293  const Eigen::MatrixBase<Tangent_t> & v,
294  const Eigen::MatrixBase<Jacobian_t> & J,
295  const ArgumentPosition arg) const;
296 
314  template <class Config_t, class Tangent_t, class Jacobian_t>
315  void dIntegrateTransport_dq(const Eigen::MatrixBase<Config_t > & q,
316  const Eigen::MatrixBase<Tangent_t> & v,
317  const Eigen::MatrixBase<Jacobian_t> & J) const;
335  template <class Config_t, class Tangent_t, class Jacobian_t>
336  void dIntegrateTransport_dv(const Eigen::MatrixBase<Config_t > & q,
337  const Eigen::MatrixBase<Tangent_t> & v,
338  const Eigen::MatrixBase<Jacobian_t> & J) const;
339 
349  template <class ConfigL_t, class ConfigR_t, class ConfigOut_t>
350  void interpolate(const Eigen::MatrixBase<ConfigL_t> & q0,
351  const Eigen::MatrixBase<ConfigR_t> & q1,
352  const Scalar& u,
353  const Eigen::MatrixBase<ConfigOut_t> & qout) const;
354 
364  template <class Config_t>
365  void normalize(const Eigen::MatrixBase<Config_t> & qout) const;
366 
375  template <class Config_t>
376  bool isNormalized(const Eigen::MatrixBase<Config_t> & qin,
377  const Scalar& prec = Eigen::NumTraits<Scalar>::dummy_precision()) const;
378 
387  template <class Config_t>
388  void random(const Eigen::MatrixBase<Config_t> & qout) const;
389 
399  template <class ConfigL_t, class ConfigR_t, class ConfigOut_t>
400  void randomConfiguration(const Eigen::MatrixBase<ConfigL_t> & lower_pos_limit,
401  const Eigen::MatrixBase<ConfigR_t> & upper_pos_limit,
402  const Eigen::MatrixBase<ConfigOut_t> & qout) const;
403 
414  template <class ConfigL_t, class ConfigR_t, class Tangent_t>
415  void difference(const Eigen::MatrixBase<ConfigL_t> & q0,
416  const Eigen::MatrixBase<ConfigR_t> & q1,
417  const Eigen::MatrixBase<Tangent_t> & v) const;
418 
439  template <ArgumentPosition arg, class ConfigL_t, class ConfigR_t, class JacobianOut_t>
440  void dDifference(const Eigen::MatrixBase<ConfigL_t> & q0,
441  const Eigen::MatrixBase<ConfigR_t> & q1,
442  const Eigen::MatrixBase<JacobianOut_t> & J) const;
443 
455  template<class ConfigL_t, class ConfigR_t, class JacobianOut_t>
456  void dDifference(const Eigen::MatrixBase<ConfigL_t> & q0,
457  const Eigen::MatrixBase<ConfigR_t> & q1,
458  const Eigen::MatrixBase<JacobianOut_t> & J,
459  const ArgumentPosition arg) const;
460 
461  template<ArgumentPosition arg, class ConfigL_t, class ConfigR_t, class JacobianIn_t, class JacobianOut_t>
462  void dDifference(const Eigen::MatrixBase<ConfigL_t> & q0,
463  const Eigen::MatrixBase<ConfigR_t> & q1,
464  const Eigen::MatrixBase<JacobianIn_t> & Jin,
465  int self,
466  const Eigen::MatrixBase<JacobianOut_t> & Jout,
467  const AssignmentOperatorType op = SETTO) const;
468 
469  template<ArgumentPosition arg, class ConfigL_t, class ConfigR_t, class JacobianIn_t, class JacobianOut_t>
470  void dDifference(const Eigen::MatrixBase<ConfigL_t> & q0,
471  const Eigen::MatrixBase<ConfigR_t> & q1,
472  int self,
473  const Eigen::MatrixBase<JacobianIn_t> & Jin,
474  const Eigen::MatrixBase<JacobianOut_t> & Jout,
475  const AssignmentOperatorType op = SETTO) const;
476 
485  template <class ConfigL_t, class ConfigR_t>
486  Scalar squaredDistance(const Eigen::MatrixBase<ConfigL_t> & q0,
487  const Eigen::MatrixBase<ConfigR_t> & q1) const;
488 
497  template <class ConfigL_t, class ConfigR_t>
498  Scalar distance(const Eigen::MatrixBase<ConfigL_t> & q0,
499  const Eigen::MatrixBase<ConfigR_t> & q1) const;
500 
509  template <class ConfigL_t, class ConfigR_t>
510  bool isSameConfiguration(const Eigen::MatrixBase<ConfigL_t> & q0,
511  const Eigen::MatrixBase<ConfigR_t> & q1,
512  const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const;
513 
514  bool operator== (const LieGroupBase& other) const
515  {
516  return derived().isEqual_impl(other.derived());
517  }
518 
519  bool operator!= (const LieGroupBase& other) const
520  {
521  return derived().isDifferent_impl(other.derived());
522  }
524 
527 
528  template <class Config_t, class Tangent_t>
529  ConfigVector_t integrate(const Eigen::MatrixBase<Config_t> & q,
530  const Eigen::MatrixBase<Tangent_t> & v) const ;
531 
532  template <class ConfigL_t, class ConfigR_t>
533  ConfigVector_t interpolate(const Eigen::MatrixBase<ConfigL_t> & q0,
534  const Eigen::MatrixBase<ConfigR_t> & q1,
535  const Scalar& u) const;
536 
537  ConfigVector_t random() const;
538 
539  template <class ConfigL_t, class ConfigR_t>
540  ConfigVector_t randomConfiguration
541  (const Eigen::MatrixBase<ConfigL_t> & lower_pos_limit,
542  const Eigen::MatrixBase<ConfigR_t> & upper_pos_limit) const;
543 
544  template <class ConfigL_t, class ConfigR_t>
545  TangentVector_t difference(const Eigen::MatrixBase<ConfigL_t> & q0,
546  const Eigen::MatrixBase<ConfigR_t> & q1) const;
548 
549 
552 
553  template <class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
554  void dIntegrate_product_impl(const Config_t & q,
555  const Tangent_t & v,
556  const JacobianIn_t & Jin,
557  JacobianOut_t & Jout,
558  bool dIntegrateOnTheLeft,
559  const ArgumentPosition arg,
560  const AssignmentOperatorType op) const;
561 
562  template <ArgumentPosition arg, class ConfigL_t, class ConfigR_t, class JacobianIn_t, class JacobianOut_t>
563  void dDifference_product_impl(const ConfigL_t & q0,
564  const ConfigR_t & q1,
565  const JacobianIn_t & Jin,
566  JacobianOut_t & Jout,
567  bool dDifferenceOnTheLeft,
568  const AssignmentOperatorType op) const;
569 
570  template <class ConfigL_t, class ConfigR_t, class ConfigOut_t>
571  void interpolate_impl(const Eigen::MatrixBase<ConfigL_t> & q0,
572  const Eigen::MatrixBase<ConfigR_t> & q1,
573  const Scalar& u,
574  const Eigen::MatrixBase<ConfigOut_t> & qout) const;
575 
576  template <class Config_t>
577  void normalize_impl(const Eigen::MatrixBase<Config_t> & qout) const;
578 
579  template <class Config_t>
580  bool isNormalized_impl(const Eigen::MatrixBase<Config_t> & qin,
581  const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision()) const;
582 
583  template <class ConfigL_t, class ConfigR_t>
584  Scalar squaredDistance_impl(const Eigen::MatrixBase<ConfigL_t> & q0,
585  const Eigen::MatrixBase<ConfigR_t> & q1) const;
586 
587  template <class ConfigL_t, class ConfigR_t>
588  bool isSameConfiguration_impl(const Eigen::MatrixBase<ConfigL_t> & q0,
589  const Eigen::MatrixBase<ConfigR_t> & q1,
590  const Scalar & prec) const;
591 
594  bool isEqual_impl (const LieGroupBase& /*other*/) const { return true; }
595  bool isDifferent_impl (const LieGroupBase& other) const
596  {
597  return !derived().isEqual_impl(other.derived());
598  }
599 
604  Index nq () const;
606  Index nv () const;
608  ConfigVector_t neutral () const;
609 
611  std::string name () const;
612 
613  Derived& derived ()
614  {
615  return static_cast <Derived&> (*this);
616  }
617 
618  const Derived& derived () const
619  {
620  return static_cast <const Derived&> (*this);
621  }
623 
624  protected:
629 
633  LieGroupBase( const LieGroupBase & /*clone*/) {}
634  }; // struct LieGroupBase
635 
636 } // namespace pinocchio
637 
638 #include "pinocchio/multibody/liegroup/liegroup-base.hxx"
639 
640 #endif // ifndef __pinocchio_multibody_liegroup_liegroup_operation_base_hpp__
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
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.
bool operator!=(const LieGroupBase &other) const
void normalize_impl(const Eigen::MatrixBase< Config_t > &qout) const
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.
ConfigVector_t neutral() const
Get neutral element as a vector.
Eigen::Matrix< Scalar, NQ, 1, Options > ConfigVector_t
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.
ArgumentPosition
Argument position. Used as template parameter to refer to an argument.
Definition: src/fwd.hpp:59
Eigen::Matrix< Scalar, NV, NV, Options > JacobianMatrix_t
void integrate(const Eigen::MatrixBase< ConfigIn_t > &q, const Eigen::MatrixBase< Tangent_t > &v, const Eigen::MatrixBase< ConfigOut_t > &qout) const
Integrate a joint&#39;s configuration with a tangent vector during one unit time duration.
void dIntegrate_product_impl(const Config_t &q, const Tangent_t &v, const JacobianIn_t &Jin, JacobianOut_t &Jout, bool dIntegrateOnTheLeft, const ArgumentPosition arg, const AssignmentOperatorType op) const
Eigen::Matrix< Scalar, NV, 1, Options > TangentVector_t
bool isNormalized_impl(const Eigen::MatrixBase< Config_t > &qin, const Scalar &prec=Eigen::NumTraits< Scalar >::dummy_precision()) const
Scalar squaredDistance(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const
Squared distance between two joint configurations.
void dDifference_product_impl(const ConfigL_t &q0, const ConfigR_t &q1, const JacobianIn_t &Jin, JacobianOut_t &Jout, bool dDifferenceOnTheLeft, const AssignmentOperatorType op) const
void integrateCoeffWiseJacobian(const Eigen::MatrixBase< Config_t > &q, const Eigen::MatrixBase< Jacobian_t > &J) const
Computes the Jacobian of the integrate operator around zero.
traits< LieGroupDerived >::Scalar Scalar
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
ConfigVector_t random() const
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
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...
const Derived & derived() const
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...
bool isSameConfiguration_impl(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &prec) const
#define PINOCCHIO_STATIC_ASSERT(condition, msg)
Definition: src/macros.hpp:63
bool isEqual_impl(const LieGroupBase &) const
Default equality check. By default, two LieGroupBase of same type are considered equal.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > const Scalar & u
AssignmentOperatorType
Definition: src/fwd.hpp:68
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&#39;s configurations.
Scalar squaredDistance_impl(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const
void normalize(const Eigen::MatrixBase< Config_t > &qout) const
Normalize the joint configuration given as input. For instance, the quaternion must be unitary...
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 originate tangent space of the integrate operation...
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 originate tangent space of the integrate operation...
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > const Eigen::MatrixBase< ConfigVectorIn2 > & q1
bool isDifferent_impl(const LieGroupBase &other) const
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...
Main pinocchio namespace.
Definition: timings.cpp:30
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorIn1 > & q0
bool operator==(const LieGroupBase &other) const
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 originate tangent space of the integrate operation...
Common traits structure to fully define base classes for CRTP.
Definition: src/fwd.hpp:44
std::string name() const
Get name of instance.
void interpolate_impl(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1, const Scalar &u, const Eigen::MatrixBase< ConfigOut_t > &qout) const
LieGroupBase(const LieGroupBase &)
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...
Index nv() const
Get dimension of Lie Group tangent space.
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...
Scalar distance(const Eigen::MatrixBase< ConfigL_t > &q0, const Eigen::MatrixBase< ConfigR_t > &q1) const
Distance between two configurations of the joint.


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