Go to the documentation of this file.
40 static const std::string
LOGNAME =
"kinematics_base";
52 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
53 double search_discretization)
64 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)
92 const std::string& base_frame,
const std::string& tip_frame,
93 double search_discretization)
95 setValues(robot_description, group_name, base_frame, std::vector<std::string>({ tip_frame }), search_discretization);
99 const std::string& ,
const std::string& ,
106 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
107 double search_discretization)
110 if (tip_frames.size() == 1)
112 return initialize(robot_description, group_name, base_frame, tip_frames[0], search_discretization);
120 const std::string& ,
const std::vector<std::string>& ,
124 "IK plugin for group '%s' relies on deprecated API. "
125 "Please implement initialize(RobotModel, ...).",
132 for (
const unsigned int& redundant_joint_index : redundant_joint_indices)
148 std::vector<unsigned int> redundant_joint_indices;
149 for (
const std::string& redundant_joint_name : redundant_joint_names)
150 for (std::size_t j = 0; j < jnames.size(); ++j)
151 if (jnames[j] == redundant_joint_name)
153 redundant_joint_indices.push_back(j);
156 return redundant_joint_indices.size() == redundant_joint_names.size() ?
setRedundantJoints(redundant_joint_indices) :
162 return (!str.empty() && str[0] ==
'/') ?
removeSlash(str.substr(1)) : str;
172 *error_text_out =
"This plugin only supports joint groups which are chains";
181 : tip_frame_(
"DEPRECATED")
184 , search_discretization_(DEFAULT_SEARCH_DISCRETIZATION)
185 , default_timeout_(DEFAULT_TIMEOUT)
193 const std::vector<double>& ik_seed_state,
197 std::vector<double> solution;
207 if (ik_poses.size() != 1)
214 if (ik_poses.empty())
221 moveit_msgs::MoveItErrorCodes error_code;
222 if (
getPositionIK(ik_poses[0], ik_seed_state, solution, error_code, options))
225 solutions[0] = solution;
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...
Core components of MoveIt.
static const std::string LOGNAME
std::vector< DiscretizationMethod > supported_methods_
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)
static const MOVEIT_KINEMATICS_BASE_EXPORT double DEFAULT_SEARCH_DISCRETIZATION
static void noDeleter(const moveit::core::RobotModel *)
double solution_percentage
virtual void setValues(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
Set the parameters for the solver, for use with kinematic chain IK solvers.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
@ MULTIPLE_TIPS_NOT_SUPPORTED
#define ROS_ERROR_NAMED(name,...)
double search_discretization_
@ UNSUPORTED_DISCRETIZATION_REQUESTED
std::string robot_description_
virtual ~KinematicsBase()
Virtual destructor for the interface.
std::vector< unsigned int > redundant_joint_indices_
virtual bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_frame, const std::string &tip_frame, double search_discretization)
Initialization function for the kinematics, for use with kinematic chain IK solvers.
API for forward and inverse kinematics.
std::string removeSlash(const std::string &str) const
virtual const std::vector< std::string > & getJointNames() const =0
Return all the joint names in the order they are used internally.
moveit::core::RobotModelConstPtr robot_model_
virtual bool supportsGroup(const moveit::core::JointModelGroup *jmg, std::string *error_text_out=nullptr) const
Check if this solver supports a given JointModelGroup.
DiscretizationMethod discretization_method
void setSearchDiscretization(double sd)
Set the search discretization value for all the redundant joints.
std::vector< std::string > tip_frames_
A set of options for the kinematics solver.
bool isChain() const
Check if this group is a linear chain.
#define ROS_WARN_NAMED(name,...)
static const MOVEIT_KINEMATICS_BASE_EXPORT double DEFAULT_TIMEOUT
virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::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.
KinematicError kinematic_error
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Tue Dec 24 2024 03:27:14