$search
00001 /* 00002 * TreeIkSolverVel_wdls.cpp 00003 * 00004 * Created on: Nov 28, 2008 00005 * Author: rubensmits 00006 */ 00007 00008 #include "treeiksolvervel_wdls.hpp" 00009 #include "utilities/svd_eigen_HH.hpp" 00010 00011 namespace KDL { 00012 using namespace std; 00013 00014 TreeIkSolverVel_wdls::TreeIkSolverVel_wdls(const Tree& tree_in, const std::vector<std::string>& endpoints) : 00015 tree(tree_in), jnttojacsolver(tree), 00016 J(MatrixXd::Zero(6 * endpoints.size(), tree.getNrOfJoints())), 00017 Wy(MatrixXd::Identity(J.rows(),J.rows())), 00018 Wq(MatrixXd::Identity(J.cols(),J.cols())), 00019 J_Wq(J.rows(),J.cols()),Wy_J_Wq(J.rows(),J.cols()), 00020 U(MatrixXd::Identity(J.rows(),J.cols())), 00021 V(MatrixXd::Identity(J.cols(),J.cols())), 00022 Wy_U(J.rows(),J.rows()),Wq_V(J.cols(),J.cols()), 00023 t(VectorXd::Zero(J.rows())), Wy_t(VectorXd::Zero(J.rows())), 00024 qdot(VectorXd::Zero(J.cols())), 00025 tmp(VectorXd::Zero(J.cols())),S(VectorXd::Zero(J.cols())) 00026 { 00027 00028 for (size_t i = 0; i < endpoints.size(); ++i) { 00029 jacobians.insert(Jacobians::value_type(endpoints[i], Jacobian(tree.getNrOfJoints()))); 00030 } 00031 00032 } 00033 00034 TreeIkSolverVel_wdls::~TreeIkSolverVel_wdls() { 00035 } 00036 00037 void TreeIkSolverVel_wdls::setWeightJS(const MatrixXd& Mq) { 00038 Wq = Mq; 00039 } 00040 00041 void TreeIkSolverVel_wdls::setWeightTS(const MatrixXd& Mx) { 00042 Wy = Mx; 00043 } 00044 00045 void TreeIkSolverVel_wdls::setLambda(const double& lambda_in) { 00046 lambda = lambda_in; 00047 } 00048 00049 double TreeIkSolverVel_wdls::CartToJnt(const JntArray& q_in, const Twists& v_in, JntArray& qdot_out) { 00050 00051 //First check if we are configured for this Twists: 00052 for (Twists::const_iterator v_it = v_in.begin(); v_it != v_in.end(); ++v_it) { 00053 if (jacobians.find(v_it->first) == jacobians.end()) 00054 return -2; 00055 } 00056 //Check if q_in has the right size 00057 if (q_in.rows() != tree.getNrOfJoints()) 00058 return -1; 00059 00060 //Lets get all the jacobians we need: 00061 unsigned int k = 0; 00062 for (Jacobians::iterator jac_it = jacobians.begin(); jac_it 00063 != jacobians.end(); ++jac_it) { 00064 int ret = jnttojacsolver.JntToJac(q_in, jac_it->second, jac_it->first); 00065 if (ret < 0) 00066 return ret; 00067 else { 00068 //lets put the jacobian in the big matrix and put the twist in the big t: 00069 J.block(6*k,0, 6,tree.getNrOfJoints()) = jac_it->second.data; 00070 const Twist& twist=v_in.find(jac_it->first)->second; 00071 t.segment(6*k,3) = Eigen::Map<const Eigen::Vector3d>(twist.vel.data); 00072 t.segment(6*k+3,3) = Eigen::Map<const Eigen::Vector3d>(twist.rot.data); 00073 } 00074 ++k; 00075 } 00076 00077 //Lets use the wdls algorithm to find the qdot: 00078 // Create the Weighted jacobian 00079 J_Wq = J.lazyProduct(Wq); 00080 Wy_J_Wq = Wy.lazyProduct(J_Wq); 00081 00082 // Compute the SVD of the weighted jacobian 00083 int ret = svd_eigen_HH(Wy_J_Wq, U, S, V, tmp); 00084 00085 //Pre-multiply U and V by the task space and joint space weighting matrix respectively 00086 Wy_t = Wy.lazyProduct(t); 00087 Wq_V = Wq.lazyProduct(V); 00088 00089 // tmp = (Si*Wy*U'*y), 00090 for (unsigned int i = 0; i < J.cols(); i++) { 00091 double sum = 0.0; 00092 for (unsigned int j = 0; j < J.rows(); j++) { 00093 if (i < Wy_t.size()) 00094 sum += U(j, i) * Wy_t(j); 00095 else 00096 sum += 0.0; 00097 } 00098 tmp( i) = sum * ((S(i) / (S(i) * S(i) + lambda * lambda))); 00099 } 00100 00101 // x = Lx^-1*V*tmp + x 00102 qdot_out.data = Wq_V.lazyProduct(tmp); 00103 00104 return Wy_t.norm(); 00105 } 00106 }