chainidsolver_vereshchagin.cpp
Go to the documentation of this file.
1 // Copyright (C) 2009, 2011
2 
3 // Version: 1.0
4 // Author: Ruben Smits, Herman Bruyninckx, Azamat Shakhimardanov
5 // Maintainer: Ruben Smits, Azamat Shakhimardanov
6 // URL: http://www.orocos.org/kdl
7 
8 // This library is free software; you can redistribute it and/or
9 // modify it under the terms of the GNU Lesser General Public
10 // License as published by the Free Software Foundation; either
11 // version 2.1 of the License, or (at your option) any later version.
12 
13 // This library is distributed in the hope that it will be useful,
14 // but WITHOUT ANY WARRANTY; without even the implied warranty of
15 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
16 // Lesser General Public License for more details.
17 
18 // You should have received a copy of the GNU Lesser General Public
19 // License along with this library; if not, write to the Free Software
20 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA
21 
23 #include "frames_io.hpp"
25 
26 
27 namespace KDL
28 {
29 using namespace Eigen;
30 
31 ChainIdSolver_Vereshchagin::ChainIdSolver_Vereshchagin(const Chain& chain_, Twist root_acc, unsigned int _nc) :
32  chain(chain_), nj(chain.getNrOfJoints()), ns(chain.getNrOfSegments()), nc(_nc),
33  results(ns + 1, segment_info(nc))
34 {
35  acc_root = root_acc;
36 
37  //Provide the necessary memory for computing the inverse of M0
38  nu_sum.resize(nc);
39  M_0_inverse.resize(nc, nc);
40  Um = MatrixXd::Identity(nc, nc);
41  Vm = MatrixXd::Identity(nc, nc);
42  Sm = VectorXd::Ones(nc);
43  tmpm = VectorXd::Ones(nc);
44 }
45 
48  results.resize(ns+1,segment_info(nc));
49 }
50 
51 int ChainIdSolver_Vereshchagin::CartToJnt(const JntArray &q, const JntArray &q_dot, JntArray &q_dotdot, const Jacobian& alfa, const JntArray& beta, const Wrenches& f_ext, JntArray &torques)
52 {
54  if(ns != chain.getNrOfSegments())
55  return (error = E_NOT_UP_TO_DATE);
56  //Check sizes always
57  if (q.rows() != nj || q_dot.rows() != nj || q_dotdot.rows() != nj || torques.rows() != nj || f_ext.size() != ns)
58  return (error = E_SIZE_MISMATCH);
59  if (alfa.columns() != nc || beta.rows() != nc)
60  return (error = E_SIZE_MISMATCH);
61  //do an upward recursion for position and velocities
62  this->initial_upwards_sweep(q, q_dot, q_dotdot, f_ext);
63  //do an inward recursion for inertia, forces and constraints
64  this->downwards_sweep(alfa, torques);
65  //Solve for the constraint forces
66  this->constraint_calculation(beta);
67  //do an upward recursion to propagate the result
68  this->final_upwards_sweep(q_dotdot, torques);
69  return (error = E_NOERROR);
70 }
71 
72 void ChainIdSolver_Vereshchagin::initial_upwards_sweep(const JntArray &q, const JntArray &qdot, const JntArray &qdotdot, const Wrenches& f_ext)
73 {
74  //if (q.rows() != nj || qdot.rows() != nj || qdotdot.rows() != nj || f_ext.size() != ns)
75  // return -1;
76 
77  unsigned int j = 0;
79  for (unsigned int i = 0; i < ns; i++)
80  {
81  //Express everything in the segments reference frame (body coordinates)
82  //which is at the segments tip, i.e. where the next joint is attached.
83 
84  //Calculate segment properties: X,S,vj,cj
85  const Segment& segment = chain.getSegment(i);
86  segment_info& s = results[i + 1];
87  //The pose between the joint root and the segment tip (tip expressed in joint root coordinates)
88  s.F = segment.pose(q(j)); //X pose of each link in link coord system
89 
90  F_total = F_total * s.F; //X pose of the each link in root coord system
91  s.F_base = F_total; //X pose of the each link in root coord system for getter functions
92 
93  //The velocity due to the joint motion of the segment expressed in the segments reference frame (tip)
94  Twist vj = s.F.M.Inverse(segment.twist(q(j), qdot(j))); //XDot of each link
95  //Twist aj = s.F.M.Inverse(segment.twist(q(j), qdotdot(j))); //XDotDot of each link
96 
97  //The unit velocity due to the joint motion of the segment expressed in the segments reference frame (tip)
98  s.Z = s.F.M.Inverse(segment.twist(q(j), 1.0));
99  //Put Z in the joint root reference frame:
100  s.Z = s.F * s.Z;
101 
102  //The total velocity of the segment expressed in the segments reference frame (tip)
103  if (i != 0)
104  {
105  s.v = s.F.Inverse(results[i].v) + vj; // recursive velocity of each link in segment frame
106  //s.A=s.F.Inverse(results[i].A)+aj;
107  s.A = s.F.M.Inverse(results[i].A);
108  }
109  else
110  {
111  s.v = vj;
112  s.A = s.F.M.Inverse(acc_root);
113  }
114  //c[i] = cj + v[i]xvj (remark: cj=0, since our S is not time dependent in local coordinates)
115  //The velocity product acceleration
116  //std::cout << i << " Initial upward" << s.v << std::endl;
117  s.C = s.v*vj; //This is a cross product: cartesian space BIAS acceleration in local link coord.
118  //Put C in the joint root reference frame
119  s.C = s.F * s.C; //+F_total.M.Inverse(acc_root));
120  //The rigid body inertia of the segment, expressed in the segments reference frame (tip)
121  s.H = segment.getInertia();
122 
123  //wrench of the rigid body bias forces and the external forces on the segment (in body coordinates, tip)
124  //external forces are taken into account through s.U.
125  Wrench FextLocal = F_total.M.Inverse() * f_ext[i];
126  s.U = s.v * (s.H * s.v) - FextLocal; //f_ext[i];
127  if (segment.getJoint().getType() != Joint::None)
128  j++;
129  }
130 
131 }
132 
134 {
135  int j = nj - 1;
136  for (int i = ns; i >= 0; i--)
137  {
138  //Get a handle for the segment we are working on.
139  segment_info& s = results[i];
140  //For segment N,
141  //tilde is in the segment refframe (tip, not joint root)
142  //without tilde is at the joint root (the childs tip!!!)
143  //P_tilde is the articulated body inertia
144  //R_tilde is the sum of external and coriolis/centrifugal forces
145  //M is the (unit) acceleration energy already generated at link i
146  //G is the (unit) magnitude of the constraint forces at link i
147  //E are the (unit) constraint forces due to the constraints
148  if (i == (int)ns)
149  {
150  s.P_tilde = s.H;
151  s.R_tilde = s.U;
152  s.M.setZero();
153  s.G.setZero();
154  //changeBase(alfa_N,F_total.M.Inverse(),alfa_N2);
155  for (unsigned int r = 0; r < 3; r++)
156  for (unsigned int c = 0; c < nc; c++)
157  {
158  //copy alfa constrain force matrix in E~
159  s.E_tilde(r, c) = alfa(r + 3, c);
160  s.E_tilde(r + 3, c) = alfa(r, c);
161  }
162  //Change the reference frame of alfa to the segmentN tip frame
163  //F_Total holds end effector frame, if done per segment bases then constraints could be extended to all segments
164  Rotation base_to_end = F_total.M.Inverse();
165  for (unsigned int c = 0; c < nc; c++)
166  {
167  Wrench col(Vector(s.E_tilde(3, c), s.E_tilde(4, c), s.E_tilde(5, c)),
168  Vector(s.E_tilde(0, c), s.E_tilde(1, c), s.E_tilde(2, c)));
169  col = base_to_end*col;
170  s.E_tilde.col(c) << Vector3d::Map(col.torque.data), Vector3d::Map(col.force.data);
171  }
172  }
173  else
174  {
175  //For all others:
176  //Everything should expressed in the body coordinates of segment i
177  segment_info& child = results[i + 1];
178  //Copy PZ into a vector so we can do matrix manipulations, put torques above forces
179  Vector6d vPZ;
180  vPZ << Vector3d::Map(child.PZ.torque.data), Vector3d::Map(child.PZ.force.data);
181  Matrix6d PZDPZt;
182  PZDPZt.noalias() = vPZ * vPZ.transpose();
183  PZDPZt /= child.D;
184 
185  //equation a) (see Vereshchagin89) PZDPZt=[I,H;H',M]
186  //Azamat:articulated body inertia as in Featherstone (7.19)
187  s.P_tilde = s.H + child.P - ArticulatedBodyInertia(PZDPZt.bottomRightCorner<3,3>(), PZDPZt.topRightCorner<3,3>(), PZDPZt.topLeftCorner<3,3>());
188  //equation b) (see Vereshchagin89)
189  //Azamat: bias force as in Featherstone (7.20)
190  s.R_tilde = s.U + child.R + child.PC + (child.PZ / child.D) * child.u;
191  //equation c) (see Vereshchagin89)
192  s.E_tilde = child.E;
193 
194  //Azamat: equation (c) right side term
195  s.E_tilde.noalias() -= (vPZ * child.EZ.transpose()) / child.D;
196 
197  //equation d) (see Vereshchagin89)
198  s.M = child.M;
199  //Azamat: equation (d) right side term
200  s.M.noalias() -= (child.EZ * child.EZ.transpose()) / child.D;
201 
202  //equation e) (see Vereshchagin89)
203  s.G = child.G;
204  Twist CiZDu = child.C + (child.Z / child.D) * child.u;
205  Vector6d vCiZDu;
206  vCiZDu << Vector3d::Map(CiZDu.rot.data), Vector3d::Map(CiZDu.vel.data);
207  s.G.noalias() += child.E.transpose() * vCiZDu;
208  }
209  if (i != 0)
210  {
211  //Transform all results to joint root coordinates of segment i (== body coordinates segment i-1)
212  //equation a)
213  s.P = s.F * s.P_tilde;
214  //equation b)
215  s.R = s.F * s.R_tilde;
216  //equation c), in matrix: torques above forces, so switch and switch back
217  for (unsigned int c = 0; c < nc; c++)
218  {
219  Wrench col(Vector(s.E_tilde(3, c), s.E_tilde(4, c), s.E_tilde(5, c)),
220  Vector(s.E_tilde(0, c), s.E_tilde(1, c), s.E_tilde(2, c)));
221  col = s.F*col;
222  s.E.col(c) << Vector3d::Map(col.torque.data), Vector3d::Map(col.force.data);
223  }
224 
225  //needed for next recursion
226  s.PZ = s.P * s.Z;
227  s.D = dot(s.Z, s.PZ);
228  s.PC = s.P * s.C;
229 
230  //u=(Q-Z(R+PC)=sum of external forces along the joint axes,
231  //R are the forces coming from the children,
232  //Q is taken zero (do we need to take the previous calculated torques?
233 
234  //projection of coriolis and centrepital forces into joint subspace (0 0 Z)
235  s.totalBias = -dot(s.Z, s.R + s.PC);
236  s.u = torques(j) + s.totalBias;
237 
238  //Matrix form of Z, put rotations above translations
239  Vector6d vZ;
240  vZ << Vector3d::Map(s.Z.rot.data), Vector3d::Map(s.Z.vel.data);
241  s.EZ.noalias() = s.E.transpose() * vZ;
242 
243  if (chain.getSegment(i - 1).getJoint().getType() != Joint::None)
244  j--;
245  }
246  }
247 }
248 
250 {
251  //equation f) nu = M_0_inverse*(beta_N - E0_tilde`*acc0 - G0)
252  //M_0_inverse, always nc*nc symmetric matrix
253  //std::cout<<"M0: "<<results[0].M<<std::endl;
254  //results[0].M-=MatrixXd::Identity(nc,nc);
255  //std::cout<<"augmented M0: "<<results[0].M<<std::endl;
256 
257 
258  //ToDo: Need to check ill conditions
259 
260  //M_0_inverse=results[0].M.inverse();
261  svd_eigen_HH(results[0].M, Um, Sm, Vm, tmpm);
262  //truncated svd, what would sdls, dls physically mean?
263  for (unsigned int i = 0; i < nc; i++)
264  if (Sm(i) < 1e-14)
265  Sm(i) = 0.0;
266  else
267  Sm(i) = 1 / Sm(i);
268 
269  results[0].M.noalias() = Vm * Sm.asDiagonal();
270  M_0_inverse.noalias() = results[0].M * Um.transpose();
271  //results[0].M.ldlt().solve(MatrixXd::Identity(nc,nc),&M_0_inverse);
272  //results[0].M.computeInverse(&M_0_inverse);
273  Vector6d acc;
274  acc << Vector3d::Map(acc_root.rot.data), Vector3d::Map(acc_root.vel.data);
275  nu_sum.noalias() = -(results[0].E_tilde.transpose() * acc);
276  //nu_sum.setZero();
277  nu_sum += beta.data;
278  nu_sum -= results[0].G;
279 
280  //equation f) nu = M_0_inverse*(beta_N - E0_tilde`*acc0 - G0)
281  nu.noalias() = M_0_inverse * nu_sum;
282 }
283 
285 {
286  unsigned int j = 0;
287 
288  for (unsigned int i = 1; i <= ns; i++)
289  {
290  segment_info& s = results[i];
291  //Calculation of joint and segment accelerations
292  //equation g) qdotdot[i] = D^-1*(Q - Z'(R + P(C + acc[i-1]) + E*nu))
293  // = D^-1(u - Z'(P*acc[i-1] + E*nu)
294  Twist a_g;
295  Twist a_p;
296  if (i == 1)
297  {
298  a_p = acc_root;
299  }
300  else
301  {
302  a_p = results[i - 1].acc;
303  }
304 
305  //The contribution of the constraint forces at segment i
306  Vector6d tmp = s.E*nu;
307  Wrench constraint_force = Wrench(Vector(tmp(3), tmp(4), tmp(5)),
308  Vector(tmp(0), tmp(1), tmp(2)));
309 
310  //acceleration components are also computed
311  //Contribution of the acceleration of the parent (i-1)
312  Wrench parent_force = s.P*a_p;
313  double parent_forceProjection = -dot(s.Z, parent_force);
314  double parentAccComp = parent_forceProjection / s.D;
315 
316  //The constraint force and acceleration force projected on the joint axes -> axis torque/force
317  double constraint_torque = -dot(s.Z, constraint_force);
318  //The result should be the torque at this joint
319 
320  torques(j) = constraint_torque;
321  //s.constAccComp = torques(j) / s.D;
322  s.constAccComp = constraint_torque / s.D;
323  s.nullspaceAccComp = s.u / s.D;
324  //total joint space acceleration resulting from accelerations of parent joints, constraint forces and
325  // nullspace forces.
326  q_dotdot(j) = (s.nullspaceAccComp + parentAccComp + s.constAccComp);
327  s.acc = s.F.Inverse(a_p + s.Z * q_dotdot(j) + s.C);//returns acceleration in link distal tip coordinates. For use needs to be transformed
328  if (chain.getSegment(i - 1).getJoint().getType() != Joint::None)
329  j++;
330  }
331 }
332 
333 /*
334 void ChainIdSolver_Vereshchagin::getLinkCartesianPose(Frames& x_base)
335 {
336  for (int i = 0; i < ns; i++)
337  {
338  x_base[i] = results[i + 1].F_base;
339  }
340  return;
341 }
342 
343 void ChainIdSolver_Vereshchagin::getLinkCartesianVelocity(Twists& xDot_base)
344 {
345 
346  for (int i = 0; i < ns; i++)
347  {
348  xDot_base[i] = results[i + 1].F_base.M * results[i + 1].v;
349  }
350  return;
351 }
352 
353 void ChainIdSolver_Vereshchagin::getLinkCartesianAcceleration(Twists& xDotDot_base)
354 {
355 
356  for (int i = 0; i < ns; i++)
357  {
358  xDotDot_base[i] = results[i + 1].F_base.M * results[i + 1].acc;
359  //std::cout << "XDotDot_base[i] " << xDotDot_base[i] << std::endl;
360  }
361  return;
362 }
363 
364 void ChainIdSolver_Vereshchagin::getLinkPose(Frames& x_local)
365 {
366  for (int i = 0; i < ns; i++)
367  {
368  x_local[i] = results[i + 1].F;
369  }
370  return;
371 }
372 
373 void ChainIdSolver_Vereshchagin::getLinkVelocity(Twists& xDot_local)
374 {
375  for (int i = 0; i < ns; i++)
376  {
377  xDot_local[i] = results[i + 1].v;
378  }
379  return;
380 
381 }
382 
383 void ChainIdSolver_Vereshchagin::getLinkAcceleration(Twists& xDotdot_local)
384 {
385  for (int i = 0; i < ns; i++)
386  {
387  xDotdot_local[i] = results[i + 1].acc;
388  }
389  return;
390 
391 }
392 
393 void ChainIdSolver_Vereshchagin::getJointBiasAcceleration(JntArray& bias_q_dotdot)
394 {
395  for (int i = 0; i < ns; i++)
396  {
397  //this is only force
398  double tmp = results[i + 1].totalBias;
399  //this is acceleration
400  bias_q_dotdot(i) = tmp / results[i + 1].D;
401 
402  //s.totalBias = - dot(s.Z, s.R + s.PC);
403  //std::cout << "totalBiasAccComponent" << i << ": " << bias_q_dotdot(i) << std::endl;
404  //bias_q_dotdot(i) = s.totalBias/s.D
405 
406  }
407  return;
408 
409 }
410 
411 void ChainIdSolver_Vereshchagin::getJointConstraintAcceleration(JntArray& constraint_q_dotdot)
412 {
413  for (int i = 0; i < ns; i++)
414  {
415  constraint_q_dotdot(i) = results[i + 1].constAccComp;
416  //double tmp = results[i + 1].u;
417  //s.u = torques(j) + s.totalBias;
418  // std::cout << "s.constraintAccComp" << i << ": " << results[i+1].constAccComp << std::endl;
419  //nullspace_q_dotdot(i) = s.u/s.D
420 
421  }
422  return;
423 
424 
425 }
426 
427 //Check the name it does not seem to be appropriate
428 
429 void ChainIdSolver_Vereshchagin::getJointNullSpaceAcceleration(JntArray& nullspace_q_dotdot)
430 {
431  for (int i = 0; i < ns; i++)
432  {
433  nullspace_q_dotdot(i) = results[i + 1].nullspaceAccComp;
434  //double tmp = results[i + 1].u;
435  //s.u = torques(j) + s.totalBias;
436  //std::cout << "s.nullSpaceAccComp" << i << ": " << results[i+1].nullspaceAccComp << std::endl;
437  //nullspace_q_dotdot(i) = s.u/s.D
438 
439  }
440  return;
441 
442 
443 }
444 
445 //This is not only a bias force energy but also includes generalized forces
446 //change type of parameter G
447 //this method should return array of G's
448 
449 void ChainIdSolver_Vereshchagin::getLinkBiasForceAcceleratoinEnergy(Eigen::VectorXd& G)
450 {
451  for (int i = 0; i < ns; i++)
452  {
453  G = results[i + 1].G;
454  //double tmp = results[i + 1].u;
455  //s.u = torques(j) + s.totalBias;
456  //std::cout << "s.G " << i << ": " << results[i+1].G << std::endl;
457  //nullspace_q_dotdot(i) = s.u/s.D
458 
459  }
460  return;
461 
462 }
463 
464 //this method should return array of R's
465 
466 void ChainIdSolver_Vereshchagin::getLinkBiasForceMatrix(Wrenches& R_tilde)
467 {
468  for (int i = 0; i < ns; i++)
469  {
470  R_tilde[i] = results[i + 1].R_tilde;
471  //Azamat: bias force as in Featherstone (7.20)
472  //s.R_tilde = s.U + child.R + child.PC + child.PZ / child.D * child.u;
473  std::cout << "s.R_tilde " << i << ": " << results[i + 1].R_tilde << std::endl;
474  }
475  return;
476 }
477 
478 */
479 
480 }//namespace
represents rotations in 3 dimensional space.
Definition: frames.hpp:301
const Segment & getSegment(unsigned int nr) const
Definition: chain.cpp:68
This class encapsulates a simple segment, that is a "rigid body" (i.e., a frame and a rigid body...
Definition: segment.hpp:46
unsigned int rows() const
Definition: jntarray.cpp:72
Rotation Inverse() const
Gives back the inverse rotation matrix of *this.
Definition: frames.hpp:633
This class encapsulates a serial kinematic interconnection structure. It is built out of segments...
Definition: chain.hpp:35
Vector vel
The velocity of that point.
Definition: frames.hpp:722
Eigen::Matrix< double, 6, 1 > Vector6d
Chain size changed.
Definition: solveri.hpp:97
unsigned int getNrOfSegments() const
Definition: chain.hpp:76
This class represents an fixed size array containing joint values of a KDL::Chain.
Definition: jntarray.hpp:69
Input size does not match internal state.
Definition: solveri.hpp:99
Vector torque
Torque that is applied at the origin of the current ref frame.
Definition: frames.hpp:882
doubleAcc dot(const VectorAcc &lhs, const VectorAcc &rhs)
Definition: frameacc.hpp:138
unsigned int columns() const
Definition: jacobian.cpp:75
int svd_eigen_HH(const MatrixXd &A, MatrixXd &U, VectorXd &S, MatrixXd &V, VectorXd &tmp, int maxiter, double epsilon)
Rotation M
Orientation of the Frame.
Definition: frames.hpp:573
Frame pose(const double &q) const
Definition: segment.cpp:57
Twist twist(const double &q, const double &qdot) const
Definition: segment.cpp:62
represents both translational and rotational velocities.
Definition: frames.hpp:720
int CartToJnt(const JntArray &q, const JntArray &q_dot, JntArray &q_dotdot, const Jacobian &alfa, const JntArray &beta, const Wrenches &f_ext, JntArray &torques)
6D Inertia of a articulated body
A concrete implementation of a 3 dimensional vector class.
Definition: frames.hpp:160
Vector rot
The rotational velocity of that point.
Definition: frames.hpp:723
double data[3]
Definition: frames.hpp:163
void constraint_calculation(const JntArray &beta)
Eigen::VectorXd data
Definition: jntarray.hpp:72
void final_upwards_sweep(JntArray &q_dotdot, JntArray &torques)
const Joint & getJoint() const
Definition: segment.hpp:118
unsigned int getNrOfJoints() const
Definition: chain.hpp:71
Frame Inverse() const
Gives back inverse transformation of a Frame.
Definition: frames.hpp:423
ChainIdSolver_Vereshchagin(const Chain &chain, Twist root_acc, unsigned int nc)
Vector force
Force that is applied at the origin of the current ref frame.
Definition: frames.hpp:881
void downwards_sweep(const Jacobian &alfa, const JntArray &torques)
std::vector< Wrench > Wrenches
void initial_upwards_sweep(const JntArray &q, const JntArray &q_dot, const JntArray &q_dotdot, const Wrenches &f_ext)
static Frame Identity()
Definition: frames.hpp:696
represents both translational and rotational acceleration.
Definition: frames.hpp:878
std::vector< segment_info, Eigen::aligned_allocator< segment_info > > results
int error
Latest error, initialized to E_NOERROR in constructor.
Definition: solveri.hpp:149
const RigidBodyInertia & getInertia() const
Definition: segment.hpp:128
const JointType & getType() const
Definition: joint.hpp:159
Eigen::Matrix< double, 6, 6 > Matrix6d


orocos_kdl
Author(s):
autogenerated on Sat Jun 15 2019 19:07:36