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
00038
00039 #ifndef MOVEIT_PR2_ARM_IK_SOLVER_
00040 #define MOVEIT_PR2_ARM_IK_SOLVER_
00041
00042 #include <urdf/model.h>
00043 #include <Eigen/Core>
00044 #include <kdl/chainiksolver.hpp>
00045 #include <moveit/pr2_arm_kinematics/pr2_arm_ik.h>
00046 #include <moveit/kinematics_base/kinematics_base.h>
00047 #include <moveit/pr2_arm_kinematics/pr2_arm_kinematics_utils.h>
00048 #include <moveit_msgs/GetKinematicSolverInfo.h>
00049 #include <moveit_msgs/PositionIKRequest.h>
00050 #include <geometry_msgs/PoseStamped.h>
00051 #include <tf_conversions/tf_kdl.h>
00052
00053 namespace pr2_arm_kinematics
00054 {
00055
00056 static const int NO_IK_SOLUTION = -1;
00057 static const int TIMED_OUT = -2;
00058
00059 class PR2ArmIKSolver : public KDL::ChainIkSolverPos
00060 {
00061 public:
00062
00068 PR2ArmIKSolver(const urdf::Model &robot_model,
00069 const std::string &root_frame_name,
00070 const std::string &tip_frame_name,
00071 const double &search_discretization_angle,
00072 const int &free_angle);
00073
00074 ~PR2ArmIKSolver(){};
00075
00079 PR2ArmIK pr2_arm_ik_;
00080
00084 bool active_;
00085
00098 int CartToJnt(const KDL::JntArray& q_init,
00099 const KDL::Frame& p_in,
00100 KDL::JntArray& q_out);
00101
00114 int CartToJnt(const KDL::JntArray& q_init,
00115 const KDL::Frame& p_in,
00116 std::vector<KDL::JntArray> &q_out);
00117
00129 int CartToJntSearch(const KDL::JntArray& q_in,
00130 const KDL::Frame& p_in,
00131 std::vector<KDL::JntArray> &q_out,
00132 const double &timeout);
00133
00145 int CartToJntSearch(const KDL::JntArray& q_in,
00146 const KDL::Frame& p_in,
00147 KDL::JntArray &q_out,
00148 const double &timeout);
00149
00164 int CartToJntSearch(const KDL::JntArray& q_in,
00165 const KDL::Frame& p_in,
00166 KDL::JntArray &q_out,
00167 const double &timeout,
00168 const double& consistency_limit);
00169
00183 int CartToJntSearch(const KDL::JntArray& q_in,
00184 const KDL::Frame& p_in,
00185 KDL::JntArray &q_out,
00186 const double &timeout,
00187 moveit_msgs::MoveItErrorCodes &error_code,
00188 const kinematics::KinematicsBase::IKCallbackFn &solution_callback);
00189
00204 int CartToJntSearch(const KDL::JntArray& q_in,
00205 const KDL::Frame& p_in,
00206 KDL::JntArray &q_out,
00207 const double &timeout,
00208 const double& consistency_limit,
00209 moveit_msgs::MoveItErrorCodes &error_code,
00210 const kinematics::KinematicsBase::IKCallbackFn &solution_callback);
00211
00217 void getSolverInfo(moveit_msgs::KinematicSolverInfo &response);
00218
00219 std::string getFrameId();
00220
00221 unsigned int getFreeAngle() const {
00222 return free_angle_;
00223 }
00224
00225 void setFreeAngle(const unsigned int& free_angle) {
00226 free_angle_ = free_angle;
00227 }
00228
00229 private:
00230
00246 int CartToJntSearch(const KDL::JntArray& q_in,
00247 const KDL::Frame& p_in,
00248 KDL::JntArray &q_out,
00249 const double &timeout,
00250 bool use_consistency_limit,
00251 const double& consistency_limit,
00252 moveit_msgs::MoveItErrorCodes &error_code,
00253 const kinematics::KinematicsBase::IKCallbackFn &solution_callback);
00254
00255 bool getCount(int &count, const int &max_count, const int &min_count);
00256
00257 double search_discretization_angle_;
00258
00259 int free_angle_;
00260
00261 std::string root_frame_name_;
00262 };
00263 }
00264 #endif// PR2_ARM_IK_SOLVER_H