pinocchio  2.1.3
joint-planar.hpp
1 //
2 // Copyright (c) 2015-2018 CNRS
3 // Copyright (c) 2015-2016 Wandercraft, 86 rue de Paris 91400 Orsay, France.
4 //
5 
6 #ifndef __pinocchio_joint_planar_hpp__
7 #define __pinocchio_joint_planar_hpp__
8 
9 #include "pinocchio/macros.hpp"
10 #include "pinocchio/multibody/joint/joint-base.hpp"
11 #include "pinocchio/spatial/cartesian-axis.hpp"
12 #include "pinocchio/multibody/constraint.hpp"
13 #include "pinocchio/spatial/motion.hpp"
14 #include "pinocchio/spatial/inertia.hpp"
15 
16 namespace pinocchio
17 {
18 
19  template<typename Scalar, int Options = 0> struct MotionPlanarTpl;
21 
22  namespace internal
23  {
24  template<typename Scalar, int Options>
25  struct SE3GroupAction< MotionPlanarTpl<Scalar,Options> >
26  {
27  typedef MotionTpl<Scalar,Options> ReturnType;
28  };
29 
30  template<typename Scalar, int Options, typename MotionDerived>
31  struct MotionAlgebraAction< MotionPlanarTpl<Scalar,Options>, MotionDerived>
32  {
33  typedef MotionTpl<Scalar,Options> ReturnType;
34  };
35  }
36 
37  template<typename _Scalar, int _Options>
38  struct traits< MotionPlanarTpl<_Scalar,_Options> >
39  {
40  typedef _Scalar Scalar;
41  enum { Options = _Options };
42  typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
43  typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
44  typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
45  typedef typename PINOCCHIO_EIGEN_REF_CONST_TYPE(Vector6) ToVectorConstReturnType;
46  typedef typename PINOCCHIO_EIGEN_REF_TYPE(Vector6) ToVectorReturnType;
47  typedef Vector3 AngularType;
48  typedef Vector3 LinearType;
49  typedef const Vector3 ConstAngularType;
50  typedef const Vector3 ConstLinearType;
51  typedef Matrix6 ActionMatrixType;
53  enum {
54  LINEAR = 0,
55  ANGULAR = 3
56  };
57  }; // traits MotionPlanarTpl
58 
59  template<typename _Scalar, int _Options>
60  struct MotionPlanarTpl : MotionBase< MotionPlanarTpl<_Scalar,_Options> >
61  {
62  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
63  MOTION_TYPEDEF_TPL(MotionPlanarTpl);
64 
65  typedef CartesianAxis<2> AxisZ;
66 
67  MotionPlanarTpl() {}
68 
69  MotionPlanarTpl(const Scalar & x_dot, const Scalar & y_dot,
70  const Scalar & theta_dot)
71  : m_x_dot(x_dot), m_y_dot(y_dot), m_theta_dot(theta_dot)
72  {}
73 
74  template<typename Vector3Like>
75  MotionPlanarTpl(const Eigen::MatrixBase<Vector3Like> & vj)
76  : m_x_dot(vj[0]), m_y_dot(vj[1]), m_theta_dot(vj[2])
77  {
78  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
79  }
80 
81 // operator MotionPlain() const
82 // {
83 // return MotionPlain(typename MotionPlain::Vector3(m_x_dot,m_y_dot,Scalar(0)),
84 // typename MotionPlain::Vector3(Scalar(0),Scalar(0),m_theta_dot));
85 // }
86 
87  template<typename Derived>
88  void addTo(MotionDense<Derived> & other) const
89  {
90  other.linear()[0] += m_x_dot;
91  other.linear()[1] += m_y_dot;
92  other.angular()[2] += m_theta_dot;
93  }
94 
95  template<typename MotionDerived>
96  void setTo(MotionDense<MotionDerived> & other) const
97  {
98  other.linear() << m_x_dot, m_y_dot, (Scalar)0;
99  other.angular() << (Scalar)0, (Scalar)0, m_theta_dot;
100  }
101 
102  template<typename S2, int O2, typename D2>
103  void se3Action_impl(const SE3Tpl<S2,O2> & m, MotionDense<D2> & v) const
104  {
105  v.angular().noalias() = m.rotation().col(2) * m_theta_dot;
106  v.linear().noalias() = m.translation().cross(v.angular());
107  v.linear() += m.rotation().col(0) * m_x_dot;
108  v.linear() += m.rotation().col(1) * m_y_dot;
109  }
110 
111  template<typename S2, int O2>
112  MotionPlain se3Action_impl(const SE3Tpl<S2,O2> & m) const
113  {
114  MotionPlain res;
115  se3Action_impl(m,res);
116  return res;
117  }
118 
119  template<typename S2, int O2, typename D2>
120  void se3ActionInverse_impl(const SE3Tpl<S2,O2> & m, MotionDense<D2> & v) const
121  {
122  // Linear
123  // TODO: use v.angular() as temporary variable
124  Vector3 v3_tmp;
125  AxisZ::alphaCross(m_theta_dot,m.translation(),v3_tmp);
126  v3_tmp[0] += m_x_dot; v3_tmp[1] += m_y_dot;
127  v.linear().noalias() = m.rotation().transpose() * v3_tmp;
128 
129  // Angular
130  v.angular().noalias() = m.rotation().transpose().col(2) * m_theta_dot;
131  }
132 
133  template<typename S2, int O2>
134  MotionPlain se3ActionInverse_impl(const SE3Tpl<S2,O2> & m) const
135  {
136  MotionPlain res;
137  se3ActionInverse_impl(m,res);
138  return res;
139  }
140 
141  template<typename M1, typename M2>
142  void motionAction(const MotionDense<M1> & v, MotionDense<M2> & mout) const
143  {
144  // Linear
145  AxisZ::alphaCross(-m_theta_dot,v.linear(),mout.linear());
146 
147  typename M1::ConstAngularType w_in = v.angular();
148  typename M2::LinearType v_out = mout.linear();
149 
150  v_out[0] -= w_in[2] * m_y_dot;
151  v_out[1] += w_in[2] * m_x_dot;
152  v_out[2] += -w_in[1] * m_x_dot + w_in[0] * m_y_dot ;
153 
154  // Angular
155  AxisZ::alphaCross(-m_theta_dot,v.angular(),mout.angular());
156  }
157 
158  template<typename M1>
159  MotionPlain motionAction(const MotionDense<M1> & v) const
160  {
161  MotionPlain res;
162  motionAction(v,res);
163  return res;
164  }
165 
166  // data
167  Scalar m_x_dot;
168  Scalar m_y_dot;
169  Scalar m_theta_dot;
170 
171  }; // struct MotionPlanarTpl
172 
173  template<typename Scalar, int Options, typename MotionDerived>
174  inline typename MotionDerived::MotionPlain
175  operator+(const MotionPlanarTpl<Scalar,Options> & m1, const MotionDense<MotionDerived> & m2)
176  {
177  typename MotionDerived::MotionPlain result(m2);
178  result.linear()[0] += m1.m_x_dot;
179  result.linear()[1] += m1.m_y_dot;
180 
181  result.angular()[2] += m1.m_theta_dot;
182 
183  return result;
184  }
185 
186  template<typename Scalar, int Options> struct ConstraintPlanarTpl;
187 
188  template<typename _Scalar, int _Options>
189  struct traits< ConstraintPlanarTpl<_Scalar,_Options> >
190  {
191  typedef _Scalar Scalar;
192  enum { Options = _Options };
193  typedef Eigen::Matrix<Scalar,3,1,Options> Vector3;
194  typedef Eigen::Matrix<Scalar,4,1,Options> Vector4;
195  typedef Eigen::Matrix<Scalar,6,1,Options> Vector6;
196  typedef Eigen::Matrix<Scalar,3,3,Options> Matrix3;
197  typedef Eigen::Matrix<Scalar,4,4,Options> Matrix4;
198  typedef Eigen::Matrix<Scalar,6,6,Options> Matrix6;
199  typedef Matrix3 Angular_t;
200  typedef Vector3 Linear_t;
201  typedef const Matrix3 ConstAngular_t;
202  typedef const Vector3 ConstLinear_t;
203  typedef Matrix6 ActionMatrix_t;
204  typedef Eigen::Quaternion<Scalar,Options> Quaternion_t;
205  typedef SE3Tpl<Scalar,Options> SE3;
209  enum {
210  LINEAR = 0,
211  ANGULAR = 3
212  };
214  typedef Eigen::Matrix<Scalar,3,1,Options> JointForce;
215  typedef Eigen::Matrix<Scalar,6,3,Options> DenseBase;
216  typedef DenseBase MatrixReturnType;
217  typedef const DenseBase ConstMatrixReturnType;
218  }; // struct traits ConstraintPlanarTpl
219 
220  template<typename _Scalar, int _Options>
221  struct ConstraintPlanarTpl : ConstraintBase< ConstraintPlanarTpl<_Scalar,_Options> >
222  {
223  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
224  SPATIAL_TYPEDEF_TEMPLATE(ConstraintPlanarTpl);
225 
226  enum { NV = 3, Options = _Options }; // to check
228  typedef typename traits<ConstraintPlanarTpl>::JointForce JointForce;
229  typedef typename traits<ConstraintPlanarTpl>::DenseBase DenseBase;
230 
231  template<typename Vector3Like>
232  JointMotion __mult__(const Eigen::MatrixBase<Vector3Like> & vj) const
233  {
234  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like,3);
235  return JointMotion(vj);
236  }
237 
238  int nv_impl() const { return NV; }
239 
241  {
242  const ConstraintPlanarTpl & ref;
243  ConstraintTranspose(const ConstraintPlanarTpl & ref) : ref(ref) {}
244 
245  template<typename Derived>
246  typename ForceDense<Derived>::Vector3 operator* (const ForceDense<Derived> & phi)
247  {
248  typedef typename ForceDense<Derived>::Vector3 Vector3;
249  return Vector3(phi.linear()[0], phi.linear()[1], phi.angular()[2]);
250  }
251 
252  /* [CRBA] MatrixBase operator* (Constraint::Transpose S, ForceSet::Block) */
253  template<typename Derived>
254  friend typename Eigen::Matrix <typename Eigen::MatrixBase<Derived>::Scalar, 3, Derived::ColsAtCompileTime>
255  operator*(const ConstraintTranspose &, const Eigen::MatrixBase<Derived> & F)
256  {
257  typedef typename Eigen::MatrixBase<Derived>::Scalar Scalar;
258  typedef Eigen::Matrix<Scalar, 3, Derived::ColsAtCompileTime> MatrixReturnType;
259  assert(F.rows()==6);
260 
261  MatrixReturnType result(3, F.cols ());
262  result.template topRows<2>() = F.template topRows<2>();
263  result.template bottomRows<1>() = F.template bottomRows<1>();
264  return result;
265  }
266 
267  }; // struct ConstraintTranspose
268 
269  ConstraintTranspose transpose () const { return ConstraintTranspose(*this); }
270 
271  DenseBase matrix_impl() const
272  {
273  DenseBase S;
274  S.template block<3,3>(Inertia::LINEAR, 0).setZero ();
275  S.template block<3,3>(Inertia::ANGULAR, 0).setZero ();
276  S(Inertia::LINEAR + 0,0) = Scalar(1);
277  S(Inertia::LINEAR + 1,1) = Scalar(1);
278  S(Inertia::ANGULAR + 2,2) = Scalar(1);
279  return S;
280  }
281 
282  template<typename S1, int O1>
283  DenseBase se3Action(const SE3Tpl<S1,O1> & m) const
284  {
285  DenseBase X_subspace;
286  X_subspace.template block <3,2>(Motion::LINEAR, 0) = m.rotation ().template leftCols <2> ();
287  X_subspace.template block <3,1>(Motion::LINEAR, 2) = m.translation().cross(m.rotation ().template rightCols<1>());
288 
289  X_subspace.template block <3,2>(Motion::ANGULAR, 0).setZero ();
290  X_subspace.template block <3,1>(Motion::ANGULAR, 2) = m.rotation ().template rightCols<1>();
291 
292  return X_subspace;
293  }
294 
295  template<typename MotionDerived>
296  DenseBase motionAction(const MotionDense<MotionDerived> & m) const
297  {
298  const typename MotionDerived::ConstLinearType v = m.linear();
299  const typename MotionDerived::ConstAngularType w = m.angular();
300  DenseBase res(DenseBase::Zero());
301 
302  res(0,1) = -w[2]; res(0,2) = v[1];
303  res(1,0) = w[2]; res(1,2) = -v[0];
304  res(2,0) = -w[1]; res(2,1) = w[0];
305  res(3,2) = w[1];
306  res(4,2) = -w[0];
307 
308  return res;
309  }
310  }; // struct ConstraintPlanarTpl
311 
312  template<typename MotionDerived, typename S2, int O2>
313  inline typename MotionDerived::MotionPlain
314  operator^(const MotionDense<MotionDerived> & m1, const MotionPlanarTpl<S2,O2> & m2)
315  {
316  return m2.motionAction(m1);
317  }
318 
319  /* [CRBA] ForceSet operator* (Inertia Y,Constraint S) */
320  template<typename S1, int O1, typename S2, int O2>
321  inline typename Eigen::Matrix<S1,6,3,O1>
322  operator*(const InertiaTpl<S1,O1> & Y, const ConstraintPlanarTpl<S2,O2> &)
323  {
324  typedef InertiaTpl<S1,O1> Inertia;
325  typedef typename Inertia::Scalar Scalar;
326  typedef Eigen::Matrix<S1,6,3,O1> ReturnType;
327 
328  ReturnType M;
329  const Scalar mass = Y.mass();
330  const typename Inertia::Vector3 & com = Y.lever();
331  const typename Inertia::Symmetric3 & inertia = Y.inertia();
332 
333  M.template topLeftCorner<3,3>().setZero();
334  M.template topLeftCorner<2,2>().diagonal().fill(mass);
335 
336  const typename Inertia::Vector3 mc(mass * com);
337  M.template rightCols<1>().template head<2>() << -mc(1), mc(0);
338 
339  M.template bottomLeftCorner<3,2>() << (Scalar)0, -mc(2), mc(2), (Scalar)0, -mc(1), mc(0);
340  M.template rightCols<1>().template tail<3>() = inertia.data().template tail<3>();
341  M.template rightCols<1>()[3] -= mc(0)*com(2);
342  M.template rightCols<1>()[4] -= mc(1)*com(2);
343  M.template rightCols<1>()[5] += mass*(com(0)*com(0) + com(1)*com(1));
344 
345  return M;
346  }
347 
348  /* [ABA] Y*S operator (Inertia Y,Constraint S) */
349  // inline Eigen::Matrix<double,6,1>
350 
351  template<typename M6Like, typename S2, int O2>
352  inline Eigen::Matrix<S2,6,3,O2>
353  operator*(const Eigen::MatrixBase<M6Like> & Y,
355  {
356  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(M6Like,6,6);
357  typedef Eigen::Matrix<S2,6,3,O2> Matrix63;
358 
359  Matrix63 IS;
360  IS.template leftCols<2>() = Y.template leftCols<2>();
361  IS.template rightCols<1>() = Y.template rightCols<1>();
362 
363  return IS;
364  }
365 
366  namespace internal
367  {
368  template<typename S1, int O1>
369  struct SE3GroupAction< ConstraintPlanarTpl<S1,O1> >
370  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
371 
372  template<typename S1, int O1, typename MotionDerived>
373  struct MotionAlgebraAction< ConstraintPlanarTpl<S1,O1>,MotionDerived >
374  { typedef Eigen::Matrix<S1,6,3,O1> ReturnType; };
375  }
376 
377  template<typename Scalar, int Options> struct JointPlanarTpl;
378 
379  template<typename _Scalar, int _Options>
380  struct traits< JointPlanarTpl<_Scalar,_Options> >
381  {
382  enum {
383  NQ = 4,
384  NV = 3
385  };
386  enum { Options = _Options };
387  typedef _Scalar Scalar;
394  typedef Eigen::Matrix<Scalar,6,NV,Options> F_t;
395 
396  // [ABA]
397  typedef Eigen::Matrix<Scalar,6,NV,Options> U_t;
398  typedef Eigen::Matrix<Scalar,NV,NV,Options> D_t;
399  typedef Eigen::Matrix<Scalar,6,NV,Options> UD_t;
400 
401  PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE
402 
403  typedef Eigen::Matrix<Scalar,NQ,1,Options> ConfigVector_t;
404  typedef Eigen::Matrix<Scalar,NV,1,Options> TangentVector_t;
405  };
406 
407  template<typename Scalar, int Options>
409  template<typename Scalar, int Options>
411 
412  template<typename _Scalar, int _Options>
413  struct JointDataPlanarTpl : public JointDataBase< JointDataPlanarTpl<_Scalar,_Options> >
414  {
415  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
417  PINOCCHIO_JOINT_DATA_TYPEDEF_TEMPLATE;
418  PINOCCHIO_JOINT_DATA_BASE_DEFAULT_ACCESSOR
419 
420  Constraint_t S;
421  Transformation_t M;
422  Motion_t v;
423  Bias_t c;
424 
425  F_t F; // TODO if not used anymore, clean F_t
426 
427  // [ABA] specific data
428  U_t U;
429  D_t Dinv;
430  UD_t UDinv;
431 
432  D_t StU;
433 
434  JointDataPlanarTpl () : M(1), U(), Dinv(), UDinv() {}
435 
436  static std::string classname() { return std::string("JointDataPlanar"); }
437  std::string shortname() const { return classname(); }
438 
439  }; // struct JointDataPlanarTpl
440 
441  PINOCCHIO_JOINT_CAST_TYPE_SPECIALIZATION(JointModelPlanarTpl);
442  template<typename _Scalar, int _Options>
443  struct JointModelPlanarTpl
444  : public JointModelBase< JointModelPlanarTpl<_Scalar,_Options> >
445  {
446  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
448  PINOCCHIO_JOINT_TYPEDEF_TEMPLATE;
449 
451  using Base::id;
452  using Base::idx_q;
453  using Base::idx_v;
454  using Base::setIndexes;
455 
456  JointDataDerived createData() const { return JointDataDerived(); }
457 
458  template<typename ConfigVector>
459  inline void forwardKinematics(Transformation_t & M, const Eigen::MatrixBase<ConfigVector> & q_joint) const
460  {
461  const Scalar
462  & c_theta = q_joint(2),
463  & s_theta = q_joint(3);
464 
465  M.rotation().template topLeftCorner<2,2>() << c_theta, -s_theta, s_theta, c_theta;
466  M.translation().template head<2>() = q_joint.template head<2>();
467  }
468 
469  template<typename ConfigVector>
470  void calc(JointDataDerived & data,
471  const typename Eigen::MatrixBase<ConfigVector> & qs) const
472  {
473  typedef typename ConfigVector::Scalar Scalar;
474  typename ConfigVector::template ConstFixedSegmentReturnType<NQ>::Type & q = qs.template segment<NQ>(idx_q());
475 
476  const Scalar
477  &c_theta = q(2),
478  &s_theta = q(3);
479 
480  data.M.rotation().template topLeftCorner<2,2>() << c_theta, -s_theta, s_theta, c_theta;
481  data.M.translation().template head<2>() = q.template head<2>();
482 
483  }
484 
485  template<typename ConfigVector, typename TangentVector>
486  void calc(JointDataDerived & data,
487  const typename Eigen::MatrixBase<ConfigVector> & qs,
488  const typename Eigen::MatrixBase<TangentVector> & vs) const
489  {
490  calc(data,qs.derived());
491 
492  typename TangentVector::template ConstFixedSegmentReturnType<NV>::Type & q_dot = vs.template segment<NV>(idx_v ());
493 
494  data.v.m_x_dot = q_dot(0);
495  data.v.m_y_dot = q_dot(1);
496  data.v.m_theta_dot = q_dot(2);
497  }
498 
499  template<typename Matrix6Like>
500  void calc_aba(JointDataDerived & data, const Eigen::MatrixBase<Matrix6Like> & I, const bool update_I) const
501  {
502  data.U.template leftCols<2>() = I.template leftCols<2>();
503  data.U.template rightCols<1>() = I.template rightCols<1>();
504 
505  data.StU.template leftCols<2>() = data.U.template topRows<2>().transpose();
506  data.StU.template rightCols<1>() = data.U.template bottomRows<1>();
507 
508  // compute inverse
509  data.Dinv.setIdentity();
510  data.StU.llt().solveInPlace(data.Dinv);
511 
512  data.UDinv.noalias() = data.U * data.Dinv;
513 
514  if (update_I)
515  PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like,I) -= data.UDinv * data.U.transpose();
516  }
517 
518  Scalar finiteDifferenceIncrement() const
519  {
520  using math::sqrt;
521  return 2.*sqrt(sqrt(Eigen::NumTraits<Scalar>::epsilon()));
522  }
523 
524  static std::string classname() { return std::string("JointModelPlanar");}
525  std::string shortname() const { return classname(); }
526 
528  template<typename NewScalar>
530  {
531  typedef JointModelPlanarTpl<NewScalar,Options> ReturnType;
532  ReturnType res;
533  res.setIndexes(id(),idx_q(),idx_v());
534  return res;
535  }
536 
537  }; // struct JointModelPlanarTpl
538 
539 } // namespace pinocchio
540 
541 #include <boost/type_traits.hpp>
542 
543 namespace boost
544 {
545  template<typename Scalar, int Options>
546  struct has_nothrow_constructor< ::pinocchio::JointModelPlanarTpl<Scalar,Options> >
547  : public integral_constant<bool,true> {};
548 
549  template<typename Scalar, int Options>
550  struct has_nothrow_copy< ::pinocchio::JointModelPlanarTpl<Scalar,Options> >
551  : public integral_constant<bool,true> {};
552 
553  template<typename Scalar, int Options>
554  struct has_nothrow_constructor< ::pinocchio::JointDataPlanarTpl<Scalar,Options> >
555  : public integral_constant<bool,true> {};
556 
557  template<typename Scalar, int Options>
558  struct has_nothrow_copy< ::pinocchio::JointDataPlanarTpl<Scalar,Options> >
559  : public integral_constant<bool,true> {};
560 }
561 
562 #endif // ifndef __pinocchio_joint_planar_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...
JointModelPlanarTpl< 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...
ConstAngularType angular() const
Return the angular part of the force vector.
Definition: force-base.hpp:40
Main pinocchio namespace.
Definition: treeview.dox:24
Common traits structure to fully define base classes for CRTP.
Definition: spatial/fwd.hpp:29
ConstLinearType linear() const
Return the linear part of the force vector.
Definition: force-base.hpp:47
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...