00001 // Copyright (C) 2007 Francois Cauwe <francois at cauwe dot org> 00002 // Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be> 00003 00004 // Version: 1.0 00005 // Author: Ruben Smits <ruben dot smits at mech dot kuleuven dot be> 00006 // Maintainer: Ruben Smits <ruben dot smits at mech dot kuleuven dot be> 00007 // URL: http://www.orocos.org/kdl 00008 00009 // This library is free software; you can redistribute it and/or 00010 // modify it under the terms of the GNU Lesser General Public 00011 // License as published by the Free Software Foundation; either 00012 // version 2.1 of the License, or (at your option) any later version. 00013 00014 // This library is distributed in the hope that it will be useful, 00015 // but WITHOUT ANY WARRANTY; without even the implied warranty of 00016 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU 00017 // Lesser General Public License for more details. 00018 00019 // You should have received a copy of the GNU Lesser General Public 00020 // License along with this library; if not, write to the Free Software 00021 // Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA 00022 00023 #include "chainfksolverpos_recursive.hpp" 00024 #include <iostream> 00025 00026 namespace KDL { 00027 00028 ChainFkSolverPos_recursive::ChainFkSolverPos_recursive(const Chain& _chain): 00029 chain(_chain) 00030 { 00031 } 00032 00033 int ChainFkSolverPos_recursive::JntToCart(const JntArray& q_in, Frame& p_out, int seg_nr) { 00034 unsigned int segmentNr; 00035 if(seg_nr<0) 00036 segmentNr=chain.getNrOfSegments(); 00037 else 00038 segmentNr = seg_nr; 00039 00040 p_out = Frame::Identity(); 00041 00042 if(q_in.rows()!=chain.getNrOfJoints()) 00043 return -1; 00044 else if(segmentNr>chain.getNrOfSegments()) 00045 return -1; 00046 else{ 00047 int j=0; 00048 for(unsigned int i=0;i<segmentNr;i++){ 00049 if(chain.getSegment(i).getJoint().getType()!=Joint::None){ 00050 p_out = p_out*chain.getSegment(i).pose(q_in(j)); 00051 j++; 00052 }else{ 00053 p_out = p_out*chain.getSegment(i).pose(0.0); 00054 } 00055 } 00056 return 0; 00057 } 00058 } 00059 00060 00061 ChainFkSolverPos_recursive::~ChainFkSolverPos_recursive() 00062 { 00063 } 00064 00065 00066 }