pinocchio  UNKNOWN
aba-derivatives.hxx
1 //
2 // Copyright (c) 2018 CNRS
3 //
4 // This file is part of Pinocchio
5 // Pinocchio is free software: you can redistribute it
6 // and/or modify it under the terms of the GNU Lesser General Public
7 // License as published by the Free Software Foundation, either version
8 // 3 of the License, or (at your option) any later version.
9 //
10 // Pinocchio is distributed in the hope that it will be
11 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
12 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
13 // General Lesser Public License for more details. You should have
14 // received a copy of the GNU Lesser General Public License along with
15 // Pinocchio If not, see
16 // <http://www.gnu.org/licenses/>.
17 
18 #ifndef __se3_aba_derivatives_hxx__
19 #define __se3_aba_derivatives_hxx__
20 
21 #include "pinocchio/multibody/visitor.hpp"
22 #include "pinocchio/algorithm/check.hpp"
23 #include "pinocchio/algorithm/aba.hpp"
24 #include "pinocchio/algorithm/rnea-derivatives.hxx"
25 
26 namespace se3
27 {
28  struct computeABADerivativesForwardStep1 : public fusion::JointVisitor<computeABADerivativesForwardStep1>
29  {
30  typedef boost::fusion::vector<
31  const se3::Model &,
32  se3::Data &,
33  const Eigen::VectorXd &,
34  const Eigen::VectorXd &
35  > ArgsType;
36 
37  JOINT_VISITOR_INIT(computeABADerivativesForwardStep1);
38 
39  template<typename JointModel>
40  static void algo(const se3::JointModelBase<JointModel> & jmodel,
42  const se3::Model & model,
43  se3::Data & data,
44  const Eigen::VectorXd & q,
45  const Eigen::VectorXd & v)
46  {
47  const Model::JointIndex & i = jmodel.id();
48  const Model::JointIndex & parent = model.parents[i];
49  Motion & ov = data.ov[i];
50 
51  jmodel.calc(jdata.derived(),q,v);
52 
53  data.liMi[i] = model.jointPlacements[i]*jdata.M();
54  data.v[i] = jdata.v();
55 
56  if(parent > 0)
57  {
58  data.oMi[i] = data.oMi[parent] * data.liMi[i];
59  data.v[i] += data.liMi[i].actInv(data.v[parent]);
60  }
61  else
62  data.oMi[i] = data.liMi[i];
63 
64  ov = data.oMi[i].act(data.v[i]);
65  data.a[i] = jdata.c() + (data.v[i] ^ jdata.v());
66  data.Yaba[i] = model.inertias[i].matrix();
67  data.oYcrb[i] = data.oMi[i].act(model.inertias[i]);
68 
69  data.oh[i] = data.oYcrb[i] * ov;
70  data.of[i] = ov.cross(data.oh[i]);
71  data.f[i] = data.oMi[i].actInv(data.of[i]);
72 
73  typedef typename SizeDepType<JointModel::NV>::template ColsReturn<Data::Matrix6x>::Type ColsBlock;
74  ColsBlock J_cols = jmodel.jointCols(data.J);
75  J_cols = data.oMi[i].act(jdata.S());
76 
77  }
78 
79  };
80 
81  struct computeABADerivativesBackwardStep1 : public fusion::JointVisitor<computeABADerivativesBackwardStep1>
82  {
83  typedef boost::fusion::vector<const Model &,
84  Data &,
85  Data::RowMatrixXd &
86  > ArgsType;
87 
88  JOINT_VISITOR_INIT(computeABADerivativesBackwardStep1);
89 
90  template<typename JointModel>
91  static void algo(const JointModelBase<JointModel> & jmodel,
93  const Model & model,
94  Data & data,
95  Data::RowMatrixXd & Minv)
96  {
97  const Model::JointIndex & i = jmodel.id();
98  const Model::JointIndex & parent = model.parents[i];
99 
100  Inertia::Matrix6 & Ia = data.Yaba[i];
101  jmodel.calc_aba(jdata.derived(), Ia, parent > 0);
102 
103  Data::Matrix6x & Fcrb = data.Fcrb[0];
104  Data::Matrix6x & FcrbTmp = data.Fcrb.back();
105 
106  typedef typename SizeDepType<JointModel::NV>::template ColsReturn<Data::Matrix6x>::Type ColsBlock;
107 
108  ColsBlock U_cols = jmodel.jointCols(data.IS);
109  forceSet::se3Action(data.oMi[i],jdata.U(),U_cols); // expressed in the world frame
110 
111  Minv.block(jmodel.idx_v(),jmodel.idx_v(),jmodel.nv(),jmodel.nv()) = jdata.Dinv();
112  const int nv_children = data.nvSubtree[i] - jmodel.nv();
113  if(nv_children > 0)
114  {
115  ColsBlock J_cols = jmodel.jointCols(data.J);
116  ColsBlock SDinv_cols = jmodel.jointCols(data.SDinv);
117  SDinv_cols.noalias() = J_cols * jdata.Dinv();
118 
119  Minv.block(jmodel.idx_v(),jmodel.idx_v()+jmodel.nv(),jmodel.nv(),nv_children).noalias()
120  = -SDinv_cols.transpose() * Fcrb.middleCols(jmodel.idx_v()+jmodel.nv(),nv_children);
121 
122  if(parent > 0)
123  {
124  FcrbTmp.leftCols(data.nvSubtree[i]).noalias()
125  = U_cols * Minv.block(jmodel.idx_v(),jmodel.idx_v(),jmodel.nv(),data.nvSubtree[i]);
126  Fcrb.middleCols(jmodel.idx_v(),data.nvSubtree[i]) += FcrbTmp.leftCols(data.nvSubtree[i]);
127  }
128  }
129  else // This a leaf of the kinematic tree
130  {
131  Fcrb.middleCols(jmodel.idx_v(),data.nvSubtree[i]).noalias()
132  = U_cols * Minv.block(jmodel.idx_v(),jmodel.idx_v(),jmodel.nv(),data.nvSubtree[i]);
133  }
134 
135  jmodel.jointVelocitySelector(data.u) -= jdata.S().transpose()*data.f[i];
136 
137  if (parent > 0)
138  {
139  Force & pa = data.f[i];
140  pa.toVector() += Ia * data.a[i].toVector() + jdata.UDinv() * jmodel.jointVelocitySelector(data.u);
141  data.Yaba[parent] += AbaBackwardStep::SE3actOn(data.liMi[i], Ia);
142  data.f[parent] += data.liMi[i].act(pa);
143  }
144 
145  }
146 
147  };
148 
149  struct computeABADerivativesForwardStep2 : public fusion::JointVisitor<computeABADerivativesForwardStep2>
150  {
151  typedef boost::fusion::vector<const se3::Model &,
152  se3::Data &,
153  Data::RowMatrixXd &
154  > ArgsType;
155 
156  JOINT_VISITOR_INIT(computeABADerivativesForwardStep2);
157 
158  template<typename JointModel>
159  static void algo(const se3::JointModelBase<JointModel> & jmodel,
161  const se3::Model & model,
162  se3::Data & data,
163  Data::RowMatrixXd & Minv)
164  {
165  const Model::JointIndex & i = jmodel.id();
166  const Model::Index & parent = model.parents[i];
167  Motion & ov = data.ov[i];
168  Motion & oa = data.oa[i];
169  Force & of = data.of[i];
170 
171  data.a[i] += data.liMi[i].actInv(data.a[parent]);
172  jmodel.jointVelocitySelector(data.ddq).noalias() =
173  jdata.Dinv() * jmodel.jointVelocitySelector(data.u) - jdata.UDinv().transpose() * data.a[i].toVector();
174 
175  data.a[i] += jdata.S() * jmodel.jointVelocitySelector(data.ddq);
176  oa = data.oMi[i].act(data.a[i]);
177  of = data.oYcrb[i] * oa + ov.cross(data.oh[i]);
178 
179  Data::Matrix6x & FcrbTmp = data.Fcrb.back();
180 
181  typedef typename SizeDepType<JointModel::NV>::template ColsReturn<Data::Matrix6x>::Type ColsBlock;
182  ColsBlock UDinv_cols = jmodel.jointCols(data.UDinv);
183  forceSet::se3Action(data.oMi[i],jdata.UDinv(),UDinv_cols); // expressed in the world frame
184 
185  if(parent > 0)
186  {
187  FcrbTmp.topRows(jmodel.nv()).rightCols(model.nv - jmodel.idx_v()).noalias()
188  = UDinv_cols.transpose() * data.Fcrb[parent].rightCols(model.nv - jmodel.idx_v());
189  Minv.middleRows(jmodel.idx_v(),jmodel.nv()).rightCols(model.nv - jmodel.idx_v())
190  -= FcrbTmp.topRows(jmodel.nv()).rightCols(model.nv - jmodel.idx_v());
191  }
192 
193  ColsBlock J_cols = jmodel.jointCols(data.J);
194  data.Fcrb[i].rightCols(model.nv - jmodel.idx_v()).noalias() = J_cols * Minv.middleRows(jmodel.idx_v(),jmodel.nv()).rightCols(model.nv - jmodel.idx_v());
195  if(parent > 0)
196  data.Fcrb[i].rightCols(model.nv - jmodel.idx_v()) += data.Fcrb[parent].rightCols(model.nv - jmodel.idx_v());
197 
198  ColsBlock dJ_cols = jmodel.jointCols(data.dJ);
199  ColsBlock dVdq_cols = jmodel.jointCols(data.dVdq);
200  ColsBlock dAdq_cols = jmodel.jointCols(data.dAdq);
201  ColsBlock dAdv_cols = jmodel.jointCols(data.dAdv);
202 
203  motionSet::motionAction(ov,J_cols,dJ_cols);
204  motionSet::motionAction(data.oa[parent],J_cols,dAdq_cols);
205  dAdv_cols = dJ_cols;
206  if(parent > 0)
207  {
208  motionSet::motionAction(data.ov[parent],J_cols,dVdq_cols);
209  motionSet::motionAction<ADDTO>(data.ov[parent],dVdq_cols,dAdq_cols);
210  dAdv_cols += dVdq_cols;
211  }
212  else
213  dVdq_cols.setZero();
214 
215  // computes variation of inertias
216  data.doYcrb[i] = data.oYcrb[i].variation(ov);
217  computeRNEADerivativesForwardStep::addForceCrossMatrix(data.oh[i],data.doYcrb[i]);
218  }
219 
220  };
221 
222  struct computeABADerivativesBackwardStep2 : public fusion::JointModelVisitor<computeABADerivativesBackwardStep2>
223  {
224  typedef boost::fusion::vector<const Model &,
225  Data &
226  > ArgsType;
227 
228  JOINT_MODEL_VISITOR_INIT(computeABADerivativesBackwardStep2);
229 
230  template<typename JointModel>
231  static void algo(const JointModelBase<JointModel> & jmodel,
232  const Model & model,
233  Data & data)
234  {
235  const Model::JointIndex & i = jmodel.id();
236  const Model::JointIndex & parent = model.parents[i];
237  Data::RowMatrix6 & M6tmpR = data.M6tmpR;
238 
239  Eigen::MatrixXd & rnea_partial_dq = data.dtau_dq;
240  Eigen::MatrixXd & rnea_partial_dv = data.dtau_dv;
241 
242  typedef typename SizeDepType<JointModel::NV>::template ColsReturn<Data::Matrix6x>::Type ColsBlock;
243 
244  ColsBlock J_cols = jmodel.jointCols(data.J);
245  ColsBlock dVdq_cols = jmodel.jointCols(data.dVdq);
246  ColsBlock dAdq_cols = jmodel.jointCols(data.dAdq);
247  ColsBlock dAdv_cols = jmodel.jointCols(data.dAdv);
248  ColsBlock dFdq_cols = jmodel.jointCols(data.dFdq);
249  ColsBlock dFdv_cols = jmodel.jointCols(data.dFdv);
250 
251  // dtau/dv
252  motionSet::inertiaAction(data.oYcrb[i],dAdv_cols,dFdv_cols);
253  dFdv_cols += data.doYcrb[i] * J_cols;
254 
255  rnea_partial_dv.block(jmodel.idx_v(),jmodel.idx_v(),jmodel.nv(),data.nvSubtree[i]).noalias()
256  = J_cols.transpose()*data.dFdv.middleCols(jmodel.idx_v(),data.nvSubtree[i]);
257 
258  // dtau/dq
259  motionSet::inertiaAction(data.oYcrb[i],dAdq_cols,dFdq_cols);
260  if(parent>0)
261  dFdq_cols += data.doYcrb[i] * dVdq_cols;
262 
263  rnea_partial_dq.block(jmodel.idx_v(),jmodel.idx_v(),jmodel.nv(),data.nvSubtree[i]).noalias()
264  = J_cols.transpose()*data.dFdq.middleCols(jmodel.idx_v(),data.nvSubtree[i]);
265 
266  motionSet::act<ADDTO>(J_cols,data.of[i],dFdq_cols);
267 
268  if(parent > 0)
269  {
270  lhsInertiaMult(data.oYcrb[i],J_cols.transpose(),M6tmpR.topRows(jmodel.nv()));
271  for(int j = data.parents_fromRow[(Model::Index)jmodel.idx_v()];j >= 0; j = data.parents_fromRow[(Model::Index)j])
272  rnea_partial_dq.middleRows(jmodel.idx_v(),jmodel.nv()).col(j).noalias() = M6tmpR.topRows(jmodel.nv()) * data.dAdq.col(j);
273  for(int j = data.parents_fromRow[(Model::Index)jmodel.idx_v()];j >= 0; j = data.parents_fromRow[(Model::Index)j])
274  rnea_partial_dv.middleRows(jmodel.idx_v(),jmodel.nv()).col(j).noalias() = M6tmpR.topRows(jmodel.nv()) * data.dAdv.col(j);
275 
276  M6tmpR.topRows(jmodel.nv()).noalias() = J_cols.transpose() * data.doYcrb[i];
277  for(int j = data.parents_fromRow[(Model::Index)jmodel.idx_v()];j >= 0; j = data.parents_fromRow[(Model::Index)j])
278  rnea_partial_dq.middleRows(jmodel.idx_v(),jmodel.nv()).col(j) += M6tmpR.topRows(jmodel.nv()) * data.dVdq.col(j);
279  for(int j = data.parents_fromRow[(Model::Index)jmodel.idx_v()];j >= 0; j = data.parents_fromRow[(Model::Index)j])
280  rnea_partial_dv.middleRows(jmodel.idx_v(),jmodel.nv()).col(j) += M6tmpR.topRows(jmodel.nv()) * data.J.col(j);
281  }
282 
283  if(parent>0)
284  {
285  data.oYcrb[parent] += data.oYcrb[i];
286  data.doYcrb[parent] += data.doYcrb[i];
287  data.of[parent] += data.of[i];
288  }
289  }
290 
291  template<typename Min, typename Mout>
292  static void lhsInertiaMult(const Inertia & Y,
293  const Eigen::MatrixBase<Min> & J,
294  const Eigen::MatrixBase<Mout> & F)
295  {
296  Mout & F_ = const_cast<Mout &>(F.derived());
297  motionSet::inertiaAction(Y,J.derived().transpose(),F_.transpose());
298  }
299  };
300 
301  inline void computeABADerivatives(const Model & model,
302  Data & data,
303  const Eigen::VectorXd & q,
304  const Eigen::VectorXd & v,
305  const Eigen::VectorXd & tau,
306  Eigen::MatrixXd & aba_partial_dq,
307  Eigen::MatrixXd & aba_partial_dv,
308  Data::RowMatrixXd & aba_partial_dtau)
309  {
310  assert(q.size() == model.nq && "The joint configuration vector is not of right size");
311  assert(v.size() == model.nv && "The joint velocity vector is not of right size");
312  assert(tau.size() == model.nv && "The joint acceleration vector is not of right size");
313  assert(aba_partial_dq.cols() == model.nv);
314  assert(aba_partial_dq.rows() == model.nv);
315  assert(aba_partial_dv.cols() == model.nv);
316  assert(aba_partial_dv.rows() == model.nv);
317  assert(aba_partial_dtau.cols() == model.nv);
318  assert(aba_partial_dtau.rows() == model.nv);
319  assert(model.check(data) && "data is not consistent with model.");
320 
321  data.a[0] = -model.gravity;
322  data.oa[0] = -model.gravity;
323  data.u = tau;
324 
325  Data::RowMatrixXd & Minv = aba_partial_dtau;
326 
328  for(Model::JointIndex i=1; i<(Model::JointIndex) model.njoints; ++i)
329  {
330  computeABADerivativesForwardStep1::run(model.joints[i],data.joints[i],
331  computeABADerivativesForwardStep1::ArgsType(model,data,q,v));
332  }
333 
334  data.Fcrb[0].setZero();
335  for(size_t i=(size_t) (model.njoints-1);i>0;--i)
336  {
337  computeABADerivativesBackwardStep1::run(model.joints[i],data.joints[i],
338  computeABADerivativesBackwardStep1::ArgsType(model,data,Minv));
339  }
340 
341  for(Model::JointIndex i=1; i<(Model::JointIndex) model.njoints; ++i)
342  {
343  computeABADerivativesForwardStep2::run(model.joints[i],data.joints[i],
344  computeABADerivativesForwardStep2::ArgsType(model,data,Minv));
345  }
346 
347  for(size_t i=(size_t) (model.njoints-1);i>0;--i)
348  {
349  computeABADerivativesBackwardStep2::run(model.joints[i],
350  computeABADerivativesBackwardStep2::ArgsType(model,data));
351  }
352 
353  Minv.triangularView<Eigen::StrictlyLower>()
354  = Minv.transpose().triangularView<Eigen::StrictlyLower>();
355 
356  aba_partial_dq.noalias() = -Minv*data.dtau_dq;
357  aba_partial_dv.noalias() = -Minv*data.dtau_dv;
358 
359  }
360 
361 
362 } // namespace se3
363 
364 #endif // ifndef __se3_aba_derivatives_hxx__
365 
container::aligned_vector< Force > oh
Vector of spatial momenta expressed in the world frame.
Definition: data.hpp:84
container::aligned_vector< Motion > a
Vector of joint accelerations expressed at the centers of the joints.
Definition: data.hpp:58
int nq
Dimension of the configuration vector representation.
Definition: model.hpp:49
void computeABADerivatives(const Model &model, Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const Eigen::VectorXd &tau, Eigen::MatrixXd &aba_partial_dq, Eigen::MatrixXd &aba_partial_dv, Data::RowMatrixXd &aba_partial_dtau)
The derivatives of the Articulated-Body algorithm.
int nv
Dimension of the velocity vector space.
Definition: model.hpp:52
container::aligned_vector< SE3 > jointPlacements
Placement (SE3) of the input of joint i regarding to the parent joint output li.
Definition: model.hpp:67
std::vector< int > nvSubtree
Dimension of the subtree motion space (for CRBA)
Definition: data.hpp:195
container::aligned_vector< Inertia > oYcrb
Inertia quantities expressed in the world frame.
Definition: data.hpp:149
Eigen::VectorXd u
Intermediate quantity corresponding to apparent torque [ABA].
Definition: data.hpp:168
Eigen::MatrixXd dtau_dv
Partial derivative of the joint torque vector with respect to the joint velocity. ...
Definition: data.hpp:235
Matrix6x dAdq
Variation of the spatial acceleration set with respect to the joint configuration.
Definition: data.hpp:226
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef Eigen::Matrix< double, 6, Eigen::Dynamic > Matrix6x
The 6d jacobian type (temporary)
Definition: data.hpp:45
JointModelVector joints
Model of joint i, encapsulated in a JointModelAccessor.
Definition: model.hpp:70
Matrix6x J
Jacobian of joint placements.
Definition: data.hpp:217
container::aligned_vector< Motion > oa
Vector of joint accelerations expressed at the origin.
Definition: data.hpp:61
container::aligned_vector< Inertia::Matrix6 > doYcrb
Time variation of the inertia quantities expressed in the world frame.
Definition: data.hpp:152
Matrix6x dVdq
Variation of the spatial velocity set with respect to the joint configuration.
Definition: data.hpp:223
Matrix6x dFdv
Variation of the forceset with respect to the joint velocity.
Definition: data.hpp:128
Eigen::VectorXd ddq
The joint accelerations computed from ABA.
Definition: data.hpp:161
container::aligned_vector< Force > of
Vector of body forces expressed in the world frame. For each body, the force represents the sum of al...
Definition: data.hpp:78
std::vector< JointIndex > parents
Joint parent of joint i, denoted li (li==parents[i]).
Definition: model.hpp:73
Matrix6x dAdv
Variation of the spatial acceleration set with respect to the joint velocity.
Definition: data.hpp:229
Matrix6x UDinv
Used in computeMinverse.
Definition: data.hpp:137
Matrix6x dFdq
Variation of the forceset with respect to the joint configuration.
Definition: data.hpp:125
Matrix6x SDinv
Used in computeMinverse.
Definition: data.hpp:134
container::aligned_vector< Inertia::Matrix6 > Yaba
Inertia matrix of the subtree expressed as dense matrix [ABA].
Definition: data.hpp:165
container::aligned_vector< Motion > ov
Vector of joint velocities expressed at the origin.
Definition: data.hpp:70
container::aligned_vector< Matrix6x > Fcrb
Spatial forces set, used in CRBA and CCRBA.
Definition: data.hpp:190
Matrix6x dJ
Derivative of the Jacobian with respect to the time.
Definition: data.hpp:220
Matrix6x IS
Used in computeMinverse.
Definition: data.hpp:140
JointDataVector joints
Vector of se3::JointData associated to the se3::JointModel stored in model, encapsulated in JointData...
Definition: data.hpp:55
Motion gravity
Spatial gravity of the model.
Definition: model.hpp:106
container::aligned_vector< SE3 > liMi
Vector of relative joint placements (wrt the body parent).
Definition: data.hpp:90
container::aligned_vector< SE3 > oMi
Vector of absolute joint placements (wrt the world).
Definition: data.hpp:87
bool check(const AlgorithmCheckerBase< D > &checker=AlgorithmCheckerBase< D >()) const
Definition: model.hpp:331
container::aligned_vector< Inertia > inertias
Spatial inertias of the body i expressed in the supporting joint frame i.
Definition: model.hpp:64
container::aligned_vector< Force > f
Vector of body forces expressed in the local frame of the joint. For each body, the force represents ...
Definition: data.hpp:74
RowMatrix6 M6tmpR
Temporary for derivative algorithms.
Definition: data.hpp:158
std::vector< int > parents_fromRow
First previous non-zero row in M (used in Cholesky Decomposition).
Definition: data.hpp:210
Eigen::MatrixXd dtau_dq
Partial derivative of the joint torque vector with respect to the joint configuration.
Definition: data.hpp:232
ToVectorConstReturnType toVector() const
Return the force as an Eigen vector.
Definition: force-base.hpp:99
container::aligned_vector< Motion > v
Vector of joint velocities expressed at the centers of the joints.
Definition: data.hpp:67
int njoints
Number of joints.
Definition: model.hpp:55