moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers. This version can be used with any robot. Supports non-chain kinematic groups. More...
#include <srv_kinematics_plugin.h>
Public Member Functions | |
SrvKinematicsPlugin () | |
Default constructor. | |
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 override |
Given a desired pose of the end-effector, compute the joint angles to reach it. | |
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 override |
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). | |
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 override |
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). | |
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 override |
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). | |
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 override |
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). | |
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 override |
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). | |
bool | getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::msg::Pose > &poses) const override |
Given a set of joint angles and a set of links, compute their pose. | |
bool | initialize (const rclcpp::Node::SharedPtr &node, const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_name, const std::vector< std::string > &tip_frames, double search_discretization) override |
Initialization function for the kinematics, for use with kinematic chain IK solvers. | |
const std::vector< std::string > & | getJointNames () const override |
Return all the joint names in the order they are used internally. | |
const std::vector< std::string > & | getLinkNames () const override |
Return all the link names in the order they are represented internally. | |
const std::vector< std::string > & | getVariableNames () const |
Return all the variable names in the order they are represented internally. | |
Public Member Functions inherited from kinematics::KinematicsBase | |
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 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 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 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. | |
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 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 () | |
Protected Member Functions | |
bool | setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices) override |
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. | |
Protected Member Functions inherited from kinematics::KinematicsBase | |
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) |
Additional Inherited Members | |
Public Types inherited from kinematics::KinematicsBase | |
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. | |
Static Public Attributes inherited from kinematics::KinematicsBase | |
static const double | DEFAULT_SEARCH_DISCRETIZATION = 0.1 |
static const double | DEFAULT_TIMEOUT = 1.0 |
Protected Attributes inherited from kinematics::KinematicsBase | |
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_ |
Specific implementation of kinematics using ROS service calls to communicate with external IK solvers. This version can be used with any robot. Supports non-chain kinematic groups.
Definition at line 66 of file srv_kinematics_plugin.h.
srv_kinematics_plugin::SrvKinematicsPlugin::SrvKinematicsPlugin | ( | ) |
Default constructor.
Definition at line 61 of file srv_kinematics_plugin.cpp.
|
overridevirtual |
Return all the joint names in the order they are used internally.
Implements kinematics::KinematicsBase.
Definition at line 410 of file srv_kinematics_plugin.cpp.
|
overridevirtual |
Return all the link names in the order they are represented internally.
Implements kinematics::KinematicsBase.
Definition at line 415 of file srv_kinematics_plugin.cpp.
|
overridevirtual |
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()) |
Implements kinematics::KinematicsBase.
Definition at line 389 of file srv_kinematics_plugin.cpp.
|
overridevirtual |
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. |
Implements kinematics::KinematicsBase.
Definition at line 188 of file srv_kinematics_plugin.cpp.
const std::vector< std::string > & srv_kinematics_plugin::SrvKinematicsPlugin::getVariableNames | ( | ) | const |
Return all the variable names in the order they are represented internally.
Definition at line 420 of file srv_kinematics_plugin.cpp.
|
overridevirtual |
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 from kinematics::KinematicsBase.
Definition at line 65 of file srv_kinematics_plugin.cpp.
|
overridevirtual |
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. |
Implements kinematics::KinematicsBase.
Definition at line 232 of file srv_kinematics_plugin.cpp.
|
overridevirtual |
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. |
Implements kinematics::KinematicsBase.
Definition at line 211 of file srv_kinematics_plugin.cpp.
|
overridevirtual |
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. |
Implements kinematics::KinematicsBase.
Definition at line 221 of file srv_kinematics_plugin.cpp.
|
overridevirtual |
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. |
Implements kinematics::KinematicsBase.
Definition at line 199 of file srv_kinematics_plugin.cpp.
|
overridevirtual |
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 from kinematics::KinematicsBase.
Definition at line 247 of file srv_kinematics_plugin.cpp.
|
overrideprotectedvirtual |
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 from kinematics::KinematicsBase.
Definition at line 147 of file srv_kinematics_plugin.cpp.