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>
77 virtual bool getPositionIK(
const geometry_msgs::Pose &ik_pose,
78 const std::vector<double> &ik_seed_state,
79 std::vector<double> &solution,
80 moveit_msgs::MoveItErrorCodes &error_code,
84 const std::vector<double> &ik_seed_state,
86 std::vector<double> &solution,
87 moveit_msgs::MoveItErrorCodes &error_code,
91 const std::vector<double> &ik_seed_state,
93 const std::vector<double> &consistency_limits,
94 std::vector<double> &solution,
95 moveit_msgs::MoveItErrorCodes &error_code,
99 const std::vector<double> &ik_seed_state,
101 std::vector<double> &solution,
103 moveit_msgs::MoveItErrorCodes &error_code,
107 const std::vector<double> &ik_seed_state,
109 const std::vector<double> &consistency_limits,
110 std::vector<double> &solution,
112 moveit_msgs::MoveItErrorCodes &error_code,
115 virtual bool getPositionFK(
const std::vector<std::string> &link_names,
116 const std::vector<double> &joint_angles,
117 std::vector<geometry_msgs::Pose> &poses)
const;
123 virtual bool initialize(
const std::string& robot_description,
124 const std::string& group_name,
125 const std::string& base_frame,
126 const std::string& tip_frame,
127 double search_discretization);
146 ros::ServiceServer ik_service_,fk_service_,ik_solver_info_service_,fk_solver_info_service_;