39#include <rclcpp/logger.hpp>
60 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
61 double search_discretization)
67 robot_model_ = moveit::core::RobotModelConstPtr(&robot_model, &noDeleter);
72 for (
const std::string& name : tip_frames)
78 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
79 double search_discretization)
86 for (
const std::string& name : tip_frames)
93 const std::string& ,
const std::vector<std::string>& ,
96 RCLCPP_ERROR(getLogger(),
97 "IK plugin for group '%s' relies on deprecated API. "
98 "Please implement initialize(rclcpp::Node::SharedPtr, RobotModel, ...).",
105 for (
unsigned int redundant_joint_index : redundant_joint_indices)
121 std::vector<unsigned int> redundant_joint_indices;
122 for (
const std::string& redundant_joint_name : redundant_joint_names)
124 for (std::size_t j = 0; j < jnames.size(); ++j)
126 if (jnames[j] == redundant_joint_name)
128 redundant_joint_indices.push_back(j);
133 return redundant_joint_indices.size() == redundant_joint_names.size() ?
setRedundantJoints(redundant_joint_indices) :
137std::string KinematicsBase::removeSlash(
const std::string& str)
const
139 return (!str.empty() && str[0] ==
'/') ? removeSlash(str.substr(1)) : str;
149 *error_text_out =
"This plugin only supports joint groups which are chains";
165 const std::vector<double>& ik_seed_state,
169 std::vector<double> solution;
179 if (ik_poses.size() != 1)
181 RCLCPP_ERROR(getLogger(),
"This kinematic solver does not support getPositionIK for multiple tips");
186 if (ik_poses.empty())
188 RCLCPP_ERROR(getLogger(),
"Input ik_poses array is empty");
193 moveit_msgs::msg::MoveItErrorCodes error_code;
194 if (
getPositionIK(ik_poses[0], ik_seed_state, solution, error_code, options))
197 solutions[0] = solution;
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_
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...
virtual const std::vector< std::string > & getJointNames() const =0
Return all the joint names in the order they are used internally.
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...
rclcpp::Logger getLogger()
@ MULTIPLE_TIPS_NOT_SUPPORTED
@ UNSUPORTED_DISCRETIZATION_REQUESTED
API for forward and inverse kinematics.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
A set of options for the kinematics solver.
KinematicError kinematic_error
double solution_percentage