GCC Code Coverage Report


Directory: ./
File: include/hpp/pinocchio/liegroup-space.hh
Date: 2025-05-04 12:09:19
Exec Total Coverage
Lines: 19 22 86.4%
Branches: 6 14 42.9%

Line Branch Exec Source
1 // Copyright (c) 2017, CNRS
2 // Authors: Florent Lamiraux
3 //
4
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are
7 // met:
8 //
9 // 1. Redistributions of source code must retain the above copyright
10 // notice, this list of conditions and the following disclaimer.
11 //
12 // 2. Redistributions in binary form must reproduce the above copyright
13 // notice, this list of conditions and the following disclaimer in the
14 // documentation and/or other materials provided with the distribution.
15 //
16 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
17 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
18 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
19 // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
20 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
21 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
22 // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23 // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
24 // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
26 // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
27 // DAMAGE.
28
29 #ifndef HPP_PINOCCHIO_LIEGROUP_SPACE_HH
30 #define HPP_PINOCCHIO_LIEGROUP_SPACE_HH
31
32 #include <boost/variant.hpp>
33 #include <hpp/pinocchio/fwd.hh>
34 #include <hpp/pinocchio/liegroup.hh>
35 #include <hpp/util/serialization-fwd.hh>
36 #include <pinocchio/fwd.hpp>
37 #include <pinocchio/multibody/liegroup/special-euclidean.hpp>
38 #include <pinocchio/multibody/liegroup/special-orthogonal.hpp>
39 #include <pinocchio/multibody/liegroup/vector-space.hpp>
40 #include <string>
41 #include <vector>
42
43 namespace hpp {
44 namespace pinocchio {
45 /// \addtogroup liegroup
46 /// \{
47
48 #ifdef HPP_PINOCCHIO_PARSED_BY_DOXYGEN
49 /// Elementary Lie groups
50 /// A boost variant with the following classes:
51 /// \li \f$\mathbf{R}^n\f$, where \f$n\f$ is either 1, 2, 3 or dynamic,
52 /// \li \f$\mathbf{R}^n \times SO(n) \f$, where \f$n\f$ is either 2 or 3,
53 /// \li \f$SO(n) \f$, where \f$n\f$ is either 2 or 3,
54 /// \li \f$SE(n) \f$, where \f$n\f$ is either 2 or 3.
55 /// \sa hpp::pinocchio::liegroup::VectorSpaceOperation,
56 /// hpp::pinocchio::liegroup::CartesianProductOperation,
57 /// hpp::pinocchio::liegroup::SpecialOrthogonalOperation,
58 /// hpp::pinocchio::liegroup::SpecialEuclideanOperation,
59 typedef ABoostVariant LiegroupType;
60 #else
61 typedef boost::variant<liegroup::VectorSpaceOperation<Eigen::Dynamic, false>,
62 liegroup::VectorSpaceOperation<1, true>,
63 liegroup::VectorSpaceOperation<1, false>,
64 liegroup::VectorSpaceOperation<2, false>,
65 liegroup::VectorSpaceOperation<3, false>,
66 liegroup::VectorSpaceOperation<3, true>,
67 liegroup::CartesianProductOperation<
68 liegroup::VectorSpaceOperation<3, false>,
69 liegroup::SpecialOrthogonalOperation<3> >,
70 liegroup::CartesianProductOperation<
71 liegroup::VectorSpaceOperation<2, false>,
72 liegroup::SpecialOrthogonalOperation<2> >,
73 liegroup::SpecialOrthogonalOperation<2>,
74 liegroup::SpecialOrthogonalOperation<3>,
75 liegroup::SpecialEuclideanOperation<2>,
76 liegroup::SpecialEuclideanOperation<3> >
77 LiegroupType;
78 #endif
79
80 enum DerivativeProduct { DerivativeTimesInput, InputTimesDerivative };
81
82 /// Cartesian product of elementary Lie groups
83 ///
84 /// Some values produced and manipulated by functions belong to Lie groups
85 /// For instance rotations, rigid-body motions are element of Lie groups.
86 ///
87 /// Elements of Lie groups are usually applied common operations, like
88 /// \li integrating a velocity from a given element during unit time,
89 /// \li computing the constant velocity that moves from one element to
90 /// another one in unit time.
91 ///
92 /// By analogy with vector spaces that are a particular type of Lie group,
93 /// the above operations are implemented as operators + and - respectively
94 /// acting on LiegroupElement instances.
95 ///
96 /// This class represents a Lie group as the cartesian product of elementaty
97 /// Lie groups. Those elementary Lie groups are gathered in a variant called
98 /// LiegroupType.
99 ///
100 /// Elements of a Lie group are represented by class LiegroupElement.
101 class LiegroupSpace {
102 public:
103 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
104 /// \name Elementary Lie groups
105 /// \{
106
107 /// Return \f$\mathbf{R}^n\f$ as a Lie group
108 /// \param n dimension of vector space
109 static LiegroupSpacePtr_t Rn(const size_type& n);
110 /// Return \f$\mathbf{R}\f$ as a Lie group
111 /// \param rotation whether values of this space represent angles or
112 /// lengths.
113 static LiegroupSpacePtr_t R1(bool rotation = false);
114 /// Return \f$\mathbf{R}^2\f$ as a Lie group
115 static LiegroupSpacePtr_t R2();
116 /// Return \f$\mathbf{R}^3\f$ as a Lie group
117 static LiegroupSpacePtr_t R3();
118 /// Return \f$SE(2)\f$
119 static LiegroupSpacePtr_t SE2();
120 /// Return \f$SE(3)\f$
121 static LiegroupSpacePtr_t SE3();
122 /// Return \f$SO(2)\f$
123 static LiegroupSpacePtr_t SO2();
124 /// Return \f$SO(3)\f$
125 static LiegroupSpacePtr_t SO3();
126 /// Return \f$\mathbf{R}^2 \times SO(2)\f$
127 static LiegroupSpacePtr_t R2xSO2();
128 /// Return \f$\mathbf{R}^3 \times SO(3)\f$
129 static LiegroupSpacePtr_t R3xSO3();
130 /// Return empty Lie group
131 static LiegroupSpacePtr_t empty();
132 /// \}
133
134 /// Create instance of vector space of given size
135 204 static LiegroupSpacePtr_t create(const size_type& size) {
136
1/2
✓ Branch 2 taken 204 times.
✗ Branch 3 not taken.
204 LiegroupSpace* ptr(new LiegroupSpace(size));
137 204 LiegroupSpacePtr_t shPtr(ptr);
138
1/2
✓ Branch 2 taken 204 times.
✗ Branch 3 not taken.
204 ptr->init(shPtr);
139 204 return shPtr;
140 }
141
142 /// Create copy
143 24 static LiegroupSpacePtr_t createCopy(const LiegroupSpaceConstPtr_t& other) {
144
1/2
✓ Branch 3 taken 24 times.
✗ Branch 4 not taken.
24 LiegroupSpace* ptr(new LiegroupSpace(*other));
145 24 LiegroupSpacePtr_t shPtr(ptr);
146
1/2
✓ Branch 2 taken 24 times.
✗ Branch 3 not taken.
24 ptr->init(shPtr);
147 24 return shPtr;
148 }
149
150 /// Create instance with one Elementary Lie group
151 1114 static LiegroupSpacePtr_t create(const LiegroupType& type) {
152
1/2
✓ Branch 2 taken 1114 times.
✗ Branch 3 not taken.
1114 LiegroupSpace* ptr(new LiegroupSpace(type));
153 1114 LiegroupSpacePtr_t shPtr(ptr);
154
1/2
✓ Branch 2 taken 1114 times.
✗ Branch 3 not taken.
1114 ptr->init(shPtr);
155 1114 return shPtr;
156 }
157
158 /// Dimension of the vector representation
159 4405 size_type nq() const { return nq_; }
160 /// Dimension of the Lie group tangent space
161 1810 size_type nv() const { return nv_; }
162 /// Dimension of elementary Liegroup at given rank
163 size_type nq(const std::size_t& rank) const;
164 /// Dimension of elementary Liegroup tangent space at given rank
165 size_type nv(const std::size_t& rank) const;
166
167 /// Get reference to vector of elementary types
168 4201 const std::vector<LiegroupType>& liegroupTypes() const {
169 4201 return liegroupTypes_;
170 }
171
172 /// Return the neutral element as a vector
173 LiegroupElement neutral() const;
174
175 /// Create a LiegroupElement from a configuration.
176 LiegroupElement element(vectorIn_t q) const;
177
178 /// Create a LiegroupElementRef from a configuration.
179 LiegroupElementRef elementRef(vectorOut_t q) const;
180
181 /// Create a LiegroupElementRef from a configuration.
182 LiegroupElementConstRef elementConstRef(vectorIn_t q) const;
183
184 /// Return exponential of a tangent vector
185 LiegroupElement exp(vectorIn_t v) const;
186
187 /// Compute the Jacobian of the integration operation with respect to
188 /// \f$\mathbf{q}\f$.
189 ///
190 /// Given \f$ \mathbf{p} = \mathbf{q} + \mathbf{v} \f$,
191 /// compute \f$J_{\mathbf{q}}\f$ such that
192 ///
193 /// \f{equation}
194 /// \dot{\mathbf{p}} = J_{\mathbf{q}}\dot{\mathbf{q}}
195 /// \f}
196 /// for constant \f$\mathbf{v}\f$. \f$J_{\mathbf{q}}\f$ is a block
197 /// diagonal matrix, each block corresponding to an elementary Lie group.
198 ///
199 /// \tparam side side to multiply in place the Jacobian blocks. See
200 /// "Return values" for an explanation.
201 /// \param q the configuration,
202 /// \param v the velocity vector,
203 /// \retval J in place multiplied result. \f$J\leftarrow J.J_{\mathbf{q}}\f$
204 /// if side is
205 /// InputTimesDerivative
206 /// \f$J\leftarrow J_{\mathbf{q}}.J\f$ if side is
207 /// DerivativeTimesInput. If \f$J\f$ is initialized to identity,
208 /// both results are the same.
209 template <DerivativeProduct side>
210 void dIntegrate_dq(LiegroupElementConstRef q, vectorIn_t v,
211 matrixOut_t J) const;
212
213 /// Compute the Jacobian of the integration operation with respect to
214 /// \f$\mathbf{v}\f$.
215 ///
216 /// Given \f$ \mathbf{p} = \mathbf{q} + \mathbf{v} \f$,
217 /// compute \f$J_{\mathbf{q}}\f$ such that
218 ///
219 /// \f{equation}
220 /// \dot{\mathbf{p}} = J_{\mathbf{v}}\dot{\mathbf{v}}
221 /// \f}
222 /// for constant \f$\mathbf{q}\f$. \f$J_{\mathbf{v}}\f$ is a block
223 /// diagonal matrix, each block corresponding to an elementary Lie group.
224 ///
225 /// \tparam side side to multiply in place the Jacobian blocks. See
226 /// "Return values" for an explanation.
227 /// \param q the configuration,
228 /// \param v the velocity vector,
229 /// \retval J in place multiplied result.
230 /// \f$J\leftarrow J.J_{\mathbf{v}}\f$ if side is
231 /// InputTimesDerivative
232 /// \f$J\leftarrow J_{\mathbf{v}}.J\f$ if side is
233 /// DerivativeTimesInput. If \f$J\f$ is initialized to identity,
234 /// both results are the same.
235 template <DerivativeProduct side>
236 void dIntegrate_dv(LiegroupElementConstRef q, vectorIn_t v,
237 matrixOut_t Jv) const;
238
239 /// \deprecated Use dDifference_dq0 and dDifference_dq1
240 template <bool ApplyOnTheLeft>
241 void Jdifference(vectorIn_t q0, vectorIn_t q1, matrixOut_t J0,
242 matrixOut_t J1) const;
243
244 /// Compute the Jacobian matrices of the difference operation.
245 /// Given \f$ \mathbf{v} = \mathbf{q}_1 - \mathbf{q}_0 \f$,
246 ///
247 /// Compute matrices \f$J_{0}\f$ and \f$J_{1}\f$ such that
248 /// \f{equation}
249 /// \dot{\mathbf{v}} = J_{0}\dot{\mathbf{q}_0} + J_{1}\dot{\mathbf{q}_1}
250 /// \f}
251 /// \param[in] q0,q1 Lie group elements,
252 /// \param[out] J0 the Jacobian of v with respect to q0.
253 template <DerivativeProduct side>
254 void dDifference_dq0(vectorIn_t q0, vectorIn_t q1, matrixOut_t J0) const;
255
256 /// Compute the Jacobian matrices of the difference operation.
257 /// Given \f$ \mathbf{v} = \mathbf{q}_1 - \mathbf{q}_0 \f$,
258 ///
259 /// Compute matrices \f$J_{0}\f$ and \f$J_{1}\f$ such that
260 /// \f{equation}
261 /// \dot{\mathbf{v}} = J_{0}\dot{\mathbf{q}_0} + J_{1}\dot{\mathbf{q}_1}
262 /// \f}
263 /// \param[in] q0,q1 Lie group elements,
264 /// \param[out] J1 the Jacobian of v with respect to q1.
265 template <DerivativeProduct side>
266 void dDifference_dq1(vectorIn_t q0, vectorIn_t q1, matrixOut_t J1) const;
267
268 /// Interpolate between two elements of the Lie group.
269 ///
270 /// This is equivalent to \f$ q_0 \oplus u*(q_1 \ominus q_0) \f$.
271 ///
272 /// \param q0, q1 two elements
273 /// \param u in [0,1] position along the interpolation: q0 for u=0,
274 /// q1 for u=1
275 /// \retval result interpolated configuration
276 void interpolate(vectorIn_t q0, vectorIn_t q1, value_type u,
277 vectorOut_t result) const;
278
279 /// Return name of Lie group
280 std::string name() const;
281
282 void mergeVectorSpaces();
283
284 LiegroupSpacePtr_t vectorSpacesMerged() const;
285
286 bool isVectorSpace() const;
287
288 bool operator==(const LiegroupSpace& other) const;
289 bool operator!=(const LiegroupSpace& other) const;
290
291 LiegroupSpacePtr_t operator*=(const LiegroupSpaceConstPtr_t& other);
292
293 protected:
294 /// Constructor of vector space of given size
295 LiegroupSpace(const size_type& size);
296 LiegroupSpace(const LiegroupSpace& other);
297 LiegroupSpace(const LiegroupType& type);
298
299 private:
300 /// Constructor of empty space
301 LiegroupSpace();
302 /// Initialize weak pointer to itself
303 void init(const LiegroupSpaceWkPtr_t weak);
304 /// Compute size of space
305 void computeSize();
306 /// Compute neutral element as a vector
307 void computeNeutral();
308 typedef std::vector<LiegroupType> LiegroupTypes;
309 LiegroupTypes liegroupTypes_;
310 /// Size of vector representation and of Lie group tangent space
311 size_type nq_, nv_;
312 /// Neutral element of the Lie group
313 vector_t neutral_;
314 /// weak pointer to itself
315 LiegroupSpaceWkPtr_t weak_;
316
317 HPP_SERIALIZABLE();
318 }; // class LiegroupSpace
319 /// Writing in a stream
320 inline std::ostream& operator<<(std::ostream& os, const LiegroupSpace& space) {
321 os << space.name();
322 return os;
323 }
324
325 /// \}
326 } // namespace pinocchio
327 } // namespace hpp
328
329 namespace std {
330 /// \addtogroup liegroup
331 /// \{
332
333 /// Cartesian product between Lie groups
334 hpp::pinocchio::LiegroupSpacePtr_t operator*(
335 const hpp::pinocchio::LiegroupSpaceConstPtr_t& sp1,
336 const hpp::pinocchio::LiegroupSpaceConstPtr_t& sp2);
337 /// Cartesian power by an integer
338 hpp::pinocchio::LiegroupSpacePtr_t operator^(
339 const hpp::pinocchio::LiegroupSpaceConstPtr_t& sp,
340 hpp::pinocchio::size_type n);
341 /// \}
342 } // namespace std
343
344 #endif // HPP_PINOCCHIO_LIEGROUP_SPACE_HH
345