pinocchio  3.7.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
 
Loading...
Searching...
No Matches
joint-revolute.hpp
1//
2// Copyright (c) 2015-2020 CNRS INRIA
3// Copyright (c) 2015-2016 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4//
5
6#ifndef __pinocchio_multibody_joint_revolute_hpp__
7#define __pinocchio_multibody_joint_revolute_hpp__
8
9#include "pinocchio/math/sincos.hpp"
10#include "pinocchio/spatial/inertia.hpp"
11#include "pinocchio/multibody/joint-motion-subspace.hpp"
12#include "pinocchio/multibody/joint/joint-base.hpp"
13#include "pinocchio/spatial/spatial-axis.hpp"
14#include "pinocchio/utils/axis-label.hpp"
15
16namespace pinocchio
17{
18
19 template<typename Scalar, int Options, int axis>
20 struct MotionRevoluteTpl;
21
22 template<typename Scalar, int Options, int axis>
23 struct SE3GroupAction<MotionRevoluteTpl<Scalar, Options, axis>>
24 {
26 };
27
28 template<typename Scalar, int Options, int axis, typename MotionDerived>
29 struct MotionAlgebraAction<MotionRevoluteTpl<Scalar, Options, axis>, MotionDerived>
30 {
32 };
33
34 template<typename _Scalar, int _Options, int axis>
36 {
37 typedef _Scalar Scalar;
38 enum
39 {
40 Options = _Options
41 };
42 typedef Eigen::Matrix<Scalar, 3, 1, Options> Vector3;
43 typedef Eigen::Matrix<Scalar, 6, 1, Options> Vector6;
44 typedef Eigen::Matrix<Scalar, 4, 4, Options> Matrix4;
45 typedef Eigen::Matrix<Scalar, 6, 6, Options> Matrix6;
46 typedef typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector6) ToVectorConstReturnType;
47 typedef typename PINOCCHIO_EIGEN_REF_TYPE(Vector6) ToVectorReturnType;
48 typedef Vector3 AngularType;
49 typedef Vector3 LinearType;
50 typedef const Vector3 ConstAngularType;
51 typedef const Vector3 ConstLinearType;
52 typedef Matrix6 ActionMatrixType;
53 typedef Matrix4 HomogeneousMatrixType;
56 enum
57 {
58 LINEAR = 0,
59 ANGULAR = 3
60 };
61 }; // traits MotionRevoluteTpl
62
63 template<typename Scalar, int Options, int axis>
65
66 template<typename _Scalar, int _Options, int _axis>
68 {
69 enum
70 {
71 axis = _axis,
72 Options = _Options,
73 LINEAR = 0,
74 ANGULAR = 3
75 };
76 typedef _Scalar Scalar;
78 typedef Eigen::Matrix<Scalar, 3, 1, Options> Vector3;
79 typedef Eigen::Matrix<Scalar, 3, 3, Options> Matrix3;
80 typedef Matrix3 AngularType;
81 typedef Matrix3 AngularRef;
82 typedef Matrix3 ConstAngularRef;
83 typedef typename Vector3::ConstantReturnType LinearType;
84 typedef typename Vector3::ConstantReturnType LinearRef;
85 typedef const typename Vector3::ConstantReturnType ConstLinearRef;
86 typedef typename traits<PlainType>::ActionMatrixType ActionMatrixType;
87 typedef typename traits<PlainType>::HomogeneousMatrixType HomogeneousMatrixType;
88 }; // traits TransformRevoluteTpl
89
90 template<typename Scalar, int Options, int axis>
91 struct SE3GroupAction<TransformRevoluteTpl<Scalar, Options, axis>>
92 {
93 typedef typename traits<TransformRevoluteTpl<Scalar, Options, axis>>::PlainType ReturnType;
94 };
95
96 template<typename _Scalar, int _Options, int axis>
97 struct TransformRevoluteTpl : SE3Base<TransformRevoluteTpl<_Scalar, _Options, axis>>
98 {
100 PINOCCHIO_SE3_TYPEDEF_TPL(TransformRevoluteTpl);
101
103 {
104 }
105 TransformRevoluteTpl(const Scalar & sin, const Scalar & cos)
106 : m_sin(sin)
107 , m_cos(cos)
108 {
109 }
110
111 PlainType plain() const
112 {
113 PlainType res(PlainType::Identity());
114 _setRotation(res.rotation());
115 return res;
116 }
117
118 operator PlainType() const
119 {
120 return plain();
121 }
122
123 template<typename S2, int O2>
124 typename SE3GroupAction<TransformRevoluteTpl>::ReturnType
125 se3action(const SE3Tpl<S2, O2> & m) const
126 {
127 typedef typename SE3GroupAction<TransformRevoluteTpl>::ReturnType ReturnType;
128 ReturnType res;
129 switch (axis)
130 {
131 case 0: {
132 res.rotation().col(0) = m.rotation().col(0);
133 res.rotation().col(1).noalias() = m_cos * m.rotation().col(1) + m_sin * m.rotation().col(2);
134 res.rotation().col(2).noalias() = res.rotation().col(0).cross(res.rotation().col(1));
135 break;
136 }
137 case 1: {
138 res.rotation().col(2).noalias() = m_cos * m.rotation().col(2) + m_sin * m.rotation().col(0);
139 res.rotation().col(1) = m.rotation().col(1);
140 res.rotation().col(0).noalias() = res.rotation().col(1).cross(res.rotation().col(2));
141 break;
142 }
143 case 2: {
144 res.rotation().col(0).noalias() = m_cos * m.rotation().col(0) + m_sin * m.rotation().col(1);
145 res.rotation().col(1).noalias() = res.rotation().col(2).cross(res.rotation().col(0));
146 res.rotation().col(2) = m.rotation().col(2);
147 break;
148 }
149 default: {
150 assert(false && "must never happened");
151 break;
152 }
153 }
154 res.translation() = m.translation();
155 return res;
156 }
157
158 const Scalar & sin() const
159 {
160 return m_sin;
161 }
162 Scalar & sin()
163 {
164 return m_sin;
165 }
166
167 const Scalar & cos() const
168 {
169 return m_cos;
170 }
171 Scalar & cos()
172 {
173 return m_cos;
174 }
175
176 template<typename OtherScalar>
177 void setValues(const OtherScalar & sin, const OtherScalar & cos)
178 {
179 m_sin = sin;
180 m_cos = cos;
181 }
182
183 LinearType translation() const
184 {
185 return LinearType::PlainObject::Zero(3);
186 }
187 AngularType rotation() const
188 {
189 AngularType m(AngularType::Identity());
190 _setRotation(m);
191 return m;
192 }
193
194 bool isEqual(const TransformRevoluteTpl & other) const
195 {
196 return internal::comparison_eq(m_cos, other.m_cos)
197 && internal::comparison_eq(m_sin, other.m_sin);
198 }
199
200 protected:
201 Scalar m_sin, m_cos;
202 inline void _setRotation(typename PlainType::AngularRef & rot) const
203 {
204 switch (axis)
205 {
206 case 0: {
207 rot.coeffRef(1, 1) = m_cos;
208 rot.coeffRef(1, 2) = -m_sin;
209 rot.coeffRef(2, 1) = m_sin;
210 rot.coeffRef(2, 2) = m_cos;
211 break;
212 }
213 case 1: {
214 rot.coeffRef(0, 0) = m_cos;
215 rot.coeffRef(0, 2) = m_sin;
216 rot.coeffRef(2, 0) = -m_sin;
217 rot.coeffRef(2, 2) = m_cos;
218 break;
219 }
220 case 2: {
221 rot.coeffRef(0, 0) = m_cos;
222 rot.coeffRef(0, 1) = -m_sin;
223 rot.coeffRef(1, 0) = m_sin;
224 rot.coeffRef(1, 1) = m_cos;
225 break;
226 }
227 default: {
228 assert(false && "must never happened");
229 break;
230 }
231 }
232 }
233 };
234
235 template<typename _Scalar, int _Options, int axis>
236 struct MotionRevoluteTpl : MotionBase<MotionRevoluteTpl<_Scalar, _Options, axis>>
237 {
239
240 MOTION_TYPEDEF_TPL(MotionRevoluteTpl);
242 typedef typename Axis::CartesianAxis3 CartesianAxis3;
243
245 {
246 }
247
248 MotionRevoluteTpl(const Scalar & w)
249 : m_w(w)
250 {
251 }
252
253 template<typename Vector1Like>
254 MotionRevoluteTpl(const Eigen::MatrixBase<Vector1Like> & v)
255 : m_w(v[0])
256 {
257 using namespace Eigen;
259 }
260
261 inline PlainReturnType plain() const
262 {
263 return Axis() * m_w;
264 }
265
266 template<typename OtherScalar>
267 MotionRevoluteTpl __mult__(const OtherScalar & alpha) const
268 {
269 return MotionRevoluteTpl(alpha * m_w);
270 }
271
272 template<typename MotionDerived>
273 void setTo(MotionDense<MotionDerived> & m) const
274 {
275 m.linear().setZero();
276 for (Eigen::DenseIndex k = 0; k < 3; ++k)
277 {
278 m.angular()[k] = k == axis ? m_w : Scalar(0);
279 }
280 }
281
282 template<typename MotionDerived>
283 inline void addTo(MotionDense<MotionDerived> & v) const
284 {
285 typedef typename MotionDense<MotionDerived>::Scalar OtherScalar;
286 v.angular()[axis] += (OtherScalar)m_w;
287 }
288
289 template<typename S2, int O2, typename D2>
290 inline void se3Action_impl(const SE3Tpl<S2, O2> & m, MotionDense<D2> & v) const
291 {
292 v.angular().noalias() = m.rotation().col(axis) * m_w;
293 v.linear().noalias() = m.translation().cross(v.angular());
294 }
295
296 template<typename S2, int O2>
297 MotionPlain se3Action_impl(const SE3Tpl<S2, O2> & m) const
298 {
299 MotionPlain res;
300 se3Action_impl(m, res);
301 return res;
302 }
303
304 template<typename S2, int O2, typename D2>
305 void se3ActionInverse_impl(const SE3Tpl<S2, O2> & m, MotionDense<D2> & v) const
306 {
307 // Linear
308 CartesianAxis3::alphaCross(m_w, m.translation(), v.angular());
309 v.linear().noalias() = m.rotation().transpose() * v.angular();
310
311 // Angular
312 v.angular().noalias() = m.rotation().transpose().col(axis) * m_w;
313 }
314
315 template<typename S2, int O2>
316 MotionPlain se3ActionInverse_impl(const SE3Tpl<S2, O2> & m) const
317 {
318 MotionPlain res;
319 se3ActionInverse_impl(m, res);
320 return res;
321 }
322
323 template<typename M1, typename M2>
324 EIGEN_STRONG_INLINE void motionAction(const MotionDense<M1> & v, MotionDense<M2> & mout) const
325 {
326 // Linear
327 CartesianAxis3::alphaCross(-m_w, v.linear(), mout.linear());
328
329 // Angular
330 CartesianAxis3::alphaCross(-m_w, v.angular(), mout.angular());
331 }
332
333 template<typename M1>
334 MotionPlain motionAction(const MotionDense<M1> & v) const
335 {
336 MotionPlain res;
337 motionAction(v, res);
338 return res;
339 }
340
341 Scalar & angularRate()
342 {
343 return m_w;
344 }
345 const Scalar & angularRate() const
346 {
347 return m_w;
348 }
349
350 bool isEqual_impl(const MotionRevoluteTpl & other) const
351 {
352 return internal::comparison_eq(m_w, other.m_w);
353 }
354
355 protected:
356 Scalar m_w;
357 }; // struct MotionRevoluteTpl
358
359 template<typename S1, int O1, int axis, typename MotionDerived>
360 typename MotionDerived::MotionPlain
362 {
363 typename MotionDerived::MotionPlain res(m2);
364 res += m1;
365 return res;
366 }
367
368 template<typename MotionDerived, typename S2, int O2, int axis>
369 EIGEN_STRONG_INLINE typename MotionDerived::MotionPlain
370 operator^(const MotionDense<MotionDerived> & m1, const MotionRevoluteTpl<S2, O2, axis> & m2)
371 {
372 return m2.motionAction(m1);
373 }
374
375 template<typename Scalar, int Options, int axis>
376 struct JointMotionSubspaceRevoluteTpl;
377
378 template<typename Scalar, int Options, int axis>
379 struct SE3GroupAction<JointMotionSubspaceRevoluteTpl<Scalar, Options, axis>>
380 {
381 typedef Eigen::Matrix<Scalar, 6, 1, Options> ReturnType;
382 };
383
384 template<typename Scalar, int Options, int axis, typename MotionDerived>
386 {
387 typedef Eigen::Matrix<Scalar, 6, 1, Options> ReturnType;
388 };
389
390 template<typename Scalar, int Options, int axis, typename ForceDerived>
392 {
393 typedef typename ForceDense<
394 ForceDerived>::ConstAngularType::template ConstFixedSegmentReturnType<1>::Type ReturnType;
395 };
396
397 template<typename Scalar, int Options, int axis, typename ForceSet>
399 {
400 typedef typename Eigen::MatrixBase<ForceSet>::ConstRowXpr ReturnType;
401 };
402
403 template<typename _Scalar, int _Options, int axis>
405 {
406 typedef _Scalar Scalar;
407 enum
408 {
409 Options = _Options
410 };
411 enum
412 {
413 LINEAR = 0,
414 ANGULAR = 3
415 };
416
418 typedef Eigen::Matrix<Scalar, 1, 1, Options> JointForce;
419 typedef Eigen::Matrix<Scalar, 6, 1, Options> DenseBase;
420 typedef Eigen::Matrix<Scalar, 1, 1, Options> ReducedSquaredMatrix;
421
422 typedef DenseBase MatrixReturnType;
423 typedef const DenseBase ConstMatrixReturnType;
424
425 typedef typename ReducedSquaredMatrix::IdentityReturnType StDiagonalMatrixSOperationReturnType;
426 }; // traits JointMotionSubspaceRevoluteTpl
427
428 template<typename _Scalar, int _Options, int axis>
430 : JointMotionSubspaceBase<JointMotionSubspaceRevoluteTpl<_Scalar, _Options, axis>>
431 {
433
434 PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(JointMotionSubspaceRevoluteTpl)
435 enum
436 {
437 NV = 1
438 };
439
441
443 {
444 }
445
446 template<typename Vector1Like>
447 JointMotion __mult__(const Eigen::MatrixBase<Vector1Like> & v) const
448 {
449 return JointMotion(v[0]);
450 }
451
452 template<typename S1, int O1>
453 typename SE3GroupAction<JointMotionSubspaceRevoluteTpl>::ReturnType
454 se3Action(const SE3Tpl<S1, O1> & m) const
455 {
456 typedef typename SE3GroupAction<JointMotionSubspaceRevoluteTpl>::ReturnType ReturnType;
457 ReturnType res;
458 res.template segment<3>(LINEAR) = m.translation().cross(m.rotation().col(axis));
459 res.template segment<3>(ANGULAR) = m.rotation().col(axis);
460 return res;
461 }
462
463 template<typename S1, int O1>
464 typename SE3GroupAction<JointMotionSubspaceRevoluteTpl>::ReturnType
465 se3ActionInverse(const SE3Tpl<S1, O1> & m) const
466 {
467 typedef typename SE3GroupAction<JointMotionSubspaceRevoluteTpl>::ReturnType ReturnType;
468 typedef typename Axis::CartesianAxis3 CartesianAxis3;
469 ReturnType res;
470 res.template segment<3>(LINEAR).noalias() =
471 m.rotation().transpose() * CartesianAxis3::cross(m.translation());
472 res.template segment<3>(ANGULAR) = m.rotation().transpose().col(axis);
473 return res;
474 }
475
476 int nv_impl() const
477 {
478 return NV;
479 }
480
481 struct TransposeConst : JointMotionSubspaceTransposeBase<JointMotionSubspaceRevoluteTpl>
482 {
485 : ref(ref)
486 {
487 }
488
489 template<typename ForceDerived>
491 operator*(const ForceDense<ForceDerived> & f) const
492 {
493 return f.angular().template segment<1>(axis);
494 }
495
497 template<typename Derived>
499 operator*(const Eigen::MatrixBase<Derived> & F) const
500 {
501 assert(F.rows() == 6);
502 return F.row(ANGULAR + axis);
503 }
504 }; // struct TransposeConst
505
506 TransposeConst transpose() const
507 {
508 return TransposeConst(*this);
509 }
510
511 /* CRBA joint operators
512 * - ForceSet::Block = ForceSet
513 * - ForceSet operator* (Inertia Y,Constraint S)
514 * - MatrixBase operator* (Constraint::Transpose S, ForceSet::Block)
515 * - SE3::act(ForceSet::Block)
516 */
517 DenseBase matrix_impl() const
518 {
519 DenseBase S;
520 MotionRef<DenseBase> v(S);
521 v << Axis();
522 return S;
523 }
524
525 template<typename MotionDerived>
526 typename MotionAlgebraAction<JointMotionSubspaceRevoluteTpl, MotionDerived>::ReturnType
527 motionAction(const MotionDense<MotionDerived> & m) const
528 {
529 typedef
530 typename MotionAlgebraAction<JointMotionSubspaceRevoluteTpl, MotionDerived>::ReturnType
531 ReturnType;
532 ReturnType res;
533 MotionRef<ReturnType> v(res);
534 v = m.cross(Axis());
535 return res;
536 }
537
538 bool isEqual(const JointMotionSubspaceRevoluteTpl &) const
539 {
540 return true;
541 }
542
543 }; // struct JointMotionSubspaceRevoluteTpl
544
545 template<typename _Scalar, int _Options, int _axis>
547 {
548 typedef _Scalar Scalar;
549
550 enum
551 {
552 Options = _Options,
553 axis = _axis
554 };
555 };
556
557 template<typename S1, int O1, typename S2, int O2, int axis>
559 {
560 typedef Eigen::Matrix<S2, 6, 1, O2> ReturnType;
561 };
562
563 /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
564 namespace impl
565 {
566 template<typename S1, int O1, typename S2, int O2>
568 {
571 typedef typename MultiplicationOp<Inertia, Constraint>::ReturnType ReturnType;
572 static inline ReturnType run(const Inertia & Y, const Constraint & /*constraint*/)
573 {
574 ReturnType res;
575
576 /* Y(:,3) = ( 0,-z, y, I00+yy+zz, I01-xy , I02-xz ) */
577 const S1 &m = Y.mass(), &x = Y.lever()[0], &y = Y.lever()[1], &z = Y.lever()[2];
578 const typename Inertia::Symmetric3 & I = Y.inertia();
579
580 res << (S2)0, -m * z, m * y, I(0, 0) + m * (y * y + z * z), I(0, 1) - m * x * y,
581 I(0, 2) - m * x * z;
582
583 return res;
584 }
585 };
586
587 template<typename S1, int O1, typename S2, int O2>
589 {
592 typedef typename MultiplicationOp<Inertia, Constraint>::ReturnType ReturnType;
593 static inline ReturnType run(const Inertia & Y, const Constraint & /*constraint*/)
594 {
595 ReturnType res;
596
597 /* Y(:,4) = ( z, 0,-x, I10-xy , I11+xx+zz, I12-yz ) */
598 const S1 &m = Y.mass(), &x = Y.lever()[0], &y = Y.lever()[1], &z = Y.lever()[2];
599 const typename Inertia::Symmetric3 & I = Y.inertia();
600
601 res << m * z, (S2)0, -m * x, I(1, 0) - m * x * y, I(1, 1) + m * (x * x + z * z),
602 I(1, 2) - m * y * z;
603
604 return res;
605 }
606 };
607
608 template<typename S1, int O1, typename S2, int O2>
610 {
613 typedef typename MultiplicationOp<Inertia, Constraint>::ReturnType ReturnType;
614 static inline ReturnType run(const Inertia & Y, const Constraint & /*constraint*/)
615 {
616 ReturnType res;
617
618 /* Y(:,5) = (-y, x, 0, I20-xz , I21-yz , I22+xx+yy) */
619 const S1 &m = Y.mass(), &x = Y.lever()[0], &y = Y.lever()[1], &z = Y.lever()[2];
620 const typename Inertia::Symmetric3 & I = Y.inertia();
621
622 res << -m * y, m * x, (S2)0, I(2, 0) - m * x * z, I(2, 1) - m * y * z,
623 I(2, 2) + m * (x * x + y * y);
624
625 return res;
626 }
627 };
628 } // namespace impl
629
630 template<typename M6Like, typename S2, int O2, int axis>
631 struct MultiplicationOp<Eigen::MatrixBase<M6Like>, JointMotionSubspaceRevoluteTpl<S2, O2, axis>>
632 {
633 typedef typename M6Like::ConstColXpr ReturnType;
634 };
635
636 /* [ABA] operator* (Inertia Y,Constraint S) */
637 namespace impl
638 {
639 template<typename M6Like, typename Scalar, int Options, int axis>
641 Eigen::MatrixBase<M6Like>,
642 JointMotionSubspaceRevoluteTpl<Scalar, Options, axis>>
643 {
645 typedef
646 typename MultiplicationOp<Eigen::MatrixBase<M6Like>, Constraint>::ReturnType ReturnType;
647 static inline ReturnType
648 run(const Eigen::MatrixBase<M6Like> & Y, const Constraint & /*constraint*/)
649 {
651 return Y.col(Inertia::ANGULAR + axis);
652 }
653 };
654 } // namespace impl
655
656 template<typename _Scalar, int _Options, int axis>
658 {
659 enum
660 {
661 NQ = 1,
662 NV = 1,
663 NVExtended = 1
664 };
665 typedef _Scalar Scalar;
666 enum
667 {
668 Options = _Options
669 };
676
677 // [ABA]
678 typedef Eigen::Matrix<Scalar, 6, NV, Options> U_t;
679 typedef Eigen::Matrix<Scalar, NV, NV, Options> D_t;
680 typedef Eigen::Matrix<Scalar, 6, NV, Options> UD_t;
681
682 typedef Eigen::Matrix<Scalar, NQ, 1, Options> ConfigVector_t;
683 typedef Eigen::Matrix<Scalar, NV, 1, Options> TangentVector_t;
684
685 typedef boost::mpl::true_ is_mimicable_t;
686
687 PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
688 };
689
690 template<typename _Scalar, int _Options, int axis>
696
697 template<typename _Scalar, int _Options, int axis>
703
704 template<typename _Scalar, int _Options, int axis>
705 struct JointDataRevoluteTpl : public JointDataBase<JointDataRevoluteTpl<_Scalar, _Options, axis>>
706 {
709 PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived);
710 PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
711
712 ConfigVector_t joint_q;
713 TangentVector_t joint_v;
714
715 Constraint_t S;
716 Transformation_t M;
717 Motion_t v;
718 Bias_t c;
719
720 // [ABA] specific data
721 U_t U;
722 D_t Dinv;
723 UD_t UDinv;
724 D_t StU;
725
727 : joint_q(ConfigVector_t::Zero())
728 , joint_v(TangentVector_t::Zero())
729 , M((Scalar)0, (Scalar)1)
730 , v((Scalar)0)
731 , U(U_t::Zero())
732 , Dinv(D_t::Zero())
733 , UDinv(UD_t::Zero())
734 , StU(D_t::Zero())
735 {
736 }
737
738 static std::string classname()
739 {
740 return std::string("JointDataR") + axisLabel<axis>();
741 }
742 std::string shortname() const
743 {
744 return classname();
745 }
746
747 }; // struct JointDataRevoluteTpl
748
749 template<typename NewScalar, typename Scalar, int Options, int axis>
750 struct CastType<NewScalar, JointModelRevoluteTpl<Scalar, Options, axis>>
751 {
753 };
754
755 template<typename _Scalar, int _Options, int axis>
757 : public JointModelBase<JointModelRevoluteTpl<_Scalar, _Options, axis>>
758 {
761 PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived);
762
764 using Base::id;
765 using Base::idx_q;
766 using Base::idx_v;
767 using Base::idx_vExtended;
768 using Base::setIndexes;
769
770 typedef Eigen::Matrix<Scalar, 3, 1, _Options> Vector3;
771
772 JointDataDerived createData() const
773 {
774 return JointDataDerived();
775 }
776
778 {
779 }
780
781 const std::vector<bool> hasConfigurationLimit() const
782 {
783 return {true};
784 }
785
786 const std::vector<bool> hasConfigurationLimitInTangent() const
787 {
788 return {true};
789 }
790
791 template<typename ConfigVector>
792 PINOCCHIO_DONT_INLINE void
793 calc(JointDataDerived & data, const typename Eigen::MatrixBase<ConfigVector> & qs) const
794 {
795 data.joint_q[0] = qs[idx_q()];
796 Scalar ca, sa;
797 SINCOS(data.joint_q[0], &sa, &ca);
798 data.M.setValues(sa, ca);
799 }
800
801 template<typename TangentVector>
802 PINOCCHIO_DONT_INLINE void
803 calc(JointDataDerived & data, const Blank, const typename Eigen::MatrixBase<TangentVector> & vs)
804 const
805 {
806 data.joint_v[0] = vs[idx_v()];
807 data.v.angularRate() = data.joint_v[0];
808 }
809
810 template<typename ConfigVector, typename TangentVector>
811 PINOCCHIO_DONT_INLINE void calc(
812 JointDataDerived & data,
813 const typename Eigen::MatrixBase<ConfigVector> & qs,
814 const typename Eigen::MatrixBase<TangentVector> & vs) const
815 {
816 calc(data, qs.derived());
817
818 data.joint_v[0] = vs[idx_v()];
819 data.v.angularRate() = data.joint_v[0];
820 }
821
822 template<typename VectorLike, typename Matrix6Like>
823 void calc_aba(
824 JointDataDerived & data,
825 const Eigen::MatrixBase<VectorLike> & armature,
826 const Eigen::MatrixBase<Matrix6Like> & I,
827 const bool update_I) const
828 {
829 data.U = I.col(Inertia::ANGULAR + axis);
830 data.Dinv[0] =
831 Scalar(1) / (I(Inertia::ANGULAR + axis, Inertia::ANGULAR + axis) + armature[0]);
832 data.UDinv.noalias() = data.U * data.Dinv[0];
833
834 if (update_I)
835 PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose();
836 }
837
838 static std::string classname()
839 {
840 return std::string("JointModelR") + axisLabel<axis>();
841 }
842 std::string shortname() const
843 {
844 return classname();
845 }
846
847 Vector3 getMotionAxis() const
848 {
849 switch (axis)
850 {
851 case 0:
852 return Vector3::UnitX();
853 case 1:
854 return Vector3::UnitY();
855 case 2:
856 return Vector3::UnitZ();
857 default:
858 assert(false && "must never happen");
859 break;
860 }
861 }
862
864 template<typename NewScalar>
866 {
868 ReturnType res;
869 res.setIndexes(id(), idx_q(), idx_v(), idx_vExtended());
870 return res;
871 }
872
873 }; // struct JointModelRevoluteTpl
874
875 typedef JointRevoluteTpl<context::Scalar, context::Options, 0> JointRX;
876 typedef JointDataRevoluteTpl<context::Scalar, context::Options, 0> JointDataRX;
877 typedef JointModelRevoluteTpl<context::Scalar, context::Options, 0> JointModelRX;
878
879 typedef JointRevoluteTpl<context::Scalar, context::Options, 1> JointRY;
880 typedef JointDataRevoluteTpl<context::Scalar, context::Options, 1> JointDataRY;
881 typedef JointModelRevoluteTpl<context::Scalar, context::Options, 1> JointModelRY;
882
883 typedef JointRevoluteTpl<context::Scalar, context::Options, 2> JointRZ;
884 typedef JointDataRevoluteTpl<context::Scalar, context::Options, 2> JointDataRZ;
885 typedef JointModelRevoluteTpl<context::Scalar, context::Options, 2> JointModelRZ;
886
887 template<typename Scalar, int Options, int axis>
888 struct ConfigVectorAffineTransform<JointRevoluteTpl<Scalar, Options, axis>>
889 {
891 };
892} // namespace pinocchio
893
894#include <boost/type_traits.hpp>
895
896namespace boost
897{
898 template<typename Scalar, int Options, int axis>
899 struct has_nothrow_constructor<::pinocchio::JointModelRevoluteTpl<Scalar, Options, axis>>
900 : public integral_constant<bool, true>
901 {
902 };
903
904 template<typename Scalar, int Options, int axis>
905 struct has_nothrow_copy<::pinocchio::JointModelRevoluteTpl<Scalar, Options, axis>>
906 : public integral_constant<bool, true>
907 {
908 };
909
910 template<typename Scalar, int Options, int axis>
911 struct has_nothrow_constructor<::pinocchio::JointDataRevoluteTpl<Scalar, Options, axis>>
912 : public integral_constant<bool, true>
913 {
914 };
915
916 template<typename Scalar, int Options, int axis>
917 struct has_nothrow_copy<::pinocchio::JointDataRevoluteTpl<Scalar, Options, axis>>
918 : public integral_constant<bool, true>
919 {
920 };
921} // namespace boost
922
923#endif // ifndef __pinocchio_multibody_joint_revolute_hpp__
Main pinocchio namespace.
Definition treeview.dox:11
void SINCOS(const S1 &a, S2 *sa, S3 *ca)
Computes sin/cos values of a given input scalar.
Definition sincos.hpp:27
JointDataTpl< Scalar, Options, JointCollectionTpl >::TangentVector_t joint_v(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataVariant through JointConfigVisitor to get the joint velocity vector.
JointDataTpl< Scalar, Options, JointCollectionTpl >::ConfigVector_t joint_q(const JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata)
Visit a JointDataVariant through JointConfigVisitor to get the joint configuration vector.
Blank type.
Definition fwd.hpp:77
Type of the cast of a class C templated by Scalar and Options, to a new NewScalar type....
Definition fwd.hpp:99
Assign the correct configuration vector space affine transformation according to the joint type....
Return type of the Constraint::Transpose * Force operation.
Return type of the Constraint::Transpose * ForceSet operation.
JointModelRevoluteTpl< NewScalar, Options, axis > cast() const
ConstraintForceSetOp< JointMotionSubspaceRevoluteTpl, Derived >::ReturnType operator*(const Eigen::MatrixBase< Derived > &F) const
[CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block)
Linear affine transformation of the configuration vector. Valide for most common joints which are evo...
Return type of the ation of a Motion onto an object of type D.
Definition motion.hpp:46
Forward declaration of the multiplication operation return type. Should be overloaded,...
Definition binary-op.hpp:15
Base class for rigid transformation.
Definition se3-base.hpp:31
Common traits structure to fully define base classes for CRTP.
Definition fwd.hpp:72