45 #include <rclcpp/rclcpp.hpp>
51 #include <geometry_msgs/msg/pose.hpp>
52 #include <moveit_msgs/msg/kinematic_solver_info.hpp>
53 #include <moveit_msgs/msg/move_it_error_codes.hpp>
74 getPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
75 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
79 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
80 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
84 const geometry_msgs::msg::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::msg::MoveItErrorCodes& error_code,
90 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
91 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
92 moveit_msgs::msg::MoveItErrorCodes& error_code,
96 const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
97 const std::vector<double>& consistency_limits, std::vector<double>& solution,
98 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
101 bool searchPositionIK(
const std::vector<geometry_msgs::msg::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
102 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
103 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
107 bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
108 std::vector<geometry_msgs::msg::Pose>& poses)
const override;
111 const std::string& group_name,
const std::string& base_name,
112 const std::vector<std::string>& tip_frames,
double search_discretization)
override;
117 const std::vector<std::string>&
getJointNames()
const override;
122 const std::vector<std::string>&
getLinkNames()
const override;
130 bool setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices)
override;
133 bool timedOut(
const rclcpp::Time& start_time,
double duration)
const;
135 int getJointIndex(
const std::string&
name)
const;
137 bool isRedundantJoint(
unsigned int index)
const;
141 moveit_msgs::msg::KinematicSolverInfo ik_group_info_;
143 unsigned int dimension_;
147 moveit::core::RobotStatePtr robot_state_;
149 int num_possible_redundant_joints_;
151 rclcpp::Client<moveit_msgs::srv::GetPositionIK>::SharedPtr ik_service_client_;
153 rclcpp::Node::SharedPtr node_;
Provides an interface for kinematics solvers.
std::function< void(const geometry_msgs::msg::Pose &, const std::vector< double > &, moveit_msgs::msg::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers...
bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices) override
Set a set of redundant joints for the kinematics solver to use. This can fail, depending on the IK so...
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
bool searchPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
Given a desired pose of the end-effector, search for the joint angles required to reach it....
bool getPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
Given a desired pose of the end-effector, compute the joint angles to reach it.
const std::vector< std::string > & getVariableNames() const
Return all the variable names in the order they are represented internally.
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::msg::Pose > &poses) const override
Given a set of joint angles and a set of links, compute their pose.
bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_name, const std::vector< std::string > &tip_frames, double search_discretization) override
Initialization function for the kinematics, for use with kinematic chain IK solvers.
SrvKinematicsPlugin()
Default constructor.
A set of options for the kinematics solver.