Blender V2.61 - r43446

chainjnttojacsolver.cpp

Go to the documentation of this file.
00001 
00004 // Copyright  (C)  2007  Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
00005 
00006 // Version: 1.0
00007 // Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
00008 // Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be>
00009 // URL: http://www.orocos.org/kdl
00010 
00011 // This library is free software; you can redistribute it and/or
00012 // modify it under the terms of the GNU Lesser General Public
00013 // License as published by the Free Software Foundation; either
00014 // version 2.1 of the License, or (at your option) any later version.
00015 
00016 // This library is distributed in the hope that it will be useful,
00017 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00018 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00019 // Lesser General Public License for more details.
00020 
00021 // You should have received a copy of the GNU Lesser General Public
00022 // License along with this library; if not, write to the Free Software
00023 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
00024 
00025 #include "chainjnttojacsolver.hpp"
00026 
00027 namespace KDL
00028 {
00029     ChainJntToJacSolver::ChainJntToJacSolver(const Chain& _chain):
00030         chain(_chain)
00031     {
00032     }
00033 
00034     ChainJntToJacSolver::~ChainJntToJacSolver()
00035     {
00036     }
00037 
00038     int ChainJntToJacSolver::JntToJac(const JntArray& q_in,Jacobian& jac)
00039     {
00040         assert(q_in.rows()==chain.getNrOfJoints()&&
00041                q_in.rows()==jac.columns());
00042 
00043 
00044         Frame T_local, T_joint;
00045         T_total = Frame::Identity();
00046         SetToZero(t_local);
00047 
00048         int i=chain.getNrOfSegments()-1;
00049         unsigned int q_nr = chain.getNrOfJoints();
00050 
00051         //Lets recursively iterate until we are in the root segment
00052         while (i >= 0) {
00053             const Segment& segment = chain.getSegment(i);
00054             int ndof = segment.getJoint().getNDof();
00055             q_nr -= ndof;
00056 
00057             //get the pose of the joint.
00058             T_joint = segment.getJoint().pose(((JntArray&)q_in)(q_nr));
00059             // combine with the tip to have the tip pose
00060             T_local = T_joint*segment.getFrameToTip();
00061             //calculate new T_end:
00062             T_total = T_local * T_total;
00063 
00064             for (int dof=0; dof<ndof; dof++) {
00065                 // combine joint rotation with tip position to get a reference frame for the joint
00066                 T_joint.p = T_local.p;
00067                 // in which the twist can be computed (needed for NDof joint)
00068                 t_local = segment.twist(T_joint, 1.0, dof);
00069                 //transform the endpoint of the local twist to the global endpoint:
00070                 t_local = t_local.RefPoint(T_total.p - T_local.p);
00071                 //transform the base of the twist to the endpoint
00072                 t_local = T_total.M.Inverse(t_local);
00073                 //store the twist in the jacobian:
00074                 jac.twists[q_nr+dof] = t_local;
00075             }
00076             i--;
00077         }//endwhile
00078         //Change the base of the complete jacobian from the endpoint to the base
00079         changeBase(jac, T_total.M, jac);
00080         return 0;
00081     }
00082 }
00083