#include <pr2_arm_ik.h>
|  | 
| void | computeIKShoulderPan (const Eigen::Isometry3f &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.  More... 
 | 
|  | 
| void | computeIKShoulderRoll (const Eigen::Isometry3f &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.  More... 
 | 
|  | 
| 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.  More... 
 | 
|  | 
| 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.  More... 
 | 
|  | 
|  | PR2ArmIK () | 
|  | Inverse kinematics for the PR2 arm.  More... 
 | 
|  | 
|  | ~PR2ArmIK () | 
|  | 
Definition at line 149 of file pr2_arm_ik.h.
 
◆ PR2ArmIK()
◆ ~PR2ArmIK()
  
  | 
        
          | pr2_arm_kinematics::PR2ArmIK::~PR2ArmIK | ( |  | ) |  |  | inline | 
 
 
◆ addJointToChainInfo()
  
  | 
        
          | void PR2ArmIK::addJointToChainInfo | ( | const urdf::JointConstSharedPtr & | joint, |  
          |  |  | moveit_msgs::KinematicSolverInfo & | info |  
          |  | ) |  |  |  | private | 
 
 
◆ checkJointLimits() [1/2]
  
  | 
        
          | bool PR2ArmIK::checkJointLimits | ( | const double & | joint_value, |  
          |  |  | const int & | joint_num |  
          |  | ) |  | const |  | private | 
 
 
◆ checkJointLimits() [2/2]
  
  | 
        
          | bool PR2ArmIK::checkJointLimits | ( | const std::vector< double > & | joint_values | ) | const |  | private | 
 
 
◆ computeIKShoulderPan()
      
        
          | void PR2ArmIK::computeIKShoulderPan | ( | const Eigen::Isometry3f & | 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. 
- Parameters
- 
  
    | g_in | Input pose for end-effector |  | shoulder_pan_initial_guess | Initial guess for shoulder pan angle |  
 
Definition at line 197 of file pr2_arm_ik.cpp.
 
 
◆ computeIKShoulderRoll()
      
        
          | void PR2ArmIK::computeIKShoulderRoll | ( | const Eigen::Isometry3f & | 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. 
- Parameters
- 
  
    | g_in | Input pose for end-effector |  | shoulder_roll_initial_guess | Initial guess for shoulder roll angle |  
 
Definition at line 462 of file pr2_arm_ik.cpp.
 
 
◆ getSolverInfo()
      
        
          | 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. 
- Parameters
- 
  
    | info | The response structure to be filled in. |  
 
Definition at line 192 of file pr2_arm_ik.cpp.
 
 
◆ init()
      
        
          | 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. 
- Parameters
- 
  
    | robot_model | A urdf::Model representation of the PR2 robot model |  | root_name | The root joint name of the arm |  | tip_name | The tip joint name of the arm |  
 
- Returns
- true if initialization was successful, false otherwise. 
Definition at line 56 of file pr2_arm_ik.cpp.
 
 
◆ angle_multipliers_
  
  | 
        
          | std::vector<double> pr2_arm_kinematics::PR2ArmIK::angle_multipliers_ |  | private | 
 
 
◆ continuous_joint_
  
  | 
        
          | std::vector<bool> pr2_arm_kinematics::PR2ArmIK::continuous_joint_ |  | private | 
 
 
◆ elbow_wrist_offset_
  
  | 
        
          | double pr2_arm_kinematics::PR2ArmIK::elbow_wrist_offset_ |  | private | 
 
 
◆ gf_
  
  | 
        
          | Eigen::Isometry3f pr2_arm_kinematics::PR2ArmIK::gf_ |  | private | 
 
 
◆ grhs_
  
  | 
        
          | Eigen::Isometry3f pr2_arm_kinematics::PR2ArmIK::grhs_ |  | private | 
 
 
◆ home_inv_
  
  | 
        
          | Eigen::Isometry3f pr2_arm_kinematics::PR2ArmIK::home_inv_ |  | private | 
 
 
◆ max_angles_
  
  | 
        
          | std::vector<double> pr2_arm_kinematics::PR2ArmIK::max_angles_ |  | private | 
 
 
◆ min_angles_
  
  | 
        
          | std::vector<double> pr2_arm_kinematics::PR2ArmIK::min_angles_ |  | private | 
 
 
◆ shoulder_elbow_offset_
  
  | 
        
          | double pr2_arm_kinematics::PR2ArmIK::shoulder_elbow_offset_ |  | private | 
 
 
◆ shoulder_upperarm_offset_
  
  | 
        
          | double pr2_arm_kinematics::PR2ArmIK::shoulder_upperarm_offset_ |  | private | 
 
 
◆ shoulder_wrist_offset_
  
  | 
        
          | double pr2_arm_kinematics::PR2ArmIK::shoulder_wrist_offset_ |  | private | 
 
 
◆ solution_
  
  | 
        
          | std::vector<double> pr2_arm_kinematics::PR2ArmIK::solution_ |  | private | 
 
 
◆ solver_info_
      
        
          | moveit_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmIK::solver_info_ | 
      
 
get chain information about the arm. 
Definition at line 194 of file pr2_arm_ik.h.
 
 
◆ torso_shoulder_offset_x_
  
  | 
        
          | double pr2_arm_kinematics::PR2ArmIK::torso_shoulder_offset_x_ |  | private | 
 
 
◆ torso_shoulder_offset_y_
  
  | 
        
          | double pr2_arm_kinematics::PR2ArmIK::torso_shoulder_offset_y_ |  | private | 
 
 
◆ torso_shoulder_offset_z_
  
  | 
        
          | double pr2_arm_kinematics::PR2ArmIK::torso_shoulder_offset_z_ |  | private | 
 
 
◆ upperarm_elbow_offset_
  
  | 
        
          | double pr2_arm_kinematics::PR2ArmIK::upperarm_elbow_offset_ |  | private | 
 
 
The documentation for this class was generated from the following files: