39 #include <rclcpp/logger.hpp>
44 const rclcpp::Logger
KinematicsBase::LOGGER = rclcpp::get_logger(
"moveit_kinematics_base.kinematics_base");
53 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
54 double search_discretization)
60 robot_model_ = moveit::core::RobotModelConstPtr(&robot_model, &noDeleter);
65 for (
const std::string&
name : tip_frames)
71 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
72 double search_discretization)
79 for (
const std::string&
name : tip_frames)
86 const std::string& ,
const std::vector<std::string>& ,
90 "IK plugin for group '%s' relies on deprecated API. "
91 "Please implement initialize(rclcpp::Node::SharedPtr, RobotModel, ...).",
98 for (
const unsigned int& redundant_joint_index : redundant_joint_indices)
114 std::vector<unsigned int> redundant_joint_indices;
115 for (
const std::string& redundant_joint_name : redundant_joint_names)
116 for (std::size_t j = 0; j < jnames.size(); ++j)
117 if (jnames[j] == redundant_joint_name)
119 redundant_joint_indices.push_back(j);
122 return redundant_joint_indices.size() == redundant_joint_names.size() ?
setRedundantJoints(redundant_joint_indices) :
126 std::string KinematicsBase::removeSlash(
const std::string& str)
const
128 return (!str.empty() && str[0] ==
'/') ? removeSlash(str.substr(1)) : str;
138 *error_text_out =
"This plugin only supports joint groups which are chains";
154 const std::vector<double>& ik_seed_state,
158 std::vector<double> solution;
168 if (ik_poses.size() != 1)
170 RCLCPP_ERROR(
LOGGER,
"This kinematic solver does not support getPositionIK for multiple tips");
175 if (ik_poses.empty())
177 RCLCPP_ERROR(
LOGGER,
"Input ik_poses array is empty");
182 moveit_msgs::msg::MoveItErrorCodes error_code;
186 solutions[0] = solution;
virtual const std::vector< std::string > & getJointNames() const =0
Return all the joint names in the order they are used internally.
void setSearchDiscretization(double sd)
Set the search discretization value for all the redundant joints.
void storeValues(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
virtual void setValues(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
Set the parameters for the solver, for use with non-chain IK solvers.
std::vector< unsigned int > redundant_joint_indices_
static const rclcpp::Logger LOGGER
std::vector< DiscretizationMethod > supported_methods_
virtual bool initialize(const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization)
Initialization function for the kinematics, for use with kinematic chain IK solvers.
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.
virtual ~KinematicsBase()
Virtual destructor for the interface.
std::vector< std::string > tip_frames_
virtual bool supportsGroup(const moveit::core::JointModelGroup *jmg, std::string *error_text_out=nullptr) const
Check if this solver supports a given JointModelGroup.
static const double DEFAULT_TIMEOUT
moveit::core::RobotModelConstPtr robot_model_
static const double DEFAULT_SEARCH_DISCRETIZATION
std::string robot_description_
virtual bool setRedundantJoints(const std::vector< unsigned int > &redundant_joint_indices)
Set a set of redundant joints for the kinematics solver to use. This can fail, depending on the IK so...
bool isChain() const
Check if this group is a linear chain.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
@ MULTIPLE_TIPS_NOT_SUPPORTED
@ UNSUPORTED_DISCRETIZATION_REQUESTED
API for forward and inverse kinematics.
A set of options for the kinematics solver.
KinematicError kinematic_error
double solution_percentage