39#include <geometry_msgs/msg/pose.hpp>
40#include <moveit_msgs/msg/move_it_error_codes.hpp>
42#include <rclcpp/logging.hpp>
43#include <rclcpp/node.hpp>
48#include <moveit_kinematics_base_export.h>
68namespace DiscretizationMethods
88namespace KinematicErrors
154 using IKCallbackFn = std::function<void(
const geometry_msgs::msg::Pose&,
const std::vector<double>&,
155 moveit_msgs::msg::MoveItErrorCodes&)>;
174 getPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
175 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
199 virtual bool getPositionIK(
const std::vector<geometry_msgs::msg::Pose>& ik_poses,
200 const std::vector<double>& ik_seed_state, std::vector<std::vector<double> >& solutions,
216 searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
217 std::vector<double>& solution, moveit_msgs::msg::MoveItErrorCodes& error_code,
235 searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
236 const std::vector<double>& consistency_limits, std::vector<double>& solution,
237 moveit_msgs::msg::MoveItErrorCodes& error_code,
254 searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
255 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
256 moveit_msgs::msg::MoveItErrorCodes& error_code,
275 searchPositionIK(
const geometry_msgs::msg::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
276 const std::vector<double>& consistency_limits, std::vector<double>& solution,
277 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
302 searchPositionIK(
const std::vector<geometry_msgs::msg::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
303 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
304 const IKCallbackFn& solution_callback, moveit_msgs::msg::MoveItErrorCodes& error_code,
310 if (ik_poses.size() == 1)
313 if (solution_callback)
315 return searchPositionIK(ik_poses[0], ik_seed_state, timeout, consistency_limits, solution, solution_callback,
316 error_code, options);
320 return searchPositionIK(ik_poses[0], ik_seed_state, timeout, consistency_limits, solution, error_code, options);
326 "This kinematic solver does not support searchPositionIK with multiple poses");
353 searchPositionIK(
const std::vector<geometry_msgs::msg::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
354 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
356 moveit_msgs::msg::MoveItErrorCodes& error_code,
363 return searchPositionIK(ik_poses, ik_seed_state, timeout, consistency_limits, solution, solution_callback,
364 error_code, options, context_state);
367 "This kinematic solver does not support IK solution cost functions");
378 virtual bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
379 std::vector<geometry_msgs::msg::Pose>& poses)
const = 0;
391 virtual void setValues(
const std::string& robot_description,
const std::string& group_name,
392 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
393 double search_discretization);
409 const std::string& group_name,
const std::string& base_frame,
410 const std::vector<std::string>& tip_frames,
double search_discretization);
438 if (tip_frames_.size() > 1)
441 "This kinematic solver has more than one tip frame, "
442 "do not call getTipFrame()");
445 return tip_frames_[0];
466 virtual bool setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices);
474 bool setRedundantJoints(
const std::vector<std::string>& redundant_joint_names);
481 redundant_joint_indices = redundant_joint_indices_;
517 redundant_joint_discretization_.clear();
518 for (
unsigned int index : redundant_joint_indices_)
519 redundant_joint_discretization_[index] = sd;
531 redundant_joint_discretization_.clear();
532 redundant_joint_indices_.clear();
533 for (
const auto& pair : discretization)
535 redundant_joint_discretization_.insert(pair);
536 redundant_joint_indices_.push_back(pair.first);
545 if (redundant_joint_discretization_.count(joint_index) > 0)
547 return redundant_joint_discretization_.at(joint_index);
561 return supported_methods_;
568 default_timeout_ = timeout;
575 return default_timeout_;
607 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
608 double search_discretization);
611 std::string removeSlash(
const std::string& str)
const;
#define MOVEIT_CLASS_FORWARD(C)
Provides an interface for kinematics solvers.
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::msg::Pose > &poses) const =0
Given a set of joint angles and a set of links, compute their pose.
virtual bool searchPositionIK(const std::vector< geometry_msgs::msg::Pose > &ik_poses, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, const IKCallbackFn &solution_callback, const IKCostFn &cost_function, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const moveit::core::RobotState *context_state=nullptr) const
Given a set of desired poses for a planning group with multiple end-effectors, search for the joint a...
virtual bool searchPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const =0
Given a desired pose of the end-effector, search for the joint angles required to reach it....
void setSearchDiscretization(double sd)
Set the search discretization value for all the redundant joints.
virtual void getRedundantJoints(std::vector< unsigned int > &redundant_joint_indices) const
Get the set of redundant joints.
std::vector< DiscretizationMethod > getSupportedDiscretizationMethods() const
Returns the set of supported kinematics discretization search types. This implementation only support...
virtual bool searchPositionIK(const std::vector< geometry_msgs::msg::Pose > &ik_poses, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const moveit::core::RobotState *context_state=nullptr) const
Given a set of desired poses for a planning group with multiple end-effectors, search for the joint a...
std::map< int, double > redundant_joint_discretization_
std::vector< unsigned int > redundant_joint_indices_
virtual const std::vector< std::string > & getLinkNames() const =0
Return all the link names in the order they are represented internally.
virtual const std::string & getGroupName() const
Return the name of the group that the solver is operating on.
std::function< double(const geometry_msgs::msg::Pose &, const moveit::core::RobotState &, const moveit::core::JointModelGroup *, const std::vector< double > &)> IKCostFn
Signature for a cost function used to evaluate IK solutions.
std::vector< DiscretizationMethod > supported_methods_
void setDefaultTimeout(double timeout)
For functions that require a timeout specified but one is not specified using arguments,...
virtual 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 =0
Given a desired pose of the end-effector, search for the joint angles required to reach it....
virtual 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 =0
Given a desired pose of the end-effector, compute the joint angles to reach it.
double getSearchDiscretization(int joint_index=0) const
Get the value of the search discretization.
virtual bool searchPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, std::vector< double > &solution, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const =0
Given a desired pose of the end-effector, search for the joint angles required to reach it....
rclcpp::Node::SharedPtr node_
virtual const std::string & getTipFrame() const
Return the name of the tip frame of the chain on which the solver is operating. This is usually a lin...
virtual ~KinematicsBase()
Virtual destructor for the interface.
std::vector< std::string > tip_frames_
virtual bool searchPositionIK(const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::msg::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const =0
Given a desired pose of the end-effector, search for the joint angles required to reach it....
static const double DEFAULT_TIMEOUT
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.
virtual const std::vector< std::string > & getTipFrames() const
Return the names of the tip frames of the kinematic tree on which the solver is operating....
moveit::core::RobotModelConstPtr robot_model_
double getDefaultTimeout() const
For functions that require a timeout specified but one is not specified using arguments,...
void setSearchDiscretization(const std::map< int, double > &discretization)
Sets individual discretization values for each redundant joint.
static const double DEFAULT_SEARCH_DISCRETIZATION
virtual const std::string & getBaseFrame() const
Return the name of the frame in which the solver is operating. This is usually a link name....
std::string robot_description_
virtual const std::vector< std::string > & getJointNames() const =0
Return all the joint names in the order they are used internally.
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.
@ DISCRETIZATION_NOT_INITIALIZED
@ MULTIPLE_TIPS_NOT_SUPPORTED
@ UNSUPORTED_DISCRETIZATION_REQUESTED
API for forward and inverse kinematics.
Main namespace for MoveIt.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
A set of options for the kinematics solver.
DiscretizationMethod discretization_method
bool lock_redundant_joints
bool return_approximate_solution
KinematicError kinematic_error
double solution_percentage