Go to the documentation of this file.
39 #include <geometry_msgs/Pose.h>
40 #include <moveit_msgs/MoveItErrorCodes.h>
44 #include <boost/function.hpp>
47 #include <moveit/moveit_kinematics_base_export.h>
67 namespace DiscretizationMethods
87 namespace KinematicErrors
153 boost::function<void(
const geometry_msgs::Pose&,
const std::vector<double>&, moveit_msgs::MoveItErrorCodes&)>;
168 getPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
169 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
193 virtual bool getPositionIK(
const std::vector<geometry_msgs::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
210 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
211 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
229 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
230 const std::vector<double>& consistency_limits, std::vector<double>& solution,
231 moveit_msgs::MoveItErrorCodes& error_code,
248 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
249 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
250 moveit_msgs::MoveItErrorCodes& error_code,
269 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
270 const std::vector<double>& consistency_limits, std::vector<double>& solution,
271 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
296 searchPositionIK(
const std::vector<geometry_msgs::Pose>& ik_poses,
const std::vector<double>& ik_seed_state,
297 double timeout,
const std::vector<double>& consistency_limits, std::vector<double>& solution,
298 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
304 if (ik_poses.size() == 1)
307 if (solution_callback)
309 return searchPositionIK(ik_poses[0], ik_seed_state, timeout, consistency_limits, solution, solution_callback,
310 error_code, options);
314 return searchPositionIK(ik_poses[0], ik_seed_state, timeout, consistency_limits, solution, error_code, options);
319 ROS_ERROR_NAMED(
"kinematics_base",
"This kinematic solver does not support searchPositionIK with multiple poses");
330 virtual bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
331 std::vector<geometry_msgs::Pose>& poses)
const = 0;
344 [[deprecated]]
virtual void setValues(
const std::string& robot_description,
const std::string& group_name,
345 const std::string& base_frame,
const std::string& tip_frame,
346 double search_discretization);
358 virtual void setValues(
const std::string& robot_description,
const std::string& group_name,
359 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
360 double search_discretization);
376 [[deprecated]]
virtual bool initialize(
const std::string& robot_description,
const std::string& group_name,
377 const std::string& base_frame,
const std::string& tip_frame,
378 double search_discretization);
394 virtual bool initialize(
const std::string& robot_description,
const std::string& group_name,
395 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
396 double search_discretization);
413 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
414 double search_discretization);
443 ROS_ERROR_NAMED(
"kinematics_base",
"This kinematic solver has more than one tip frame, "
444 "do not call getTipFrame()");
467 virtual bool setRedundantJoints(
const std::vector<unsigned int>& redundant_joint_indices);
488 virtual const std::vector<std::string>&
getJointNames()
const = 0;
493 virtual const std::vector<std::string>&
getLinkNames()
const = 0;
534 for (
const auto& pair : discretization)
617 template <
typename T>
618 inline bool lookupParam(
const std::string& param, T& val,
const T& default_val)
const
642 val = nh.
param(
"robot_description_kinematics/" +
param, default_val);
660 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
661 double search_discretization);
664 std::string
removeSlash(
const std::string& str)
const;
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.
bool return_approximate_solution
std::vector< DiscretizationMethod > supported_methods_
bool lookupParam(const std::string ¶m, T &val, const T &default_val) const
Enables kinematics plugins access to parameters that are defined for the private namespace and inside...
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)
double getDefaultTimeout() const
For functions that require a timeout specified but one is not specified using arguments,...
static const MOVEIT_KINEMATICS_BASE_EXPORT double DEFAULT_SEARCH_DISCRETIZATION
void setSearchDiscretization(const std::map< int, double > &discretization)
Sets individual discretization values for each redundant joint.
virtual bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const =0
Given a set of joint angles and a set of links, compute their pose.
std::vector< DiscretizationMethod > getSupportedDiscretizationMethods() const
Returns the set of supported kinematics discretization search types. This implementation only support...
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
virtual const std::string & getGroupName() const
Return the name of the group that the solver is operating on.
std::map< int, double > redundant_joint_discretization_
#define ROS_ERROR_NAMED(name,...)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
double search_discretization_
boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
@ UNSUPORTED_DISCRETIZATION_REQUESTED
virtual const std::vector< std::string > & getLinkNames() const =0
Return all the link names in the order they are represented internally.
virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, 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, search for the joint angles required to reach it....
@ DISCRETIZATION_NOT_INITIALIZED
std::string robot_description_
virtual ~KinematicsBase()
Virtual destructor for the interface.
std::vector< unsigned int > redundant_joint_indices_
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....
Provides an interface for kinematics solvers.
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.
MOVEIT_CLASS_FORWARD(KinematicsBase)
API for forward and inverse kinematics.
bool hasParam(const std::string &key) const
std::string removeSlash(const std::string &str) const
void setDefaultTimeout(double timeout)
For functions that require a timeout specified but one is not specified using arguments,...
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.
bool lock_redundant_joints
double getSearchDiscretization(int joint_index=0) const
Get the value of the search discretization.
std::vector< std::string > tip_frames_
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...
Main namespace for MoveIt.
A set of options for the kinematics solver.
MOVEIT_CLASS_FORWARD(JointModelGroup)
T param(const std::string ¶m_name, const T &default_val) const
T param(const std::string ¶m_name, const T &default_val)
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.
virtual const std::string & getBaseFrame() const
Return the name of the frame in which the solver is operating. This is usually a link name....
KinematicError kinematic_error
virtual void getRedundantJoints(std::vector< unsigned int > &redundant_joint_indices) const
Get the set of redundant joints.
virtual bool searchPositionIK(const std::vector< geometry_msgs::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::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...
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Tue Dec 24 2024 03:27:14