moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Public Member Functions | |
IKFastKinematicsPlugin () | |
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 | getPositionIK (const std::vector< geometry_msgs::msg::Pose > &ik_poses, const std::vector< double > &ik_seed_state, std::vector< std::vector< double > > &solutions, kinematics::KinematicsResult &result, const kinematics::KinematicsQueryOptions &options) const override |
Given a desired pose of the end-effector, compute the set joint angles solutions that are able 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 solutions 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 solutions 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 solutions 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 solutions by stepping through the redundancy (or other numerical routines). The consistency_limit specifies that only certain redundancy positions around those specified in the seed state are admissible and need to be searched. | |
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. | |
void | setSearchDiscretization (const std::map< unsigned int, double > &discretization) |
Sets the discretization value for the redundant joint. | |
bool | setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices) override |
Overrides the default method to prevent changing the redundant joints. | |
Public Member Functions inherited from kinematics::KinematicsBase | |
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 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 () | |
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 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) |
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_ |
Definition at line 163 of file ikfast61_moveit_plugin_template.cpp.
|
inline |
Definition at line 208 of file ikfast61_moveit_plugin_template.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 774 of file ikfast61_moveit_plugin_template.cpp.
|
overridevirtual |
Given a desired pose of the end-effector, compute the joint angles to reach it.
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 |
Implements kinematics::KinematicsBase.
Definition at line 1097 of file ikfast61_moveit_plugin_template.cpp.
|
overridevirtual |
Given a desired pose of the end-effector, compute the set joint angles solutions that are able to reach it.
This is a default implementation that returns only one solution and so its result is equivalent to calling 'getPositionIK(...)' with a zero initialized seed.
ik_poses | The desired pose of each tip link |
ik_seed_state | an initial guess solution for the inverse kinematics |
solutions | A vector of vectors where each entry is a valid joint solution |
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 KinmaticSearches::NO_DISCRETIZATION method; requesting any other will result in failure. |
Reimplemented from kinematics::KinematicsBase.
Definition at line 1208 of file ikfast61_moveit_plugin_template.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 solutions by stepping through the redundancy (or other numerical routines). The consistency_limit specifies that only certain redundancy positions around those specified in the seed state are admissible and need to be searched.
ik_pose | the desired pose of the link |
ik_seed_state | an initial guess solution for the inverse kinematics |
consistency_limit | the distance that the redundancy can be from the current position |
Implements kinematics::KinematicsBase.
Definition at line 866 of file ikfast61_moveit_plugin_template.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 solutions 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 |
the | distance that the redundancy can be from the current position |
Implements kinematics::KinematicsBase.
Definition at line 844 of file ikfast61_moveit_plugin_template.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 solutions 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 |
Implements kinematics::KinematicsBase.
Definition at line 855 of file ikfast61_moveit_plugin_template.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 solutions 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 |
Implements kinematics::KinematicsBase.
Definition at line 833 of file ikfast61_moveit_plugin_template.cpp.
|
overridevirtual |
Overrides the default method to prevent changing the redundant joints.
Reimplemented from kinematics::KinematicsBase.
Definition at line 555 of file ikfast61_moveit_plugin_template.cpp.
void _NAMESPACE_::IKFastKinematicsPlugin::setSearchDiscretization | ( | const std::map< unsigned int, double > & | discretization | ) |
Sets the discretization value for the redundant joint.
Since this ikfast implementation allows for one redundant joint then only the first entry will be in the discretization map will be used. Calling this method replaces previous discretization settings.
discretization | a map of joint indices and discretization value pairs. |
Definition at line 522 of file ikfast61_moveit_plugin_template.cpp.