Public Types | Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | Private Member Functions | List of all members
kinematics::KinematicsBase Class Referenceabstract

Provides an interface for kinematics solvers. More...

#include <kinematics_base.h>

Inheritance diagram for kinematics::KinematicsBase:
Inheritance graph
[legend]

Public Types

using IKCallbackFn = boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)>
 Signature for a callback to validate an IK solution. Typically used for collision checking. More...
 

Public Member Functions

virtual const std::string & getBaseFrame () const
 Return the name of the frame in which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used. More...
 
double getDefaultTimeout () const
 For functions that require a timeout specified but one is not specified using arguments, this default timeout is used. More...
 
virtual const std::string & getGroupName () const
 Return the name of the group that the solver is operating on. More...
 
virtual const std::vector< std::string > & getJointNames () const =0
 Return all the joint names in the order they are used internally. More...
 
virtual const std::vector< std::string > & getLinkNames () const =0
 Return all the link names in the order they are represented internally. More...
 
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. More...
 
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. More...
 
virtual bool getPositionIK (const std::vector< geometry_msgs::Pose > &ik_poses, const std::vector< double > &ik_seed_state, std::vector< std::vector< double > > &solutions, KinematicsResult &result, const kinematics::KinematicsQueryOptions &options) const
 Given the desired poses of all end-effectors, compute joint angles that are able to reach it. More...
 
virtual void getRedundantJoints (std::vector< unsigned int > &redundant_joint_indices) const
 Get the set of redundant joints. More...
 
double getSearchDiscretization (int joint_index=0) const
 Get the value of the search discretization. More...
 
std::vector< DiscretizationMethodgetSupportedDiscretizationMethods () const
 Returns the set of supported kinematics discretization search types. This implementation only supports the DiscretizationMethods::ONE search. More...
 
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 link name. No namespacing (e.g., no "/" prefix) should be used. More...
 
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. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used. More...
 
