chaindynparam.cpp
Go to the documentation of this file.
00001 // Copyright  (C)  2009  Dominick Vanthienen <dominick dot vanthienen at mech dot kuleuven dot be>
00002 
00003 // Version: 1.0
00004 // Author: Dominick Vanthienen <dominick dot vanthienen at mech dot kuleuven dot be>
00005 // Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
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 "chaindynparam.hpp"
00023 #include "frames_io.hpp"
00024 #include <iostream>
00025 
00026 namespace KDL {
00027 
00028     ChainDynParam::ChainDynParam(const Chain& _chain, Vector _grav):
00029             chain(_chain),
00030             nr(0),
00031             nj(chain.getNrOfJoints()),
00032             ns(chain.getNrOfSegments()),
00033             grav(_grav),
00034             jntarraynull(nj),
00035             chainidsolver_coriolis( chain, Vector::Zero()),
00036             chainidsolver_gravity( chain, grav),
00037             wrenchnull(ns,Wrench::Zero()),
00038             X(ns),
00039             S(ns),
00040             Ic(ns)
00041     {
00042         ag=-Twist(grav,Vector::Zero());
00043     }
00044 
00045     void ChainDynParam::updateInternalDataStructures() {
00046         nj = chain.getNrOfJoints();
00047         ns = chain.getNrOfSegments();
00048         jntarraynull.resize(nj);
00049         chainidsolver_coriolis.updateInternalDataStructures();
00050         chainidsolver_gravity.updateInternalDataStructures();
00051         wrenchnull.resize(ns,Wrench::Zero());
00052         X.resize(ns);
00053         S.resize(ns);
00054         Ic.resize(ns);
00055     }
00056 
00057 
00058     //calculate inertia matrix H
00059     int ChainDynParam::JntToMass(const JntArray &q, JntSpaceInertiaMatrix& H)
00060     {
00061         if(nj != chain.getNrOfJoints() || ns != chain.getNrOfSegments())
00062             return (error = E_NOT_UP_TO_DATE);
00063         //Check sizes when in debug mode
00064         if(q.rows()!=nj || H.rows()!=nj || H.columns()!=nj )
00065             return (error = E_SIZE_MISMATCH);
00066         unsigned int k=0;
00067         double q_;
00068         
00069         //Sweep from root to leaf
00070         for(unsigned int i=0;i<ns;i++)
00071         {
00072           //Collect RigidBodyInertia
00073           Ic[i]=chain.getSegment(i).getInertia();
00074           if(chain.getSegment(i).getJoint().getType()!=Joint::None)
00075           {
00076               q_=q(k);
00077               k++;
00078           }
00079           else
00080           {
00081             q_=0.0;
00082           }
00083           X[i]=chain.getSegment(i).pose(q_);//Remark this is the inverse of the frame for transformations from the parent to the current coord frame
00084           S[i]=X[i].M.Inverse(chain.getSegment(i).twist(q_,1.0));  
00085         }
00086         //Sweep from leaf to root
00087         int j,l;
00088         k=nj-1; //reset k
00089         for(int i=ns-1;i>=0;i--)
00090         {
00091           
00092           if(i!=0)
00093             {
00094               //assumption that previous segment is parent
00095               Ic[i-1]=Ic[i-1]+X[i]*Ic[i];
00096             } 
00097 
00098           F=Ic[i]*S[i];
00099           if(chain.getSegment(i).getJoint().getType()!=Joint::None)
00100           {
00101           H(k,k)=dot(S[i],F);
00102           H(k,k)+=chain.getSegment(i).getJoint().getInertia();  // add joint inertia
00103               j=k; //countervariable for the joints
00104               l=i; //countervariable for the segments
00105               while(l!=0) //go from leaf to root starting at i
00106                 {
00107                   //assumption that previous segment is parent
00108                   F=X[l]*F; //calculate the unit force (cfr S) for every segment: F[l-1]=X[l]*F[l]
00109                   l--; //go down a segment
00110                   
00111                   if(chain.getSegment(l).getJoint().getType()!=Joint::None) //if the joint connected to segment is not a fixed joint
00112                   {    
00113                     j--;
00114                     H(k,j)=dot(F,S[l]); //here you actually match a certain not fixed joint with a segment 
00115                     H(j,k)=H(k,j);
00116                   }
00117                 } 
00118               k--; //this if-loop should be repeated nj times (k=nj-1 to k=0)
00119           }
00120 
00121         }
00122         return (error = E_NOERROR);
00123     }
00124 
00125     //calculate coriolis matrix C
00126     int ChainDynParam::JntToCoriolis(const JntArray &q, const JntArray &q_dot, JntArray &coriolis)
00127     {
00128     //make a null matrix with the size of q_dotdot and a null wrench
00129         SetToZero(jntarraynull);
00130 
00131         
00132         //the calculation of coriolis matrix C
00133         return chainidsolver_coriolis.CartToJnt(q, q_dot, jntarraynull, wrenchnull, coriolis);
00134         
00135     }
00136 
00137     //calculate gravity matrix G
00138     int ChainDynParam::JntToGravity(const JntArray &q,JntArray &gravity)
00139     {
00140 
00141         //make a null matrix with the size of q_dotdot and a null wrench
00142         
00143         SetToZero(jntarraynull);
00144         //the calculation of coriolis matrix C
00145         return chainidsolver_gravity.CartToJnt(q, jntarraynull, jntarraynull, wrenchnull, gravity);
00146     }
00147 
00148     ChainDynParam::~ChainDynParam()
00149     {
00150     }
00151 
00152 
00153 }


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