75 getPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
76 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
80 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
81 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
85 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
86 const std::vector<double>& consistency_limits, std::vector<double>& solution,
87 moveit_msgs::msg::MoveItErrorCodes& error_code,
91 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
92 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
93 moveit_msgs::msg::MoveItErrorCodes& error_code,
97 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
98 const std::vector<double>& consistency_limits, std::vector<double>& solution,
99 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
102 bool searchPositionIK(
const std::vector<geometry_msgs::msg::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
103 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
104 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
108 bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
109 std::vector<geometry_msgs::msg::Pose>& poses)
const override;
112 const std::string& group_name,
const std::string& base_name,
113 const std::vector<std::string>& tip_frames,
double search_discretization)
override;
118 const std::vector<std::string>&
getJointNames()
const override;
123 const std::vector<std::string>&
getLinkNames()
const override;
131 bool setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices)
override;
134 bool timedOut(
const rclcpp::Time& start_time,
double duration)
const;
136 int getJointIndex(
const std::string& name)
const;
138 bool isRedundantJoint(
unsigned int index)
const;
142 moveit_msgs::msg::KinematicSolverInfo ik_group_info_;
144 unsigned int dimension_;
148 moveit::core::RobotStatePtr robot_state_;
150 int num_possible_redundant_joints_;
152 rclcpp::Client<moveit_msgs::srv::GetPositionIK>::SharedPtr ik_service_client_;
154 rclcpp::Node::SharedPtr node_;
156 std::shared_ptr<srv_kinematics::ParamListener> param_listener_;
157 srv_kinematics::Params params_;