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 (error = E_SIZE_MISMATCH); 00044 else if(segmentNr>chain.getNrOfSegments()) 00045 return (error = E_OUT_OF_RANGE); 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 (error = E_NOERROR); 00057 } 00058 } 00059 int ChainFkSolverPos_recursive::JntToCart(const JntArray& q_in, std::vector<Frame>& p_out, int seg_nr) { 00060 unsigned int segmentNr; 00061 if(seg_nr<0) 00062 segmentNr=chain.getNrOfSegments(); 00063 else 00064 segmentNr = seg_nr; 00065 00066 if(q_in.rows()!=chain.getNrOfJoints()) 00067 return -1; 00068 else if(segmentNr>chain.getNrOfSegments()) 00069 return -1; 00070 else if(p_out.size() != segmentNr) 00071 return -1; 00072 else if(segmentNr == 0) 00073 return -1; 00074 else{ 00075 int j=0; 00076 // Initialization 00077 if(chain.getSegment(0).getJoint().getType()!=Joint::None){ 00078 p_out[0] = chain.getSegment(0).pose(q_in(j)); 00079 j++; 00080 }else 00081 p_out[0] = chain.getSegment(0).pose(0.0); 00082 00083 for(unsigned int i=1;i<segmentNr;i++){ 00084 if(chain.getSegment(i).getJoint().getType()!=Joint::None){ 00085 p_out[i] = p_out[i-1]*chain.getSegment(i).pose(q_in(j)); 00086 j++; 00087 }else{ 00088 p_out[i] = p_out[i-1]*chain.getSegment(i).pose(0.0); 00089 } 00090 } 00091 return 0; 00092 } 00093 } 00094 00095 ChainFkSolverPos_recursive::~ChainFkSolverPos_recursive() 00096 { 00097 } 00098 00099 00100 }