virtual bool initialize (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. More...
 
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. More...
 
virtual bool initialize (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)
 Initialization function for the kinematics, for use with non-chain IK solvers. More...
 
 KinematicsBase ()
 
virtual bool searchPositionIK (const geometry_msgs::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::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. This particular method is intended for "searching" for a solution by stepping through the redundancy (or other numerical routines). More...
 
virtual bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, 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. This particular method is intended for "searching" for a solution by stepping through the redundancy (or other numerical routines). More...
 
virtual bool searchPositionIK (const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, const IKCallbackFn &solution_callback, 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. This particular method is intended for "searching" for a solution by stepping through the redundancy (or other numerical routines). More...
 
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. This particular method is intended for "searching" for a solution by stepping through the redundancy (or other numerical routines). More...
 
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 angles required to reach them. This is useful for e.g. biped robots that need to perform whole-body IK. Not necessary for most robots that have kinematic chains. This particular method is intended for "searching" for a solution by stepping through the redundancy (or other numerical routines). More...
 
void setDefaultTimeout (double timeout)
 For functions that require a timeout specified but one is not specified using arguments, a default timeout is used, as set by this function (and initialized to KinematicsBase::DEFAULT_TIMEOUT) More...
 
bool setRedundantJoints (const std::vector< std::string > &redundant_joint_names)
 Set a set of redundant joints for the kinematics solver to use. This function is just a convenience function that calls the previous definition of setRedundantJoints() More...
 
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 solver and choice of redundant joints!. Also, it sets the discretization values for each redundant joint to a default value. More...
 
void setSearchDiscretization (const std::map< int, double > &discretization)
 Sets individual discretization values for each redundant joint. More...
 
void setSearchDiscretization (double sd)
 Set the search discretization value for all the redundant joints. More...
 
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. More...
 
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. More...
 
virtual bool supportsGroup (const moveit::core::JointModelGroup *jmg, std::string *error_text_out=nullptr) const
 Check if this solver supports a given JointModelGroup. More...
 
virtual ~KinematicsBase ()
 Virtual destructor for the interface. More...
 

Static Public Attributes

static const MOVEIT_KINEMATICS_BASE_EXPORT double DEFAULT_SEARCH_DISCRETIZATION = 0.1
 
static const MOVEIT_KINEMATICS_BASE_EXPORT double DEFAULT_TIMEOUT = 1.0
 

Protected Member Functions

template<typename T >
bool lookupParam (const std::string &param, T &val, const T &default_val) const
 Enables kinematics plugins access to parameters that are defined for the private namespace and inside 'robot_description_kinematics'. Parameters are searched in the following locations and order. More...
 
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)
 

Protected Attributes

std::string base_frame_
 
double default_timeout_
 
std::string group_name_
 
std::map< int, double > redundant_joint_discretization_
 
std::vector< unsigned int > redundant_joint_indices_
 
std::string robot_description_
 
moveit::core::RobotModelConstPtr robot_model_
 
double search_discretization_
 
std::vector< DiscretizationMethodsupported_methods_
 
std::string tip_frame_
 
std::vector< std::string > tip_frames_
 

Private Member Functions

std::string removeSlash (const std::string &str) const
 

Detailed Description

Provides an interface for kinematics solvers.

Definition at line 145 of file kinematics_base.h.

Member Typedef Documentation

◆ IKCallbackFn

using kinematics::KinematicsBase::IKCallbackFn = boost::function<void(const geometry_msgs::Pose&, const std::vector<double>&, moveit_msgs::MoveItErrorCodes&)>

Signature for a callback to validate an IK solution. Typically used for collision checking.

Definition at line 153 of file kinematics_base.h.

Constructor & Destructor Documentation

◆ ~KinematicsBase()

kinematics::KinematicsBase::~KinematicsBase ( )
virtualdefault

Virtual destructor for the interface.

◆ KinematicsBase()

kinematics::KinematicsBase::KinematicsBase ( )

Definition at line 180 of file kinematics_base.cpp.

Member Function Documentation

◆ getBaseFrame()

virtual const std::string& kinematics::KinematicsBase::getBaseFrame ( ) const
inlinevirtual

Return the name of the frame in which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used.

Returns
The string name of the frame in which the solver is operating

Definition at line 430 of file kinematics_base.h.

◆ getDefaultTimeout()

double kinematics::KinematicsBase::getDefaultTimeout ( ) const
inline

For functions that require a timeout specified but one is not specified using arguments, this default timeout is used.

Definition at line 574 of file kinematics_base.h.

◆ getGroupName()

virtual const std::string& kinematics::KinematicsBase::getGroupName ( ) const
inlinevirtual

Return the name of the group that the solver is operating on.

Returns
The string name of the group that the solver is operating on

Definition at line 420 of file kinematics_base.h.

◆ getJointNames()

virtual const std::vector<std::string>& kinematics::KinematicsBase::getJointNames ( ) const
pure virtual

Return all the joint names in the order they are used internally.

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

◆ getLinkNames()

virtual const std::vector<std::string>& kinematics::KinematicsBase::getLinkNames ( ) const
pure virtual

Return all the link names in the order they are represented internally.

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

◆ getPositionFK()

virtual bool kinematics::KinematicsBase::getPositionFK ( const std::vector< std::string > &  link_names,
const std::vector< double > &  joint_angles,
std::vector< geometry_msgs::Pose > &  poses 
) const
pure virtual

Given a set of joint angles and a set of links, compute their pose.

Parameters
link_namesA set of links for which FK needs to be computed
joint_anglesThe state for which FK is being computed
posesThe resultant set of poses (in the frame returned by getBaseFrame())
Returns
True if a valid solution was found, false otherwise

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

◆ getPositionIK() [1/2]

virtual bool kinematics::KinematicsBase::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
pure virtual

Given a desired pose of the end-effector, compute the joint angles to reach it.

In contrast to the searchPositionIK methods, this one is expected to return the solution closest to the seed state. Randomly re-seeding is explicitly not allowed.

Parameters
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
solutionthe solution vector
error_codean error code that encodes the reason for failure or success
optionscontainer for other IK options. See definition of KinematicsQueryOptions for details.
Returns
True if a valid solution was found, false otherwise

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

◆ getPositionIK() [2/2]

bool kinematics::KinematicsBase::getPositionIK ( const std::vector< geometry_msgs::Pose > &  ik_poses,
const std::vector< double > &  ik_seed_state,
std::vector< std::vector< double > > &  solutions,
KinematicsResult result,
const kinematics::KinematicsQueryOptions options 
) const
virtual

Given the desired poses of all end-effectors, compute joint angles that are able to reach it.

The default implementation returns only one solution and so its result is equivalent to calling 'getPositionIK(...)' with a zero initialized seed.

Some planners (e.g. IKFast) support getting multiple joint solutions for a single pose. This can be enabled using the |DiscretizationMethods| enum and choosing an option that is not |NO_DISCRETIZATION|.

Parameters
ik_posesThe desired pose of each tip link
ik_seed_statean initial guess solution for the inverse kinematics
solutionsA vector of valid joint vectors. This return has two variant behaviors: 1) Return a joint solution for every input |ik_poses|, e.g. multi-arm support 2) Return multiple joint solutions for a single |ik_poses| input, e.g. underconstrained IK TODO(dave): This dual behavior is confusing and should be changed in a future refactor of this API
resultA struct that reports the results of the query
optionsAn option struct which contains the type of redundancy discretization used. This default implementation only supports the KinematicSearches::NO_DISCRETIZATION method; requesting any other will result in failure.
Returns
True if a valid set of solutions was found, false otherwise.

