Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
pr2_arm_kinematics::PR2ArmKinematics Class Reference

#include <pr2_arm_kinematics.h>

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. More...
 
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. More...
 
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. More...
 
virtual 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. More...
 
bool isActive ()
 Specifies if the node is active or not. More...
 
 PR2ArmKinematics (bool create_transform_listener=true)
 
virtual ~PR2ArmKinematics ()
 

Protected Member Functions

bool getPositionIKHelper (kinematics_msgs::GetPositionIK::Request &request, kinematics_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_
 
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_recursivejnt_to_pose_solver_
 
KDL::Chain kdl_chain_
 
ros::NodeHandle node_handle_
 
boost::shared_ptr< pr2_arm_kinematics::PR2ArmIKSolverpr2_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.

pr2_arm_kinematics::PR2ArmKinematics::~PR2ArmKinematics ( )
virtual

Definition at line 131 of file pr2_arm_kinematics.cpp.

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
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 241 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
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 229 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
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 253 of file pr2_arm_kinematics.cpp.

bool pr2_arm_kinematics::PR2ArmKinematics::getPositionIK ( kinematics_msgs::GetPositionIK::Request &  request,
kinematics_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 ( kinematics_msgs::GetPositionIK::Request &  request,
kinematics_msgs::GetPositionIK::Response &  response 
)
protected

Definition at line 176 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 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 
)
protectedvirtual

Definition at line 307 of file pr2_arm_kinematics.cpp.

Member Data Documentation

bool pr2_arm_kinematics::PR2ArmKinematics::active_
protected

Definition at line 125 of file pr2_arm_kinematics.h.

int pr2_arm_kinematics::PR2ArmKinematics::dimension_
protected

Definition at line 134 of file pr2_arm_kinematics.h.

ros::ServiceServer pr2_arm_kinematics::PR2ArmKinematics::fk_service_
protected

Definition at line 131 of file pr2_arm_kinematics.h.

kinematics_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmKinematics::fk_solver_info_
protected

Definition at line 137 of file pr2_arm_kinematics.h.

ros::ServiceServer pr2_arm_kinematics::PR2ArmKinematics::fk_solver_info_service_
protected

Definition at line 131 of file pr2_arm_kinematics.h.

int pr2_arm_kinematics::PR2ArmKinematics::free_angle_
protected

Definition at line 126 of file pr2_arm_kinematics.h.

ros::ServiceServer pr2_arm_kinematics::PR2ArmKinematics::ik_service_
protected

Definition at line 131 of file pr2_arm_kinematics.h.

kinematics_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmKinematics::ik_solver_info_
protected

Definition at line 137 of file pr2_arm_kinematics.h.

ros::ServiceServer pr2_arm_kinematics::PR2ArmKinematics::ik_solver_info_service_
protected

Definition at line 131 of file pr2_arm_kinematics.h.

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

Definition at line 135 of file pr2_arm_kinematics.h.

KDL::Chain pr2_arm_kinematics::PR2ArmKinematics::kdl_chain_
protected

Definition at line 136 of file pr2_arm_kinematics.h.

ros::NodeHandle pr2_arm_kinematics::PR2ArmKinematics::node_handle_
protected

Definition at line 129 of file pr2_arm_kinematics.h.

boost::shared_ptr<pr2_arm_kinematics::PR2ArmIKSolver> pr2_arm_kinematics::PR2ArmKinematics::pr2_arm_ik_solver_
protected

Definition at line 130 of file pr2_arm_kinematics.h.

urdf::Model pr2_arm_kinematics::PR2ArmKinematics::robot_model_
protected

Definition at line 127 of file pr2_arm_kinematics.h.

ros::NodeHandle pr2_arm_kinematics::PR2ArmKinematics::root_handle_
protected

Definition at line 129 of file pr2_arm_kinematics.h.

std::string pr2_arm_kinematics::PR2ArmKinematics::root_name_
protected

Definition at line 133 of file pr2_arm_kinematics.h.

double pr2_arm_kinematics::PR2ArmKinematics::search_discretization_
protected

Definition at line 128 of file pr2_arm_kinematics.h.

tf::TransformListener* pr2_arm_kinematics::PR2ArmKinematics::tf_
protected

Definition at line 132 of file pr2_arm_kinematics.h.


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


pr2_moveit_plugins
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Sun Nov 17 2019 03:24:45