Go to the documentation of this file.
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
double upperarm_elbow_offset_
Namespace for the PR2ArmKinematics.
void addJointToChainInfo(const urdf::JointConstSharedPtr &joint, moveit_msgs::KinematicSolverInfo &info)
std::vector< double > min_angles_
double torso_shoulder_offset_y_
double torso_shoulder_offset_x_
std::vector< double > angle_multipliers_
Eigen::Isometry3f home_inv_
double shoulder_elbow_offset_
void computeIKShoulderRoll(const Eigen::Isometry3f &g_in, const double &shoulder_roll_initial_guess, std::vector< std::vector< double > > &solution) const
std::vector< bool > continuous_joint_
std::vector< double > solution_
bool init(const urdf::ModelInterface &robot_model, const std::string &root_name, const std::string &tip_name)
void getSolverInfo(moveit_msgs::KinematicSolverInfo &info)
void computeIKShoulderPan(const Eigen::Isometry3f &g_in, const double &shoulder_pan_initial_guess, std::vector< std::vector< double > > &solution) const
double shoulder_wrist_offset_
double shoulder_upperarm_offset_
double torso_shoulder_offset_z_
double elbow_wrist_offset_
bool checkJointLimits(const double &joint_value, const int &joint_num) const
moveit_msgs::KinematicSolverInfo solver_info_
get chain information about the arm.
std::vector< double > max_angles_