GCC Code Coverage Report


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