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 MOVEIT_PR2_ARM_IK_SOLVER_
00038 #define MOVEIT_PR2_ARM_IK_SOLVER_
00039 
00040 #include <urdf/model.h>
00041 #include <Eigen/Core>
00042 #include <kdl/chainiksolver.hpp>
00043 #include <moveit/pr2_arm_kinematics/pr2_arm_ik.h>
00044 #include <moveit/kinematics_base/kinematics_base.h>
00045 #include <moveit/pr2_arm_kinematics/pr2_arm_kinematics_utils.h>
00046 #include <moveit_msgs/GetKinematicSolverInfo.h>
00047 #include <moveit_msgs/PositionIKRequest.h>
00048 #include <geometry_msgs/PoseStamped.h>
00049 #include <tf_conversions/tf_kdl.h>
00050 
00051 namespace pr2_arm_kinematics
00052 {
00053 
00054 static const int NO_IK_SOLUTION = -1;
00055 static const int TIMED_OUT = -2;
00056 
00057   class PR2ArmIKSolver : public KDL::ChainIkSolverPos
00058   {
00059     public:
00060 
00066     PR2ArmIKSolver(const urdf::Model &robot_model,
00067                    const std::string &root_frame_name,
00068                    const std::string &tip_frame_name,
00069                    const double &search_discretization_angle,
00070                    const int &free_angle);
00071 
00072     ~PR2ArmIKSolver(){ delete pr2_arm_ik_; };
00073 
00077     PR2ArmIK *pr2_arm_ik_;
00078 
00082     bool active_;
00083 
00096     int CartToJnt(const KDL::JntArray& q_init,
00097                   const KDL::Frame& p_in,
00098                   KDL::JntArray& q_out);
00099 
00112     int CartToJnt(const KDL::JntArray& q_init,
00113                   const KDL::Frame& p_in,
00114                   std::vector<KDL::JntArray> &q_out);
00115 
00127     int CartToJntSearch(const KDL::JntArray& q_in,
00128                         const KDL::Frame& p_in,
00129                         std::vector<KDL::JntArray> &q_out,
00130                         const double &timeout);
00131 
00143     int CartToJntSearch(const KDL::JntArray& q_in,
00144                         const KDL::Frame& p_in,
00145                         KDL::JntArray &q_out,
00146                         const double &timeout);
00147 
00162     int CartToJntSearch(const KDL::JntArray& q_in,
00163                         const KDL::Frame& p_in,
00164                         KDL::JntArray &q_out,
00165                         const double &timeout,
00166                         const double& consistency_limit);
00167 
00181     int CartToJntSearch(const KDL::JntArray& q_in,
00182                         const KDL::Frame& p_in,
00183                         KDL::JntArray &q_out,
00184                         const double &timeout,
00185                         moveit_msgs::MoveItErrorCodes &error_code,
00186                         const kinematics::KinematicsBase::IKCallbackFn &solution_callback);
00187 
00202     int CartToJntSearch(const KDL::JntArray& q_in,
00203                         const KDL::Frame& p_in,
00204                         KDL::JntArray &q_out,
00205                         const double &timeout,
00206                         const double& consistency_limit,
00207                         moveit_msgs::MoveItErrorCodes &error_code,
00208                         const kinematics::KinematicsBase::IKCallbackFn &solution_callback);
00209 
00215     void getSolverInfo(moveit_msgs::KinematicSolverInfo &response);
00216 
00217     std::string getFrameId();
00218 
00219     unsigned int getFreeAngle() const {
00220       return free_angle_;
00221     }
00222 
00223     void setFreeAngle(const unsigned int& free_angle) {
00224       free_angle_ = free_angle;
00225     }
00226 
00227   private:
00228 
00244     int CartToJntSearch(const KDL::JntArray& q_in,
00245                         const KDL::Frame& p_in,
00246                         KDL::JntArray &q_out,
00247                         const double &timeout,
00248                         bool use_consistency_limit,
00249                         const double& consistency_limit,
00250                         moveit_msgs::MoveItErrorCodes &error_code,
00251                         const kinematics::KinematicsBase::IKCallbackFn &solution_callback);
00252 
00253     bool getCount(int &count, const int &max_count, const int &min_count);
00254 
00255     double search_discretization_angle_;
00256 
00257     int free_angle_;
00258 
00259     std::string root_frame_name_;
00260   };
00261 }
00262 #endif// PR2_ARM_IK_SOLVER_H