Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
pr2_arm_kinematics::PR2ArmIKConstraintAware Class Reference

#include <pr2_arm_kinematics_constraint_aware.h>

Inheritance diagram for pr2_arm_kinematics::PR2ArmIKConstraintAware:
Inheritance graph
[legend]

List of all members.

Public Member Functions

int 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.
bool getConstraintAwarePositionIK (kinematics_msgs::GetConstraintAwarePositionIK::Request &request, kinematics_msgs::GetConstraintAwarePositionIK::Response &response)
 This method searches for and returns the closest solution to the initial guess in the first set of solutions it finds.
virtual bool getPositionIK (kinematics_msgs::GetPositionIK::Request &request, kinematics_msgs::GetPositionIK::Response &response)
 PR2ArmIKConstraintAware ()
virtual ~PR2ArmIKConstraintAware ()

Protected Member Functions

virtual bool transformPose (const std::string &des_frame, const geometry_msgs::PoseStamped &pose_in, geometry_msgs::PoseStamped &pose_out)

Private Member Functions

void advertiseIK ()
void collisionCheck (const KDL::JntArray &jnt_array, const KDL::Frame &p_in, arm_navigation_msgs::ArmNavigationErrorCodes &error_code)
void contactFound (collision_space::EnvironmentModel::Contact &contact)
void initialPoseCheck (const KDL::JntArray &jnt_array, const KDL::Frame &p_in, arm_navigation_msgs::ArmNavigationErrorCodes &error_code)
bool isReady (arm_navigation_msgs::ArmNavigationErrorCodes &error_code)
void printStringVec (const std::string &prefix, const std::vector< std::string > &string_vector)
void sendEndEffectorPose (const planning_models::KinematicState *state, bool valid)

Private Attributes

std::vector< std::string > arm_links_
planning_environment::CollisionModelsInterfacecollision_models_interface_
arm_navigation_msgs::Constraints constraints_
ros::Publisher display_trajectory_publisher_
std::vector< std::string > end_effector_collision_links_
std::string group_
ros::ServiceServer ik_collision_service_
kinematics_msgs::PositionIKRequest ik_request_
ros::Time last_planning_scene_drop_
bool use_collision_map_
ros::Publisher vis_marker_array_publisher_
ros::Publisher vis_marker_publisher_
bool visualize_solution_

Detailed Description

Definition at line 60 of file pr2_arm_kinematics_constraint_aware.h.


Constructor & Destructor Documentation

Definition at line 59 of file pr2_arm_kinematics_constraint_aware.cpp.

Definition at line 76 of file pr2_arm_kinematics_constraint_aware.h.


Member Function Documentation

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.

Returns:
< 0 if no solution is found
Parameters:
q_inThe 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_inA KDL::Frame representation of the position of the end-effector for which the IK is being solved.
q_outA std::vector of KDL::JntArray containing all found solutions.
timeoutThe 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.

This method searches for and returns the closest solution to the initial guess in the first set of solutions it finds.

Returns:
< 0 if no solution is found
Parameters:
q_inThe 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_inA KDL::Frame representation of the position of the end-effector for which the IK is being solved.
q_outA std::vector of KDL::JntArray containing all found solutions.
timeoutThe amount of time (in seconds) to spend looking for a solution.

Definition at line 175 of file pr2_arm_kinematics_constraint_aware.cpp.

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.

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.

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.


Member Data Documentation

std::vector<std::string> pr2_arm_kinematics::PR2ArmIKConstraintAware::arm_links_ [private]

Definition at line 131 of file pr2_arm_kinematics_constraint_aware.h.

Definition at line 124 of file pr2_arm_kinematics_constraint_aware.h.

Definition at line 143 of file pr2_arm_kinematics_constraint_aware.h.

Definition at line 139 of file pr2_arm_kinematics_constraint_aware.h.

Definition at line 130 of file pr2_arm_kinematics_constraint_aware.h.

Definition at line 125 of file pr2_arm_kinematics_constraint_aware.h.

Definition at line 123 of file pr2_arm_kinematics_constraint_aware.h.

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.


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


pr2_arm_kinematics_constraint_aware
Author(s): Sachin Chitta
autogenerated on Tue Apr 22 2014 19:33:25