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 getPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
78 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
82 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
83 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
87 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
88 const std::vector<double>& consistency_limits, std::vector<double>& solution,
89 moveit_msgs::MoveItErrorCodes& error_code,
93 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
94 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
95 moveit_msgs::MoveItErrorCodes& error_code,
99 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
100 const std::vector<double>& consistency_limits, std::vector<double>& solution,
101 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
104 virtual bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
105 std::vector<geometry_msgs::Pose>& poses)
const;
111 virtual bool initialize(
const std::string& robot_description,
const std::string& group_name,
112 const std::string& base_frame,
const std::string& tip_frame,
double search_discretization);
130 ros::ServiceServer ik_service_, fk_service_, ik_solver_info_service_, fk_solver_info_service_;
Namespace for the PR2ArmKinematics.
pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_
moveit_msgs::KinematicSolverInfo fk_solver_info_
std::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
moveit_msgs::KinematicSolverInfo ik_solver_info_
const std::vector< std::string > & getJointNames() const override
bool initialize(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) override
const std::vector< std::string > & getLinkNames() const override
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override