#include <pr2_arm_kinematics_constraint_aware.h>
Definition at line 60 of file pr2_arm_kinematics_constraint_aware.h.
Definition at line 59 of file pr2_arm_kinematics_constraint_aware.cpp.
virtual pr2_arm_kinematics::PR2ArmIKConstraintAware::~PR2ArmIKConstraintAware | ( | ) | [inline, virtual] |
Definition at line 76 of file pr2_arm_kinematics_constraint_aware.h.
void pr2_arm_kinematics::PR2ArmIKConstraintAware::advertiseIK | ( | ) | [private] |
Definition at line 92 of file pr2_arm_kinematics_constraint_aware.cpp.
int pr2_arm_kinematics::PR2ArmIKConstraintAware::CartToJntSearch | ( | const KDL::JntArray & | q_in, |
const KDL::Frame & | p_in, | ||
KDL::JntArray & | q_out, | ||
const double & | timeout, | ||
arm_navigation_msgs::ArmNavigationErrorCodes & | error_code | ||
) |
This method searches for and returns the closest solution to the initial guess in the first set of solutions it finds.
q_in | The initial guess for the inverse kinematics solution. The solver uses the joint value q_init(pr2_ik_->free_angle_) as as an input to the inverse kinematics. pr2_ik_->free_angle_ can either be 0 or 2 corresponding to the shoulder pan or shoulder roll angle |
p_in | A KDL::Frame representation of the position of the end-effector for which the IK is being solved. |
q_out | A std::vector of KDL::JntArray containing all found solutions. |
timeout | The amount of time (in seconds) to spend looking for a solution. |
Definition at line 130 of file pr2_arm_kinematics_constraint_aware.cpp.
void pr2_arm_kinematics::PR2ArmIKConstraintAware::collisionCheck | ( | const KDL::JntArray & | jnt_array, |
const KDL::Frame & | p_in, | ||
arm_navigation_msgs::ArmNavigationErrorCodes & | error_code | ||
) | [private] |
Definition at line 309 of file pr2_arm_kinematics_constraint_aware.cpp.
void pr2_arm_kinematics::PR2ArmIKConstraintAware::contactFound | ( | collision_space::EnvironmentModel::Contact & | contact | ) | [private] |
This method searches for and returns the closest solution to the initial guess in the first set of solutions it finds.
q_in | The initial guess for the inverse kinematics solution. The solver uses the joint value q_init(pr2_ik_->free_angle_) as as an input to the inverse kinematics. pr2_ik_->free_angle_ can either be 0 or 2 corresponding to the shoulder pan or shoulder roll angle |
p_in | A KDL::Frame representation of the position of the end-effector for which the IK is being solved. |
q_out | A std::vector of KDL::JntArray containing all found solutions. |
timeout | The amount of time (in seconds) to spend looking for a solution. |
Definition at line 175 of file pr2_arm_kinematics_constraint_aware.cpp.
bool pr2_arm_kinematics::PR2ArmIKConstraintAware::getPositionIK | ( | kinematics_msgs::GetPositionIK::Request & | request, |
kinematics_msgs::GetPositionIK::Response & | response | ||
) | [virtual] |
Reimplemented from pr2_arm_kinematics::PR2ArmKinematics.
Definition at line 149 of file pr2_arm_kinematics_constraint_aware.cpp.
void pr2_arm_kinematics::PR2ArmIKConstraintAware::initialPoseCheck | ( | const KDL::JntArray & | jnt_array, |
const KDL::Frame & | p_in, | ||
arm_navigation_msgs::ArmNavigationErrorCodes & | error_code | ||
) | [private] |
Definition at line 348 of file pr2_arm_kinematics_constraint_aware.cpp.
bool pr2_arm_kinematics::PR2ArmIKConstraintAware::isReady | ( | arm_navigation_msgs::ArmNavigationErrorCodes & | error_code | ) | [private] |
Definition at line 98 of file pr2_arm_kinematics_constraint_aware.cpp.
void pr2_arm_kinematics::PR2ArmIKConstraintAware::printStringVec | ( | const std::string & | prefix, |
const std::vector< std::string > & | string_vector | ||
) | [private] |
Definition at line 425 of file pr2_arm_kinematics_constraint_aware.cpp.
void pr2_arm_kinematics::PR2ArmIKConstraintAware::sendEndEffectorPose | ( | const planning_models::KinematicState * | state, |
bool | valid | ||
) | [private] |
Definition at line 404 of file pr2_arm_kinematics_constraint_aware.cpp.
bool pr2_arm_kinematics::PR2ArmIKConstraintAware::transformPose | ( | const std::string & | des_frame, |
const geometry_msgs::PoseStamped & | pose_in, | ||
geometry_msgs::PoseStamped & | pose_out | ||
) | [protected, virtual] |
Reimplemented from pr2_arm_kinematics::PR2ArmKinematics.
Definition at line 114 of file pr2_arm_kinematics_constraint_aware.cpp.
std::vector<std::string> pr2_arm_kinematics::PR2ArmIKConstraintAware::arm_links_ [private] |
Definition at line 131 of file pr2_arm_kinematics_constraint_aware.h.
planning_environment::CollisionModelsInterface* pr2_arm_kinematics::PR2ArmIKConstraintAware::collision_models_interface_ [private] |
Definition at line 124 of file pr2_arm_kinematics_constraint_aware.h.
arm_navigation_msgs::Constraints pr2_arm_kinematics::PR2ArmIKConstraintAware::constraints_ [private] |
Definition at line 143 of file pr2_arm_kinematics_constraint_aware.h.
Definition at line 139 of file pr2_arm_kinematics_constraint_aware.h.
std::vector<std::string> pr2_arm_kinematics::PR2ArmIKConstraintAware::end_effector_collision_links_ [private] |
Definition at line 130 of file pr2_arm_kinematics_constraint_aware.h.
std::string pr2_arm_kinematics::PR2ArmIKConstraintAware::group_ [private] |
Definition at line 125 of file pr2_arm_kinematics_constraint_aware.h.
Definition at line 123 of file pr2_arm_kinematics_constraint_aware.h.
kinematics_msgs::PositionIKRequest pr2_arm_kinematics::PR2ArmIKConstraintAware::ik_request_ [private] |
Definition at line 141 of file pr2_arm_kinematics_constraint_aware.h.
Definition at line 142 of file pr2_arm_kinematics_constraint_aware.h.
Definition at line 126 of file pr2_arm_kinematics_constraint_aware.h.
Definition at line 128 of file pr2_arm_kinematics_constraint_aware.h.
Definition at line 127 of file pr2_arm_kinematics_constraint_aware.h.
Definition at line 140 of file pr2_arm_kinematics_constraint_aware.h.