#include <pr2_arm_ik.h>
Public Member Functions | |
void | computeIKShoulderPan (const Eigen::Matrix4f &g_in, const double &shoulder_pan_initial_guess, std::vector< std::vector< double > > &solution) const |
compute IK based on an initial guess for the shoulder pan angle. | |
void | computeIKShoulderRoll (const Eigen::Matrix4f &g_in, const double &shoulder_roll_initial_guess, std::vector< std::vector< double > > &solution) const |
compute IK based on an initial guess for the shoulder roll angle. h | |
void | getSolverInfo (moveit_msgs::KinematicSolverInfo &info) |
get chain information about the arm. This populates the IK query response, filling in joint level information including names and joint limits. | |
bool | init (const urdf::ModelInterface &robot_model, const std::string &root_name, const std::string &tip_name) |
Initialize the solver by providing a urdf::Model and a root and tip name. | |
PR2ArmIK () | |
~PR2ArmIK () | |
Public Attributes | |
moveit_msgs::KinematicSolverInfo | solver_info_ |
get chain information about the arm. | |
Private Member Functions | |
void | addJointToChainInfo (boost::shared_ptr< const urdf::Joint > joint, moveit_msgs::KinematicSolverInfo &info) |
bool | checkJointLimits (const std::vector< double > &joint_values) const |
bool | checkJointLimits (const double &joint_value, const int &joint_num) const |
Private Attributes | |
std::vector< double > | angle_multipliers_ |
std::vector< bool > | continuous_joint_ |
double | elbow_wrist_offset_ |
Eigen::Matrix4f | gf_ |
Eigen::Matrix4f | grhs_ |
Eigen::Matrix4f | home_ |
Eigen::Matrix4f | home_inv_ |
std::vector< double > | max_angles_ |
std::vector< double > | min_angles_ |
double | shoulder_elbow_offset_ |
double | shoulder_upperarm_offset_ |
double | shoulder_wrist_offset_ |
std::vector< double > | solution_ |
double | torso_shoulder_offset_x_ |
double | torso_shoulder_offset_y_ |
double | torso_shoulder_offset_z_ |
double | upperarm_elbow_offset_ |
Definition at line 117 of file pr2_arm_ik.h.
Definition at line 53 of file pr2_arm_ik.cpp.
pr2_arm_kinematics::PR2ArmIK::~PR2ArmIK | ( | ) | [inline] |
Definition at line 127 of file pr2_arm_ik.h.
void PR2ArmIK::addJointToChainInfo | ( | boost::shared_ptr< const urdf::Joint > | joint, |
moveit_msgs::KinematicSolverInfo & | info | ||
) | [private] |
Definition at line 152 of file pr2_arm_ik.cpp.
bool PR2ArmIK::checkJointLimits | ( | const std::vector< double > & | joint_values | ) | const [private] |
Definition at line 678 of file pr2_arm_ik.cpp.
bool PR2ArmIK::checkJointLimits | ( | const double & | joint_value, |
const int & | joint_num | ||
) | const [private] |
Definition at line 690 of file pr2_arm_ik.cpp.
void PR2ArmIK::computeIKShoulderPan | ( | const Eigen::Matrix4f & | g_in, |
const double & | shoulder_pan_initial_guess, | ||
std::vector< std::vector< double > > & | solution | ||
) | const |
compute IK based on an initial guess for the shoulder pan angle.
Input | pose for end-effector |
Initial | guess for shoulder pan angle |
Definition at line 197 of file pr2_arm_ik.cpp.
void PR2ArmIK::computeIKShoulderRoll | ( | const Eigen::Matrix4f & | g_in, |
const double & | shoulder_roll_initial_guess, | ||
std::vector< std::vector< double > > & | solution | ||
) | const |
compute IK based on an initial guess for the shoulder roll angle. h
Input | pose for end-effector |
Initial | guess for shoulder roll angle |
Definition at line 419 of file pr2_arm_ik.cpp.
void PR2ArmIK::getSolverInfo | ( | moveit_msgs::KinematicSolverInfo & | info | ) |
get chain information about the arm. This populates the IK query response, filling in joint level information including names and joint limits.
The | response structure to be filled in. |
Definition at line 191 of file pr2_arm_ik.cpp.
bool PR2ArmIK::init | ( | const urdf::ModelInterface & | robot_model, |
const std::string & | root_name, | ||
const std::string & | tip_name | ||
) |
Initialize the solver by providing a urdf::Model and a root and tip name.
A | urdf::Model representation of the PR2 robot model |
The | root joint name of the arm |
The | tip joint name of the arm |
Definition at line 57 of file pr2_arm_ik.cpp.
std::vector<double> pr2_arm_kinematics::PR2ArmIK::angle_multipliers_ [private] |
Definition at line 178 of file pr2_arm_ik.h.
std::vector<bool> pr2_arm_kinematics::PR2ArmIK::continuous_joint_ [private] |
Definition at line 188 of file pr2_arm_ik.h.
double pr2_arm_kinematics::PR2ArmIK::elbow_wrist_offset_ [private] |
Definition at line 182 of file pr2_arm_ik.h.
Eigen::Matrix4f pr2_arm_kinematics::PR2ArmIK::gf_ [private] |
Definition at line 176 of file pr2_arm_ik.h.
Eigen::Matrix4f pr2_arm_kinematics::PR2ArmIK::grhs_ [private] |
Definition at line 176 of file pr2_arm_ik.h.
Eigen::Matrix4f pr2_arm_kinematics::PR2ArmIK::home_ [private] |
Definition at line 176 of file pr2_arm_ik.h.
Eigen::Matrix4f pr2_arm_kinematics::PR2ArmIK::home_inv_ [private] |
Definition at line 176 of file pr2_arm_ik.h.
std::vector<double> pr2_arm_kinematics::PR2ArmIK::max_angles_ [private] |
Definition at line 186 of file pr2_arm_ik.h.
std::vector<double> pr2_arm_kinematics::PR2ArmIK::min_angles_ [private] |
Definition at line 184 of file pr2_arm_ik.h.
double pr2_arm_kinematics::PR2ArmIK::shoulder_elbow_offset_ [private] |
Definition at line 182 of file pr2_arm_ik.h.
double pr2_arm_kinematics::PR2ArmIK::shoulder_upperarm_offset_ [private] |
Definition at line 182 of file pr2_arm_ik.h.
double pr2_arm_kinematics::PR2ArmIK::shoulder_wrist_offset_ [private] |
Definition at line 182 of file pr2_arm_ik.h.
std::vector<double> pr2_arm_kinematics::PR2ArmIK::solution_ [private] |
Definition at line 180 of file pr2_arm_ik.h.
moveit_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmIK::solver_info_ |
get chain information about the arm.
Definition at line 164 of file pr2_arm_ik.h.
double pr2_arm_kinematics::PR2ArmIK::torso_shoulder_offset_x_ [private] |
Definition at line 182 of file pr2_arm_ik.h.
double pr2_arm_kinematics::PR2ArmIK::torso_shoulder_offset_y_ [private] |
Definition at line 182 of file pr2_arm_ik.h.
double pr2_arm_kinematics::PR2ArmIK::torso_shoulder_offset_z_ [private] |
Definition at line 182 of file pr2_arm_ik.h.
double pr2_arm_kinematics::PR2ArmIK::upperarm_elbow_offset_ [private] |
Definition at line 182 of file pr2_arm_ik.h.