pinocchio  2.1.3
joint-free-flyer.hpp
1 //
2 // Copyright (c) 2015-2019 CNRS INRIA
3 // Copyright (c) 2015-2016 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #ifndef __pinocchio_joint_free_flyer_hpp__
7 #define __pinocchio_joint_free_flyer_hpp__
8 
9 #include "pinocchio/macros.hpp"
10 #include "pinocchio/spatial/inertia.hpp"
11 #include "pinocchio/spatial/explog.hpp"
12 #include "pinocchio/multibody/joint/joint-base.hpp"
13 #include "pinocchio/multibody/constraint.hpp"
14 #include "pinocchio/math/fwd.hpp"
15 #include "pinocchio/math/quaternion.hpp"
16 
17 namespace pinocchio
18 {
19 
20  template<typename Scalar, int Options> struct ConstraintIdentityTpl;
21 
22  template<typename _Scalar, int _Options>
23  struct traits< ConstraintIdentityTpl<_Scalar,_Options> >
24  {
25  typedef _Scalar Scalar;
26  enum { Options = _Options };
27  typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
28  typedef Eigen::Matrix<Scalar,4,1,Options> Vector4;
29  typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
30  typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
31  typedef Eigen::Matrix<Scalar,4,4,Options> Matrix4;
32  typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
33  typedef Matrix3 Angular_t;
34  typedef Vector3 Linear_t;
35  typedef const Matrix3 ConstAngular_t;
36  typedef const Vector3 ConstLinear_t;
37  typedef Matrix6 ActionMatrix_t;
38  typedef Eigen::Quaternion<Scalar,Options> Quaternion_t;
43  enum {
44  LINEAR = 0,
45  ANGULAR = 3
46  };
48  typedef Eigen::Matrix<Scalar,6,1,Options> JointForce;
49  typedef Eigen::Matrix<Scalar,6,6,Options> DenseBase;
50  typedef typename Matrix6::IdentityReturnType ConstMatrixReturnType;
51  typedef typename Matrix6::IdentityReturnType MatrixReturnType;
52  }; // traits ConstraintRevolute
53 
54 
55  template<typename _Scalar, int _Options>
57  : ConstraintBase< ConstraintIdentityTpl<_Scalar,_Options> >
58  {
59  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
60  SPATIAL_TYPEDEF_TEMPLATE(ConstraintIdentityTpl);
61 
62  enum { NV = 6, Options = _Options };
64  typedef typename traits<ConstraintIdentityTpl>::JointForce JointForce;
65  typedef typename traits<ConstraintIdentityTpl>::DenseBase DenseBase;
66  typedef typename traits<ConstraintIdentityTpl>::MatrixReturnType MatrixReturnType;
67 
68  template<typename Vector6Like>
69  JointMotion __mult__(const Eigen::MatrixBase<Vector6Like> & vj) const
70  {
71  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector6Like,6);
72  return JointMotion(vj);
73  }
74 
75  template<typename S1, int O1>
76  typename SE3::ActionMatrixType se3Action(const SE3Tpl<S1,O1> & m) const
77  { return m.toActionMatrix(); }
78 
79  int nv_impl() const { return NV; }
80 
82  {
83  template<typename Derived>
85  operator*(const ForceDense<Derived> & phi)
86  { return phi.toVector(); }
87 
88  /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
89  template<typename MatrixDerived>
90  typename PINOCCHIO_EIGEN_REF_CONST_TYPE(MatrixDerived)
91  operator*(const Eigen::MatrixBase<MatrixDerived> & F)
92  {
93  return F.derived();
94  }
95  };
96 
97  TransposeConst transpose() const { return TransposeConst(); }
98  MatrixReturnType matrix_impl() const { return DenseBase::Identity(); }
99 
100  template<typename MotionDerived>
101  typename MotionDerived::ActionMatrixType
102  motionAction(const MotionBase<MotionDerived> & v) const
103  { return v.toActionMatrix(); }
104 
105  }; // struct ConstraintIdentityTpl
106 
107  template<typename Scalar, int Options, typename Vector6Like>
109  operator*(const ConstraintIdentityTpl<Scalar,Options> &,
110  const Eigen::MatrixBase<Vector6Like> & v)
111  {
112  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector6Like,6);
113 // typedef typename ConstraintIdentityTpl<Scalar,Options>::Motion Motion;
115  return Motion(v.derived());
116  }
117 
118  /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
119  template<typename S1, int O1, typename S2, int O2>
120  inline typename InertiaTpl<S1,O1>::Matrix6
121  operator*(const InertiaTpl<S1,O1> & Y, const ConstraintIdentityTpl<S2,O2> &)
122  {
123  return Y.matrix();
124  }
125 
126  /* [ABA] Y*S operator*/
127  template<typename Matrix6Like, typename S2, int O2>
128  inline typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Matrix6Like)
129  operator*(const Eigen::MatrixBase<Matrix6Like> & Y, const ConstraintIdentityTpl<S2,O2> &)
130  {
131  return Y.derived();
132  }
133 
134  namespace internal
135  {
136  template<typename S1, int O1>
137  struct SE3GroupAction< ConstraintIdentityTpl<S1,O1> >
138  { typedef typename SE3Tpl<S1,O1>::ActionMatrixType ReturnType; };
139 
140  template<typename S1, int O1, typename MotionDerived>
141  struct MotionAlgebraAction< ConstraintIdentityTpl<S1,O1>,MotionDerived >
142  { typedef typename SE3Tpl<S1,O1>::ActionMatrixType ReturnType; };
143  }
144 
145  template<typename Scalar, int Options> struct JointFreeFlyerTpl;
146 
147  template<typename _Scalar, int _Options>
148  struct traits< JointFreeFlyerTpl<_Scalar,_Options> >
149  {
150  enum {
151  NQ = 7,
152  NV = 6
153  };
154  typedef _Scalar Scalar;
155  enum { Options = _Options };
162  typedef Eigen::Matrix<Scalar,6,NV,Options> F_t;
163 
164  // [ABA]
165  typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
166  typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
167  typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
168 
169  PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
170 
171  typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
172  typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
173  };
174 
175  template<typename Scalar, int Options>
176  struct traits< JointDataFreeFlyerTpl<Scalar,Options> >
178 
179  template<typename Scalar, int Options>
180  struct traits< JointModelFreeFlyerTpl<Scalar,Options> >
182 
183  template<typename _Scalar, int _Options>
184  struct JointDataFreeFlyerTpl : public JointDataBase< JointDataFreeFlyerTpl<_Scalar,_Options> >
185  {
186  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
188  PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE;
189  PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
190 
191  Constraint_t S;
192  Transformation_t M;
193  Motion_t v;
194  Bias_t c;
195 
196  F_t F; // TODO if not used anymore, clean F_t
197 
198  // [ABA] specific data
199  U_t U;
200  D_t Dinv;
201  UD_t UDinv;
202 
203  JointDataFreeFlyerTpl() : M(1), U(), Dinv(), UDinv(UD_t::Identity()) {}
204 
205  static std::string classname() { return std::string("JointDataFreeFlyer"); }
206  std::string shortname() const { return classname(); }
207 
208  }; // struct JointDataFreeFlyerTpl
209 
210  PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelFreeFlyerTpl);
211  template<typename _Scalar, int _Options>
213  : public JointModelBase< JointModelFreeFlyerTpl<_Scalar,_Options> >
214  {
215  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
217  PINOCCHIO_JOINT_TYPEDEF_TEMPLATE;
218 
220  using Base::id;
221  using Base::idx_q;
222  using Base::idx_v;
223  using Base::setIndexes;
224 
225  JointDataDerived createData() const { return JointDataDerived(); }
226 
227  template<typename ConfigVectorLike>
228  inline void forwardKinematics(Transformation_t & M, const Eigen::MatrixBase<ConfigVectorLike> & q_joint) const
229  {
230  EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t,ConfigVectorLike);
231  typedef typename Eigen::Quaternion<typename ConfigVectorLike::Scalar,PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorLike)::Options> Quaternion;
232  typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
233 
234  ConstQuaternionMap quat(q_joint.template tail<4>().data());
235  //assert(math::fabs(quat.coeffs().squaredNorm()-1.) <= sqrt(Eigen::NumTraits<typename V::Scalar>::epsilon())); TODO: check validity of the rhs precision
236  assert(math::fabs(quat.coeffs().squaredNorm()-1.) <= 1e-4);
237 
238  M.rotation(quat.matrix());
239  M.translation(q_joint.template head<3>());
240  }
241 
242  template<typename Vector3Derived, typename QuaternionDerived>
243  EIGEN_DONT_INLINE
244  void calc(JointDataDerived & data,
245  const typename Eigen::MatrixBase<Vector3Derived> & trans,
246  const typename Eigen::QuaternionBase<QuaternionDerived> & quat) const
247  {
248  data.M.translation(trans);
249  data.M.rotation(quat.matrix());
250  }
251 
252  template<typename ConfigVector>
253  EIGEN_DONT_INLINE
254  void calc(JointDataDerived & data,
255  const typename Eigen::PlainObjectBase<ConfigVector> & qs) const
256  {
257  typedef typename Eigen::Quaternion<typename ConfigVector::Scalar,ConfigVector::Options> Quaternion;
258  typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
259 
260  typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type q = qs.template segment<NQ>(idx_q());
261  ConstQuaternionMap quat(q.template tail<4>().data());
262 
263  calc(data,q.template head<3>(),quat);
264  }
265 
266  template<typename ConfigVector>
267  EIGEN_DONT_INLINE
268  void calc(JointDataDerived & data,
269  const typename Eigen::MatrixBase<ConfigVector> & qs) const
270  {
271  typedef typename Eigen::Quaternion<Scalar,Options> Quaternion;
272 
273  typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type q = qs.template segment<NQ>(idx_q());
274  const Quaternion quat(q.template tail<4>());
275 
276  calc(data,q.template head<3>(),quat);
277  }
278 
279  template<typename ConfigVector, typename TangentVector>
280  EIGEN_DONT_INLINE
281  void calc(JointDataDerived & data,
282  const typename Eigen::MatrixBase<ConfigVector> & qs,
283  const typename Eigen::MatrixBase<TangentVector> & vs) const
284  {
285  calc(data,qs.derived());
286 
287  data.v = vs.template segment<NV>(idx_v());
288  }
289 
290  template<typename Matrix6Like>
291  void calc_aba(JointDataDerived & data, const Eigen::MatrixBase<Matrix6Like> & I, const bool update_I) const
292  {
293  data.U = I;
294  data.Dinv.setIdentity();
295  I.llt().solveInPlace(data.Dinv);
296 
297  if (update_I)
298  PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,I).setZero();
299  }
300 
301  Scalar finiteDifferenceIncrement() const
302  {
303  using math::sqrt;
304  return 2.*sqrt(sqrt(Eigen::NumTraits<Scalar>::epsilon()));
305  }
306 
307  static std::string classname() { return std::string("JointModelFreeFlyer"); }
308  std::string shortname() const { return classname(); }
309 
311  template<typename NewScalar>
313  {
315  ReturnType res;
316  res.setIndexes(id(),idx_q(),idx_v());
317  return res;
318  }
319 
320  }; // struct JointModelFreeFlyerTpl
321 
322 } // namespace pinocchio
323 
324 #include <boost/type_traits.hpp>
325 
326 namespace boost
327 {
328  template<typename Scalar, int Options>
329  struct has_nothrow_constructor< ::pinocchio::JointModelFreeFlyerTpl<Scalar,Options> >
330  : public integral_constant<bool,true> {};
331 
332  template<typename Scalar, int Options>
333  struct has_nothrow_copy< ::pinocchio::JointModelFreeFlyerTpl<Scalar,Options> >
334  : public integral_constant<bool,true> {};
335 
336  template<typename Scalar, int Options>
337  struct has_nothrow_constructor< ::pinocchio::JointDataFreeFlyerTpl<Scalar,Options> >
338  : public integral_constant<bool,true> {};
339 
340  template<typename Scalar, int Options>
341  struct has_nothrow_copy< ::pinocchio::JointDataFreeFlyerTpl<Scalar,Options> >
342  : public integral_constant<bool,true> {};
343 }
344 
345 #endif // ifndef __pinocchio_joint_free_flyer_hpp__
int idx_q(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxQVisitor to get the index in the full model configuration space...
JointModelFreeFlyerTpl< NewScalar, Options > cast() const
int idx_v(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointIdxVVisitor to get the index in the full model tangent space corre...
JointDataTpl< Scalar, Options, JointCollectionTpl > createData(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through CreateData visitor to create a JointDataTpl.
ModelTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType finiteDifferenceIncrement(const ModelTpl< Scalar, Options, JointCollectionTpl > &model)
Computes the finite difference increments for each degree of freedom according to the current joint c...
void forwardKinematics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q)
Update the joint placements according to the current joint configuration.
std::string shortname(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel)
Visit a JointModelTpl through JointShortnameVisitor to get the shortname of the derived joint model...
ToVectorConstReturnType toVector() const
Return the force as an Eigen vector.
Definition: force-base.hpp:86
Main pinocchio namespace.
Definition: treeview.dox:24
Common traits structure to fully define base classes for CRTP.
Definition: spatial/fwd.hpp:29
void calc_aba(const JointModelTpl< Scalar, Options, JointCollectionTpl > &jmodel, JointDataTpl< Scalar, Options, JointCollectionTpl > &jdata, const Eigen::MatrixBase< Matrix6Type > &I, const bool update_I)
Visit a JointModelTpl and the corresponding JointDataTpl through JointCalcAbaVisitor to...