pinocchio  UNKNOWN
joint-free-flyer.hpp
1 //
2 // Copyright (c) 2015-2018 CNRS
3 // Copyright (c) 2015-2016 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 // This file is part of Pinocchio
6 // Pinocchio is free software: you can redistribute it
7 // and/or modify it under the terms of the GNU Lesser General Public
8 // License as published by the Free Software Foundation, either version
9 // 3 of the License, or (at your option) any later version.
10 //
11 // Pinocchio is distributed in the hope that it will be
12 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
13 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
14 // General Lesser Public License for more details. You should have
15 // received a copy of the GNU Lesser General Public License along with
16 // Pinocchio If not, see
17 // <http://www.gnu.org/licenses/>.
18 
19 #ifndef __se3_joint_free_flyer_hpp__
20 #define __se3_joint_free_flyer_hpp__
21 
22 #include "pinocchio/macros.hpp"
23 #include "pinocchio/spatial/inertia.hpp"
24 #include "pinocchio/spatial/explog.hpp"
25 #include "pinocchio/multibody/joint/joint-base.hpp"
26 #include "pinocchio/multibody/constraint.hpp"
27 #include "pinocchio/math/fwd.hpp"
28 #include "pinocchio/math/quaternion.hpp"
29 
30 namespace se3
31 {
32 
33  template<typename Scalar, int Options> struct ConstraintIdentityTpl;
34 
35  template<typename _Scalar, int _Options>
36  struct traits< ConstraintIdentityTpl<_Scalar,_Options> >
37  {
38  typedef _Scalar Scalar;
39  enum { Options = _Options };
40  typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
41  typedef Eigen::Matrix<Scalar,4,1,Options> Vector4;
42  typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
43  typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
44  typedef Eigen::Matrix<Scalar,4,4,Options> Matrix4;
45  typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
46  typedef Matrix3 Angular_t;
47  typedef Vector3 Linear_t;
48  typedef const Matrix3 ConstAngular_t;
49  typedef const Vector3 ConstLinear_t;
50  typedef Matrix6 ActionMatrix_t;
51  typedef Eigen::Quaternion<Scalar,Options> Quaternion_t;
56  enum {
57  LINEAR = 0,
58  ANGULAR = 3
59  };
60  typedef Eigen::Matrix<Scalar,6,1,Options> JointMotion;
61  typedef Eigen::Matrix<Scalar,6,1,Options> JointForce;
62  typedef Eigen::Matrix<Scalar,6,6,Options> DenseBase;
63  typedef const DenseBase ConstMatrixReturnType;
64  typedef DenseBase MatrixReturnType;
65  }; // traits ConstraintRevolute
66 
67 
68  template<typename _Scalar, int _Options>
69  struct ConstraintIdentityTpl : ConstraintBase< ConstraintIdentityTpl<_Scalar,_Options> >
70  {
71  SPATIAL_TYPEDEF_TEMPLATE(ConstraintIdentityTpl);
72  enum { NV = 6, Options = 0 };
73  typedef typename traits<ConstraintIdentityTpl>::JointMotion JointMotion;
74  typedef typename traits<ConstraintIdentityTpl>::JointForce JointForce;
75  typedef typename traits<ConstraintIdentityTpl>::DenseBase DenseBase;
76 
77  template<typename S1, int O1>
78  typename SE3::Matrix6 se3Action(const SE3Tpl<S1,O1> & m) const
79  { return m.toActionMatrix(); }
80 
81  int nv_impl() const { return NV; }
82 
84  {
85  template<typename Derived>
87  operator*(const ForceDense<Derived> & phi)
88  { return phi.toVector(); }
89 
90  /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
91  template<typename MatrixDerived>
92  typename EIGEN_REF_CONSTTYPE(MatrixDerived)
93  operator*(const Eigen::MatrixBase<MatrixDerived> & F)
94  {
95  return F.derived();
96  }
97  };
98 
99  TransposeConst transpose() const { return TransposeConst(); }
100  DenseBase matrix_impl() const { return DenseBase::Identity(); }
101 
102  template<typename MotionDerived>
103  typename MotionDerived::ActionMatrixType
104  motionAction(const MotionBase<MotionDerived> & v) const
105  { return v.toActionMatrix(); }
106 
107  }; // struct ConstraintIdentityTpl
108 
109  template<typename Scalar, int Options, typename Vector6Like>
111  operator*(const ConstraintIdentityTpl<Scalar,Options> &, const Eigen::MatrixBase<Vector6Like>& v)
112  {
113  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector6Like,6);
115  return Motion(v);
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 EIGEN_REF_CONSTTYPE(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>::Matrix6 ReturnType; };
139 
140  template<typename S1, int O1, typename MotionDerived>
141  struct MotionAlgebraAction< ConstraintIdentityTpl<S1,O1>,MotionDerived >
142  { typedef typename SE3Tpl<S1,O1>::Matrix6 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 double Scalar;
155  enum { Options = _Options };
161  typedef BiasZero Bias_t;
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  typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
170  typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
171  };
172 
173  template<typename Scalar, int Options>
174  struct traits< JointDataFreeFlyerTpl<Scalar,Options> >
176 
177  template<typename Scalar, int Options>
178  struct traits< JointModelFreeFlyerTpl<Scalar,Options> >
180 
181  template<typename _Scalar, int _Options>
182  struct JointDataFreeFlyerTpl : public JointDataBase< JointDataFreeFlyerTpl<_Scalar,_Options> >
183  {
185  SE3_JOINT_TYPEDEF_TEMPLATE;
186 
187  Constraint_t S;
188  Transformation_t M;
189  Motion_t v;
190  Bias_t c;
191 
192  F_t F; // TODO if not used anymore, clean F_t
193 
194  // [ABA] specific data
195  U_t U;
196  D_t Dinv;
197  UD_t UDinv;
198 
199  JointDataFreeFlyerTpl() : M(1), U(), Dinv(), UDinv(UD_t::Identity()) {}
200 
201  }; // struct JointDataFreeFlyerTpl
202 
203  template<typename _Scalar, int _Options>
204  struct JointModelFreeFlyerTpl : public JointModelBase< JointModelFreeFlyerTpl<_Scalar,_Options> >
205  {
207  SE3_JOINT_TYPEDEF_TEMPLATE;
208 
213 
214  JointDataDerived createData() const { return JointDataDerived(); }
215 
216  template<typename ConfigVectorLike>
217  inline void forwardKinematics(Transformation_t & M, const Eigen::MatrixBase<ConfigVectorLike> & q_joint) const
218  {
219  EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ConfigVector_t,ConfigVectorLike);
220  typedef typename Eigen::Quaternion<typename ConfigVectorLike::Scalar,EIGEN_PLAIN_TYPE(ConfigVectorLike)::Options> Quaternion;
221  typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
222 
223  ConstQuaternionMap quat(q_joint.template tail<4>().data());
224  //assert(std::fabs(quat.coeffs().squaredNorm()-1.) <= sqrt(Eigen::NumTraits<typename V::Scalar>::epsilon())); TODO: check validity of the rhs precision
225  assert(std::fabs(quat.coeffs().squaredNorm()-1.) <= 1e-4);
226 
227  M.rotation(quat.matrix());
228  M.translation(q_joint.template head<3>());
229  }
230 
231  template<typename ConfigVector>
232  void calc(JointDataDerived & data,
233  const typename Eigen::MatrixBase<ConfigVector> & qs) const
234  {
235  EIGEN_STATIC_ASSERT_VECTOR_ONLY(ConfigVector);
236  typedef typename Eigen::Quaternion<typename ConfigVector::Scalar,ConfigVector::Options> Quaternion;
237  typedef Eigen::Map<const Quaternion> ConstQuaternionMap;
238 
239  typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type q = qs.template segment<NQ>(idx_q());
240  ConstQuaternionMap quat(q.template tail<4>().data());
241 
242  data.M.rotation(quat.matrix());
243  data.M.translation(q.template head<3>());
244  }
245 
246  template<typename ConfigVector, typename TangentVector>
247  void calc(JointDataDerived & data,
248  const typename Eigen::MatrixBase<ConfigVector> & qs,
249  const typename Eigen::MatrixBase<TangentVector> & vs) const
250  {
251  EIGEN_STATIC_ASSERT_VECTOR_ONLY(TangentVector);
252  calc(data,qs.derived());
253 
254  data.v = vs.template segment<NV>(idx_v());
255  }
256 
257  template<typename S2, int O2>
258  void calc_aba(JointDataDerived & data, Eigen::Matrix<S2,6,6,O2> & I, const bool update_I) const
259  {
260  data.U = I;
261  data.Dinv = I.inverse();
262 
263  if (update_I)
264  I.setZero();
265  }
266 
267  Scalar finiteDifferenceIncrement() const
268  {
269  using std::sqrt;
270  return 2.*sqrt(sqrt(Eigen::NumTraits<Scalar>::epsilon()));
271  }
272 
273  static std::string classname() { return std::string("JointModelFreeFlyer"); }
274  std::string shortname() const { return classname(); }
275 
276  }; // struct JointModelFreeFlyerTpl
277 
278 } // namespace se3
279 
280 #endif // ifndef __se3_joint_free_flyer_hpp__
JointDataVariant createData(const JointModelVariant &jmodel)
Visit a JointModelVariant through CreateData visitor to create a JointDataVariant.
void calc_aba(const JointModelVariant &jmodel, JointDataVariant &jdata, Inertia::Matrix6 &I, const bool update_I)
Visit a JointDataVariant and the corresponding JointModelVariant through JointCalcAbaVisitor to...
std::string shortname(const JointModelVariant &jmodel)
Visit a JointModelVariant through JointShortnameVisitor to get the shortname of the derived joint mod...
int idx_q(const JointModelVariant &jmodel)
Visit a JointModelVariant through JointIdxQVisitor to get the index in the full model configuration s...
Eigen::VectorXd finiteDifferenceIncrement(const Model &model)
Computes the finite difference increments for each degree of freedom according to the current joint c...
void forwardKinematics(const Model &model, Data &data, const Eigen::VectorXd &q)
Update the joint placements according to the current joint configuration.
Definition: kinematics.hxx:106
int idx_v(const JointModelVariant &jmodel)
Visit a JointModelVariant through JointIdxVVisitor to get the index in the full model tangent space c...
ToVectorConstReturnType toVector() const
Return the force as an Eigen vector.
Definition: force-base.hpp:99