GCC Code Coverage Report
Directory: ./ Exec Total Coverage
File: include/pinocchio/multibody/liegroup/liegroup-variant-visitors.hpp Lines: 2 2 100.0 %
Date: 2024-01-23 21:41:47 Branches: 0 0 - %

Line Branch Exec Source
1
//
2
// Copyright (c) 2018 CNRS
3
//
4
5
#ifndef __pinocchio_lie_group_variant_visitor_hpp__
6
#define __pinocchio_lie_group_variant_visitor_hpp__
7
8
#include "pinocchio/multibody/liegroup/fwd.hpp"
9
10
namespace pinocchio
11
{
12
13
  /**
14
   * @brief      Visit a LieGroupVariant to get the dimension of
15
   *             the Lie group configuration space
16
   *
17
   * @param[in]  lg  the LieGroupVariant.
18
   *
19
   * @return     The dimension of the Lie group configuration space
20
   */
21
  template<typename LieGroupCollection>
22
  inline int nq(const LieGroupGenericTpl<LieGroupCollection> & lg);
23
24
  /**
25
   * @brief      Visit a LieGroupVariant to get the dimension of
26
   *             the Lie group tangent space
27
   *
28
   * @param[in]  lg  the LieGroupVariant.
29
   *
30
   * @return     The dimension of the Lie group tangent space
31
   */
32
  template<typename LieGroupCollection>
33
  inline int nv(const LieGroupGenericTpl<LieGroupCollection> & lg);
34
35
  /**
36
   * @brief      Visit a LieGroupVariant to get the name of it
37
   *
38
   * @param[in]  lg  the LieGroupVariant.
39
   *
40
   * @return     The Lie group name
41
   */
42
  template<typename LieGroupCollection>
43
  inline std::string name(const LieGroupGenericTpl<LieGroupCollection> & lg);
44
45
  /**
46
   * @brief      Visit a LieGroupVariant to get the neutral element of it
47
   *
48
   * @param[in]  lg  the LieGroupVariant.
49
   *
50
   * @return     The Lie group neutral element
51
   */
52
  template<typename LieGroupCollection>
53
  inline Eigen::Matrix<typename LieGroupCollection::Scalar,Eigen::Dynamic,1,LieGroupCollection::Options>
54
  neutral(const LieGroupGenericTpl<LieGroupCollection> & lg);
55
56
  /**
57
   * @brief      Visit a LieGroupVariant to call its integrate method
58
   *
59
   * @param[in]  lg  the LieGroupVariant.
60
   * @param[in]  q   the starting configuration.
61
   * @param[in]  v   the tangent velocity.
62
   *
63
   */
64
  template<typename LieGroupCollection, class ConfigIn_t, class Tangent_t, class ConfigOut_t>
65
  inline void integrate(const LieGroupGenericTpl<LieGroupCollection> & lg,
66
                        const Eigen::MatrixBase<ConfigIn_t> & q,
67
                        const Eigen::MatrixBase<Tangent_t>  & v,
68
                        const Eigen::MatrixBase<ConfigOut_t>& qout);
69
70
  template<typename LieGroupCollection, class Config_t>
71
  inline void random(const LieGroupGenericTpl<LieGroupCollection> & lg,
72
                     const Eigen::MatrixBase<Config_t> & qout);
73
74
  template<typename LieGroupCollection, class Config_t>
75
  inline void normalize(const LieGroupGenericTpl<LieGroupCollection> & lg,
76
                        const Eigen::MatrixBase<Config_t> & qout);
77
78
  template<typename LieGroupCollection, class Config_t>
79
  inline bool isNormalized(const LieGroupGenericTpl<LieGroupCollection> & lg,
80
                           const Eigen::MatrixBase<Config_t> & qin,
81
                           const typename Config_t::Scalar& prec = Eigen::NumTraits<typename Config_t::Scalar>::dummy_precision());
82
83
  template<typename LieGroupCollection, class ConfigL_t, class ConfigR_t>
84
  inline bool isSameConfiguration(const LieGroupGenericTpl<LieGroupCollection> & lg,
85
                          const Eigen::MatrixBase<ConfigL_t> & q0,
86
                          const Eigen::MatrixBase<ConfigR_t> & q1,
87
                          const typename ConfigL_t::Scalar& prec);
88
89
  template<typename LieGroupCollection, class ConfigL_t, class ConfigR_t>
90
  inline typename ConfigL_t::Scalar
91
  squaredDistance(const LieGroupGenericTpl<LieGroupCollection> & lg,
92
                  const Eigen::MatrixBase<ConfigL_t> & q0,
93
                  const Eigen::MatrixBase<ConfigR_t> & q1);
94
95
  template<typename LieGroupCollection, class ConfigL_t, class ConfigR_t>
96
  inline typename ConfigL_t::Scalar
97
8
  distance(const LieGroupGenericTpl<LieGroupCollection> & lg,
98
           const Eigen::MatrixBase<ConfigL_t> & q0,
99
           const Eigen::MatrixBase<ConfigR_t> & q1)
100
  {
101
8
    return std::sqrt(squaredDistance(lg, q0, q1));
102
  }
103
104
  template<typename LieGroupCollection, class ConfigL_t, class ConfigR_t, class Tangent_t>
105
  inline void difference(const LieGroupGenericTpl<LieGroupCollection> & lg,
106
                         const Eigen::MatrixBase<ConfigL_t> & q0,
107
                         const Eigen::MatrixBase<ConfigR_t> & q1,
108
                         const Eigen::MatrixBase<Tangent_t> & v);
109
110
  template<typename LieGroupCollection, class ConfigL_t, class ConfigR_t, class ConfigOut_t>
111
  inline void randomConfiguration(const LieGroupGenericTpl<LieGroupCollection> & lg,
112
                                  const Eigen::MatrixBase<ConfigL_t> & q0,
113
                                  const Eigen::MatrixBase<ConfigR_t> & q1,
114
                                  const Eigen::MatrixBase<ConfigOut_t> & qout);
115
116
  template<typename LieGroupCollection, class ConfigL_t, class ConfigR_t, class ConfigOut_t>
117
  inline void interpolate(const LieGroupGenericTpl<LieGroupCollection> & lg,
118
                          const Eigen::MatrixBase<ConfigL_t> & q0,
119
                          const Eigen::MatrixBase<ConfigR_t> & q1,
120
                          const typename ConfigL_t::Scalar& u,
121
                          const Eigen::MatrixBase<ConfigOut_t> & qout);
122
123
  template<typename LieGroupCollection, class Config_t, class Tangent_t, class JacobianOut_t>
124
  void dIntegrate(const LieGroupGenericTpl<LieGroupCollection> & lg,
125
                  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);
130
131
  template<typename LieGroupCollection, class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
132
  void dIntegrate(const LieGroupGenericTpl<LieGroupCollection> & lg,
133
                  const Eigen::MatrixBase<Config_t >  & q,
134
                  const Eigen::MatrixBase<Tangent_t>  & v,
135
                  const Eigen::MatrixBase<JacobianIn_t> & J_in,
136
                  int self,
137
                  const Eigen::MatrixBase<JacobianOut_t> & J_out,
138
                  const ArgumentPosition arg,
139
                  const AssignmentOperatorType op = SETTO);
140
141
  template<typename LieGroupCollection, class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
142
  void dIntegrate(const LieGroupGenericTpl<LieGroupCollection> & lg,
143
                  const Eigen::MatrixBase<Config_t >  & q,
144
                  const Eigen::MatrixBase<Tangent_t>  & v,
145
                  int self,
146
                  const Eigen::MatrixBase<JacobianIn_t> & J_in,
147
                  const Eigen::MatrixBase<JacobianOut_t> & J_out,
148
                  const ArgumentPosition arg,
149
                  const AssignmentOperatorType op = SETTO);
150
151
  template<typename LieGroupCollection, class ConfigL_t, class ConfigR_t, class JacobianOut_t>
152
  void dDifference(const LieGroupGenericTpl<LieGroupCollection> & lg,
153
                   const Eigen::MatrixBase<ConfigL_t> & q0,
154
                   const Eigen::MatrixBase<ConfigR_t> & q1,
155
                   const Eigen::MatrixBase<JacobianOut_t> & J,
156
                   const ArgumentPosition arg);
157
158
  template<ArgumentPosition arg, typename LieGroupCollection, class ConfigL_t, class ConfigR_t, class JacobianIn_t, class JacobianOut_t>
159
  void dDifference(const LieGroupGenericTpl<LieGroupCollection> & lg,
160
                   const Eigen::MatrixBase<ConfigL_t> & q0,
161
                   const Eigen::MatrixBase<ConfigR_t> & q1,
162
                   const Eigen::MatrixBase<JacobianIn_t> & Jin,
163
                   int self,
164
                   const Eigen::MatrixBase<JacobianOut_t> & Jout);
165
166
  template<ArgumentPosition arg, typename LieGroupCollection, class ConfigL_t, class ConfigR_t, class JacobianIn_t, class JacobianOut_t>
167
  void dDifference(const LieGroupGenericTpl<LieGroupCollection> & lg,
168
                   const Eigen::MatrixBase<ConfigL_t> & q0,
169
                   const Eigen::MatrixBase<ConfigR_t> & q1,
170
                   int self,
171
                   const Eigen::MatrixBase<JacobianIn_t> & Jin,
172
                   const Eigen::MatrixBase<JacobianOut_t> & Jout);
173
174
  template<typename LieGroupCollection, class Config_t, class Tangent_t, class JacobianIn_t, class JacobianOut_t>
175
  void dIntegrateTransport(const LieGroupGenericTpl<LieGroupCollection> & lg,
176
                           const Eigen::MatrixBase<Config_t > & q,
177
                           const Eigen::MatrixBase<Tangent_t> & v,
178
                           const Eigen::MatrixBase<JacobianIn_t> & J_in,
179
                           const Eigen::MatrixBase<JacobianOut_t> & J_out,
180
                           const ArgumentPosition arg);
181
182
  template<typename LieGroupCollection, class Config_t, class Tangent_t, class JacobianOut_t>
183
  void dIntegrateTransport(const LieGroupGenericTpl<LieGroupCollection> & lg,
184
                           const Eigen::MatrixBase<Config_t > & q,
185
                           const Eigen::MatrixBase<Tangent_t> & v,
186
                           const Eigen::MatrixBase<JacobianOut_t> & J,
187
                           const ArgumentPosition arg);
188
}
189
190
/// Details
191
#include "pinocchio/multibody/liegroup/liegroup-variant-visitors.hxx"
192
193
#endif // ifndef __pinocchio_lie_group_variant_visitor_hpp__