$search
00001 // Copyright (C) 2007 Ruben Smits <ruben dot smits at mech dot kuleuven dot be> 00002 00003 // Version: 1.0 00004 // Author: Ruben Smits <ruben dot smits 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 "chainiksolvervel_wdls.hpp" 00023 #include "utilities/svd_eigen_HH.hpp" 00024 00025 namespace KDL 00026 { 00027 00028 ChainIkSolverVel_wdls::ChainIkSolverVel_wdls(const Chain& _chain,double _eps,int _maxiter): 00029 chain(_chain), 00030 jnt2jac(chain), 00031 jac(chain.getNrOfJoints()), 00032 U(MatrixXd::Zero(6,chain.getNrOfJoints())), 00033 S(VectorXd::Zero(chain.getNrOfJoints())), 00034 V(MatrixXd::Zero(chain.getNrOfJoints(),chain.getNrOfJoints())), 00035 eps(_eps), 00036 maxiter(_maxiter), 00037 tmp(VectorXd::Zero(chain.getNrOfJoints())), 00038 tmp_jac(MatrixXd::Zero(6,chain.getNrOfJoints())), 00039 tmp_jac_weight1(MatrixXd::Zero(6,chain.getNrOfJoints())), 00040 tmp_jac_weight2(MatrixXd::Zero(6,chain.getNrOfJoints())), 00041 tmp_ts(MatrixXd::Zero(6,6)), 00042 tmp_js(MatrixXd::Zero(chain.getNrOfJoints(),chain.getNrOfJoints())), 00043 weight_ts(MatrixXd::Identity(6,6)), 00044 weight_js(MatrixXd::Identity(chain.getNrOfJoints(),chain.getNrOfJoints())), 00045 lambda(0.0) 00046 { 00047 } 00048 00049 ChainIkSolverVel_wdls::~ChainIkSolverVel_wdls() 00050 { 00051 } 00052 00053 void ChainIkSolverVel_wdls::setWeightJS(const MatrixXd& Mq){ 00054 weight_js = Mq; 00055 } 00056 00057 void ChainIkSolverVel_wdls::setWeightTS(const MatrixXd& Mx){ 00058 weight_ts = Mx; 00059 } 00060 00061 void ChainIkSolverVel_wdls::setLambda(const double& lambda_in) 00062 { 00063 lambda=lambda_in; 00064 } 00065 00066 int ChainIkSolverVel_wdls::CartToJnt(const JntArray& q_in, const Twist& v_in, JntArray& qdot_out) 00067 { 00068 jnt2jac.JntToJac(q_in,jac); 00069 00070 double sum; 00071 unsigned int i,j; 00072 00073 /* 00074 for (i=0;i<jac.rows();i++) { 00075 for (j=0;j<jac.columns();j++) 00076 tmp_jac(i,j) = jac(i,j); 00077 } 00078 */ 00079 00080 // Create the Weighted jacobian 00081 tmp_jac_weight1 = jac.data.lazyProduct(weight_js); 00082 tmp_jac_weight2 = weight_ts.lazyProduct(tmp_jac_weight1); 00083 00084 // Compute the SVD of the weighted jacobian 00085 int ret = svd_eigen_HH(tmp_jac_weight2,U,S,V,tmp,maxiter); 00086 00087 //Pre-multiply U and V by the task space and joint space weighting matrix respectively 00088 tmp_ts = weight_ts.lazyProduct(U.topLeftCorner(6,6)); 00089 tmp_js = weight_js.lazyProduct(V); 00090 00091 // tmp = (Si*U'*Ly*y), 00092 for (i=0;i<jac.columns();i++) { 00093 sum = 0.0; 00094 for (j=0;j<jac.rows();j++) { 00095 if(i<6) 00096 sum+= tmp_ts(j,i)*v_in(j); 00097 else 00098 sum+=0.0; 00099 } 00100 if(S(i)==0||S(i)<eps) 00101 tmp(i) = sum*((S(i)/(S(i)*S(i)+lambda*lambda))); 00102 else 00103 tmp(i) = sum/S(i); 00104 } 00105 /* 00106 // x = Lx^-1*V*tmp + x 00107 for (i=0;i<jac.columns();i++) { 00108 sum = 0.0; 00109 for (j=0;j<jac.columns();j++) { 00110 sum+=tmp_js(i,j)*tmp(j); 00111 } 00112 qdot_out(i)=sum; 00113 } 00114 */ 00115 qdot_out.data=tmp_js.lazyProduct(tmp); 00116 return ret; 00117 } 00118 00119 }