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_H
00038 #define MOVEIT_PR2_ARM_IK_H
00039
00040 #include <urdf/model.h>
00041 #include <Eigen/Core>
00042 #include <Eigen/LU>
00043 #include <kdl/chainiksolver.hpp>
00044 #include <pr2_arm_kinematics/pr2_arm_kinematics_utils.h>
00045 #include <pr2_arm_kinematics/pr2_arm_kinematics_constants.h>
00046
00047
00048 namespace pr2_arm_kinematics
00049 {
00050 class PR2ArmIK
00051 {
00052 public:
00053
00059 PR2ArmIK();
00060 ~PR2ArmIK(){};
00061
00069 bool init(const urdf::Model &robot_model, const std::string &root_name, const std::string &tip_name);
00070
00076 void computeIKShoulderPan(const Eigen::Matrix4f &g_in, const double &shoulder_pan_initial_guess,std::vector<std::vector<double> > &solution) const;
00077
00083 void computeIKShoulderRoll(const Eigen::Matrix4f &g_in, const double &shoulder_roll_initial_guess,std::vector<std::vector<double> > &solution) const;
00084
00085
00086
00087
00092 void getSolverInfo(moveit_msgs::KinematicSolverInfo &info);
00093
00097 moveit_msgs::KinematicSolverInfo solver_info_;
00098
00099 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00100
00101 private:
00102
00103 void addJointToChainInfo(boost::shared_ptr<const urdf::Joint> joint,moveit_msgs::KinematicSolverInfo &info);
00104
00105 bool checkJointLimits(const std::vector<double> &joint_values) const;
00106
00107 bool checkJointLimits(const double &joint_value, const int &joint_num) const;
00108
00109 Eigen::Matrix4f grhs_, gf_, home_inv_, home_;
00110
00111 std::vector<double> angle_multipliers_;
00112
00113 std::vector<double> solution_;
00114
00115 double shoulder_upperarm_offset_, upperarm_elbow_offset_, elbow_wrist_offset_, shoulder_wrist_offset_, shoulder_elbow_offset_, torso_shoulder_offset_x_, torso_shoulder_offset_y_, torso_shoulder_offset_z_;
00116
00117 std::vector<double> min_angles_;
00118
00119 std::vector<double> max_angles_;
00120
00121 std::vector<bool> continuous_joint_;
00122
00123 };
00124 }
00125 #endif// PR2_ARM_IK_H