Public Member Functions | Protected Member Functions | Protected Attributes
pr2_arm_kinematics::PR2ArmKinematics Class Reference

#include <pr2_arm_kinematics.h>

List of all members.

Public Member Functions

bool getFKSolverInfo (moveit_msgs::GetKinematicSolverInfo::Request &request, moveit_msgs::GetKinematicSolverInfo::Response &response)
 This is the basic kinematics info service that will return information about the kinematics node.
bool getIKSolverInfo (moveit_msgs::GetKinematicSolverInfo::Request &request, moveit_msgs::GetKinematicSolverInfo::Response &response)
 This is the basic kinematics info service that will return information about the kinematics node.
bool getPositionFK (moveit_msgs::GetPositionFK::Request &request, moveit_msgs::GetPositionFK::Response &response)
 This is the basic forward kinematics service that will return information about the kinematics node.
virtual bool getPositionIK (moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response)
 This is the basic IK service method that will compute and return an IK solution.
bool isActive ()
 Specifies if the node is active or not.
 PR2ArmKinematics (bool create_transform_listener=true)
virtual ~PR2ArmKinematics ()

Protected Member Functions

bool getPositionIKHelper (moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response)
virtual bool transformPose (const std::string &des_frame, const geometry_msgs::PoseStamped &pose_in, geometry_msgs::PoseStamped &pose_out)

Protected Attributes

bool active_
int dimension_
ros::ServiceServer fk_service_
moveit_msgs::KinematicSolverInfo fk_solver_info_
ros::ServiceServer fk_solver_info_service_
int free_angle_
ros::ServiceServer ik_service_
moveit_msgs::KinematicSolverInfo ik_solver_info_
ros::ServiceServer ik_solver_info_service_
boost::shared_ptr
< KDL::ChainFkSolverPos_recursive
jnt_to_pose_solver_
KDL::Chain kdl_chain_
ros::NodeHandle node_handle_
boost::shared_ptr
< pr2_arm_kinematics::PR2ArmIKSolver
pr2_arm_ik_solver_
urdf::Model robot_model_
ros::NodeHandle root_handle_
std::string root_name_
double search_discretization_
tf::TransformListenertf_

Detailed Description

Definition at line 59 of file pr2_arm_kinematics.h.


Constructor & Destructor Documentation

pr2_arm_kinematics::PR2ArmKinematics::PR2ArmKinematics ( bool  create_transform_listener = true)

Definition at line 58 of file pr2_arm_kinematics.cpp.

Definition at line 131 of file pr2_arm_kinematics.cpp.


Member Function Documentation

bool pr2_arm_kinematics::PR2ArmKinematics::getFKSolverInfo ( moveit_msgs::GetKinematicSolverInfo::Request &  request,
moveit_msgs::GetKinematicSolverInfo::Response &  response 
)

This is the basic kinematics info service that will return information about the kinematics node.

Parameters:
Arequest message. See service definition for GetKinematicSolverInfo for more information on this message.
Theresponse message. See service definition for GetKinematicSolverInfo for more information on this message.

Definition at line 242 of file pr2_arm_kinematics.cpp.

bool pr2_arm_kinematics::PR2ArmKinematics::getIKSolverInfo ( moveit_msgs::GetKinematicSolverInfo::Request &  request,
moveit_msgs::GetKinematicSolverInfo::Response &  response 
)

This is the basic kinematics info service that will return information about the kinematics node.

Parameters:
Arequest message. See service definition for GetKinematicSolverInfo for more information on this message.
Theresponse message. See service definition for GetKinematicSolverInfo for more information on this message.

Definition at line 230 of file pr2_arm_kinematics.cpp.

bool pr2_arm_kinematics::PR2ArmKinematics::getPositionFK ( moveit_msgs::GetPositionFK::Request &  request,
moveit_msgs::GetPositionFK::Response &  response 
)

This is the basic forward kinematics service that will return information about the kinematics node.

Parameters:
Arequest message. See service definition for GetPositionFK for more information on this message.
Theresponse message. See service definition for GetPositionFK for more information on this message.

Definition at line 254 of file pr2_arm_kinematics.cpp.

bool pr2_arm_kinematics::PR2ArmKinematics::getPositionIK ( moveit_msgs::GetPositionIK::Request &  request,
moveit_msgs::GetPositionIK::Response &  response 
) [virtual]

This is the basic IK service method that will compute and return an IK solution.

Parameters:
Arequest message. See service definition for GetPositionIK for more information on this message.
Theresponse message. See service definition for GetPositionIK for more information on this message.

Definition at line 145 of file pr2_arm_kinematics.cpp.

bool pr2_arm_kinematics::PR2ArmKinematics::getPositionIKHelper ( moveit_msgs::GetPositionIK::Request &  request,
moveit_msgs::GetPositionIK::Response &  response 
) [protected]

Definition at line 175 of file pr2_arm_kinematics.cpp.

Specifies if the node is active or not.

Returns:
True if the node is active, false otherwise.

Definition at line 138 of file pr2_arm_kinematics.cpp.

bool pr2_arm_kinematics::PR2ArmKinematics::transformPose ( const std::string &  des_frame,
const geometry_msgs::PoseStamped &  pose_in,
geometry_msgs::PoseStamped &  pose_out 
) [protected, virtual]

Definition at line 308 of file pr2_arm_kinematics.cpp.


Member Data Documentation

Definition at line 125 of file pr2_arm_kinematics.h.

Definition at line 134 of file pr2_arm_kinematics.h.

Definition at line 131 of file pr2_arm_kinematics.h.

moveit_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmKinematics::fk_solver_info_ [protected]

Definition at line 137 of file pr2_arm_kinematics.h.

Definition at line 131 of file pr2_arm_kinematics.h.

Definition at line 126 of file pr2_arm_kinematics.h.

Definition at line 131 of file pr2_arm_kinematics.h.

moveit_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmKinematics::ik_solver_info_ [protected]

Definition at line 137 of file pr2_arm_kinematics.h.

Definition at line 131 of file pr2_arm_kinematics.h.

Definition at line 135 of file pr2_arm_kinematics.h.

Definition at line 136 of file pr2_arm_kinematics.h.

Definition at line 129 of file pr2_arm_kinematics.h.

Definition at line 130 of file pr2_arm_kinematics.h.

Definition at line 127 of file pr2_arm_kinematics.h.

Definition at line 129 of file pr2_arm_kinematics.h.

Definition at line 133 of file pr2_arm_kinematics.h.

Definition at line 128 of file pr2_arm_kinematics.h.

Definition at line 132 of file pr2_arm_kinematics.h.


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


pr2_arm_kinematics
Author(s): Sachin Chitta
autogenerated on Wed Aug 26 2015 15:36:29