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 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. More...
 
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. 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 (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::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 91 of file pr2_arm_kinematics.h.

Constructor & Destructor Documentation

◆ PR2ArmKinematics()

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

Definition at line 58 of file pr2_arm_kinematics.cpp.

◆ ~PR2ArmKinematics()

pr2_arm_kinematics::PR2ArmKinematics::~PR2ArmKinematics ( )
virtual

Definition at line 128 of file pr2_arm_kinematics.cpp.

Member Function Documentation

◆ getPositionFK()

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 227 of file pr2_arm_kinematics.cpp.

◆ getPositionIK()

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 142 of file pr2_arm_kinematics.cpp.

◆ getPositionIKHelper()

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

Definition at line 172 of file pr2_arm_kinematics.cpp.

◆ isActive()

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 135 of file pr2_arm_kinematics.cpp.

◆ transformPose()

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 281 of file pr2_arm_kinematics.cpp.

Member Data Documentation

◆ active_

bool pr2_arm_kinematics::PR2ArmKinematics::active_
protected

Definition at line 173 of file pr2_arm_kinematics.h.

◆ dimension_

int pr2_arm_kinematics::PR2ArmKinematics::dimension_
protected

Definition at line 182 of file pr2_arm_kinematics.h.

◆ fk_service_

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

Definition at line 179 of file pr2_arm_kinematics.h.

◆ fk_solver_info_

moveit_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmKinematics::fk_solver_info_
protected

Definition at line 185 of file pr2_arm_kinematics.h.

◆ fk_solver_info_service_

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

Definition at line 179 of file pr2_arm_kinematics.h.

◆ free_angle_

int pr2_arm_kinematics::PR2ArmKinematics::free_angle_
protected

Definition at line 174 of file pr2_arm_kinematics.h.

◆ ik_service_

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

Definition at line 179 of file pr2_arm_kinematics.h.

◆ ik_solver_info_

moveit_msgs::KinematicSolverInfo pr2_arm_kinematics::PR2ArmKinematics::ik_solver_info_
protected

Definition at line 185 of file pr2_arm_kinematics.h.

◆ ik_solver_info_service_

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

Definition at line 179 of file pr2_arm_kinematics.h.

◆ jnt_to_pose_solver_

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

Definition at line 183 of file pr2_arm_kinematics.h.

◆ kdl_chain_

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

Definition at line 184 of file pr2_arm_kinematics.h.

◆ node_handle_

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

Definition at line 177 of file pr2_arm_kinematics.h.

◆ pr2_arm_ik_solver_

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

Definition at line 178 of file pr2_arm_kinematics.h.

◆ robot_model_

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

Definition at line 175 of file pr2_arm_kinematics.h.

◆ root_handle_

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

Definition at line 177 of file pr2_arm_kinematics.h.

◆ root_name_

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

Definition at line 181 of file pr2_arm_kinematics.h.

◆ search_discretization_

double pr2_arm_kinematics::PR2ArmKinematics::search_discretization_
protected

Definition at line 176 of file pr2_arm_kinematics.h.

◆ tf_

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

Definition at line 180 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 Mar 2 2022 00:45:20