Class TRAC_IKKinematicsPlugin

Inheritance Relationships

Base Type

  • public kinematics::KinematicsBase

Class Documentation

class TRAC_IKKinematicsPlugin : public kinematics::KinematicsBase

Public Functions

inline const std::vector<std::string> &getJointNames() const
inline const std::vector<std::string> &getLinkNames() const
inline TRAC_IKKinematicsPlugin()
inline ~TRAC_IKKinematicsPlugin()
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.

Parameters:
  • 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

Returns:

True if a valid solution was found, false otherwise

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).

Parameters:
  • ik_pose – the desired pose of the link

  • ik_seed_state – an initial guess solution for the inverse kinematics

Returns:

True if a valid solution was found, false otherwise

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).

Parameters:
  • 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

Returns:

True if a valid solution was found, false otherwise

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

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).

Parameters:
  • ik_pose – the desired pose of the link

  • ik_seed_state – an initial guess solution for the inverse kinematics

Returns:

True if a valid solution was found, false otherwise

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.

Parameters:
  • 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

Returns:

True if a valid solution was found, false otherwise

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 std::vector<double> &consistency_limits, const kinematics::KinematicsQueryOptions &options) const
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.

This FK routine is only used if ‘use_plugin_fk’ is set in the ‘arm_kinematics_constraint_aware’ node, otherwise ROS TF is used to calculate the forward kinematics

Parameters:
  • 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())

Returns:

True if a valid solution was found, false otherwise

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) override