51 #include <geometry_msgs/Pose.h>
52 #include <moveit_msgs/KinematicSolverInfo.h>
53 #include <moveit_msgs/MoveItErrorCodes.h>
74 getPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
75 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
79 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
80 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
84 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
85 const std::vector<double>& consistency_limits, std::vector<double>& solution,
86 moveit_msgs::MoveItErrorCodes& error_code,
90 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
91 std::vector<double>& solution,
const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
95 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
96 const std::vector<double>& consistency_limits, std::vector<double>& solution,
97 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
100 bool searchPositionIK(
const std::vector<geometry_msgs::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
101 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
102 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
106 bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
107 std::vector<geometry_msgs::Pose>& poses)
const override;
110 const std::string& base_name,
const std::vector<std::string>& tip_frames,
111 double search_discretization)
override;
116 const std::vector<std::string>&
getJointNames()
const override;
121 const std::vector<std::string>&
getLinkNames()
const override;
129 bool setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices)
override;