chainiksolver_vel_pinv_mimic.hpp
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 // Modified to account for "mimic" joints, i.e. joints whose motion has a
00023 // linear relationship to that of another joint.
00024 // Copyright  (C)  2013  Sachin Chitta, Willow Garage
00025 
00026 #ifndef KDL_CHAIN_IKSOLVERVEL_PINV_Mimic_HPP
00027 #define KDL_CHAIN_IKSOLVERVEL_PINV_Mimic_HPP
00028 
00029 #include "kdl/chainiksolver.hpp"
00030 #include "kdl/chainjnttojacsolver.hpp"
00031 #include "kdl/utilities/svd_HH.hpp"
00032 #include "kdl/utilities/svd_eigen_HH.hpp"
00033 
00034 #include <moveit/kdl_kinematics_plugin/joint_mimic.hpp>
00035 
00036 namespace KDL
00037 {
00047 class ChainIkSolverVel_pinv_mimic : public ChainIkSolverVel
00048 {
00049 public:
00066   explicit ChainIkSolverVel_pinv_mimic(const Chain& chain, int num_mimic_joints = 0, int num_redundant_joints = 0,
00067                                        bool position_ik = false, double eps = 0.00001, int maxiter = 150);
00068 
00069   ~ChainIkSolverVel_pinv_mimic();
00070 
00071   virtual int CartToJnt(const JntArray& q_in, const Twist& v_in, JntArray& qdot_out);
00072 
00073   virtual int CartToJntRedundant(const JntArray& q_in, const Twist& v_in, JntArray& qdot_out);
00074 
00079   virtual int CartToJnt(const JntArray& q_init, const FrameVel& v_in, JntArrayVel& q_out)
00080   {
00081     return -1;
00082   };
00083 
00092   bool setMimicJoints(const std::vector<kdl_kinematics_plugin::JointMimic>& _mimic_joints);
00093 
00102   bool setRedundantJointsMapIndex(const std::vector<unsigned int>& redundant_joints_map_index);
00103 
00104   void lockRedundantJoints()
00105   {
00106     redundant_joints_locked = true;
00107   }
00108 
00109   void unlockRedundantJoints()
00110   {
00111     redundant_joints_locked = false;
00112   }
00113 
00114 private:
00115   bool jacToJacReduced(const Jacobian& jac, Jacobian& jac_mimic);
00116   bool jacToJacLocked(const Jacobian& jac, Jacobian& jac_locked);
00117 
00118   const Chain chain;
00119   ChainJntToJacSolver jnt2jac;
00120 
00121   // This set of variables are all used in the default case, i.e. where we are solving for the
00122   // full end-effector pose
00123   Jacobian jac;
00124   std::vector<JntArray> U;
00125   JntArray S;
00126   std::vector<JntArray> V;
00127   JntArray tmp;
00128 
00129   // This is the "reduced" jacobian, i.e. the contributions of the mimic joints have been mapped onto
00130   // the active DOFs here
00131   Jacobian jac_reduced;
00132   JntArray qdot_out_reduced;
00133 
00134   // This is the set of variable used when solving for position only inverse kinematics
00135   Eigen::MatrixXd U_translate;
00136   Eigen::VectorXd S_translate;
00137   Eigen::MatrixXd V_translate;
00138   Eigen::VectorXd tmp_translate;
00139 
00140   // This is the jacobian when the redundant joint is "locked" and plays no part
00141   Jacobian jac_locked;
00142   JntArray qdot_out_reduced_locked, qdot_out_locked;
00143 
00144   SVD_HH svd;
00145   double eps;
00146   int maxiter;
00147 
00148   // Mimic joint specific
00149   std::vector<kdl_kinematics_plugin::JointMimic> mimic_joints_;
00150   int num_mimic_joints;
00151 
00152   bool position_ik;
00153 
00154   // This is the set of variable used when solving for inverse kinematics
00155   // for the case where the redundant joint is "locked" and plays no part
00156   Eigen::MatrixXd U_locked;
00157   Eigen::VectorXd S_locked;
00158   Eigen::MatrixXd V_locked;
00159   Eigen::VectorXd tmp_locked;
00160 
00161   // This is the set of variable used when solving for position only inverse kinematics
00162   // for the case where the redundant joint is "locked" and plays no part
00163   Eigen::MatrixXd U_translate_locked;
00164   Eigen::VectorXd S_translate_locked;
00165   Eigen::MatrixXd V_translate_locked;
00166   Eigen::VectorXd tmp_translate_locked;
00167 
00168   // Internal storage for a map from the "locked" state to the full active state
00169   std::vector<unsigned int> locked_joints_map_index;
00170   unsigned int num_redundant_joints;
00171   bool redundant_joints_locked;
00172 };
00173 }
00174 #endif


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Mon Jul 24 2017 02:21:29