chainiksolvervel_wdls.hpp
Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022 #ifndef KDL_CHAIN_IKSOLVERVEL_WDLS_HPP
00023 #define KDL_CHAIN_IKSOLVERVEL_WDLS_HPP
00024
00025 #include "chainiksolver.hpp"
00026 #include "chainjnttojacsolver.hpp"
00027 #include <Eigen/Core>
00028
00029 namespace KDL
00030 {
00063 class ChainIkSolverVel_wdls : public ChainIkSolverVel
00064 {
00065 public:
00078 ChainIkSolverVel_wdls(const Chain& chain,double eps=0.00001,int maxiter=150);
00079
00080 ~ChainIkSolverVel_wdls();
00081
00082 virtual int CartToJnt(const JntArray& q_in, const Twist& v_in, JntArray& qdot_out);
00087 virtual int CartToJnt(const JntArray& q_init, const FrameVel& v_in, JntArrayVel& q_out){return -1;};
00088
00112 void setWeightJS(const Eigen::MatrixXd& Mq);
00113
00138 void setWeightTS(const Eigen::MatrixXd& Mx);
00139
00140 void setLambda(const double& lambda);
00141
00142 private:
00143 const Chain chain;
00144 ChainJntToJacSolver jnt2jac;
00145 Jacobian jac;
00146 Eigen::MatrixXd U;
00147 Eigen::VectorXd S;
00148 Eigen::MatrixXd V;
00149 double eps;
00150 int maxiter;
00151 Eigen::VectorXd tmp;
00152 Eigen::MatrixXd tmp_jac;
00153 Eigen::MatrixXd tmp_jac_weight1;
00154 Eigen::MatrixXd tmp_jac_weight2;
00155 Eigen::MatrixXd tmp_ts;
00156 Eigen::MatrixXd tmp_js;
00157 Eigen::MatrixXd weight_ts;
00158 Eigen::MatrixXd weight_js;
00159 double lambda;
00160 };
00161 }
00162 #endif
00163