Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
pr2_arm_kinematics::PR2ArmIK Class Reference

#include <pr2_arm_ik.h>

Public Member Functions

void computeIKShoulderPan (const Eigen::Affine3f &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::Affine3f &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 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 ()
 
 ~PR2ArmIK ()
 

Public Attributes

moveit_msgs::KinematicSolverInfo solver_info_
 get chain information about the arm. More...
 

Private Member Functions

void addJointToChainInfo (urdf::JointConstSharedPtr 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::Affine3f gf_
 
Eigen::Affine3f grhs_
 
Eigen::Affine3f 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 118 of file pr2_arm_ik.h.

Constructor & Destructor Documentation

PR2ArmIK::PR2ArmIK ( )

Definition at line 52 of file pr2_arm_ik.cpp.

pr2_arm_kinematics::PR2ArmIK::~PR2ArmIK ( )
inline

Definition at line 127 of file pr2_arm_ik.h.

Member Function Documentation

void PR2ArmIK::addJointToChainInfo ( urdf::JointConstSharedPtr  joint,
moveit_msgs::KinematicSolverInfo &  info 
)
private

Definition at line 154 of file pr2_arm_ik.cpp.

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

Definition at line 768 of file pr2_arm_ik.cpp.

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

Definition at line 780 of file pr2_arm_ik.cpp.

void PR2ArmIK::computeIKShoulderPan ( const Eigen::Affine3f &  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
Inputpose for end-effector
Initialguess for shoulder pan angle

Definition at line 197 of file pr2_arm_ik.cpp.

void PR2ArmIK::computeIKShoulderRoll ( const Eigen::Affine3f &  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

Parameters
Inputpose for end-effector
Initialguess for shoulder roll angle

Definition at line 464 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.

Parameters
Theresponse structure to be filled in.

Definition at line 192 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.

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 56 of file pr2_arm_ik.cpp.

Member Data Documentation

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

Definition at line 179 of file pr2_arm_ik.h.

std::vector<bool> pr2_arm_kinematics::PR2ArmIK::continuous_joint_
private

Definition at line 190 of file pr2_arm_ik.h.

double pr2_arm_kinematics::PR2ArmIK::elbow_wrist_offset_
private

Definition at line 183 of file pr2_arm_ik.h.

Eigen::Affine3f pr2_arm_kinematics::PR2ArmIK::gf_
private

Definition at line 177 of file pr2_arm_ik.h.

Eigen::Affine3f pr2_arm_kinematics::PR2ArmIK::grhs_
private

Definition at line 177 of file pr2_arm_ik.h.

Eigen::Affine3f pr2_arm_kinematics::PR2ArmIK::home_inv_
private

Definition at line 177 of file pr2_arm_ik.h.

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

Definition at line 188 of file pr2_arm_ik.h.

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

Definition at line 186 of file pr2_arm_ik.h.

double pr2_arm_kinematics::PR2ArmIK::shoulder_elbow_offset_
private

Definition at line 183 of file pr2_arm_ik.h.

double pr2_arm_kinematics::PR2ArmIK::shoulder_upperarm_offset_
private

Definition at line 183 of file pr2_arm_ik.h.

double pr2_arm_kinematics::PR2ArmIK::shoulder_wrist_offset_
private

Definition at line 183 of file pr2_arm_ik.h.

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

Definition at line 181 of file pr2_arm_ik.h.

moveit_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmIK::solver_info_

get chain information about the arm.

Definition at line 166 of file pr2_arm_ik.h.

double pr2_arm_kinematics::PR2ArmIK::torso_shoulder_offset_x_
private

Definition at line 183 of file pr2_arm_ik.h.

double pr2_arm_kinematics::PR2ArmIK::torso_shoulder_offset_y_
private

Definition at line 183 of file pr2_arm_ik.h.

double pr2_arm_kinematics::PR2ArmIK::torso_shoulder_offset_z_
private

Definition at line 183 of file pr2_arm_ik.h.

double pr2_arm_kinematics::PR2ArmIK::upperarm_elbow_offset_
private

Definition at line 183 of file pr2_arm_ik.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Oct 18 2020 13:16:34