
| Public Member Functions | |
| bool | getPositionFK (const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const | 
| Given a set of joint angles and a set of links, compute their pose.  More... | |
| 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 | 
| Given a desired pose of the end-effector, compute the joint angles to reach it.  More... | |
| IKFastKinematicsPlugin () | |
| 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 | 
| 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).  More... | |
| 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 | 
| 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).  More... | |
| 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 | 
| 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).  More... | |
| 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 | 
| 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.  More... | |
|  Public Member Functions inherited from kinematics::KinematicsBase | |
| virtual const std::string & | getBaseFrame () const | 
| double | getDefaultTimeout () const | 
| virtual const std::string & | getGroupName () const | 
| 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 | 
| virtual void | getRedundantJoints (std::vector< unsigned int > &redundant_joint_indices) const | 
| double | getSearchDiscretization (int joint_index=0) const | 
| std::vector< DiscretizationMethod > | getSupportedDiscretizationMethods () const | 
| virtual const std::string & | getTipFrame () const | 
| virtual const std::vector< std::string > & | getTipFrames () const | 
| 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) | 
| 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) | 
| KinematicsBase () | |
| 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=NULL) const | 
| void | setDefaultTimeout (double timeout) | 
| bool | setRedundantJoints (const std::vector< std::string > &redundant_joint_names) | 
| virtual bool | setRedundantJoints (const std::vector< unsigned int > &redundant_joint_indices) | 
| void | setSearchDiscretization (double sd) | 
| void | setSearchDiscretization (const std::map< int, double > &discretization) | 
| 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) | 
| 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) | 
| virtual bool | supportsGroup (const moveit::core::JointModelGroup *jmg, std::string *error_text_out=NULL) const | 
| virtual | ~KinematicsBase () | 
| Private Member Functions | |
| void | fillFreeParams (int count, int *array) | 
| void | getClosestSolution (const IkSolutionList< IkReal > &solutions, const std::vector< double > &ik_seed_state, std::vector< double > &solution) const | 
| bool | getCount (int &count, const int &max_count, const int &min_count) const | 
| const std::vector< std::string > & | getJointNames () const | 
| const std::vector< std::string > & | getLinkNames () const | 
| void | getSolution (const IkSolutionList< IkReal > &solutions, int i, std::vector< double > &solution) const | 
| Gets a specific solution from the set.  More... | |
| double | harmonize (const std::vector< double > &ik_seed_state, std::vector< double > &solution) const | 
| bool | initialize (const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_name, double search_discretization) | 
| int | solve (KDL::Frame &pose_frame, const std::vector< double > &vfree, IkSolutionList< IkReal > &solutions) const | 
| Calls the IK solver from IKFast.  More... | |
| Private Attributes | |
| bool | active_ | 
| std::vector< int > | free_params_ | 
| std::vector< bool > | joint_has_limits_vector_ | 
| std::vector< double > | joint_max_vector_ | 
| std::vector< double > | joint_min_vector_ | 
| std::vector< std::string > | joint_names_ | 
| std::vector< std::string > | link_names_ | 
| size_t | num_joints_ | 
| Additional Inherited Members | |
|  Public Types inherited from kinematics::KinematicsBase | |
| typedef boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> | IKCallbackFn | 
|  Static Public Attributes inherited from kinematics::KinematicsBase | |
| static const double | DEFAULT_SEARCH_DISCRETIZATION | 
| static const double | DEFAULT_TIMEOUT | 
|  Protected Member Functions inherited from kinematics::KinematicsBase | |
| bool | lookupParam (const std::string ¶m, T &val, const T &default_val) const | 
| 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 | |
| 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< DiscretizationMethod > | supported_methods_ | 
| std::string | tip_frame_ | 
| std::vector< std::string > | tip_frames_ | 
Definition at line 114 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | inline | 
Definition at line 133 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Definition at line 535 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Definition at line 511 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Definition at line 541 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | inlineprivatevirtual | 
Implements kinematics::KinematicsBase.
Definition at line 125 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | inlineprivatevirtual | 
Implements kinematics::KinematicsBase.
Definition at line 126 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | virtual | 
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
| 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 577 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | virtual | 
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 850 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Gets a specific solution from the set.
Definition at line 447 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Definition at line 465 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | privatevirtual | 
Reimplemented from kinematics::KinematicsBase.
Definition at line 260 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | 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 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 619 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | 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 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 639 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | 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 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 658 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | 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 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 677 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Calls the IK solver from IKFast.
Definition at line 374 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Definition at line 123 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Definition at line 122 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Definition at line 119 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Definition at line 118 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Definition at line 117 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Definition at line 116 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Definition at line 120 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.
| 
 | private | 
Definition at line 121 of file staubli_rx160_manipulator_ikfast_moveit_plugin.cpp.