#include <pr2_arm_ik.h>
|
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 () |
|
Definition at line 118 of file pr2_arm_ik.h.
pr2_arm_kinematics::PR2ArmIK::~PR2ArmIK |
( |
| ) |
|
|
inline |
void PR2ArmIK::addJointToChainInfo |
( |
urdf::JointConstSharedPtr |
joint, |
|
|
moveit_msgs::KinematicSolverInfo & |
info |
|
) |
| |
|
private |
bool PR2ArmIK::checkJointLimits |
( |
const std::vector< double > & |
joint_values | ) |
const |
|
private |
bool PR2ArmIK::checkJointLimits |
( |
const double & |
joint_value, |
|
|
const int & |
joint_num |
|
) |
| const |
|
private |
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
-
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::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
-
Input | pose for end-effector |
Initial | guess 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
-
The | response 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
-
A | urdf::Model representation of the PR2 robot model |
The | root joint name of the arm |
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.
std::vector<double> pr2_arm_kinematics::PR2ArmIK::angle_multipliers_ |
|
private |
std::vector<bool> pr2_arm_kinematics::PR2ArmIK::continuous_joint_ |
|
private |
double pr2_arm_kinematics::PR2ArmIK::elbow_wrist_offset_ |
|
private |
Eigen::Affine3f pr2_arm_kinematics::PR2ArmIK::gf_ |
|
private |
Eigen::Affine3f pr2_arm_kinematics::PR2ArmIK::grhs_ |
|
private |
Eigen::Affine3f pr2_arm_kinematics::PR2ArmIK::home_inv_ |
|
private |
std::vector<double> pr2_arm_kinematics::PR2ArmIK::max_angles_ |
|
private |
std::vector<double> pr2_arm_kinematics::PR2ArmIK::min_angles_ |
|
private |
double pr2_arm_kinematics::PR2ArmIK::shoulder_elbow_offset_ |
|
private |
double pr2_arm_kinematics::PR2ArmIK::shoulder_upperarm_offset_ |
|
private |
double pr2_arm_kinematics::PR2ArmIK::shoulder_wrist_offset_ |
|
private |
std::vector<double> pr2_arm_kinematics::PR2ArmIK::solution_ |
|
private |
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 |
double pr2_arm_kinematics::PR2ArmIK::torso_shoulder_offset_y_ |
|
private |
double pr2_arm_kinematics::PR2ArmIK::torso_shoulder_offset_z_ |
|
private |
double pr2_arm_kinematics::PR2ArmIK::upperarm_elbow_offset_ |
|
private |
The documentation for this class was generated from the following files: