pinocchio  3.7.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
 
Loading...
Searching...
No Matches
joint-spherical.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_spherical_hpp__
7#define __pinocchio_multibody_joint_spherical_hpp__
8
9#include "pinocchio/macros.hpp"
10#include "pinocchio/multibody/joint/joint-base.hpp"
11#include "pinocchio/multibody/joint-motion-subspace.hpp"
12#include "pinocchio/math/sincos.hpp"
13#include "pinocchio/spatial/inertia.hpp"
14#include "pinocchio/spatial/skew.hpp"
15
16namespace pinocchio
17{
18
19 template<typename Scalar, int Options = context::Options>
20 struct MotionSphericalTpl;
21 typedef MotionSphericalTpl<context::Scalar> MotionSpherical;
22
23 template<typename Scalar, int Options>
24 struct SE3GroupAction<MotionSphericalTpl<Scalar, Options>>
25 {
27 };
28
29 template<typename Scalar, int Options, typename MotionDerived>
34
35 template<typename _Scalar, int _Options>
37 {
38 typedef _Scalar Scalar;
39 enum
40 {
41 Options = _Options
42 };
43 typedef Eigen::Matrix<Scalar, 3, 1, Options> Vector3;
44 typedef Eigen::Matrix<Scalar, 6, 1, Options> Vector6;
45 typedef Eigen::Matrix<Scalar, 4, 4, Options> Matrix4;
46 typedef Eigen::Matrix<Scalar, 6, 6, Options> Matrix6;
47 typedef typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector6) ToVectorConstReturnType;
48 typedef typename PINOCCHIO_EIGEN_REF_TYPE(Vector6) ToVectorReturnType;
49 typedef Vector3 AngularType;
50 typedef Vector3 LinearType;
51 typedef const Vector3 ConstAngularType;
52 typedef const Vector3 ConstLinearType;
53 typedef Matrix6 ActionMatrixType;
54 typedef Matrix4 HomogeneousMatrixType;
57 enum
58 {
59 LINEAR = 0,
60 ANGULAR = 3
61 };
62 }; // traits MotionSphericalTpl
63
64 template<typename _Scalar, int _Options>
65 struct MotionSphericalTpl : MotionBase<MotionSphericalTpl<_Scalar, _Options>>
66 {
68
69 MOTION_TYPEDEF_TPL(MotionSphericalTpl);
70
72 {
73 }
74
75 template<typename Vector3Like>
76 MotionSphericalTpl(const Eigen::MatrixBase<Vector3Like> & w)
77 : m_w(w)
78 {
79 }
80
81 Vector3 & operator()()
82 {
83 return m_w;
84 }
85 const Vector3 & operator()() const
86 {
87 return m_w;
88 }
89
90 inline PlainReturnType plain() const
91 {
92 return PlainReturnType(PlainReturnType::Vector3::Zero(), m_w);
93 }
94
95 template<typename MotionDerived>
96 void addTo(MotionDense<MotionDerived> & other) const
97 {
98 other.angular() += m_w;
99 }
100
101 template<typename Derived>
102 void setTo(MotionDense<Derived> & other) const
103 {
104 other.linear().setZero();
105 other.angular() = m_w;
106 }
107
108 MotionSphericalTpl __plus__(const MotionSphericalTpl & other) const
109 {
110 return MotionSphericalTpl(m_w + other.m_w);
111 }
112
113 bool isEqual_impl(const MotionSphericalTpl & other) const
114 {
115 return internal::comparison_eq(m_w, other.m_w);
116 }
117
118 template<typename MotionDerived>
119 bool isEqual_impl(const MotionDense<MotionDerived> & other) const
120 {
121 return internal::comparison_eq(other.angular(), m_w) && other.linear().isZero(0);
122 }
123
124 template<typename S2, int O2, typename D2>
125 void se3Action_impl(const SE3Tpl<S2, O2> & m, MotionDense<D2> & v) const
126 {
127 // Angular
128 v.angular().noalias() = m.rotation() * m_w;
129
130 // Linear
131 v.linear().noalias() = m.translation().cross(v.angular());
132 }
133
134 template<typename S2, int O2>
135 MotionPlain se3Action_impl(const SE3Tpl<S2, O2> & m) const
136 {
137 MotionPlain res;
138 se3Action_impl(m, res);
139 return res;
140 }
141
142 template<typename S2, int O2, typename D2>
143 void se3ActionInverse_impl(const SE3Tpl<S2, O2> & m, MotionDense<D2> & v) const
144 {
145 // Linear
146 // TODO: use v.angular() as temporary variable
147 Vector3 v3_tmp;
148 v3_tmp.noalias() = m_w.cross(m.translation());
149 v.linear().noalias() = m.rotation().transpose() * v3_tmp;
150
151 // Angular
152 v.angular().noalias() = m.rotation().transpose() * m_w;
153 }
154
155 template<typename S2, int O2>
156 MotionPlain se3ActionInverse_impl(const SE3Tpl<S2, O2> & m) const
157 {
158 MotionPlain res;
159 se3ActionInverse_impl(m, res);
160 return res;
161 }
162
163 template<typename M1, typename M2>
164 void motionAction(const MotionDense<M1> & v, MotionDense<M2> & mout) const
165 {
166 // Linear
167 mout.linear().noalias() = v.linear().cross(m_w);
168
169 // Angular
170 mout.angular().noalias() = v.angular().cross(m_w);
171 }
172
173 template<typename M1>
174 MotionPlain motionAction(const MotionDense<M1> & v) const
175 {
176 MotionPlain res;
177 motionAction(v, res);
178 return res;
179 }
180
181 const Vector3 & angular() const
182 {
183 return m_w;
184 }
185 Vector3 & angular()
186 {
187 return m_w;
188 }
189
190 protected:
191 Vector3 m_w;
192 }; // struct MotionSphericalTpl
193
194 template<typename S1, int O1, typename MotionDerived>
195 inline typename MotionDerived::MotionPlain
197 {
198 return typename MotionDerived::MotionPlain(m2.linear(), m2.angular() + m1.angular());
199 }
200
201 template<typename Scalar, int Options>
202 struct JointMotionSubspaceSphericalTpl;
203
204 template<typename _Scalar, int _Options>
206 {
207 typedef _Scalar Scalar;
208 enum
209 {
210 Options = _Options
211 };
212 enum
213 {
214 LINEAR = 0,
215 ANGULAR = 3
216 };
218 typedef Eigen::Matrix<Scalar, 3, 1, Options> JointForce;
219 typedef Eigen::Matrix<Scalar, 6, 3, Options> DenseBase;
220 typedef Eigen::Matrix<Scalar, 3, 3, Options> ReducedSquaredMatrix;
221
222 typedef DenseBase MatrixReturnType;
223 typedef const DenseBase ConstMatrixReturnType;
224
225 typedef typename ReducedSquaredMatrix::IdentityReturnType StDiagonalMatrixSOperationReturnType;
226 }; // struct traits struct JointMotionSubspaceSphericalTpl
227
228 template<typename _Scalar, int _Options>
230 : public JointMotionSubspaceBase<JointMotionSubspaceSphericalTpl<_Scalar, _Options>>
231 {
233
234 PINOCCHIO_CONSTRAINT_TYPEDEF_TPL(JointMotionSubspaceSphericalTpl)
235
237 {
238 }
239
240 enum
241 {
242 NV = 3
243 };
244
245 int nv_impl() const
246 {
247 return NV;
248 }
249
250 template<typename Vector3Like>
251 JointMotion __mult__(const Eigen::MatrixBase<Vector3Like> & w) const
252 {
254 return JointMotion(w);
255 }
256
257 struct TransposeConst : JointMotionSubspaceTransposeBase<JointMotionSubspaceSphericalTpl>
258 {
259 template<typename Derived>
261 {
262 return phi.angular();
263 }
264
265 /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
266 template<typename MatrixDerived>
267 const typename SizeDepType<3>::RowsReturn<MatrixDerived>::ConstType
268 operator*(const Eigen::MatrixBase<MatrixDerived> & F) const
269 {
270 assert(F.rows() == 6);
271 return F.derived().template middleRows<3>(Inertia::ANGULAR);
272 }
273 };
274
275 TransposeConst transpose() const
276 {
277 return TransposeConst();
278 }
279
280 DenseBase matrix_impl() const
281 {
282 DenseBase S;
283 S.template block<3, 3>(LINEAR, 0).setZero();
284 S.template block<3, 3>(ANGULAR, 0).setIdentity();
285 return S;
286 }
287
288 template<typename S1, int O1>
289 Eigen::Matrix<S1, 6, 3, O1> se3Action(const SE3Tpl<S1, O1> & m) const
290 {
291 Eigen::Matrix<S1, 6, 3, O1> X_subspace;
292 cross(m.translation(), m.rotation(), X_subspace.template middleRows<3>(LINEAR));
293 X_subspace.template middleRows<3>(ANGULAR) = m.rotation();
294
295 return X_subspace;
296 }
297
298 template<typename S1, int O1>
299 Eigen::Matrix<S1, 6, 3, O1> se3ActionInverse(const SE3Tpl<S1, O1> & m) const
300 {
301 Eigen::Matrix<S1, 6, 3, O1> X_subspace;
302 XAxis::cross(m.translation(), X_subspace.template middleRows<3>(ANGULAR).col(0));
303 YAxis::cross(m.translation(), X_subspace.template middleRows<3>(ANGULAR).col(1));
304 ZAxis::cross(m.translation(), X_subspace.template middleRows<3>(ANGULAR).col(2));
305
306 X_subspace.template middleRows<3>(LINEAR).noalias() =
307 m.rotation().transpose() * X_subspace.template middleRows<3>(ANGULAR);
308 X_subspace.template middleRows<3>(ANGULAR) = m.rotation().transpose();
309
310 return X_subspace;
311 }
312
313 template<typename MotionDerived>
314 DenseBase motionAction(const MotionDense<MotionDerived> & m) const
315 {
316 const typename MotionDerived::ConstLinearType v = m.linear();
317 const typename MotionDerived::ConstAngularType w = m.angular();
318
319 DenseBase res;
320 skew(v, res.template middleRows<3>(LINEAR));
321 skew(w, res.template middleRows<3>(ANGULAR));
322
323 return res;
324 }
325
326 bool isEqual(const JointMotionSubspaceSphericalTpl &) const
327 {
328 return true;
329 }
330
331 }; // struct JointMotionSubspaceSphericalTpl
332
333 template<typename MotionDerived, typename S2, int O2>
334 inline typename MotionDerived::MotionPlain
335 operator^(const MotionDense<MotionDerived> & m1, const MotionSphericalTpl<S2, O2> & m2)
336 {
337 return m2.motionAction(m1);
338 }
339
340 /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
341 template<typename S1, int O1, typename S2, int O2>
342 inline Eigen::Matrix<S2, 6, 3, O2>
343 operator*(const InertiaTpl<S1, O1> & Y, const JointMotionSubspaceSphericalTpl<S2, O2> &)
344 {
345 typedef InertiaTpl<S1, O1> Inertia;
346 typedef typename Inertia::Symmetric3 Symmetric3;
347 Eigen::Matrix<S2, 6, 3, O2> M;
348 // M.block <3,3> (Inertia::LINEAR, 0) = - Y.mass () * skew(Y.lever ());
349 M.template block<3, 3>(Inertia::LINEAR, 0) = alphaSkew(-Y.mass(), Y.lever());
350 M.template block<3, 3>(Inertia::ANGULAR, 0) =
351 (Y.inertia() - typename Symmetric3::AlphaSkewSquare(Y.mass(), Y.lever())).matrix();
352 return M;
353 }
354
355 /* [ABA] Y*S operator*/
356 template<typename M6Like, typename S2, int O2>
357 inline typename SizeDepType<3>::ColsReturn<M6Like>::ConstType
358 operator*(const Eigen::MatrixBase<M6Like> & Y, const JointMotionSubspaceSphericalTpl<S2, O2> &)
359 {
360 typedef JointMotionSubspaceSphericalTpl<S2, O2> Constraint;
361 return Y.derived().template middleCols<3>(Constraint::ANGULAR);
362 }
363
364 template<typename S1, int O1>
366 {
367 typedef Eigen::Matrix<S1, 6, 3, O1> ReturnType;
368 };
369
370 template<typename S1, int O1, typename MotionDerived>
372 {
373 typedef Eigen::Matrix<S1, 6, 3, O1> ReturnType;
374 };
375
376 template<typename Scalar, int Options>
378
379 template<typename _Scalar, int _Options>
381 {
382 enum
383 {
384 NQ = 4,
385 NV = 3,
386 NVExtended = 3
387 };
388 typedef _Scalar Scalar;
389 enum
390 {
391 Options = _Options
392 };
399
400 // [ABA]
401 typedef Eigen::Matrix<Scalar, 6, NV, Options> U_t;
402 typedef Eigen::Matrix<Scalar, NV, NV, Options> D_t;
403 typedef Eigen::Matrix<Scalar, 6, NV, Options> UD_t;
404
405 typedef Eigen::Matrix<Scalar, NQ, 1, Options> ConfigVector_t;
406 typedef Eigen::Matrix<Scalar, NV, 1, Options> TangentVector_t;
407
408 typedef boost::mpl::false_ is_mimicable_t;
409
410 PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
411 };
412
413 template<typename _Scalar, int _Options>
419
420 template<typename _Scalar, int _Options>
426
427 template<typename _Scalar, int _Options>
428 struct JointDataSphericalTpl : public JointDataBase<JointDataSphericalTpl<_Scalar, _Options>>
429 {
431
433 PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE(JointDerived);
434 PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
435
436 ConfigVector_t joint_q;
437 TangentVector_t joint_v;
438
439 Constraint_t S;
440 Transformation_t M;
441 Motion_t v;
442 Bias_t c;
443
444 // [ABA] specific data
445 U_t U;
446 D_t Dinv;
447 UD_t UDinv;
448 D_t StU;
449
451 : joint_q(Scalar(0), Scalar(0), Scalar(0), Scalar(1))
452 , joint_v(TangentVector_t::Zero())
453 , M(Transformation_t::Identity())
454 , v(Motion_t::Vector3::Zero())
455 , U(U_t::Zero())
456 , Dinv(D_t::Zero())
457 , UDinv(UD_t::Zero())
458 , StU(D_t::Zero())
459 {
460 }
461
462 static std::string classname()
463 {
464 return std::string("JointDataSpherical");
465 }
466 std::string shortname() const
467 {
468 return classname();
469 }
470
471 }; // struct JointDataSphericalTpl
472
473 PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelSphericalTpl);
474 template<typename _Scalar, int _Options>
475 struct JointModelSphericalTpl : public JointModelBase<JointModelSphericalTpl<_Scalar, _Options>>
476 {
478
480 PINOCCHIO_JOINT_TYPEDEF_TEMPLATE(JointDerived);
481
483 using Base::id;
484 using Base::idx_q;
485 using Base::idx_v;
486 using Base::idx_vExtended;
487 using Base::setIndexes;
488
489 JointDataDerived createData() const
490 {
491 return JointDataDerived();
492 }
493
494 const std::vector<bool> hasConfigurationLimit() const
495 {
496 return {false, false, false, false};
497 }
498
499 const std::vector<bool> hasConfigurationLimitInTangent() const
500 {
501 return {false, false, false};
502 }
503
504 template<typename ConfigVectorLike>
505 inline void forwardKinematics(
506 Transformation_t & M, const Eigen::MatrixBase<ConfigVectorLike> & q_joint) const
507 {
508 typedef typename ConfigVectorLike::Scalar Scalar;
510 typedef
511 typename Eigen::Quaternion<Scalar, PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorLike)::Options>
512 Quaternion;
513 typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
514
515 ConstQuaternionMap quat(q_joint.derived().data());
516 // assert(math::fabs(quat.coeffs().squaredNorm()-1.) <= sqrt(Eigen::NumTraits<typename
517 // V::Scalar>::epsilon())); TODO: check validity of the rhs precision
518 assert(math::fabs(static_cast<Scalar>(quat.coeffs().squaredNorm() - 1)) <= 1e-4);
519
520 M.rotation(quat.matrix());
521 M.translation().setZero();
522 }
523
524 template<typename QuaternionDerived>
525 void calc(
526 JointDataDerived & data, const typename Eigen::QuaternionBase<QuaternionDerived> & quat) const
527 {
528 data.joint_q = quat.coeffs();
529 data.M.rotation(quat.matrix());
530 }
531
532 template<typename ConfigVector>
533 PINOCCHIO_DONT_INLINE void
534 calc(JointDataDerived & data, const typename Eigen::PlainObjectBase<ConfigVector> & qs) const
535 {
536 typedef typename Eigen::Quaternion<typename ConfigVector::Scalar, ConfigVector::Options>
537 Quaternion;
538 typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
539
540 ConstQuaternionMap quat(qs.template segment<NQ>(idx_q()).data());
541 calc(data, quat);
542 }
543
544 template<typename ConfigVector>
545 PINOCCHIO_DONT_INLINE void
546 calc(JointDataDerived & data, const typename Eigen::MatrixBase<ConfigVector> & qs) const
547 {
548 typedef typename Eigen::Quaternion<Scalar, Options> Quaternion;
549
550 const Quaternion quat(qs.template segment<NQ>(idx_q()));
551 calc(data, quat);
552 }
553
554 template<typename TangentVector>
555 void
556 calc(JointDataDerived & data, const Blank, const typename Eigen::MatrixBase<TangentVector> & vs)
557 const
558 {
559 data.joint_v = vs.template segment<NV>(idx_v());
560 data.v.angular() = data.joint_v;
561 }
562
563 template<typename ConfigVector, typename TangentVector>
564 void calc(
565 JointDataDerived & data,
566 const typename Eigen::MatrixBase<ConfigVector> & qs,
567 const typename Eigen::MatrixBase<TangentVector> & vs) const
568 {
569 calc(data, qs.derived());
570 data.joint_v = vs.template segment<NV>(idx_v());
571 data.v.angular() = data.joint_v;
572 }
573
574 template<typename VectorLike, typename Matrix6Like>
575 void calc_aba(
576 JointDataDerived & data,
577 const Eigen::MatrixBase<VectorLike> & armature,
578 const Eigen::MatrixBase<Matrix6Like> & I,
579 const bool update_I) const
580 {
581 data.U = I.template block<6, 3>(0, Inertia::ANGULAR);
582 data.StU = data.U.template middleRows<3>(Inertia::ANGULAR);
583 data.StU.diagonal() += armature;
584
585 internal::PerformStYSInversion<Scalar>::run(data.StU, data.Dinv);
586 data.UDinv.noalias() = data.U * data.Dinv;
587
588 if (update_I)
589 PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose();
590 }
591
592 static std::string classname()
593 {
594 return std::string("JointModelSpherical");
595 }
596 std::string shortname() const
597 {
598 return classname();
599 }
600
602 template<typename NewScalar>
604 {
606 ReturnType res;
607 res.setIndexes(id(), idx_q(), idx_v(), idx_vExtended());
608 return res;
609 }
610
611 }; // struct JointModelSphericalTpl
612
613} // namespace pinocchio
614
615#include <boost/type_traits.hpp>
616
617namespace boost
618{
619 template<typename Scalar, int Options>
620 struct has_nothrow_constructor<::pinocchio::JointModelSphericalTpl<Scalar, Options>>
621 : public integral_constant<bool, true>
622 {
623 };
624
625 template<typename Scalar, int Options>
626 struct has_nothrow_copy<::pinocchio::JointModelSphericalTpl<Scalar, Options>>
627 : public integral_constant<bool, true>
628 {
629 };
630
631 template<typename Scalar, int Options>
632 struct has_nothrow_constructor<::pinocchio::JointDataSphericalTpl<Scalar, Options>>
633 : public integral_constant<bool, true>
634 {
635 };
636
637 template<typename Scalar, int Options>
638 struct has_nothrow_copy<::pinocchio::JointDataSphericalTpl<Scalar, Options>>
639 : public integral_constant<bool, true>
640 {
641 };
642} // namespace boost
643
644#endif // ifndef __pinocchio_multibody_joint_spherical_hpp__
Main pinocchio namespace.
Definition treeview.dox:11
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.
void alphaSkew(const Scalar alpha, const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector multiplied by a given scalar....
Definition skew.hpp:134
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.
void skew(const Eigen::MatrixBase< Vector3 > &v, const Eigen::MatrixBase< Matrix3 > &M)
Computes the skew representation of a given 3d vector, i.e. the antisymmetric matrix representation o...
Definition skew.hpp:22
Blank type.
Definition fwd.hpp:77
JointModelSphericalTpl< NewScalar, Options > cast() const
Return type of the ation of a Motion onto an object of type D.
Definition motion.hpp:46
Common traits structure to fully define base classes for CRTP.
Definition fwd.hpp:72