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
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef KDL_CHAIN_IKSOLVERVEL_PINV_MIMIC_H
00038 #define KDL_CHAIN_IKSOLVERVEL_PINV_MIMIC_H
00039
00040 #include "kdl/chainiksolver.hpp"
00041 #include "kdl/chainjnttojacsolver.hpp"
00042 #include "kdl/utilities/svd_HH.hpp"
00043 #include "kdl/utilities/svd_eigen_HH.hpp"
00044
00045 #include <moveit/lma_kinematics_plugin/joint_mimic.h>
00046
00047 namespace KDL
00048 {
00058 class ChainIkSolverVel_pinv_mimic : public ChainIkSolverVel
00059 {
00060 public:
00077 explicit ChainIkSolverVel_pinv_mimic(const Chain& chain, int num_mimic_joints = 0, int num_redundant_joints = 0,
00078 bool position_ik = false, double eps = 0.00001, int maxiter = 150);
00079
00080 ~ChainIkSolverVel_pinv_mimic();
00081
00082 virtual int CartToJnt(const JntArray& q_in, const Twist& v_in, JntArray& qdot_out);
00083
00084 virtual int CartToJntRedundant(const JntArray& q_in, const Twist& v_in, JntArray& qdot_out);
00085
00090 virtual int CartToJnt(const JntArray& q_init, const FrameVel& v_in, JntArrayVel& q_out)
00091 {
00092 return -1;
00093 };
00094
00103 bool setMimicJoints(const std::vector<lma_kinematics_plugin::JointMimic>& _mimic_joints);
00104
00113 bool setRedundantJointsMapIndex(const std::vector<unsigned int>& redundant_joints_map_index);
00114
00115 void lockRedundantJoints()
00116 {
00117 redundant_joints_locked = true;
00118 }
00119
00120 void unlockRedundantJoints()
00121 {
00122 redundant_joints_locked = false;
00123 }
00124
00125 private:
00126 bool jacToJacReduced(const Jacobian& jac, Jacobian& jac_mimic);
00127 bool jacToJacLocked(const Jacobian& jac, Jacobian& jac_locked);
00128
00129 const Chain chain;
00130 ChainJntToJacSolver jnt2jac;
00131
00132
00133
00134 Jacobian jac;
00135 std::vector<JntArray> U;
00136 JntArray S;
00137 std::vector<JntArray> V;
00138 JntArray tmp;
00139
00140
00141
00142 Jacobian jac_reduced;
00143 JntArray qdot_out_reduced;
00144
00145
00146 Eigen::MatrixXd U_translate;
00147 Eigen::VectorXd S_translate;
00148 Eigen::MatrixXd V_translate;
00149 Eigen::VectorXd tmp_translate;
00150
00151
00152 Jacobian jac_locked;
00153 JntArray qdot_out_reduced_locked, qdot_out_locked;
00154
00155 SVD_HH svd;
00156 double eps;
00157 int maxiter;
00158
00159
00160 std::vector<lma_kinematics_plugin::JointMimic> mimic_joints_;
00161 int num_mimic_joints;
00162
00163 bool position_ik;
00164
00165
00166
00167 Eigen::MatrixXd U_locked;
00168 Eigen::VectorXd S_locked;
00169 Eigen::MatrixXd V_locked;
00170 Eigen::VectorXd tmp_locked;
00171
00172
00173
00174 Eigen::MatrixXd U_translate_locked;
00175 Eigen::VectorXd S_translate_locked;
00176 Eigen::MatrixXd V_translate_locked;
00177 Eigen::VectorXd tmp_translate_locked;
00178
00179
00180 std::vector<unsigned int> locked_joints_map_index;
00181 unsigned int num_redundant_joints;
00182 bool redundant_joints_locked;
00183 };
00184 }
00185 #endif