chainiksolvervel_wdls.cpp
Go to the documentation of this file.
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         nj(chain.getNrOfJoints()),
00032         jac(nj),
00033         U(MatrixXd::Zero(6,nj)),
00034         S(VectorXd::Zero(nj)),
00035         V(MatrixXd::Zero(nj,nj)),
00036         eps(_eps),
00037         maxiter(_maxiter),
00038         tmp(VectorXd::Zero(nj)),
00039         tmp_jac(MatrixXd::Zero(6,nj)),
00040         tmp_jac_weight1(MatrixXd::Zero(6,nj)),
00041         tmp_jac_weight2(MatrixXd::Zero(6,nj)),
00042         tmp_ts(MatrixXd::Zero(6,6)),
00043         tmp_js(MatrixXd::Zero(nj,nj)),
00044         weight_ts(MatrixXd::Identity(6,6)),
00045         weight_js(MatrixXd::Identity(nj,nj)),
00046         lambda(0.0),
00047         lambda_scaled(0.0),
00048         nrZeroSigmas(0),
00049         svdResult(0),
00050         sigmaMin(0)
00051     {
00052     }
00053     
00054 
00055     ChainIkSolverVel_wdls::~ChainIkSolverVel_wdls()
00056     {
00057     }
00058     
00059     int ChainIkSolverVel_wdls::setWeightJS(const MatrixXd& Mq){
00060         if (Mq.size() != weight_js.size())
00061             return (error = E_SIZE_MISMATCH);
00062         weight_js = Mq;
00063         return (error = E_NOERROR);
00064     }
00065     
00066     int ChainIkSolverVel_wdls::setWeightTS(const MatrixXd& Mx){
00067         if (Mx.size() != weight_ts.size())
00068             return (error = E_SIZE_MISMATCH);
00069         weight_ts = Mx;
00070         return (error = E_NOERROR);
00071     }
00072 
00073     void ChainIkSolverVel_wdls::setLambda(const double lambda_in)
00074     {
00075         lambda=lambda_in;
00076     }
00077 
00078     void ChainIkSolverVel_wdls::setEps(const double eps_in)
00079     {
00080         eps=eps_in;
00081     }
00082 
00083     void ChainIkSolverVel_wdls::setMaxIter(const int maxiter_in)
00084     {
00085         maxiter=maxiter_in;
00086     }
00087 
00088     int ChainIkSolverVel_wdls::CartToJnt(const JntArray& q_in, const Twist& v_in, JntArray& qdot_out)
00089     {
00090         if(nj != q_in.rows() || nj != qdot_out.rows())
00091             return (error = E_SIZE_MISMATCH);
00092         error = jnt2jac.JntToJac(q_in,jac);
00093         if ( error < E_NOERROR) return error;
00094         
00095         double sum;
00096         unsigned int i,j;
00097         
00098         // Initialize (internal) return values
00099         nrZeroSigmas = 0 ;
00100         sigmaMin = 0.;
00101         lambda_scaled = 0.;
00102 
00103         /*
00104         for (i=0;i<jac.rows();i++) {
00105             for (j=0;j<jac.columns();j++)
00106                 tmp_jac(i,j) = jac(i,j);
00107         }
00108         */
00109         
00110         // Create the Weighted jacobian
00111         tmp_jac_weight1 = jac.data.lazyProduct(weight_js);
00112         tmp_jac_weight2 = weight_ts.lazyProduct(tmp_jac_weight1);
00113    
00114         // Compute the SVD of the weighted jacobian
00115         svdResult = svd_eigen_HH(tmp_jac_weight2,U,S,V,tmp,maxiter);
00116         if (0 != svdResult)
00117         {
00118             qdot_out.data.setZero() ;
00119             return (error = E_SVD_FAILED);
00120         }
00121 
00122         //Pre-multiply U and V by the task space and joint space weighting matrix respectively
00123         tmp_ts = weight_ts.lazyProduct(U.topLeftCorner(6,6));
00124         tmp_js = weight_js.lazyProduct(V);
00125 
00126         // Minimum of six largest singular values of J is S(5) if number of joints >=6 and 0 for <6
00127         if ( jac.columns() >= 6 ) {
00128             sigmaMin = S(5);
00129         }
00130         else {
00131             sigmaMin = 0.;
00132         }
00133 
00134         // tmp = (Si*U'*Ly*y),
00135         for (i=0;i<jac.columns();i++) {
00136             sum = 0.0;
00137             for (j=0;j<jac.rows();j++) {
00138                 if(i<6)
00139                     sum+= tmp_ts(j,i)*v_in(j);
00140                 else
00141                     sum+=0.0;
00142             }
00143             // If sigmaMin > eps, then wdls is not active and lambda_scaled = 0 (default value)
00144             // If sigmaMin < eps, then wdls is active and lambda_scaled is scaled from 0 to lambda
00145             // Note:  singular values are always positive so sigmaMin >=0
00146             if ( sigmaMin < eps )
00147             {
00148                             lambda_scaled = sqrt(1.0-(sigmaMin/eps)*(sigmaMin/eps))*lambda ;
00149             }
00150                         if(fabs(S(i))<eps) {
00151                                 if (i<6) {
00152                                         // Scale lambda to size of singular value sigmaMin
00153                                         tmp(i) = sum*((S(i)/(S(i)*S(i)+lambda_scaled*lambda_scaled)));
00154                                 }
00155                                 else {
00156                                         tmp(i)=0.0;  // S(i)=0 for i>=6 due to cols>rows
00157                                 }
00158                                 //  Count number of singular values near zero
00159                                 ++nrZeroSigmas ;
00160                         }
00161                         else {
00162                 tmp(i) = sum/S(i);
00163                         }
00164         }
00165 
00166         /*
00167         // x = Lx^-1*V*tmp + x
00168         for (i=0;i<jac.columns();i++) {
00169             sum = 0.0;
00170             for (j=0;j<jac.columns();j++) {
00171                 sum+=tmp_js(i,j)*tmp(j);
00172             }
00173             qdot_out(i)=sum;
00174         }
00175         */
00176         qdot_out.data=tmp_js.lazyProduct(tmp);
00177 
00178         // If number of near zero singular values is greater than the full rank
00179         // of jac, then wdls is active
00180         if ( nrZeroSigmas > (jac.columns()-jac.rows()) )        {
00181             return (error = E_CONVERGE_PINV_SINGULAR);  // converged but pinv singular
00182         } else {
00183             return (error = E_NOERROR);                 // have converged
00184         }
00185     }
00186 
00187     const char* ChainIkSolverVel_wdls::strError(const int error) const
00188     {
00189         if (E_CONVERGE_PINV_SINGULAR == error) return "Converged put pseudo inverse of jacobian is singular.";
00190         else return SolverI::strError(error);
00191     }
00192 
00193 }


orocos_kdl
Author(s):
autogenerated on Sat Oct 7 2017 03:04:28