chainidsolver_vereshchagin.cpp
Go to the documentation of this file.
00001 // Copyright  (C)  2009, 2011
00002 
00003 // Version: 1.0
00004 // Author: Ruben Smits, Herman Bruyninckx, Azamat Shakhimardanov
00005 // Maintainer: Ruben Smits, Azamat Shakhimardanov
00006 // URL: http://www.orocos.org/kdl
00007 
00008 // This library is free software; you can redistribute it and/or
00009 // modify it under the terms of the GNU Lesser General Public
00010 // License as published by the Free Software Foundation; either
00011 // version 2.1 of the License, or (at your option) any later version.
00012 
00013 // This library is distributed in the hope that it will be useful,
00014 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00015 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00016 // Lesser General Public License for more details.
00017 
00018 // You should have received a copy of the GNU Lesser General Public
00019 // License along with this library; if not, write to the Free Software
00020 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
00021 
00022 #include "chainidsolver_vereshchagin.hpp"
00023 #include "frames_io.hpp"
00024 #include "utilities/svd_eigen_HH.hpp"
00025 
00026 
00027 namespace KDL
00028 {
00029 using namespace Eigen;
00030 
00031 ChainIdSolver_Vereshchagin::ChainIdSolver_Vereshchagin(const Chain& chain_, Twist root_acc, unsigned int _nc) :
00032     chain(chain_), nj(chain.getNrOfJoints()), ns(chain.getNrOfSegments()), nc(_nc),
00033     results(ns + 1, segment_info(nc))
00034 {
00035     acc_root = root_acc;
00036 
00037     //Provide the necessary memory for computing the inverse of M0
00038     nu_sum.resize(nc);
00039     M_0_inverse.resize(nc, nc);
00040     Um = MatrixXd::Identity(nc, nc);
00041     Vm = MatrixXd::Identity(nc, nc);
00042     Sm = VectorXd::Ones(nc);
00043     tmpm = VectorXd::Ones(nc);
00044 }
00045 
00046 void ChainIdSolver_Vereshchagin::updateInternalDataStructures() {
00047     ns = chain.getNrOfSegments();
00048     results.resize(ns+1,segment_info(nc));
00049 }
00050 
00051 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)
00052 {
00053     nj = chain.getNrOfJoints();
00054     if(ns != chain.getNrOfSegments())
00055         return (error = E_NOT_UP_TO_DATE);
00056     //Check sizes always
00057     if (q.rows() != nj || q_dot.rows() != nj || q_dotdot.rows() != nj || torques.rows() != nj || f_ext.size() != ns)
00058         return (error = E_SIZE_MISMATCH);
00059     if (alfa.columns() != nc || beta.rows() != nc)
00060         return (error = E_SIZE_MISMATCH);
00061     //do an upward recursion for position and velocities
00062     this->initial_upwards_sweep(q, q_dot, q_dotdot, f_ext);
00063     //do an inward recursion for inertia, forces and constraints
00064     this->downwards_sweep(alfa, torques);
00065     //Solve for the constraint forces
00066     this->constraint_calculation(beta);
00067     //do an upward recursion to propagate the result
00068     this->final_upwards_sweep(q_dotdot, torques);
00069     return (error = E_NOERROR);
00070 }
00071 
00072 void ChainIdSolver_Vereshchagin::initial_upwards_sweep(const JntArray &q, const JntArray &qdot, const JntArray &qdotdot, const Wrenches& f_ext)
00073 {
00074     //if (q.rows() != nj || qdot.rows() != nj || qdotdot.rows() != nj || f_ext.size() != ns)
00075     //        return -1;
00076 
00077     unsigned int j = 0;
00078     F_total = Frame::Identity();
00079     for (unsigned int i = 0; i < ns; i++)
00080     {
00081         //Express everything in the segments reference frame (body coordinates)
00082         //which is at the segments tip, i.e. where the next joint is attached.
00083 
00084         //Calculate segment properties: X,S,vj,cj
00085         const Segment& segment = chain.getSegment(i);
00086         segment_info& s = results[i + 1];
00087         //The pose between the joint root and the segment tip (tip expressed in joint root coordinates)
00088         s.F = segment.pose(q(j)); //X pose of each link in link coord system
00089 
00090         F_total = F_total * s.F; //X pose of the each link in root coord system
00091         s.F_base = F_total; //X pose of the each link in root coord system for getter functions
00092 
00093         //The velocity due to the joint motion of the segment expressed in the segments reference frame (tip)
00094         Twist vj = s.F.M.Inverse(segment.twist(q(j), qdot(j))); //XDot of each link
00095         //Twist aj = s.F.M.Inverse(segment.twist(q(j), qdotdot(j))); //XDotDot of each link
00096 
00097         //The unit velocity due to the joint motion of the segment expressed in the segments reference frame (tip)
00098         s.Z = s.F.M.Inverse(segment.twist(q(j), 1.0));
00099         //Put Z in the joint root reference frame:
00100         s.Z = s.F * s.Z;
00101 
00102         //The total velocity of the segment expressed in the segments reference frame (tip)
00103         if (i != 0)
00104         {
00105             s.v = s.F.Inverse(results[i].v) + vj; // recursive velocity of each link in segment frame
00106             //s.A=s.F.Inverse(results[i].A)+aj;
00107             s.A = s.F.M.Inverse(results[i].A);
00108         }
00109         else
00110         {
00111             s.v = vj;
00112             s.A = s.F.M.Inverse(acc_root);
00113         }
00114         //c[i] = cj + v[i]xvj (remark: cj=0, since our S is not time dependent in local coordinates)
00115         //The velocity product acceleration
00116         //std::cout << i << " Initial upward" << s.v << std::endl;
00117         s.C = s.v*vj; //This is a cross product: cartesian space BIAS acceleration in local link coord.
00118         //Put C in the joint root reference frame
00119         s.C = s.F * s.C; //+F_total.M.Inverse(acc_root));
00120         //The rigid body inertia of the segment, expressed in the segments reference frame (tip)
00121         s.H = segment.getInertia();
00122 
00123         //wrench of the rigid body bias forces and the external forces on the segment (in body coordinates, tip)
00124         //external forces are taken into account through s.U.
00125         Wrench FextLocal = F_total.M.Inverse() * f_ext[i];
00126         s.U = s.v * (s.H * s.v) - FextLocal; //f_ext[i];
00127         if (segment.getJoint().getType() != Joint::None)
00128             j++;
00129     }
00130 
00131 }
00132 
00133 void ChainIdSolver_Vereshchagin::downwards_sweep(const Jacobian& alfa, const JntArray &torques)
00134 {
00135     int j = nj - 1;
00136     for (int i = ns; i >= 0; i--)
00137     {
00138         //Get a handle for the segment we are working on.
00139         segment_info& s = results[i];
00140         //For segment N,
00141         //tilde is in the segment refframe (tip, not joint root)
00142         //without tilde is at the joint root (the childs tip!!!)
00143         //P_tilde is the articulated body inertia
00144         //R_tilde is the sum of external and coriolis/centrifugal forces
00145         //M is the (unit) acceleration energy already generated at link i
00146         //G is the (unit) magnitude of the constraint forces at link i
00147         //E are the (unit) constraint forces due to the constraints
00148         if (i == (int)ns)
00149         {
00150             s.P_tilde = s.H;
00151             s.R_tilde = s.U;
00152             s.M.setZero();
00153             s.G.setZero();
00154             //changeBase(alfa_N,F_total.M.Inverse(),alfa_N2);
00155             for (unsigned int r = 0; r < 3; r++)
00156                 for (unsigned int c = 0; c < nc; c++)
00157                 {
00158                     //copy alfa constrain force matrix in E~
00159                     s.E_tilde(r, c) = alfa(r + 3, c);
00160                     s.E_tilde(r + 3, c) = alfa(r, c);
00161                 }
00162             //Change the reference frame of alfa to the segmentN tip frame
00163             //F_Total holds end effector frame, if done per segment bases then constraints could be extended to all segments
00164             Rotation base_to_end = F_total.M.Inverse();
00165             for (unsigned int c = 0; c < nc; c++)
00166             {
00167                 Wrench col(Vector(s.E_tilde(3, c), s.E_tilde(4, c), s.E_tilde(5, c)),
00168                            Vector(s.E_tilde(0, c), s.E_tilde(1, c), s.E_tilde(2, c)));
00169                 col = base_to_end*col;
00170                 s.E_tilde.col(c) << Vector3d::Map(col.torque.data), Vector3d::Map(col.force.data);
00171             }
00172         }
00173         else
00174         {
00175             //For all others:
00176             //Everything should expressed in the body coordinates of segment i
00177             segment_info& child = results[i + 1];
00178             //Copy PZ into a vector so we can do matrix manipulations, put torques above forces
00179             Vector6d vPZ;
00180             vPZ << Vector3d::Map(child.PZ.torque.data), Vector3d::Map(child.PZ.force.data);
00181             Matrix6d PZDPZt;
00182             PZDPZt.noalias() = vPZ * vPZ.transpose();
00183             PZDPZt /= child.D;
00184 
00185             //equation a) (see Vereshchagin89) PZDPZt=[I,H;H',M]
00186             //Azamat:articulated body inertia as in Featherstone (7.19)
00187             s.P_tilde = s.H + child.P - ArticulatedBodyInertia(PZDPZt.bottomRightCorner<3,3>(), PZDPZt.topRightCorner<3,3>(), PZDPZt.topLeftCorner<3,3>());
00188             //equation b) (see Vereshchagin89)
00189             //Azamat: bias force as in Featherstone (7.20)
00190             s.R_tilde = s.U + child.R + child.PC + (child.PZ / child.D) * child.u;
00191             //equation c) (see Vereshchagin89)
00192             s.E_tilde = child.E;
00193 
00194             //Azamat: equation (c) right side term
00195             s.E_tilde.noalias() -= (vPZ * child.EZ.transpose()) / child.D;
00196 
00197             //equation d) (see Vereshchagin89)
00198             s.M = child.M;
00199             //Azamat: equation (d) right side term
00200             s.M.noalias() -= (child.EZ * child.EZ.transpose()) / child.D;
00201 
00202             //equation e) (see Vereshchagin89)
00203             s.G = child.G;
00204             Twist CiZDu = child.C + (child.Z / child.D) * child.u;
00205             Vector6d vCiZDu;
00206             vCiZDu << Vector3d::Map(CiZDu.rot.data), Vector3d::Map(CiZDu.vel.data);
00207             s.G.noalias() += child.E.transpose() * vCiZDu;
00208         }
00209         if (i != 0)
00210         {
00211             //Transform all results to joint root coordinates of segment i (== body coordinates segment i-1)
00212             //equation a)
00213             s.P = s.F * s.P_tilde;
00214             //equation b)
00215             s.R = s.F * s.R_tilde;
00216             //equation c), in matrix: torques above forces, so switch and switch back
00217             for (unsigned int c = 0; c < nc; c++)
00218             {
00219                 Wrench col(Vector(s.E_tilde(3, c), s.E_tilde(4, c), s.E_tilde(5, c)),
00220                            Vector(s.E_tilde(0, c), s.E_tilde(1, c), s.E_tilde(2, c)));
00221                 col = s.F*col;
00222                 s.E.col(c) << Vector3d::Map(col.torque.data), Vector3d::Map(col.force.data);
00223             }
00224 
00225             //needed for next recursion
00226             s.PZ = s.P * s.Z;
00227             s.D = dot(s.Z, s.PZ);
00228             s.PC = s.P * s.C;
00229 
00230             //u=(Q-Z(R+PC)=sum of external forces along the joint axes,
00231             //R are the forces coming from the children,
00232             //Q is taken zero (do we need to take the previous calculated torques?
00233 
00234             //projection of coriolis and centrepital forces into joint subspace (0 0 Z)
00235             s.totalBias = -dot(s.Z, s.R + s.PC);
00236             s.u = torques(j) + s.totalBias;
00237 
00238             //Matrix form of Z, put rotations above translations
00239             Vector6d vZ;
00240             vZ << Vector3d::Map(s.Z.rot.data), Vector3d::Map(s.Z.vel.data);
00241             s.EZ.noalias() = s.E.transpose() * vZ;
00242 
00243             if (chain.getSegment(i - 1).getJoint().getType() != Joint::None)
00244                 j--;
00245         }
00246     }
00247 }
00248 
00249 void ChainIdSolver_Vereshchagin::constraint_calculation(const JntArray& beta)
00250 {
00251     //equation f) nu = M_0_inverse*(beta_N - E0_tilde`*acc0 - G0)
00252     //M_0_inverse, always nc*nc symmetric matrix
00253     //std::cout<<"M0: "<<results[0].M<<std::endl;
00254     //results[0].M-=MatrixXd::Identity(nc,nc);
00255     //std::cout<<"augmented M0: "<<results[0].M<<std::endl;
00256 
00257 
00258     //ToDo: Need to check ill conditions
00259 
00260     //M_0_inverse=results[0].M.inverse();
00261     svd_eigen_HH(results[0].M, Um, Sm, Vm, tmpm);
00262     //truncated svd, what would sdls, dls physically mean?
00263     for (unsigned int i = 0; i < nc; i++)
00264         if (Sm(i) < 1e-14)
00265             Sm(i) = 0.0;
00266         else
00267             Sm(i) = 1 / Sm(i);
00268 
00269     results[0].M.noalias() = Vm * Sm.asDiagonal();
00270     M_0_inverse.noalias() = results[0].M * Um.transpose();
00271     //results[0].M.ldlt().solve(MatrixXd::Identity(nc,nc),&M_0_inverse);
00272     //results[0].M.computeInverse(&M_0_inverse);
00273     Vector6d acc;
00274     acc << Vector3d::Map(acc_root.rot.data), Vector3d::Map(acc_root.vel.data);
00275     nu_sum.noalias() = -(results[0].E_tilde.transpose() * acc);
00276     //nu_sum.setZero();
00277     nu_sum += beta.data;
00278     nu_sum -= results[0].G;
00279 
00280     //equation f) nu = M_0_inverse*(beta_N - E0_tilde`*acc0 - G0)
00281     nu.noalias() = M_0_inverse * nu_sum;
00282 }
00283 
00284 void ChainIdSolver_Vereshchagin::final_upwards_sweep(JntArray &q_dotdot, JntArray &torques)
00285 {
00286     unsigned int j = 0;
00287 
00288     for (unsigned int i = 1; i <= ns; i++)
00289     {
00290         segment_info& s = results[i];
00291         //Calculation of joint and segment accelerations
00292         //equation g) qdotdot[i] = D^-1*(Q - Z'(R + P(C + acc[i-1]) + E*nu))
00293         // = D^-1(u - Z'(P*acc[i-1] + E*nu)
00294         Twist a_g;
00295         Twist a_p;
00296         if (i == 1)
00297         {
00298             a_p = acc_root;
00299         }
00300         else
00301         {
00302             a_p = results[i - 1].acc;
00303         }
00304 
00305         //The contribution of the constraint forces at segment i
00306         Vector6d tmp = s.E*nu;
00307         Wrench constraint_force = Wrench(Vector(tmp(3), tmp(4), tmp(5)),
00308                                          Vector(tmp(0), tmp(1), tmp(2)));
00309 
00310         //acceleration components are also computed
00311         //Contribution of the acceleration of the parent (i-1)
00312         Wrench parent_force = s.P*a_p;
00313         double parent_forceProjection = -dot(s.Z, parent_force);
00314         double parentAccComp = parent_forceProjection / s.D;
00315 
00316         //The constraint force and acceleration force projected on the joint axes -> axis torque/force
00317         double constraint_torque = -dot(s.Z, constraint_force);
00318         //The result should be the torque at this joint
00319 
00320         torques(j) = constraint_torque;
00321         //s.constAccComp = torques(j) / s.D;
00322         s.constAccComp = constraint_torque / s.D;
00323         s.nullspaceAccComp = s.u / s.D;
00324         //total joint space acceleration resulting from accelerations of parent joints, constraint forces and
00325         // nullspace forces.
00326         q_dotdot(j) = (s.nullspaceAccComp + parentAccComp + s.constAccComp);
00327         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
00328         if (chain.getSegment(i - 1).getJoint().getType() != Joint::None)
00329             j++;
00330     }
00331 }
00332 
00333 /*
00334 void ChainIdSolver_Vereshchagin::getLinkCartesianPose(Frames& x_base)
00335 {
00336     for (int i = 0; i < ns; i++)
00337     {
00338         x_base[i] = results[i + 1].F_base;
00339     }
00340     return;
00341 }
00342 
00343 void ChainIdSolver_Vereshchagin::getLinkCartesianVelocity(Twists& xDot_base)
00344 {
00345 
00346     for (int i = 0; i < ns; i++)
00347     {
00348         xDot_base[i] = results[i + 1].F_base.M * results[i + 1].v;
00349     }
00350     return;
00351 }
00352 
00353 void ChainIdSolver_Vereshchagin::getLinkCartesianAcceleration(Twists& xDotDot_base)
00354 {
00355 
00356     for (int i = 0; i < ns; i++)
00357     {
00358         xDotDot_base[i] = results[i + 1].F_base.M * results[i + 1].acc;
00359         //std::cout << "XDotDot_base[i] " << xDotDot_base[i] << std::endl;
00360     }
00361     return;
00362 }
00363 
00364 void ChainIdSolver_Vereshchagin::getLinkPose(Frames& x_local)
00365 {
00366     for (int i = 0; i < ns; i++)
00367     {
00368         x_local[i] = results[i + 1].F;
00369     }
00370     return;
00371 }
00372 
00373 void ChainIdSolver_Vereshchagin::getLinkVelocity(Twists& xDot_local)
00374 {
00375     for (int i = 0; i < ns; i++)
00376     {
00377         xDot_local[i] = results[i + 1].v;
00378     }
00379     return;
00380 
00381 }
00382 
00383 void ChainIdSolver_Vereshchagin::getLinkAcceleration(Twists& xDotdot_local)
00384 {
00385      for (int i = 0; i < ns; i++)
00386     {
00387         xDotdot_local[i] = results[i + 1].acc;
00388     }
00389     return;
00390 
00391 }
00392 
00393 void ChainIdSolver_Vereshchagin::getJointBiasAcceleration(JntArray& bias_q_dotdot)
00394 {
00395     for (int i = 0; i < ns; i++)
00396     {
00397         //this is only force
00398         double tmp = results[i + 1].totalBias;
00399         //this is acceleration
00400         bias_q_dotdot(i) = tmp / results[i + 1].D;
00401 
00402         //s.totalBias = - dot(s.Z, s.R + s.PC);
00403         //std::cout << "totalBiasAccComponent" << i << ": " << bias_q_dotdot(i) << std::endl;
00404         //bias_q_dotdot(i) = s.totalBias/s.D
00405 
00406     }
00407     return;
00408 
00409 }
00410 
00411 void ChainIdSolver_Vereshchagin::getJointConstraintAcceleration(JntArray& constraint_q_dotdot)
00412 {
00413     for (int i = 0; i < ns; i++)
00414     {
00415         constraint_q_dotdot(i) = results[i + 1].constAccComp;
00416         //double tmp = results[i + 1].u;
00417         //s.u = torques(j) + s.totalBias;
00418         // std::cout << "s.constraintAccComp" << i << ": " << results[i+1].constAccComp << std::endl;
00419         //nullspace_q_dotdot(i) = s.u/s.D
00420 
00421     }
00422     return;
00423 
00424 
00425 }
00426 
00427 //Check the name it does not seem to be appropriate
00428 
00429 void ChainIdSolver_Vereshchagin::getJointNullSpaceAcceleration(JntArray& nullspace_q_dotdot)
00430 {
00431     for (int i = 0; i < ns; i++)
00432     {
00433         nullspace_q_dotdot(i) = results[i + 1].nullspaceAccComp;
00434         //double tmp = results[i + 1].u;
00435         //s.u = torques(j) + s.totalBias;
00436         //std::cout << "s.nullSpaceAccComp" << i << ": " << results[i+1].nullspaceAccComp << std::endl;
00437         //nullspace_q_dotdot(i) = s.u/s.D
00438 
00439     }
00440     return;
00441 
00442 
00443 }
00444 
00445 //This is not only a bias force energy but also includes generalized forces
00446 //change type of parameter G
00447 //this method should return array of G's
00448 
00449 void ChainIdSolver_Vereshchagin::getLinkBiasForceAcceleratoinEnergy(Eigen::VectorXd& G)
00450 {
00451     for (int i = 0; i < ns; i++)
00452     {
00453         G = results[i + 1].G;
00454         //double tmp = results[i + 1].u;
00455         //s.u = torques(j) + s.totalBias;
00456         //std::cout << "s.G " << i << ":  " << results[i+1].G << std::endl;
00457         //nullspace_q_dotdot(i) = s.u/s.D
00458 
00459     }
00460     return;
00461 
00462 }
00463 
00464 //this method should return array of R's
00465 
00466 void ChainIdSolver_Vereshchagin::getLinkBiasForceMatrix(Wrenches& R_tilde)
00467 {
00468     for (int i = 0; i < ns; i++)
00469     {
00470         R_tilde[i] = results[i + 1].R_tilde;
00471         //Azamat: bias force as in Featherstone (7.20)
00472         //s.R_tilde = s.U + child.R + child.PC + child.PZ / child.D * child.u;
00473         std::cout << "s.R_tilde " << i << ":  " << results[i + 1].R_tilde << std::endl;
00474     }
00475     return;
00476 }
00477 
00478 */
00479 
00480 }//namespace


orocos_kdl
Author(s):
autogenerated on Fri Jun 14 2019 19:33:22