Go to the documentation of this file.
37 #ifndef PR2_ARM_IK_NODE_H
38 #define PR2_ARM_IK_NODE_H
48 #include <moveit_msgs/GetPositionFK.h>
49 #include <moveit_msgs/GetPositionIK.h>
50 #include <moveit_msgs/KinematicSolverInfo.h>
51 #include <moveit_msgs/MoveItErrorCodes.h>
53 #include <kdl/chainfksolverpos_recursive.hpp>
55 #include <boost/shared_ptr.hpp>
59 class PR2ArmKinematics
88 virtual bool getPositionIK(moveit_msgs::GetPositionIK::Request &request,
89 moveit_msgs::GetPositionIK::Response &response);
96 bool getPositionFK(moveit_msgs::GetPositionFK::Request &request,
97 moveit_msgs::GetPositionFK::Response &response);
103 moveit_msgs::GetPositionIK::Response &response);
106 const geometry_msgs::PoseStamped& pose_in,
107 geometry_msgs::PoseStamped& pose_out);
virtual ~PR2ArmKinematics()
Namespace for the PR2ArmKinematics.
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.
moveit_msgs::KinematicSolverInfo ik_solver_info_
boost::shared_ptr< pr2_arm_kinematics::PR2ArmIKSolver > pr2_arm_ik_solver_
ros::ServiceServer ik_service_
ros::NodeHandle root_handle_
virtual bool transformPose(const std::string &des_frame, const geometry_msgs::PoseStamped &pose_in, geometry_msgs::PoseStamped &pose_out)
double search_discretization_
tf::TransformListener * tf_
bool isActive()
Specifies if the node is active or not.
PR2ArmKinematics(bool create_transform_listener=true)
ros::ServiceServer ik_solver_info_service_
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.
ros::ServiceServer fk_solver_info_service_
bool getPositionIKHelper(moveit_msgs::GetPositionIK::Request &request, moveit_msgs::GetPositionIK::Response &response)
boost::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
ros::ServiceServer fk_service_
ros::NodeHandle node_handle_
moveit_msgs::KinematicSolverInfo fk_solver_info_