Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
pr2_arm_kinematics::PR2ArmIK Class Reference

#include <pr2_arm_ik.h>

List of all members.

Public Member Functions

void computeIKShoulderPan (const Eigen::Matrix4f &g_in, const double &shoulder_pan_initial_guess, std::vector< std::vector< double > > &solution)
 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)
 compute IK based on an initial guess for the shoulder roll angle. h
void getSolverInfo (kinematics_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::Model &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

kinematics_msgs::KinematicSolverInfo solver_info_
 get chain information about the arm.

Private Member Functions

void addJointToChainInfo (boost::shared_ptr< const urdf::Joint > joint, kinematics_msgs::KinematicSolverInfo &info)
bool checkJointLimits (const std::vector< double > &joint_values)
bool checkJointLimits (const double &joint_value, const int &joint_num)

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_

Detailed Description

Definition at line 46 of file pr2_arm_ik.h.


Constructor & Destructor Documentation

Definition at line 48 of file pr2_arm_ik.cpp.

Definition at line 56 of file pr2_arm_ik.h.


Member Function Documentation

void PR2ArmIK::addJointToChainInfo ( boost::shared_ptr< const urdf::Joint >  joint,
kinematics_msgs::KinematicSolverInfo info 
) [private]

Definition at line 125 of file pr2_arm_ik.cpp.

bool PR2ArmIK::checkJointLimits ( const std::vector< double > &  joint_values) [private]

Definition at line 630 of file pr2_arm_ik.cpp.

bool PR2ArmIK::checkJointLimits ( const double &  joint_value,
const int &  joint_num 
) [private]

Definition at line 642 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 
)

compute IK based on an initial guess for the shoulder pan angle.

Parameters:
Inputpose for end-effector
Initialguess for shoulder pan angle

Definition at line 154 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 
)

compute IK based on an initial guess for the shoulder roll angle. h

Parameters:
Inputpose for end-effector
Initialguess for shoulder roll angle

Definition at line 374 of file pr2_arm_ik.cpp.

get chain information about the arm. This populates the IK query response, filling in joint level information including names and joint limits.

Parameters:
Theresponse structure to be filled in.

Definition at line 148 of file pr2_arm_ik.cpp.

bool PR2ArmIK::init ( const urdf::Model 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:
Aurdf::Model representation of the PR2 robot model
Theroot joint name of the arm
Thetip joint name of the arm
Returns:
true if initialization was successful, false otherwise.

Definition at line 52 of file pr2_arm_ik.cpp.


Member Data Documentation

std::vector<double> pr2_arm_kinematics::PR2ArmIK::angle_multipliers_ [private]

Definition at line 107 of file pr2_arm_ik.h.

Definition at line 117 of file pr2_arm_ik.h.

Definition at line 111 of file pr2_arm_ik.h.

Eigen::Matrix4f pr2_arm_kinematics::PR2ArmIK::gf_ [private]

Definition at line 105 of file pr2_arm_ik.h.

Eigen::Matrix4f pr2_arm_kinematics::PR2ArmIK::grhs_ [private]

Definition at line 105 of file pr2_arm_ik.h.

Eigen::Matrix4f pr2_arm_kinematics::PR2ArmIK::home_ [private]

Definition at line 105 of file pr2_arm_ik.h.

Eigen::Matrix4f pr2_arm_kinematics::PR2ArmIK::home_inv_ [private]

Definition at line 105 of file pr2_arm_ik.h.

std::vector<double> pr2_arm_kinematics::PR2ArmIK::max_angles_ [private]

Definition at line 115 of file pr2_arm_ik.h.

std::vector<double> pr2_arm_kinematics::PR2ArmIK::min_angles_ [private]

Definition at line 113 of file pr2_arm_ik.h.

Definition at line 111 of file pr2_arm_ik.h.

Definition at line 111 of file pr2_arm_ik.h.

Definition at line 111 of file pr2_arm_ik.h.

std::vector<double> pr2_arm_kinematics::PR2ArmIK::solution_ [private]

Definition at line 109 of file pr2_arm_ik.h.

get chain information about the arm.

Definition at line 93 of file pr2_arm_ik.h.

Definition at line 111 of file pr2_arm_ik.h.

Definition at line 111 of file pr2_arm_ik.h.

Definition at line 111 of file pr2_arm_ik.h.

Definition at line 111 of file pr2_arm_ik.h.


The documentation for this class was generated from the following files:


pr2_arm_kinematics
Author(s): Sachin Chitta
autogenerated on Tue Apr 22 2014 19:33:02