45 #include <rclcpp/rclcpp.hpp>
46 #include <srv_kinematics_parameters.hpp>
52 #include <geometry_msgs/msg/pose.hpp>
53 #include <moveit_msgs/msg/kinematic_solver_info.hpp>
54 #include <moveit_msgs/msg/move_it_error_codes.hpp>
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_;
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.