Definition at line 192 of file kinematics_base.cpp.

◆ getRedundantJoints()

virtual void kinematics::KinematicsBase::getRedundantJoints ( std::vector< unsigned int > &  redundant_joint_indices) const
inlinevirtual

Get the set of redundant joints.

Definition at line 480 of file kinematics_base.h.

◆ getSearchDiscretization()

double kinematics::KinematicsBase::getSearchDiscretization ( int  joint_index = 0) const
inline

Get the value of the search discretization.

Definition at line 544 of file kinematics_base.h.

◆ getSupportedDiscretizationMethods()

std::vector<DiscretizationMethod> kinematics::KinematicsBase::getSupportedDiscretizationMethods ( ) const
inline

Returns the set of supported kinematics discretization search types. This implementation only supports the DiscretizationMethods::ONE search.

Definition at line 560 of file kinematics_base.h.

◆ getTipFrame()

virtual const std::string& kinematics::KinematicsBase::getTipFrame ( ) const
inlinevirtual

Return the name of the tip frame of the chain on which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used.

Returns
The string name of the tip frame of the chain on which the solver is operating

Definition at line 440 of file kinematics_base.h.

◆ getTipFrames()

virtual const std::vector<std::string>& kinematics::KinematicsBase::getTipFrames ( ) const
inlinevirtual

Return the names of the tip frames of the kinematic tree on which the solver is operating. This is usually a link name. No namespacing (e.g., no "/" prefix) should be used.

Returns
The vector of names of the tip frames of the kinematic tree on which the solver is operating

Definition at line 454 of file kinematics_base.h.

◆ initialize() [1/3]

