pr2_arm_kinematics::PR2ArmKinematics Class Reference

#include <pr2_arm_kinematics.h>

List of all members.

Public Member Functions

bool getFKSolverInfo (kinematics_msgs::GetKinematicSolverInfo::Request &request, kinematics_msgs::GetKinematicSolverInfo::Response &response)
 This is the basic kinematics info service that will return information about the kinematics node.
bool getIKSolverInfo (kinematics_msgs::GetKinematicSolverInfo::Request &request, kinematics_msgs::GetKinematicSolverInfo::Response &response)
 This is the basic kinematics info service that will return information about the kinematics node.
bool getPositionFK (kinematics_msgs::GetPositionFK::Request &request, kinematics_msgs::GetPositionFK::Response &response)
 This is the basic forward kinematics service that will return information about the kinematics node.
bool getPositionIK (kinematics_msgs::GetPositionIK::Request &request, kinematics_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 ()
virtual ~PR2ArmKinematics ()

Protected Attributes

bool active_
int dimension_
ros::ServiceServer fk_service_
kinematics_msgs::KinematicSolverInfo fk_solver_info_
ros::ServiceServer fk_solver_info_service_
int free_angle_
ros::ServiceServer ik_service_
kinematics_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::TransformListener tf_

Detailed Description

Definition at line 56 of file pr2_arm_kinematics.h.


Constructor & Destructor Documentation

pr2_arm_kinematics::PR2ArmKinematics::PR2ArmKinematics (  ) 

Definition at line 55 of file pr2_arm_kinematics.cpp.

virtual pr2_arm_kinematics::PR2ArmKinematics::~PR2ArmKinematics (  )  [inline, virtual]

Definition at line 70 of file pr2_arm_kinematics.h.


Member Function Documentation

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

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

Parameters:
A request message. See service definition for GetKinematicSolverInfo for more information on this message.
The response message. See service definition for GetKinematicSolverInfo for more information on this message.

Definition at line 197 of file pr2_arm_kinematics.cpp.

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

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

Parameters:
A request message. See service definition for GetKinematicSolverInfo for more information on this message.
The response message. See service definition for GetKinematicSolverInfo for more information on this message.

Definition at line 185 of file pr2_arm_kinematics.cpp.

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

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

Parameters:
A request message. See service definition for GetPositionFK for more information on this message.
The response message. See service definition for GetPositionFK for more information on this message.

Definition at line 209 of file pr2_arm_kinematics.cpp.

bool pr2_arm_kinematics::PR2ArmKinematics::getPositionIK ( kinematics_msgs::GetPositionIK::Request &  request,
kinematics_msgs::GetPositionIK::Response &  response 
)

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

Parameters:
A request message. See service definition for GetPositionIK for more information on this message.
The response message. See service definition for GetPositionIK for more information on this message.

Definition at line 120 of file pr2_arm_kinematics.cpp.

bool pr2_arm_kinematics::PR2ArmKinematics::isActive (  ) 

Specifies if the node is active or not.

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

Definition at line 113 of file pr2_arm_kinematics.cpp.


Member Data Documentation

Definition at line 112 of file pr2_arm_kinematics.h.

Definition at line 121 of file pr2_arm_kinematics.h.

ros::ServiceServer pr2_arm_kinematics::PR2ArmKinematics::fk_service_ [protected]

Definition at line 118 of file pr2_arm_kinematics.h.

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

Definition at line 124 of file pr2_arm_kinematics.h.

Definition at line 118 of file pr2_arm_kinematics.h.

Definition at line 113 of file pr2_arm_kinematics.h.

ros::ServiceServer pr2_arm_kinematics::PR2ArmKinematics::ik_service_ [protected]

Definition at line 118 of file pr2_arm_kinematics.h.

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

Definition at line 124 of file pr2_arm_kinematics.h.

Definition at line 118 of file pr2_arm_kinematics.h.

boost::shared_ptr<KDL::ChainFkSolverPos_recursive> pr2_arm_kinematics::PR2ArmKinematics::jnt_to_pose_solver_ [protected]

Definition at line 122 of file pr2_arm_kinematics.h.

Definition at line 123 of file pr2_arm_kinematics.h.

Definition at line 116 of file pr2_arm_kinematics.h.

Definition at line 117 of file pr2_arm_kinematics.h.

Definition at line 114 of file pr2_arm_kinematics.h.

Definition at line 116 of file pr2_arm_kinematics.h.

Definition at line 120 of file pr2_arm_kinematics.h.

Definition at line 115 of file pr2_arm_kinematics.h.

tf::TransformListener pr2_arm_kinematics::PR2ArmKinematics::tf_ [protected]

Definition at line 119 of file pr2_arm_kinematics.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Defines


pr2_arm_kinematics
Author(s): Sachin Chitta
autogenerated on Fri Jan 11 09:52:49 2013