GCC Code Coverage Report


Directory: ./
File: include/pinocchio/algorithm/joint-configuration.hpp
Date: 2025-02-12 21:03:38
Exec Total Coverage
Lines: 59 73 80.8%
Branches: 0 0 -%

Line Branch Exec Source
1 //
2 // Copyright (c) 2016-2021 CNRS INRIA
3 //
4
5 #ifndef __pinocchio_algorithm_joint_configuration_hpp__
6 #define __pinocchio_algorithm_joint_configuration_hpp__
7
8 #include "pinocchio/multibody/model.hpp"
9 #include "pinocchio/multibody/liegroup/liegroup.hpp"
10
11 namespace pinocchio
12 {
13
14 /// \name API with return value as argument
15 /// \{
16
17 /**
18 *
19 * @brief Integrate a configuration vector for the specified model for a tangent vector
20 * during one unit time
21 *
22 * @details This function corresponds to the exponential map of the joint configuration Lie Group.
23 * Its output can be interpreted as the "sum" from the Lie algebra to the joint
24 * configuration space \f$ q \oplus v \f$.
25 *
26 * @param[in] model Model of the kinematic tree on which the integration is performed.
27 * @param[in] q Initial configuration (size model.nq)
28 * @param[in] v Joint velocity (size model.nv)
29 *
30 * @param[out] qout The integrated configuration (size model.nq)
31 *
32 */
33 template<
34 typename LieGroup_t,
35 typename Scalar,
36 int Options,
37 template<typename, int> class JointCollectionTpl,
38 typename ConfigVectorType,
39 typename TangentVectorType,
40 typename ReturnType>
41 void integrate(
42 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
43 const Eigen::MatrixBase<ConfigVectorType> & q,
44 const Eigen::MatrixBase<TangentVectorType> & v,
45 const Eigen::MatrixBase<ReturnType> & qout);
46
47 /**
48 *
49 * @brief Integrate a configuration vector for the specified model for a tangent vector
50 * during one unit time
51 *
52 * @details This function corresponds to the exponential map of the joint configuration Lie Group.
53 * Its output can be interpreted as the "sum" from the Lie algebra to the joint
54 * configuration space \f$ q \oplus v \f$.
55 *
56 * @param[in] model Model of the kinematic tree on which the integration is performed.
57 * @param[in] q Initial configuration (size model.nq)
58 * @param[in] v Joint velocity (size model.nv)
59 *
60 * @param[out] qout The integrated configuration (size model.nq)
61 *
62 */
63 template<
64 typename Scalar,
65 int Options,
66 template<typename, int> class JointCollectionTpl,
67 typename ConfigVectorType,
68 typename TangentVectorType,
69 typename ReturnType>
70 5 void integrate(
71 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
72 const Eigen::MatrixBase<ConfigVectorType> & q,
73 const Eigen::MatrixBase<TangentVectorType> & v,
74 const Eigen::MatrixBase<ReturnType> & qout)
75 {
76 integrate<
77 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorType, TangentVectorType,
78 5 ReturnType>(model, q.derived(), v.derived(), qout.derived());
79 5 }
80
81 /**
82 *
83 * @brief Interpolate two configurations for a given model
84 *
85 * @param[in] model Model of the kinematic tree on which the interpolation is performed.
86 * @param[in] q0 Initial configuration vector (size model.nq)
87 * @param[in] q1 Final configuration vector (size model.nq)
88 * @param[in] u u in [0;1] position along the interpolation.
89 *
90 * @param[out] qout The interpolated configuration (q0 if u = 0, q1 if u = 1)
91 *
92 */
93 template<
94 typename LieGroup_t,
95 typename Scalar,
96 int Options,
97 template<typename, int> class JointCollectionTpl,
98 typename ConfigVectorIn1,
99 typename ConfigVectorIn2,
100 typename ReturnType>
101 void interpolate(
102 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
103 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
104 const Eigen::MatrixBase<ConfigVectorIn2> & q1,
105 const Scalar & u,
106 const Eigen::MatrixBase<ReturnType> & qout);
107
108 /**
109 *
110 * @brief Interpolate two configurations for a given model
111 *
112 * @param[in] model Model of the kinematic tree on which the interpolation is performed.
113 * @param[in] q0 Initial configuration vector (size model.nq)
114 * @param[in] q1 Final configuration vector (size model.nq)
115 * @param[in] u u in [0;1] position along the interpolation.
116 *
117 * @param[out] qout The interpolated configuration (q0 if u = 0, q1 if u = 1)
118 *
119 */
120 template<
121 typename Scalar,
122 int Options,
123 template<typename, int> class JointCollectionTpl,
124 typename ConfigVectorIn1,
125 typename ConfigVectorIn2,
126 typename ReturnType>
127 void interpolate(
128 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
129 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
130 const Eigen::MatrixBase<ConfigVectorIn2> & q1,
131 const Scalar & u,
132 const Eigen::MatrixBase<ReturnType> & qout)
133 {
134 interpolate<
135 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorIn1, ConfigVectorIn2,
136 ReturnType>(
137 model, q0.derived(), q1.derived(), u, PINOCCHIO_EIGEN_CONST_CAST(ReturnType, qout));
138 }
139
140 /**
141 *
142 * @brief Compute the tangent vector that must be integrated during one unit time to go from
143 * q0 to q1
144 *
145 * @details This function corresponds to the log map of the joint configuration Lie Group.
146 * Its output can be interpreted as a difference from the joint configuration space to
147 * the Lie algebra \f$ q_1 \ominus q_0 \f$.
148 *
149 * @param[in] model Model of the system on which the difference operation is performed.
150 * @param[in] q0 Initial configuration (size model.nq)
151 * @param[in] q1 Desired configuration (size model.nq)
152 *
153 * @param[out] dvout The corresponding velocity (size model.nv)
154 *
155 */
156 template<
157 typename LieGroup_t,
158 typename Scalar,
159 int Options,
160 template<typename, int> class JointCollectionTpl,
161 typename ConfigVectorIn1,
162 typename ConfigVectorIn2,
163 typename ReturnType>
164 void difference(
165 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
166 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
167 const Eigen::MatrixBase<ConfigVectorIn2> & q1,
168 const Eigen::MatrixBase<ReturnType> & dvout);
169
170 /**
171 *
172 * @brief Compute the tangent vector that must be integrated during one unit time to go from
173 * q0 to q1
174 *
175 * @details This function corresponds to the log map of the joint configuration Lie Group.
176 * Its output can be interpreted as a difference from the joint configuration space to
177 * the Lie algebra \f$ q_1 \ominus q_0 \f$.
178 *
179 * @param[in] model Model of the system on which the difference operation is performed.
180 * @param[in] q0 Initial configuration (size model.nq)
181 * @param[in] q1 Desired configuration (size model.nq)
182 *
183 * @param[out] dvout The corresponding velocity (size model.nv).
184 *
185 */
186 template<
187 typename Scalar,
188 int Options,
189 template<typename, int> class JointCollectionTpl,
190 typename ConfigVectorIn1,
191 typename ConfigVectorIn2,
192 typename ReturnType>
193 void difference(
194 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
195 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
196 const Eigen::MatrixBase<ConfigVectorIn2> & q1,
197 const Eigen::MatrixBase<ReturnType> & dvout)
198 {
199 difference<
200 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorIn1, ConfigVectorIn2,
201 ReturnType>(model, q0.derived(), q1.derived(), PINOCCHIO_EIGEN_CONST_CAST(ReturnType, dvout));
202 }
203
204 /**
205 *
206 * @brief Squared distance between two configuration vectors
207 *
208 * @param[in] model Model of the system on which the squared distance operation is
209 * performed.
210 * @param[in] q0 Configuration 0 (size model.nq)
211 * @param[in] q1 Configuration 1 (size model.nq)
212 * @param[out] out The corresponding squared distances for each joint (size
213 * model.njoints-1 = number of joints).
214 *
215 */
216 template<
217 typename LieGroup_t,
218 typename Scalar,
219 int Options,
220 template<typename, int> class JointCollectionTpl,
221 typename ConfigVectorIn1,
222 typename ConfigVectorIn2,
223 typename ReturnType>
224 void squaredDistance(
225 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
226 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
227 const Eigen::MatrixBase<ConfigVectorIn2> & q1,
228 const Eigen::MatrixBase<ReturnType> & out);
229
230 /**
231 *
232 * @brief Squared distance between two configuration vectors
233 *
234 * @param[in] model Model of the system on which the squared distance operation is
235 * performed.
236 * @param[in] q0 Configuration 0 (size model.nq)
237 * @param[in] q1 Configuration 1 (size model.nq)
238 * @param[out] out The corresponding squared distances for each joint (size
239 * model.njoints-1 = number of joints).
240 *
241 */
242 template<
243 typename Scalar,
244 int Options,
245 template<typename, int> class JointCollectionTpl,
246 typename ConfigVectorIn1,
247 typename ConfigVectorIn2,
248 typename ReturnType>
249 void squaredDistance(
250 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
251 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
252 const Eigen::MatrixBase<ConfigVectorIn2> & q1,
253 const Eigen::MatrixBase<ReturnType> & out)
254 {
255 squaredDistance<
256 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorIn1, ConfigVectorIn2,
257 ReturnType>(model, q0.derived(), q1.derived(), PINOCCHIO_EIGEN_CONST_CAST(ReturnType, out));
258 }
259
260 /**
261 *
262 * @brief Generate a configuration vector uniformly sampled among provided limits.
263 *
264 * @remarks Limits are not taken into account for rotational transformations (typically
265 * SO(2),SO(3)), because they are by definition unbounded.
266 *
267 * @warning If limits are infinite, exceptions may be thrown in the joint implementation of
268 * uniformlySample.
269 *
270 * @param[in] model Model of the system on which the random configuration
271 * operation is performed.
272 * @param[in] lowerLimits Joints lower limits (size model.nq).
273 * @param[in] upperLimits Joints upper limits (size model.nq).
274 * @param[out] qout The resulting configuration vector (size model.nq).
275 *
276 */
277 template<
278 typename LieGroup_t,
279 typename Scalar,
280 int Options,
281 template<typename, int> class JointCollectionTpl,
282 typename ConfigVectorIn1,
283 typename ConfigVectorIn2,
284 typename ReturnType>
285 void randomConfiguration(
286 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
287 const Eigen::MatrixBase<ConfigVectorIn1> & lowerLimits,
288 const Eigen::MatrixBase<ConfigVectorIn2> & upperLimits,
289 const Eigen::MatrixBase<ReturnType> & qout);
290
291 /**
292 *
293 * @brief Generate a configuration vector uniformly sampled among provided limits.
294 *
295 * @remarks Limits are not taken into account for rotational transformations (typically
296 * SO(2),SO(3)), because they are by definition unbounded.
297 *
298 * @warning If limits are infinite, exceptions may be thrown in the joint implementation of
299 * uniformlySample
300 *
301 * @param[in] model Model of the system on which the random configuration operation
302 * is performed.
303 * @param[in] lowerLimits Joints lower limits (size model.nq).
304 * @param[in] upperLimits Joints upper limits (size model.nq).
305 * @param[out] qout The resulting configuration vector (size model.nq).
306 *
307 */
308 template<
309 typename Scalar,
310 int Options,
311 template<typename, int> class JointCollectionTpl,
312 typename ConfigVectorIn1,
313 typename ConfigVectorIn2,
314 typename ReturnType>
315 void randomConfiguration(
316 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
317 const Eigen::MatrixBase<ConfigVectorIn1> & lowerLimits,
318 const Eigen::MatrixBase<ConfigVectorIn2> & upperLimits,
319 const Eigen::MatrixBase<ReturnType> & qout)
320 {
321 randomConfiguration<
322 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorIn1, ConfigVectorIn2,
323 ReturnType>(
324 model, lowerLimits.derived(), upperLimits.derived(),
325 PINOCCHIO_EIGEN_CONST_CAST(ReturnType, qout));
326 }
327
328 /**
329 *
330 * @brief Return the neutral configuration element related to the model configuration
331 * space.
332 *
333 * @param[in] model Model of the kinematic tree on which the neutral element is computed
334 *
335 * @param[out] qout The neutral configuration element (size model.nq).
336 *
337 */
338 template<
339 typename LieGroup_t,
340 typename Scalar,
341 int Options,
342 template<typename, int> class JointCollectionTpl,
343 typename ReturnType>
344 void neutral(
345 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
346 const Eigen::MatrixBase<ReturnType> & qout);
347
348 /**
349 *
350 * @brief Return the neutral configuration element related to the model configuration
351 * space.
352 *
353 * @param[in] model Model of the kinematic tree on which the neutral element is computed.
354 *
355 * @param[out] qout The neutral configuration element (size model.nq).
356 *
357 */
358 template<
359 typename Scalar,
360 int Options,
361 template<typename, int> class JointCollectionTpl,
362 typename ReturnType>
363 23 void neutral(
364 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
365 const Eigen::MatrixBase<ReturnType> & qout)
366 {
367 23 neutral<LieGroupMap, Scalar, Options, JointCollectionTpl, ReturnType>(
368 23 model, PINOCCHIO_EIGEN_CONST_CAST(ReturnType, qout));
369 23 }
370
371 /**
372 *
373 * @brief Computes the Jacobian of a small variation of the configuration vector or the tangent
374 * vector into the tangent space at identity.
375 *
376 * @details This jacobian has to be interpreted in terms of Lie group, not vector space: as such,
377 * it is expressed in the tangent space only, not the configuration space.
378 * Calling \f$ f(q, v) \f$ the integrate function, these jacobians satisfy the following
379 * relationships in the tangent space:
380 * - Jacobian relative to q: \f$ f(q \oplus \delta q, v) \ominus f(q, v) = J_q \delta q
381 * + o(\delta q)\f$.
382 * - Jacobian relative to v: \f$ f(q, v + \delta v) \ominus f(q, v) = J_v \delta v +
383 * o(\delta v)\f$.
384 *
385 * @param[in] model Model of the kinematic tree on which the integration operation is
386 * performed.
387 * @param[in] q Initial configuration (size model.nq)
388 * @param[in] v Joint velocity (size model.nv)
389 * @param[out] J Jacobian of the Integrate operation, either with respect to q or v (size
390 * model.nv x model.nv).
391 * @param[in] arg Argument (either q or v) with respect to which the differentiation is
392 * performed.
393 *
394 */
395 template<
396 typename LieGroup_t,
397 typename Scalar,
398 int Options,
399 template<typename, int> class JointCollectionTpl,
400 typename ConfigVectorType,
401 typename TangentVectorType,
402 typename JacobianMatrixType>
403 void dIntegrate(
404 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
405 const Eigen::MatrixBase<ConfigVectorType> & q,
406 const Eigen::MatrixBase<TangentVectorType> & v,
407 const Eigen::MatrixBase<JacobianMatrixType> & J,
408 const ArgumentPosition arg,
409 const AssignmentOperatorType op = SETTO);
410
411 /**
412 *
413 * @brief Computes the Jacobian of a small variation of the configuration vector or the tangent
414 * vector into the tangent space at identity.
415 *
416 * @details This jacobian has to be interpreted in terms of Lie group, not vector space: as such,
417 * it is expressed in the tangent space only, not the configuration space.
418 * Calling \f$ f(q, v) \f$ the integrate function, these jacobians satisfy the following
419 * relationships in the tangent space:
420 * - Jacobian relative to q: \f$ f(q \oplus \delta q, v) \ominus f(q, v) = J_q(q, v)
421 * \delta q + o(\delta q)\f$.
422 * - Jacobian relative to v: \f$ f(q, v + \delta v) \ominus f(q, v) = J_v(q, v) \delta v
423 * + o(\delta v)\f$.
424 *
425 * @param[in] model Model of the kinematic tree on which the integration operation is
426 * performed.
427 * @param[in] q Initial configuration (size model.nq)
428 * @param[in] v Joint velocity (size model.nv)
429 * @param[out] J Jacobian of the Integrate operation, either with respect to q or v
430 * (size model.nv x model.nv).
431 * @param[in] arg Argument (either q or v) with respect to which the differentiation is
432 * performed.
433 *
434 */
435 template<
436 typename Scalar,
437 int Options,
438 template<typename, int> class JointCollectionTpl,
439 typename ConfigVectorType,
440 typename TangentVectorType,
441 typename JacobianMatrixType>
442 14 void dIntegrate(
443 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
444 const Eigen::MatrixBase<ConfigVectorType> & q,
445 const Eigen::MatrixBase<TangentVectorType> & v,
446 const Eigen::MatrixBase<JacobianMatrixType> & J,
447 const ArgumentPosition arg)
448 {
449 dIntegrate<
450 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorType, TangentVectorType,
451 14 JacobianMatrixType>(
452 14 model, q.derived(), v.derived(), PINOCCHIO_EIGEN_CONST_CAST(JacobianMatrixType, J), arg,
453 SETTO);
454 14 }
455
456 /**
457 *
458 * @brief Computes the Jacobian of a small variation of the configuration vector or the tangent
459 * vector into the tangent space at identity.
460 *
461 * @details This jacobian has to be interpreted in terms of Lie group, not vector space: as such,
462 * it is expressed in the tangent space only, not the configuration space.
463 * Calling \f$ f(q, v) \f$ the integrate function, these jacobians satisfy the following
464 * relationships in the tangent space:
465 * - Jacobian relative to q: \f$ f(q \oplus \delta q, v) \ominus f(q, v) = J_q(q, v)
466 * \delta q + o(\delta q)\f$.
467 * - Jacobian relative to v: \f$ f(q, v + \delta v) \ominus f(q, v) = J_v(q, v) \delta v
468 * + o(\delta v)\f$.
469 *
470 * @param[in] model Model of the kinematic tree on which the integration operation is
471 * performed.
472 * @param[in] q Initial configuration (size model.nq)
473 * @param[in] v Joint velocity (size model.nv)
474 * @param[out] J Jacobian of the Integrate operation, either with respect to q or v
475 * (size model.nv x model.nv).
476 * @param[in] arg Argument (either q or v) with respect to which the differentiation is
477 * performed.
478 *
479 */
480 template<
481 typename Scalar,
482 int Options,
483 template<typename, int> class JointCollectionTpl,
484 typename ConfigVectorType,
485 typename TangentVectorType,
486 typename JacobianMatrixType>
487 18 void dIntegrate(
488 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
489 const Eigen::MatrixBase<ConfigVectorType> & q,
490 const Eigen::MatrixBase<TangentVectorType> & v,
491 const Eigen::MatrixBase<JacobianMatrixType> & J,
492 const ArgumentPosition arg,
493 const AssignmentOperatorType op)
494 {
495 dIntegrate<
496 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorType, TangentVectorType,
497 18 JacobianMatrixType>(
498 18 model, q.derived(), v.derived(), PINOCCHIO_EIGEN_CONST_CAST(JacobianMatrixType, J), arg, op);
499 18 }
500
501 /**
502 *
503 * @brief Transport a matrix from the terminal to the initial tangent space of the integrate
504 * operation, with respect to the configuration or the velocity arguments.
505 *
506 * @details This function performs the parallel transportation of an input matrix whose columns
507 * are expressed in the tangent space of the integrated element \f$ q \oplus v \f$, to the tangent
508 * space at \f$ q \f$. In other words, this functions transforms a tangent vector expressed at \f$
509 * q \oplus v \f$ to a tangent vector expressed at \f$ q \f$, considering that the change of
510 * configuration between \f$ q \oplus v \f$ and \f$ q \f$ may alter the value of this tangent
511 * vector. A typical example of parallel transportation is the action operated by a rigid
512 * transformation \f$ M \in \text{SE}(3)\f$ on a spatial velocity \f$ v \in \text{se}(3)\f$. In
513 * the context of configuration spaces assimilated to vector spaces, this operation corresponds
514 * to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
515 *
516 * @param[in] model Model of the kinematic tree on which the integration operation is
517 * performed.
518 * @param[in] q Initial configuration (size model.nq)
519 * @param[in] v Joint velocity (size model.nv)
520 * @param[out] Jin Input matrix (number of rows = model.nv).
521 * @param[out] Jout Output matrix (same size as Jin).
522 * @param[in] arg Argument (either ARG0 for q or ARG1 for v) with respect to which the
523 * differentation is performed.
524 *
525 */
526 template<
527 typename LieGroup_t,
528 typename Scalar,
529 int Options,
530 template<typename, int> class JointCollectionTpl,
531 typename ConfigVectorType,
532 typename TangentVectorType,
533 typename JacobianMatrixType1,
534 typename JacobianMatrixType2>
535 void dIntegrateTransport(
536 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
537 const Eigen::MatrixBase<ConfigVectorType> & q,
538 const Eigen::MatrixBase<TangentVectorType> & v,
539 const Eigen::MatrixBase<JacobianMatrixType1> & Jin,
540 const Eigen::MatrixBase<JacobianMatrixType2> & Jout,
541 const ArgumentPosition arg);
542
543 /**
544 *
545 * @brief Transport a matrix from the terminal to the initial tangent space of the integrate
546 * operation, with respect to the configuration or the velocity arguments.
547 *
548 * @details This function performs the parallel transportation of an input matrix whose columns
549 * are expressed in the tangent space of the integrated element \f$ q \oplus v \f$, to the tangent
550 * space at \f$ q \f$. In other words, this functions transforms a tangent vector expressed at \f$
551 * q \oplus v \f$ to a tangent vector expressed at \f$ q \f$, considering that the change of
552 * configuration between \f$ q \oplus v \f$ and \f$ q \f$ may alter the value of this tangent
553 * vector. A typical example of parallel transportation is the action operated by a rigid
554 * transformation \f$ M \in \text{SE}(3)\f$ on a spatial velocity \f$ v \in \text{se}(3)\f$. In
555 * the context of configuration spaces assimilated to vector spaces, this operation corresponds
556 * to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
557 *
558 * @param[in] model Model of the kinematic tree on which the integration operation is
559 * performed.
560 * @param[in] q Initial configuration (size model.nq)
561 * @param[in] v Joint velocity (size model.nv)
562 * @param[out] Jin Input matrix (number of rows = model.nv).
563 * @param[out] Jout Output matrix (same size as Jin).
564 * @param[in] arg Argument (either ARG0 for q or ARG1 for v) with respect to which the
565 * differentation is performed.
566 *
567 */
568 template<
569 typename Scalar,
570 int Options,
571 template<typename, int> class JointCollectionTpl,
572 typename ConfigVectorType,
573 typename TangentVectorType,
574 typename JacobianMatrixType1,
575 typename JacobianMatrixType2>
576 4 void dIntegrateTransport(
577 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
578 const Eigen::MatrixBase<ConfigVectorType> & q,
579 const Eigen::MatrixBase<TangentVectorType> & v,
580 const Eigen::MatrixBase<JacobianMatrixType1> & Jin,
581 const Eigen::MatrixBase<JacobianMatrixType2> & Jout,
582 const ArgumentPosition arg)
583 {
584 dIntegrateTransport<
585 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorType, TangentVectorType,
586 4 JacobianMatrixType1, JacobianMatrixType2>(
587 4 model, q.derived(), v.derived(), Jin.derived(),
588 4 PINOCCHIO_EIGEN_CONST_CAST(JacobianMatrixType2, Jout), arg);
589 4 }
590
591 /**
592 *
593 * @brief Transport in place a matrix from the terminal to the initial tangent space of the
594 * integrate operation, with respect to the configuration or the velocity arguments.
595 *
596 * @details This function performs the parallel transportation of an input matrix whose columns
597 * are expressed in the tangent space of the integrated element \f$ q \oplus v \f$, to the tangent
598 * space at \f$ q \f$. In other words, this functions transforms a tangent vector expressed at \f$
599 * q \oplus v \f$ to a tangent vector expressed at \f$ q \f$, considering that the change of
600 * configuration between \f$ q \oplus v \f$ and \f$ q \f$ may alter the value of this tangent
601 * vector. A typical example of parallel transportation is the action operated by a rigid
602 * transformation \f$ M \in \text{SE}(3)\f$ on a spatial velocity \f$ v \in \text{se}(3)\f$. In
603 * the context of configuration spaces assimilated to vector spaces, this operation corresponds
604 * to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
605 *
606 * @param[in] model Model of the kinematic tree on which the integration operation is
607 * performed.
608 * @param[in] q Initial configuration (size model.nq)
609 * @param[in] v Joint velocity (size model.nv)
610 * @param[in,out] J Input/output matrix (number of rows = model.nv).
611 * @param[in] arg Argument (either ARG0 for q or ARG1 for v) with respect to which the
612 * differentation is performed.
613 *
614 */
615 template<
616 typename LieGroup_t,
617 typename Scalar,
618 int Options,
619 template<typename, int> class JointCollectionTpl,
620 typename ConfigVectorType,
621 typename TangentVectorType,
622 typename JacobianMatrixType>
623 void dIntegrateTransport(
624 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
625 const Eigen::MatrixBase<ConfigVectorType> & q,
626 const Eigen::MatrixBase<TangentVectorType> & v,
627 const Eigen::MatrixBase<JacobianMatrixType> & J,
628 const ArgumentPosition arg);
629
630 /**
631 *
632 * @brief Transport in place a matrix from the terminal to the initial tangent space of the
633 * integrate operation, with respect to the configuration or the velocity arguments.
634 *
635 * @details This function performs the parallel transportation of an input matrix whose columns
636 * are expressed in the tangent space of the integrated element \f$ q \oplus v \f$, to the tangent
637 * space at \f$ q \f$. In other words, this functions transforms a tangent vector expressed at \f$
638 * q \oplus v \f$ to a tangent vector expressed at \f$ q \f$, considering that the change of
639 * configuration between \f$ q \oplus v \f$ and \f$ q \f$ may alter the value of this tangent
640 * vector. A typical example of parallel transportation is the action operated by a rigid
641 * transformation \f$ M \in \text{SE}(3)\f$ on a spatial velocity \f$ v \in \text{se}(3)\f$. In
642 * the context of configuration spaces assimilated to vector spaces, this operation corresponds
643 * to Identity. For Lie groups, its corresponds to the canonical vector field transportation.
644 *
645 * @param[in] model Model of the kinematic tree on which the integration operation is
646 * performed.
647 * @param[in] q Initial configuration (size model.nq)
648 * @param[in] v Joint velocity (size model.nv)
649 * @param[in,out] J Input/output matrix (number of rows = model.nv).
650 * @param[in] arg Argument (either ARG0 for q or ARG1 for v) with respect to which the
651 * differentation is performed.
652 *
653 */
654 template<
655 typename Scalar,
656 int Options,
657 template<typename, int> class JointCollectionTpl,
658 typename ConfigVectorType,
659 typename TangentVectorType,
660 typename JacobianMatrixType>
661 2 void dIntegrateTransport(
662 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
663 const Eigen::MatrixBase<ConfigVectorType> & q,
664 const Eigen::MatrixBase<TangentVectorType> & v,
665 const Eigen::MatrixBase<JacobianMatrixType> & J,
666 const ArgumentPosition arg)
667 {
668 dIntegrateTransport<
669 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorType, TangentVectorType,
670 2 JacobianMatrixType>(
671 2 model, q.derived(), v.derived(), PINOCCHIO_EIGEN_CONST_CAST(JacobianMatrixType, J), arg);
672 2 }
673
674 /**
675 *
676 * @brief Computes the Jacobian of a small variation of the configuration vector into the
677 * tangent space at identity.
678 *
679 * @details This jacobian has to be interpreted in terms of Lie group, not vector space: as such,
680 * it is expressed in the tangent space only, not the configuration space.
681 * Calling \f$ d(q0, q1) \f$ the difference function, these jacobians satisfy the
682 * following relationships in the tangent space:
683 * - Jacobian relative to q0: \f$ d(q_0 \oplus \delta q_0, q_1) \ominus d(q_0, q_1) =
684 * J_{q_0} \delta q_0 + o(\| \delta q_0 \|)\f$.
685 * - Jacobian relative to q1: \f$ d(q_0, q_1 \oplus \delta q_1) \ominus d(q_0, q_1) =
686 * J_{q_1} \delta q_1 + o(\| \delta q_1 \|)\f$.
687 *
688 * @param[in] model Model of the kinematic tree on which the difference operation is performed.
689 * @param[in] q0 Initial configuration (size model.nq)
690 * @param[in] q1 Joint velocity (size model.nv)
691 * @param[out] J Jacobian of the Difference operation, either with respect to q0 or q1
692 * (size model.nv x model.nv).
693 * @param[in] arg Argument (either q0 or q1) with respect to which the differentiation is
694 * performed.
695 *
696 */
697 template<
698 typename LieGroup_t,
699 typename Scalar,
700 int Options,
701 template<typename, int> class JointCollectionTpl,
702 typename ConfigVector1,
703 typename ConfigVector2,
704 typename JacobianMatrix>
705 void dDifference(
706 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
707 const Eigen::MatrixBase<ConfigVector1> & q0,
708 const Eigen::MatrixBase<ConfigVector2> & q1,
709 const Eigen::MatrixBase<JacobianMatrix> & J,
710 const ArgumentPosition arg);
711
712 /**
713 *
714 * @brief Computes the Jacobian of a small variation of the configuration vector into the
715 * tangent space at identity.
716 *
717 * @details This jacobian has to be interpreted in terms of Lie group, not vector space: as such,
718 * it is expressed in the tangent space only, not the configuration space.
719 * Calling \f$ d(q0, q1) \f$ the difference function, these jacobians satisfy the
720 * following relationships in the tangent space:
721 * - Jacobian relative to q0: \f$ d(q_0 \oplus \delta q_0, q_1) \ominus d(q_0, q_1) =
722 * J_{q_0} \delta q_0 + o(\| \delta q_0 \|)\f$.
723 * - Jacobian relative to q1: \f$ d(q_0, q_1 \oplus \delta q_1) \ominus d(q_0, q_1) =
724 * J_{q_1} \delta q_1 + o(\| \delta q_1 \|)\f$.
725 *
726 * @param[in] model Model of the kinematic tree on which the difference operation is performed.
727 * @param[in] q0 Initial configuration (size model.nq)
728 * @param[in] q1 Joint velocity (size model.nv)
729 * @param[out] J Jacobian of the Difference operation, either with respect to q0 or q1
730 * (size model.nv x model.nv).
731 * @param[in] arg Argument (either q0 or q1) with respect to which the differentiation is
732 * performed.
733 *
734 */
735 template<
736 typename Scalar,
737 int Options,
738 template<typename, int> class JointCollectionTpl,
739 typename ConfigVector1,
740 typename ConfigVector2,
741 typename JacobianMatrix>
742 14 void dDifference(
743 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
744 const Eigen::MatrixBase<ConfigVector1> & q0,
745 const Eigen::MatrixBase<ConfigVector2> & q1,
746 const Eigen::MatrixBase<JacobianMatrix> & J,
747 const ArgumentPosition arg)
748 {
749 dDifference<
750 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVector1, ConfigVector2,
751 14 JacobianMatrix>(
752 14 model, q0.derived(), q1.derived(), PINOCCHIO_EIGEN_CONST_CAST(JacobianMatrix, J), arg);
753 14 }
754 /**
755 *
756 * @brief Overall squared distance between two configuration vectors
757 *
758 * @param[in] model Model we want to compute the distance
759 * @param[in] q0 Configuration 0 (size model.nq)
760 * @param[in] q1 Configuration 1 (size model.nq)
761 *
762 * @return The squared distance between the two configurations
763 *
764 */
765 template<
766 typename LieGroup_t,
767 typename Scalar,
768 int Options,
769 template<typename, int> class JointCollectionTpl,
770 typename ConfigVectorIn1,
771 typename ConfigVectorIn2>
772 Scalar squaredDistanceSum(
773 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
774 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
775 const Eigen::MatrixBase<ConfigVectorIn2> & q1);
776
777 /**
778 *
779 * @brief Overall squared distance between two configuration vectors, namely \f$ || q_{1}
780 * \ominus q_{0} ||_2^{2} \f$.
781 *
782 * @param[in] model Model of the kinematic tree
783 * @param[in] q0 Configuration from (size model.nq)
784 * @param[in] q1 Configuration to (size model.nq)
785 *
786 * @return The squared distance between the two configurations q0 and q1.
787 *
788 */
789 template<
790 typename Scalar,
791 int Options,
792 template<typename, int> class JointCollectionTpl,
793 typename ConfigVectorIn1,
794 typename ConfigVectorIn2>
795 Scalar squaredDistanceSum(
796 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
797 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
798 const Eigen::MatrixBase<ConfigVectorIn2> & q1)
799 {
800 return squaredDistanceSum<
801 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorIn1, ConfigVectorIn2>(
802 model, q0.derived(), q1.derived());
803 }
804
805 /**
806 *
807 * @brief Distance between two configuration vectors, namely \f$ || q_{1} \ominus q_{0} ||_2
808 * \f$.
809 *
810 * @param[in] model Model we want to compute the distance
811 * @param[in] q0 Configuration 0 (size model.nq)
812 * @param[in] q1 Configuration 1 (size model.nq)
813 *
814 * @return The distance between the two configurations q0 and q1.
815 *
816 */
817 template<
818 typename LieGroup_t,
819 typename Scalar,
820 int Options,
821 template<typename, int> class JointCollectionTpl,
822 typename ConfigVectorIn1,
823 typename ConfigVectorIn2>
824 Scalar distance(
825 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
826 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
827 const Eigen::MatrixBase<ConfigVectorIn2> & q1);
828
829 /**
830 *
831 * @brief Distance between two configuration vectors
832 *
833 * @param[in] model Model we want to compute the distance
834 * @param[in] q0 Configuration 0 (size model.nq)
835 * @param[in] q1 Configuration 1 (size model.nq)
836 *
837 * @return The distance between the two configurations q0 and q1.
838 *
839 */
840 template<
841 typename Scalar,
842 int Options,
843 template<typename, int> class JointCollectionTpl,
844 typename ConfigVectorIn1,
845 typename ConfigVectorIn2>
846 4 Scalar distance(
847 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
848 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
849 const Eigen::MatrixBase<ConfigVectorIn2> & q1)
850 {
851 return distance<
852 4 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorIn1, ConfigVectorIn2>(
853 8 model, q0.derived(), q1.derived());
854 }
855
856 /**
857 *
858 * @brief Normalize a configuration vector.
859 *
860 * @param[in] model Model of the kinematic tree.
861 * @param[in,out] q Configuration to normalize (size model.nq).
862 *
863 */
864 template<
865 typename LieGroup_t,
866 typename Scalar,
867 int Options,
868 template<typename, int> class JointCollectionTpl,
869 typename ConfigVectorType>
870 void normalize(
871 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
872 const Eigen::MatrixBase<ConfigVectorType> & qout);
873
874 /**
875 *
876 * @brief Normalize a configuration vector.
877 *
878 * @param[in] model Model of the kinematic tree.
879 * @param[in,out] q Configuration to normalize (size model.nq).
880 *
881 */
882 template<
883 typename Scalar,
884 int Options,
885 template<typename, int> class JointCollectionTpl,
886 typename ConfigVectorType>
887 14 void normalize(
888 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
889 const Eigen::MatrixBase<ConfigVectorType> & qout)
890 {
891 14 normalize<LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorType>(
892 14 model, PINOCCHIO_EIGEN_CONST_CAST(ConfigVectorType, qout));
893 14 }
894
895 /**
896 *
897 * @brief Check whether a configuration vector is normalized within the given precision
898 * provided by prec.
899 *
900 * @param[in] model Model of the kinematic tree.
901 * @param[in] q Configuration to check (size model.nq).
902 * @param[in] prec Precision.
903 *
904 * @return Whether the configuration is normalized or not, within the given precision.
905 */
906 template<
907 typename LieGroup_t,
908 typename Scalar,
909 int Options,
910 template<typename, int> class JointCollectionTpl,
911 typename ConfigVectorType>
912 bool isNormalized(
913 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
914 const Eigen::MatrixBase<ConfigVectorType> & q,
915 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision());
916
917 /**
918 *
919 * @brief Check whether a configuration vector is normalized within the given precision
920 * provided by prec.
921 *
922 * @param[in] model Model of the kinematic tree.
923 * @param[in] q Configuration to check (size model.nq).
924 * @param[in] prec Precision.
925 *
926 * @return Whether the configuration is normalized or not, within the given precision.
927 */
928 template<
929 typename Scalar,
930 int Options,
931 template<typename, int> class JointCollectionTpl,
932 typename ConfigVectorType>
933 19 bool isNormalized(
934 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
935 const Eigen::MatrixBase<ConfigVectorType> & q,
936 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
937 {
938 19 return isNormalized<LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorType>(
939 19 model, q, prec);
940 }
941
942 /**
943 *
944 * @brief Return true if the given configurations are equivalents, within the given
945 * precision.
946 * @remarks Two configurations can be equivalent but not equally coefficient wise (e.g two
947 * quaternions with opposite coefficients give rise to the same orientation, i.e. they are
948 * equivalent.).
949 *
950 * @param[in] model Model of the kinematic tree.
951 * @param[in] q1 The first configuraiton to compare.
952 * @param[in] q2 The second configuration to compare.
953 * @param[in] prec precision of the comparison.
954 *
955 * @return Whether the configurations are equivalent or not, within the given precision.
956 *
957 */
958 template<
959 typename LieGroup_t,
960 typename Scalar,
961 int Options,
962 template<typename, int> class JointCollectionTpl,
963 typename ConfigVectorIn1,
964 typename ConfigVectorIn2>
965 bool isSameConfiguration(
966 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
967 const Eigen::MatrixBase<ConfigVectorIn1> & q1,
968 const Eigen::MatrixBase<ConfigVectorIn2> & q2,
969 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision());
970
971 /**
972 *
973 * @brief Return true if the given configurations are equivalents, within the given
974 * precision.
975 * @remarks Two configurations can be equivalent but not equally coefficient wise (e.g two
976 * quaternions with opposite coefficients give rise to the same orientation, i.e. they are
977 * equivalent.).
978 *
979 * @param[in] model Model of the kinematic tree.
980 * @param[in] q1 The first configuraiton to compare
981 * @param[in] q2 The second configuration to compare
982 * @param[in] prec precision of the comparison.
983 *
984 * @return Whether the configurations are equivalent or not
985 *
986 */
987 template<
988 typename Scalar,
989 int Options,
990 template<typename, int> class JointCollectionTpl,
991 typename ConfigVectorIn1,
992 typename ConfigVectorIn2>
993 7 bool isSameConfiguration(
994 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
995 const Eigen::MatrixBase<ConfigVectorIn1> & q1,
996 const Eigen::MatrixBase<ConfigVectorIn2> & q2,
997 const Scalar & prec = Eigen::NumTraits<Scalar>::dummy_precision())
998 {
999 return isSameConfiguration<
1000 7 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorIn1, ConfigVectorIn2>(
1001 14 model, q1.derived(), q2.derived(), prec);
1002 }
1003
1004 /**
1005 *
1006 * @brief Return the Jacobian of the integrate function for the components of the config
1007 * vector.
1008 *
1009 * @param[in] model Model of the kinematic tree.
1010 * @param[out] jacobian The Jacobian of the integrate operation.
1011 *
1012 * @details This function is often required for the numerical solvers that are working on
1013 * the tangent of the configuration space, instead of the configuration space itself.
1014 *
1015 */
1016 template<
1017 typename LieGroup_t,
1018 typename Scalar,
1019 int Options,
1020 template<typename, int> class JointCollectionTpl,
1021 typename ConfigVector,
1022 typename JacobianMatrix>
1023 void integrateCoeffWiseJacobian(
1024 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
1025 const Eigen::MatrixBase<ConfigVector> & q,
1026 const Eigen::MatrixBase<JacobianMatrix> & jacobian);
1027
1028 /**
1029 *
1030 * @brief Return the Jacobian of the integrate function for the components of the config
1031 * vector.
1032 *
1033 * @param[in] model Model of the kinematic tree.
1034 * @param[out] jacobian The Jacobian of the integrate operation.
1035 *
1036 * @details This function is often required for the numerical solvers that are working on
1037 * the tangent of the configuration space, instead of the configuration space itself.
1038 *
1039 */
1040 template<
1041 typename Scalar,
1042 int Options,
1043 template<typename, int> class JointCollectionTpl,
1044 typename ConfigVector,
1045 typename JacobianMatrix>
1046 1 void integrateCoeffWiseJacobian(
1047 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
1048 const Eigen::MatrixBase<ConfigVector> & q,
1049 const Eigen::MatrixBase<JacobianMatrix> & jacobian)
1050 {
1051 integrateCoeffWiseJacobian<
1052 1 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVector, JacobianMatrix>(
1053 1 model, q.derived(), PINOCCHIO_EIGEN_CONST_CAST(JacobianMatrix, jacobian));
1054 1 }
1055
1056 /// \}
1057
1058 /// \name API that allocates memory
1059 /// \{
1060
1061 /**
1062 *
1063 * @brief Integrate a configuration vector for the specified model for a tangent vector
1064 * during one unit time
1065 *
1066 * @param[in] model Model of the kinematic tree on which the integration operation is
1067 * performed.
1068 * @param[in] q Initial configuration (size model.nq)
1069 * @param[in] v Joint velocity (size model.nv)
1070 *
1071 * @return The integrated configuration (size model.nq)
1072 *
1073 */
1074 template<
1075 typename LieGroup_t,
1076 typename Scalar,
1077 int Options,
1078 template<typename, int> class JointCollectionTpl,
1079 typename ConfigVectorType,
1080 typename TangentVectorType>
1081 typename PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorType) integrate(
1082 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
1083 const Eigen::MatrixBase<ConfigVectorType> & q,
1084 const Eigen::MatrixBase<TangentVectorType> & v);
1085
1086 /**
1087 *
1088 * @brief Integrate a configuration vector for the specified model for a tangent vector
1089 * during one unit time.
1090 *
1091 * @param[in] model Model of the kinematic tree on which the integration operation is
1092 * performed.
1093 * @param[in] q Initial configuration (size model.nq)
1094 * @param[in] v Joint velocity (size model.nv)
1095 *
1096 * @return The integrated configuration (size model.nq)
1097 *
1098 */
1099 template<
1100 typename Scalar,
1101 int Options,
1102 template<typename, int> class JointCollectionTpl,
1103 typename ConfigVectorType,
1104 typename TangentVectorType>
1105 4088 typename PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorType) integrate(
1106 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
1107 const Eigen::MatrixBase<ConfigVectorType> & q,
1108 const Eigen::MatrixBase<TangentVectorType> & v)
1109 {
1110 return integrate<
1111 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorType, TangentVectorType>(
1112 4088 model, q.derived(), v.derived());
1113 }
1114
1115 /**
1116 *
1117 * @brief Interpolate two configurations for a given model.
1118 *
1119 * @param[in] model Model of the kinematic tree on which the interpolation operation is
1120 * performed.
1121 * @param[in] q0 Initial configuration vector (size model.nq)
1122 * @param[in] q1 Final configuration vector (size model.nq)
1123 * @param[in] u u in [0;1] position along the interpolation.
1124 *
1125 * @return The interpolated configuration (q0 if u = 0, q1 if u = 1)
1126 *
1127 */
1128 template<
1129 typename LieGroup_t,
1130 typename Scalar,
1131 int Options,
1132 template<typename, int> class JointCollectionTpl,
1133 typename ConfigVectorIn1,
1134 typename ConfigVectorIn2>
1135 typename PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorIn1) interpolate(
1136 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
1137 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
1138 const Eigen::MatrixBase<ConfigVectorIn2> & q1,
1139 const Scalar & u);
1140
1141 /**
1142 *
1143 * @brief Interpolate two configurations for a given model.
1144 *
1145 * @param[in] model Model of the kinematic tree on which the interpolation operation is
1146 * performed.
1147 * @param[in] q0 Initial configuration vector (size model.nq)
1148 * @param[in] q1 Final configuration vector (size model.nq)
1149 * @param[in] u u in [0;1] position along the interpolation.
1150 *
1151 * @return The interpolated configuration (q0 if u = 0, q1 if u = 1)
1152 *
1153 */
1154 template<
1155 typename Scalar,
1156 int Options,
1157 template<typename, int> class JointCollectionTpl,
1158 typename ConfigVectorIn1,
1159 typename ConfigVectorIn2>
1160 6 typename PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorIn1) interpolate(
1161 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
1162 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
1163 const Eigen::MatrixBase<ConfigVectorIn2> & q1,
1164 const Scalar & u)
1165 {
1166 return interpolate<
1167 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorIn1, ConfigVectorIn2>(
1168 6 model, q0.derived(), q1.derived(), u);
1169 }
1170
1171 /**
1172 *
1173 * @brief Compute the tangent vector that must be integrated during one unit time to go from
1174 * q0 to q1
1175 *
1176 * @param[in] model Model of the kinematic tree on which the difference operation is performed.
1177 * @param[in] q0 Initial configuration (size model.nq)
1178 * @param[in] q1 Finial configuration (size model.nq)
1179 *
1180 * @return The corresponding velocity (size model.nv)
1181 *
1182 */
1183 template<
1184 typename LieGroup_t,
1185 typename Scalar,
1186 int Options,
1187 template<typename, int> class JointCollectionTpl,
1188 typename ConfigVectorIn1,
1189 typename ConfigVectorIn2>
1190 typename PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorIn1) difference(
1191 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
1192 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
1193 const Eigen::MatrixBase<ConfigVectorIn2> & q1);
1194
1195 /**
1196 *
1197 * @brief Compute the tangent vector that must be integrated during one unit time to go from
1198 * q0 to q1.
1199 *
1200 * @param[in] model Model of the kinematic tree on which the difference operation is performed.
1201 * @param[in] q0 Initial configuration (size model.nq)
1202 * @param[in] q1 Final configuration (size model.nq)
1203 *
1204 * @return The corresponding velocity (size model.nv)
1205 *
1206 */
1207 template<
1208 typename Scalar,
1209 int Options,
1210 template<typename, int> class JointCollectionTpl,
1211 typename ConfigVectorIn1,
1212 typename ConfigVectorIn2>
1213 373 typename PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorIn1) difference(
1214 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
1215 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
1216 const Eigen::MatrixBase<ConfigVectorIn2> & q1)
1217 {
1218 return difference<
1219 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorIn1, ConfigVectorIn2>(
1220 373 model, q0.derived(), q1.derived());
1221 }
1222
1223 /**
1224 *
1225 * @brief Squared distance between two configurations.
1226 *
1227 * @param[in] model Model of the kinematic tree on which the squared distance operation is
1228 * performed.
1229 * @param[in] q0 Configuration 0 (size model.nq)
1230 * @param[in] q1 Configuration 1 (size model.nq)
1231 *
1232 * @return The corresponding squared distances for each joint (size model.njoints-1,
1233 * corresponding to the number of joints)
1234 *
1235 */
1236 template<
1237 typename LieGroup_t,
1238 typename Scalar,
1239 int Options,
1240 template<typename, int> class JointCollectionTpl,
1241 typename ConfigVectorIn1,
1242 typename ConfigVectorIn2>
1243 typename PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorIn1) squaredDistance(
1244 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
1245 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
1246 const Eigen::MatrixBase<ConfigVectorIn2> & q1);
1247
1248 /**
1249 *
1250 * @brief Squared distance between two configuration vectors
1251 *
1252 * @param[in] model Model of the kinematic tree on which the squared distance operation is
1253 * performed.
1254 * @param[in] q0 Configuration 0 (size model.nq)
1255 * @param[in] q1 Configuration 1 (size model.nq)
1256 *
1257 * @return The corresponding squared distances for each joint (size model.njoints-1,
1258 * corresponding to the number of joints)
1259 *
1260 */
1261 template<
1262 typename Scalar,
1263 int Options,
1264 template<typename, int> class JointCollectionTpl,
1265 typename ConfigVectorIn1,
1266 typename ConfigVectorIn2>
1267 3 typename PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorIn1) squaredDistance(
1268 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
1269 const Eigen::MatrixBase<ConfigVectorIn1> & q0,
1270 const Eigen::MatrixBase<ConfigVectorIn2> & q1)
1271 {
1272 return squaredDistance<
1273 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorIn1, ConfigVectorIn2>(
1274 3 model, q0.derived(), q1.derived());
1275 }
1276
1277 /**
1278 *
1279 * @brief Generate a configuration vector uniformly sampled among given limits.
1280 *
1281 * @remarks Limits are not taken into account for rotational transformations (typically
1282 * SO(2),SO(3)), because they are by definition unbounded.
1283 *
1284 * @warning If limits are infinite, exceptions may be thrown in the joint implementation of
1285 * uniformlySample
1286 *
1287 * @param[in] model Model of the kinematic tree on which the uniform sampling
1288 * operation is performed.
1289 * @param[in] lowerLimits Joints lower limits (size model.nq).
1290 * @param[in] upperLimits Joints upper limits (size model.nq).
1291 *
1292 * @return The resulting configuration vector (size model.nq).
1293 *
1294 */
1295 template<
1296 typename LieGroup_t,
1297 typename Scalar,
1298 int Options,
1299 template<typename, int> class JointCollectionTpl,
1300 typename ConfigVectorIn1,
1301 typename ConfigVectorIn2>
1302 typename PINOCCHIO_EIGEN_PLAIN_TYPE_NO_PARENS(
1303 (typename ModelTpl<Scalar, Options, JointCollectionTpl>::ConfigVectorType))
1304 randomConfiguration(
1305 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
1306 const Eigen::MatrixBase<ConfigVectorIn1> & lowerLimits,
1307 const Eigen::MatrixBase<ConfigVectorIn2> & upperLimits);
1308
1309 /**
1310 *
1311 * @brief Generate a configuration vector uniformly sampled among provided limits.
1312 *
1313 * @remarks Limits are not taken into account for rotational transformations (typically
1314 SO(2),SO(3)), because they are by definition unbounded.
1315 *
1316 * @warning If limits are infinite, exceptions may be thrown in the joint implementation of
1317 uniformlySample
1318 *
1319 * @param[in] model Model of the kinematic tree on which the uniform sampling
1320 operation is performed.
1321 * @param[in] lowerLimits Joints lower limits (size model.nq).
1322 * @param[in] upperLimits Joints upper limits (size model.nq).
1323 *
1324 * @return The resulting configuration vector (size model.nq)
1325
1326 */
1327 template<
1328 typename Scalar,
1329 int Options,
1330 template<typename, int> class JointCollectionTpl,
1331 typename ConfigVectorIn1,
1332 typename ConfigVectorIn2>
1333 typename PINOCCHIO_EIGEN_PLAIN_TYPE_NO_PARENS(
1334 (typename ModelTpl<Scalar, Options, JointCollectionTpl>::ConfigVectorType))
1335 86 randomConfiguration(
1336 const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
1337 const Eigen::MatrixBase<ConfigVectorIn1> & lowerLimits,
1338 const Eigen::MatrixBase<ConfigVectorIn2> & upperLimits)
1339 {
1340 return randomConfiguration<
1341 LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorIn1, ConfigVectorIn2>(
1342 86 model, lowerLimits.derived(), upperLimits.derived());
1343 }
1344
1345 /**
1346 *
1347 * @brief Generate a configuration vector uniformly sampled among the joint limits of the
1348 * specified Model.
1349 *
1350 * @remarks Limits are not taken into account for rotational transformations (typically
1351 * SO(2),SO(3)), because they are by definition unbounded.
1352 *
1353 * @warning If limits are infinite (no one specified when adding a body or no modification
1354 * directly in my_model.{lowerPositionLimit,upperPositionLimit}, exceptions may be thrown in the
1355 * joint implementation of uniformlySample
1356 *
1357 * @param[in] model Model of the kinematic tree on which the uniform sampling operation is
1358 * performed.
1359 *
1360 * @return The resulting configuration vector (size model.nq)
1361 *
1362 */
1363 template<
1364 typename LieGroup_t,
1365 typename Scalar,
1366 int Options,
1367 template<typename, int> class JointCollectionTpl>
1368 typename PINOCCHIO_EIGEN_PLAIN_TYPE_NO_PARENS(
1369 (typename ModelTpl<Scalar, Options, JointCollectionTpl>::ConfigVectorType))
1370 randomConfiguration(const ModelTpl<Scalar, Options, JointCollectionTpl> & model);
1371
1372 /**
1373 *
1374 * @brief Generate a configuration vector uniformly sampled among the joint limits of the
1375 * specified Model.
1376 *
1377 * @remarks Limits are not taken into account for rotational transformations (typically
1378 * SO(2),SO(3)), because they are by definition unbounded.
1379 *
1380 * @warning If limits are infinite (no one specified when adding a body or no modification
1381 * directly in my_model.{lowerPositionLimit,upperPositionLimit}, exceptions may be thrown in the
1382 * joint implementation of uniformlySample
1383 *
1384 * @param[in] model Model of the kinematic tree on which the uniform sampling operation is
1385 * performed.
1386 *
1387 * @return The resulting configuration vector (size model.nq).
1388 *
1389 */
1390 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
1391 typename PINOCCHIO_EIGEN_PLAIN_TYPE_NO_PARENS(
1392 (typename ModelTpl<Scalar, Options, JointCollectionTpl>::ConfigVectorType))
1393 2412 randomConfiguration(const ModelTpl<Scalar, Options, JointCollectionTpl> & model)
1394 {
1395 2412 return randomConfiguration<LieGroupMap, Scalar, Options, JointCollectionTpl>(model);
1396 }
1397
1398 /**
1399 *
1400 * @brief Return the neutral configuration element related to the model configuration
1401 * space.
1402 *
1403 * @param[in] model Model of the kinematic tree on which the neutral element is computed.
1404 *
1405 * @return The neutral configuration element (size model.nq).
1406 *
1407 */
1408 template<
1409 typename LieGroup_t,
1410 typename Scalar,
1411 int Options,
1412 template<typename, int> class JointCollectionTpl>
1413 Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options>
1414 neutral(const ModelTpl<Scalar, Options, JointCollectionTpl> & model);
1415
1416 /**
1417 * @brief Return the neutral configuration element related to the model configuration
1418 * space.
1419 *
1420 * @param[in] model Model of the kinematic tree on which the neutral element is computed.
1421 *
1422 * @return The neutral configuration element (size model.nq).
1423 */
1424 template<typename Scalar, int Options, template<typename, int> class JointCollectionTpl>
1425 Eigen::Matrix<Scalar, Eigen::Dynamic, 1, Options>
1426 61 neutral(const ModelTpl<Scalar, Options, JointCollectionTpl> & model)
1427 {
1428 61 return neutral<LieGroupMap, Scalar, Options, JointCollectionTpl>(model);
1429 }
1430
1431 /// \}
1432
1433 } // namespace pinocchio
1434
1435 /* --- Details -------------------------------------------------------------------- */
1436 #include "pinocchio/algorithm/joint-configuration.hxx"
1437
1438 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
1439 #include "pinocchio/algorithm/joint-configuration.txx"
1440 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
1441
1442 #endif // ifndef __pinocchio_algorithm_joint_configuration_hpp__
1443