moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Provides an interface for kinematics solvers. More...
#include <kinematics_base.h>
Public Types | |
using | IKCallbackFn = std::function< void(const geometry_msgs::msg::Pose &, const std::vector< double > &, moveit_msgs::msg::MoveItErrorCodes &)> |
Signature for a callback to validate an IK solution. Typically used for collision checking. | |
using | IKCostFn = std::function< double(const geometry_msgs::msg::Pose &, const moveit::core::RobotState &, const moveit::core::JointModelGroup *, const std::vector< double > &)> |
Signature for a cost function used to evaluate IK solutions. | |
Public Member Functions | |
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 bool | getPositionIK (const std::vector< geometry_msgs::msg::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. | |
virtual bool | searchPositionIK (const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, 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, 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). | |
virtual bool | searchPositionIK (const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, const std::vector< double > &consistency_limits, 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, 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). | |
virtual bool | searchPositionIK (const geometry_msgs::msg::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, const IKCallbackFn &solution_callback, moveit_msgs::msg::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). | |
virtual bool | searchPositionIK (const geometry_msgs::msg::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::msg::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). | |
virtual bool | searchPositionIK (const std::vector< geometry_msgs::msg::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::msg::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). | |
virtual bool | searchPositionIK (const std::vector< geometry_msgs::msg::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, const IKCostFn &cost_function, moveit_msgs::msg::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). | |
virtual bool | getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::msg::Pose > &poses) const =0 |
Given a set of joint angles and a set of links, compute their pose. | |
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. | |
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 const std::string & | getGroupName () const |
Return the name of the group that the solver is operating on. | |
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. | |
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. | |
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. | |
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. | |
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() | |
virtual void | getRedundantJoints (std::vector< unsigned int > &redundant_joint_indices) const |
Get the set of redundant joints. | |
virtual const std::vector< std::string > & | getJointNames () const =0 |
Return all the joint names in the order they are used internally. | |
virtual const std::vector< std::string > & | getLinkNames () const =0 |
Return all the link names in the order they are represented internally. | |
virtual bool | supportsGroup (const moveit::core::JointModelGroup *jmg, std::string *error_text_out=nullptr) const |
Check if this solver supports a given JointModelGroup. | |
void | setSearchDiscretization (double sd) |
Set the search discretization value for all the redundant joints. | |
void | setSearchDiscretization (const std::map< int, double > &discretization) |
Sets individual discretization values for each redundant joint. | |
double | getSearchDiscretization (int joint_index=0) const |
Get the value of the search discretization. | |
std::vector< DiscretizationMethod > | getSupportedDiscretizationMethods () const |
Returns the set of supported kinematics discretization search types. This implementation only supports the DiscretizationMethods::ONE search. | |
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) | |
double | getDefaultTimeout () const |
For functions that require a timeout specified but one is not specified using arguments, this default timeout is used. | |
virtual | ~KinematicsBase () |
Virtual destructor for the interface. | |
KinematicsBase () | |
Static Public Attributes | |
static const double | DEFAULT_SEARCH_DISCRETIZATION = 0.1 |
static const double | DEFAULT_TIMEOUT = 1.0 |
Protected Member Functions | |
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 | |
rclcpp::Node::SharedPtr | node_ |
moveit::core::RobotModelConstPtr | robot_model_ |
std::string | robot_description_ |
std::string | group_name_ |
std::string | base_frame_ |
std::vector< std::string > | tip_frames_ |
double | default_timeout_ |
std::vector< unsigned int > | redundant_joint_indices_ |
std::map< int, double > | redundant_joint_discretization_ |
std::vector< DiscretizationMethod > | supported_methods_ |
Provides an interface for kinematics solvers.
Definition at line 147 of file kinematics_base.h.
using kinematics::KinematicsBase::IKCallbackFn = std::function<void(const geometry_msgs::msg::Pose&, const std::vector<double>&, moveit_msgs::msg::MoveItErrorCodes&)> |
Signature for a callback to validate an IK solution. Typically used for collision checking.
Definition at line 154 of file kinematics_base.h.
using kinematics::KinematicsBase::IKCostFn = std::function<double(const geometry_msgs::msg::Pose&, const moveit::core::RobotState&, const moveit::core::JointModelGroup*, const std::vector<double>&)> |
Signature for a cost function used to evaluate IK solutions.
Definition at line 158 of file kinematics_base.h.
|
virtualdefault |
Virtual destructor for the interface.
kinematics::KinematicsBase::KinematicsBase | ( | ) |
Definition at line 157 of file kinematics_base.cpp.
|
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.
Definition at line 426 of file kinematics_base.h.
|
inline |
For functions that require a timeout specified but one is not specified using arguments, this default timeout is used.
Definition at line 573 of file kinematics_base.h.
|
inlinevirtual |
Return the name of the group that the solver is operating on.
Definition at line 416 of file kinematics_base.h.
|
pure virtual |
Return all the joint names in the order they are used internally.
Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin, kdl_kinematics_plugin::KDLKinematicsPlugin, and srv_kinematics_plugin::SrvKinematicsPlugin.
|
pure virtual |
Return all the link names in the order they are represented internally.
Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin, kdl_kinematics_plugin::KDLKinematicsPlugin, and srv_kinematics_plugin::SrvKinematicsPlugin.
|
pure virtual |
Given a set of joint angles and a set of links, compute their pose.
link_names | A set of links for which FK needs to be computed |
joint_angles | The state for which FK is being computed |
poses | The resultant set of poses (in the frame returned by getBaseFrame()) |
Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin, _NAMESPACE_::IKFastKinematicsPlugin, kdl_kinematics_plugin::KDLKinematicsPlugin, srv_kinematics_plugin::SrvKinematicsPlugin, and prbt_manipulator::IKFastKinematicsPlugin.
|
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.
ik_pose | the desired pose of the link |
ik_seed_state | an initial guess solution for the inverse kinematics |
solution | the solution vector |
error_code | an error code that encodes the reason for failure or success |
options | container for other IK options. See definition of KinematicsQueryOptions for details. |
Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin, _NAMESPACE_::IKFastKinematicsPlugin, kdl_kinematics_plugin::KDLKinematicsPlugin, srv_kinematics_plugin::SrvKinematicsPlugin, and prbt_manipulator::IKFastKinematicsPlugin.
|
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|.
ik_poses | The desired pose of each tip link |
ik_seed_state | an initial guess solution for the inverse kinematics |
solutions | A 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 |
result | A struct that reports the results of the query |
options | An 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. |
Reimplemented in _NAMESPACE_::IKFastKinematicsPlugin, and prbt_manipulator::IKFastKinematicsPlugin.
Definition at line 164 of file kinematics_base.cpp.
|
inlinevirtual |
Get the set of redundant joints.
Definition at line 479 of file kinematics_base.h.
|
inline |
Get the value of the search discretization.
Definition at line 543 of file kinematics_base.h.
|
inline |
Returns the set of supported kinematics discretization search types. This implementation only supports the DiscretizationMethods::ONE search.
Definition at line 559 of file kinematics_base.h.
|
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.
Definition at line 436 of file kinematics_base.h.
|
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.
Definition at line 453 of file kinematics_base.h.
|
virtual |
Initialization function for the kinematics, for use with kinematic chain IK solvers.
robot_model | - allow the URDF to be loaded much quicker by passing in a pre-parsed model of the robot |
group_name | The group for which this solver is being configured |
base_frame | The 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_frames | The tip of the chain |
search_discretization | The discretization of the search when the solver steps through the redundancy |
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, kdl_kinematics_plugin::KDLKinematicsPlugin, and srv_kinematics_plugin::SrvKinematicsPlugin.
Definition at line 91 of file kinematics_base.cpp.
|
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).
ik_pose | the desired pose of the link |
ik_seed_state | an initial guess solution for the inverse kinematics |
timeout | The amount of time (in seconds) available to the solver |
consistency_limits | the distance that any joint in the solution can be from the corresponding joints in the current seed state |
solution | the solution vector |
solution_callback | A callback to validate an IK solution |
error_code | an error code that encodes the reason for failure or success |
options | container for other IK options. See definition of KinematicsQueryOptions for details. |
Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin, _NAMESPACE_::IKFastKinematicsPlugin, kdl_kinematics_plugin::KDLKinematicsPlugin, srv_kinematics_plugin::SrvKinematicsPlugin, and prbt_manipulator::IKFastKinematicsPlugin.
|
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).
ik_pose | the desired pose of the link |
ik_seed_state | an initial guess solution for the inverse kinematics |
timeout | The amount of time (in seconds) available to the solver |
consistency_limits | the distance that any joint in the solution can be from the corresponding joints in the current seed state |
solution | the solution vector |
error_code | an error code that encodes the reason for failure or success |
options | container for other IK options. See definition of KinematicsQueryOptions for details. |
Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin, _NAMESPACE_::IKFastKinematicsPlugin, kdl_kinematics_plugin::KDLKinematicsPlugin, srv_kinematics_plugin::SrvKinematicsPlugin, and prbt_manipulator::IKFastKinematicsPlugin.
|
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).
ik_pose | the desired pose of the link |
ik_seed_state | an initial guess solution for the inverse kinematics |
timeout | The amount of time (in seconds) available to the solver |
solution | the solution vector |
solution_callback | A callback to validate an IK solution |
error_code | an error code that encodes the reason for failure or success |
options | container for other IK options. See definition of KinematicsQueryOptions for details. |
Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin, _NAMESPACE_::IKFastKinematicsPlugin, kdl_kinematics_plugin::KDLKinematicsPlugin, srv_kinematics_plugin::SrvKinematicsPlugin, and prbt_manipulator::IKFastKinematicsPlugin.
|
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).
ik_pose | the desired pose of the link |
ik_seed_state | an initial guess solution for the inverse kinematics |
timeout | The amount of time (in seconds) available to the solver |
solution | the solution vector |
error_code | an error code that encodes the reason for failure or success |
options | container for other IK options. See definition of KinematicsQueryOptions for details. |
Implemented in pr2_arm_kinematics::PR2ArmKinematicsPlugin, _NAMESPACE_::IKFastKinematicsPlugin, kdl_kinematics_plugin::KDLKinematicsPlugin, srv_kinematics_plugin::SrvKinematicsPlugin, and prbt_manipulator::IKFastKinematicsPlugin.
|
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).
ik_poses | the desired pose of each tip link, in the same order as the getTipFrames() vector |
ik_seed_state | an initial guess solution for the inverse kinematics |
timeout | The amount of time (in seconds) available to the solver |
consistency_limits | the distance that any joint in the solution can be from the corresponding joints in the current seed state |
solution | the solution vector |
solution_callback | A callback to validate an IK solution |
cost_function | A function to evaluate the cost of a particular IK solution |
error_code | an error code that encodes the reason for failure or success |
options | container 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. |
Definition at line 353 of file kinematics_base.h.
|
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).
ik_poses | the desired pose of each tip link, in the same order as the getTipFrames() vector |
ik_seed_state | an initial guess solution for the inverse kinematics |
timeout | The amount of time (in seconds) available to the solver |
consistency_limits | the distance that any joint in the solution can be from the corresponding joints in the current seed state |
solution | the solution vector |
solution_callback | A callback to validate an IK solution |
error_code | an error code that encodes the reason for failure or success |
options | container 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. |
Reimplemented in srv_kinematics_plugin::SrvKinematicsPlugin.
Definition at line 302 of file kinematics_base.h.
|
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 566 of file kinematics_base.h.
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()
redundant_joint_names | The set of redundant joint names. |
Definition at line 118 of file kinematics_base.cpp.
|
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.
redundant_joint_indices | The set of redundant joint indices (corresponding to the list of joints you get from getJointNames()). |
Reimplemented in _NAMESPACE_::IKFastKinematicsPlugin, srv_kinematics_plugin::SrvKinematicsPlugin, and prbt_manipulator::IKFastKinematicsPlugin.
Definition at line 103 of file kinematics_base.cpp.
|
inline |
Sets individual discretization values for each redundant joint.
Calling this method replaces previous discretization settings.
discretization | a map of joint indices and discretization value pairs. |
Definition at line 529 of file kinematics_base.h.
|
inline |
Set the search discretization value for all the redundant joints.
Definition at line 515 of file kinematics_base.h.
|
virtual |
Set the parameters for the solver, for use with non-chain IK solvers.
robot_description | This 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_name | The group for which this solver is being configured |
base_frame | The 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_frames | A vector of tips of the kinematic tree |
search_discretization | The discretization of the search when the solver steps through the redundancy |
Definition at line 77 of file kinematics_base.cpp.
|
protected |
Store some core variables passed via initialize().
robot_model | RobotModel, this kinematics solver should act on. |
group_name | The group for which this solver is being configured. |
base_frame | The base frame in which all input poses are expected. |
tip_frames | The tips of the kinematics tree. |
search_discretization | The discretization of the search when the solver steps through the redundancy |
Definition at line 59 of file kinematics_base.cpp.
|
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.
jmg | the planning group being proposed to be solved by this IK solver |
error_text_out | If this pointer is non-null and the group is not supported, this is filled with a description of why it's not supported. |
Definition at line 142 of file kinematics_base.cpp.
|
protected |
Definition at line 590 of file kinematics_base.h.
|
static |
Definition at line 150 of file kinematics_base.h.
|
static |
Definition at line 151 of file kinematics_base.h.
|
protected |
Definition at line 593 of file kinematics_base.h.
|
protected |
Definition at line 589 of file kinematics_base.h.
|
protected |
Definition at line 586 of file kinematics_base.h.
|
protected |
Definition at line 595 of file kinematics_base.h.
|
protected |
Definition at line 594 of file kinematics_base.h.
|
protected |
Definition at line 588 of file kinematics_base.h.
|
protected |
Definition at line 587 of file kinematics_base.h.
|
protected |
Definition at line 596 of file kinematics_base.h.
|
protected |
Definition at line 591 of file kinematics_base.h.