37 #ifndef MOVEIT_PR2_ARM_IK_H 38 #define MOVEIT_PR2_ARM_IK_H 43 #include <kdl/chainiksolver.hpp> 69 bool init(
const urdf::Model &robot_model,
const std::string &root_name,
const std::string &tip_name);
76 void computeIKShoulderPan(
const Eigen::Matrix4f &g_in,
const double &shoulder_pan_initial_guess,std::vector<std::vector<double> > &solution)
const;
83 void computeIKShoulderRoll(
const Eigen::Matrix4f &g_in,
const double &shoulder_roll_initial_guess,std::vector<std::vector<double> > &solution)
const;
103 void addJointToChainInfo(urdf::JointConstSharedPtr joint,moveit_msgs::KinematicSolverInfo &info);
107 bool checkJointLimits(
const double &joint_value,
const int &joint_num)
const;
125 #endif// PR2_ARM_IK_H std::vector< double > max_angles_
double torso_shoulder_offset_z_
Eigen::Affine3f home_inv_
std::vector< bool > continuous_joint_
double elbow_wrist_offset_
Namespace for the PR2ArmKinematics.
double shoulder_elbow_offset_
double upperarm_elbow_offset_
void computeIKShoulderRoll(const Eigen::Affine3f &g_in, const double &shoulder_roll_initial_guess, std::vector< std::vector< double > > &solution) const
double shoulder_upperarm_offset_
void addJointToChainInfo(urdf::JointConstSharedPtr joint, moveit_msgs::KinematicSolverInfo &info)
void getSolverInfo(moveit_msgs::KinematicSolverInfo &info)
std::vector< double > min_angles_
double torso_shoulder_offset_y_
std::vector< double > solution_
double torso_shoulder_offset_x_
void computeIKShoulderPan(const Eigen::Affine3f &g_in, const double &shoulder_pan_initial_guess, std::vector< std::vector< double > > &solution) const
bool init(const urdf::ModelInterface &robot_model, const std::string &root_name, const std::string &tip_name)
moveit_msgs::KinematicSolverInfo solver_info_
get chain information about the arm.
std::vector< double > angle_multipliers_
bool checkJointLimits(const std::vector< double > &joint_values) const
double shoulder_wrist_offset_