bool kinematics::KinematicsBase::initialize ( 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

Initialization function for the kinematics, for use with kinematic chain IK solvers.

Parameters
robot_model- allow the URDF to be loaded much quicker by passing in a pre-parsed model of the robot
group_nameThe group for which this solver is being configured
base_frameThe base frame in which all input poses are expected. This may (or may not) be the root frame of the chain that the solver operates on
tip_framesThe tip of the chain
search_discretizationThe discretization of the search when the solver steps through the redundancy
Returns
true if initialization was successful, false otherwise

When returning false, the KinematicsPlugingLoader will use the old method, passing a robot_description. Default implementation returns false and issues a warning to implement this new API. TODO: Make this method purely virtual after some soaking time, replacing the fallback.

Reimplemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

Definition at line 119 of file kinematics_base.cpp.

◆ initialize() [2/3]

bool kinematics::KinematicsBase::initialize ( const std::string &  robot_description,
const std::string &  group_name,
const std::string &  base_frame,
const std::string &  tip_frame,
double  search_discretization 
)
virtual

Initialization function for the kinematics, for use with kinematic chain IK solvers.

Parameters
robot_descriptionThis parameter can be used as an identifier for the robot kinematics it is computed for; For example, the name of the ROS parameter that contains the robot description;
group_nameThe group for which this solver is being configured
base_frameThe base frame in which all input poses are expected. This may (or may not) be the root frame of the chain that the solver operates on
tip_frameThe tip of the chain
search_discretizationThe discretization of the search when the solver steps through the redundancy
Returns
True if initialization was successful, false otherwise

Instead of this method, use the method passing in a RobotModel! Default implementation returns false, indicating that this API is not supported.

Definition at line 98 of file kinematics_base.cpp.

◆ initialize() [3/3]

bool kinematics::KinematicsBase::initialize ( 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 
)
virtual

Initialization function for the kinematics, for use with non-chain IK solvers.

Parameters
robot_descriptionThis parameter can be used as an identifier for the robot kinematics is computed for; For example, rhe name of the ROS parameter that contains the robot description;
group_nameThe group for which this solver is being configured
base_frameThe base frame in which all input poses are expected. This may (or may not) be the root frame of the chain that the solver operates on
tip_framesA vector of tips of the kinematic tree
search_discretizationThe discretization of the search when the solver steps through the redundancy
Returns
True if initialization was successful, false otherwise

Instead of this method, use the method passing in a RobotModel! Default implementation calls initialize() for tip_frames[0] and reports an error if tip_frames.size() != 1.

Definition at line 105 of file kinematics_base.cpp.

◆ lookupParam()

template<typename T >
bool kinematics::KinematicsBase::lookupParam ( const std::string &  param,
T &  val,
const T &  default_val 
) const
inlineprotected

Enables kinematics plugins access to parameters that are defined for the private namespace and inside 'robot_description_kinematics'. Parameters are searched in the following locations and order.

  • ~/<group_name>/<param>
  • ~/<param>
  • robot_description_kinematics/<group_name>/<param>
  • robot_description_kinematics/<param>

This order maintains default behavior by keeping the private namespace as the predominant configuration but also allows groupwise specifications.

Definition at line 618 of file kinematics_base.h.

◆ removeSlash()

std::string kinematics::KinematicsBase::removeSlash ( const std::string &  str) const
private

Definition at line 160 of file kinematics_base.cpp.

◆ searchPositionIK() [1/5]

virtual bool kinematics::KinematicsBase::searchPositionIK ( const geometry_msgs::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::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const
pure virtual

Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solution by stepping through the redundancy (or other numerical routines).

Parameters
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
timeoutThe amount of time (in seconds) available to the solver
consistency_limitsthe distance that any joint in the solution can be from the corresponding joints in the current seed state
solutionthe solution vector
solution_callbackA callback to validate an IK solution
error_codean error code that encodes the reason for failure or success
optionscontainer for other IK options. See definition of KinematicsQueryOptions for details.
Returns
True if a valid solution was found, false otherwise

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

◆ searchPositionIK() [2/5]

virtual bool kinematics::KinematicsBase::searchPositionIK ( const geometry_msgs::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
const std::vector< double > &  consistency_limits,
std::vector< double > &  solution,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const
pure virtual

Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solution by stepping through the redundancy (or other numerical routines).

Parameters
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
timeoutThe amount of time (in seconds) available to the solver
consistency_limitsthe distance that any joint in the solution can be from the corresponding joints in the current seed state
solutionthe solution vector
error_codean error code that encodes the reason for failure or success
optionscontainer for other IK options. See definition of KinematicsQueryOptions for details.
Returns
True if a valid solution was found, false otherwise

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

◆ searchPositionIK() [3/5]

virtual bool kinematics::KinematicsBase::searchPositionIK ( const geometry_msgs::Pose &  ik_pose,
const std::vector< double > &  ik_seed_state,
double  timeout,
std::vector< double > &  solution,
const IKCallbackFn solution_callback,
moveit_msgs::MoveItErrorCodes &  error_code,
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions() 
) const
pure virtual

Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solution by stepping through the redundancy (or other numerical routines).

Parameters
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
timeoutThe amount of time (in seconds) available to the solver
solutionthe solution vector
solution_callbackA callback to validate an IK solution
error_codean error code that encodes the reason for failure or success
optionscontainer for other IK options. See definition of KinematicsQueryOptions for details.
Returns
True if a valid solution was found, false otherwise

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

◆ searchPositionIK() [4/5]

virtual bool kinematics::KinematicsBase::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
pure virtual

Given a desired pose of the end-effector, search for the joint angles required to reach it. This particular method is intended for "searching" for a solution by stepping through the redundancy (or other numerical routines).

Parameters
ik_posethe desired pose of the link
ik_seed_statean initial guess solution for the inverse kinematics
timeoutThe amount of time (in seconds) available to the solver
solutionthe solution vector
error_codean error code that encodes the reason for failure or success
optionscontainer for other IK options. See definition of KinematicsQueryOptions for details.
Returns
True if a valid solution was found, false otherwise

Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin.

◆ searchPositionIK() [5/5]

virtual bool kinematics::KinematicsBase::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
inlinevirtual

Given a set of desired poses for a planning group with multiple end-effectors, search for the joint angles required to reach them. This is useful for e.g. biped robots that need to perform whole-body IK. Not necessary for most robots that have kinematic chains. This particular method is intended for "searching" for a solution by stepping through the redundancy (or other numerical routines).

Parameters
ik_posesthe desired pose of each tip link, in the same order as the getTipFrames() vector
ik_seed_statean initial guess solution for the inverse kinematics
timeoutThe amount of time (in seconds) available to the solver
consistency_limitsthe distance that any joint in the solution can be from the corresponding joints in the current seed state
solutionthe solution vector
solution_callbackA callback to validate an IK solution
error_codean error code that encodes the reason for failure or success
optionscontainer for other IK options. See definition of KinematicsQueryOptions for details.
context_state(optional) the context in which this request is being made. The position values corresponding to joints in the current group may not match those in ik_seed_state. The values in ik_seed_state are the ones to use. The state is passed to provide the other joint values, in case they are needed for context, like with an IK solver that computes a balanced result for a biped.
Returns
True if a valid solution was found, false otherwise

Definition at line 296 of file kinematics_base.h.

◆ setDefaultTimeout()

void kinematics::KinematicsBase::setDefaultTimeout ( double  timeout)
inline

For functions that require a timeout specified but one is not specified using arguments, a default timeout is used, as set by this function (and initialized to KinematicsBase::DEFAULT_TIMEOUT)

Definition at line 567 of file kinematics_base.h.

◆ setRedundantJoints() [1/2]

bool kinematics::KinematicsBase::setRedundantJoints ( const std::vector< std::string > &  redundant_joint_names)

Set a set of redundant joints for the kinematics solver to use. This function is just a convenience function that calls the previous definition of setRedundantJoints()

Parameters
redundant_joint_namesThe set of redundant joint names.
Returns
False if any of the input joint indices are invalid (exceed number of joints)

Definition at line 145 of file kinematics_base.cpp.

◆ setRedundantJoints() [2/2]

bool kinematics::KinematicsBase::setRedundantJoints ( const std::vector< unsigned int > &  redundant_joint_indices)
virtual

Set a set of redundant joints for the kinematics solver to use. This can fail, depending on the IK solver and choice of redundant joints!. Also, it sets the discretization values for each redundant joint to a default value.

Parameters
redundant_joint_indicesThe set of redundant joint indices (corresponding to the list of joints you get from getJointNames()).
Returns
False if any of the input joint indices are invalid (exceed number of joints)

Definition at line 130 of file kinematics_base.cpp.

◆ setSearchDiscretization() [1/2]

void kinematics::KinematicsBase::setSearchDiscretization ( const std::map< int, double > &  discretization)
inline

Sets individual discretization values for each redundant joint.

Calling this method replaces previous discretization settings.

Parameters
discretizationa map of joint indices and discretization value pairs.

Definition at line 530 of file kinematics_base.h.

◆ setSearchDiscretization() [2/2]

void kinematics::KinematicsBase::setSearchDiscretization ( double  sd)
inline

Set the search discretization value for all the redundant joints.

Definition at line 516 of file kinematics_base.h.

◆ setValues() [1/2]

void kinematics::KinematicsBase::setValues ( const std::string &  robot_description,
const std::string &  group_name,
const std::string &  base_frame,
const std::string &  tip_frame,
double  search_discretization 
)
virtual

Set the parameters for the solver, for use with kinematic chain IK solvers.

Parameters
robot_descriptionThis parameter can be used as an identifier for the robot kinematics it is computed for; For example, the name of the ROS parameter that contains the robot description;
group_nameThe group for which this solver is being configured
base_frameThe base frame in which all input poses are expected. This may (or may not) be the root frame of the chain that the solver operates on
tip_frameThe tip of the chain
search_discretizationThe discretization of the search when the solver steps through the redundancy

Definition at line 91 of file kinematics_base.cpp.

◆ setValues() [2/2]

void kinematics::KinematicsBase::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 
)
virtual

Set the parameters for the solver, for use with non-chain IK solvers.

Parameters
robot_descriptionThis parameter can be used as an identifier for the robot kinematics it is computed for; For example, the name of the ROS parameter that contains the robot description;
group_nameThe group for which this solver is being configured
base_frameThe base frame in which all input poses are expected. This may (or may not) be the root frame of the chain that the solver operates on
tip_framesA vector of tips of the kinematic tree
search_discretizationThe discretization of the search when the solver steps through the redundancy

Definition at line 70 of file kinematics_base.cpp.

◆ storeValues()

void kinematics::KinematicsBase::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 
)
protected

Store some core variables passed via initialize().

Parameters
robot_modelRobotModel, this kinematics solver should act on.
group_nameThe group for which this solver is being configured.
base_frameThe base frame in which all input poses are expected.
tip_framesThe tips of the kinematics tree.
search_discretizationThe discretization of the search when the solver steps through the redundancy

Definition at line 51 of file kinematics_base.cpp.

◆ supportsGroup()

bool kinematics::KinematicsBase::supportsGroup ( const moveit::core::JointModelGroup jmg,
std::string *  error_text_out = nullptr 
) const
virtual

Check if this solver supports a given JointModelGroup.

Override this function to check if your kinematics solver implementation supports the given group.

The default implementation just returns jmg->isChain(), since solvers written before this function was added all supported only chain groups.

Parameters
jmgthe planning group being proposed to be solved by this IK solver
error_text_outIf this pointer is non-null and the group is not supported, this is filled with a description of why it's not supported.
Returns
True if the group is supported, false if not.

Definition at line 165 of file kinematics_base.cpp.

Member Data Documentation

◆ base_frame_

std::string kinematics::KinematicsBase::base_frame_
protected

Definition at line 590 of file kinematics_base.h.

◆ DEFAULT_SEARCH_DISCRETIZATION

const double kinematics::KinematicsBase::DEFAULT_SEARCH_DISCRETIZATION = 0.1
static

Definition at line 148 of file kinematics_base.h.

◆ DEFAULT_TIMEOUT

const double kinematics::KinematicsBase::DEFAULT_TIMEOUT = 1.0
static

Definition at line 149 of file kinematics_base.h.

◆ default_timeout_

double kinematics::KinematicsBase::default_timeout_
protected

Definition at line 599 of file kinematics_base.h.

◆ group_name_

std::string kinematics::KinematicsBase::group_name_
protected

Definition at line 589 of file kinematics_base.h.

◆ redundant_joint_discretization_

std::map<int, double> kinematics::KinematicsBase::redundant_joint_discretization_
protected

Definition at line 601 of file kinematics_base.h.

◆ redundant_joint_indices_

std::vector<unsigned int> kinematics::KinematicsBase::redundant_joint_indices_
protected

Definition at line 600 of file kinematics_base.h.

◆ robot_description_

std::string kinematics::KinematicsBase::robot_description_
protected

Definition at line 588 of file kinematics_base.h.

◆ robot_model_

moveit::core::RobotModelConstPtr kinematics::KinematicsBase::robot_model_
protected

Definition at line 587 of file kinematics_base.h.

◆ search_discretization_

double kinematics::KinematicsBase::search_discretization_
protected

Definition at line 597 of file kinematics_base.h.

◆ supported_methods_

std::vector<DiscretizationMethod> kinematics::KinematicsBase::supported_methods_
protected

Definition at line 602 of file kinematics_base.h.

◆ tip_frame_

std::string kinematics::KinematicsBase::tip_frame_
protected

Definition at line 596 of file kinematics_base.h.

◆ tip_frames_

std::vector<std::string> kinematics::KinematicsBase::tip_frames_
protected

Definition at line 591 of file kinematics_base.h.


The documentation for this class was generated from the following files:


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Mar 3 2024 03:23:36